blob: fac264a22ce028676ea6b74c5467afe09fedabb6 [file] [log] [blame]
Austin Schuh7400da02018-01-28 19:54:58 -08001/// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE
2/// \author Rosen Diankov
3///
4/// Licensed under the Apache License, Version 2.0 (the "License");
5/// you may not use this file except in compliance with the License.
6/// You may obtain a copy of the License at
7/// http://www.apache.org/licenses/LICENSE-2.0
8///
9/// Unless required by applicable law or agreed to in writing, software
10/// distributed under the License is distributed on an "AS IS" BASIS,
11/// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12/// See the License for the specific language governing permissions and
13/// limitations under the License.
14///
15/// ikfast version 0x1000004a generated on 2017-12-12 14:08:54.348797
16/// Generated using solver transform6d
17/// To compile with gcc:
18/// gcc -lstdc++ ik.cpp
19/// To compile without any main function as a shared object (might need -llapack):
20/// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp
21#define IKFAST_HAS_LIBRARY
22#include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
23using namespace ikfast;
24
25// check if the included ikfast version matches what this file was compiled with
26#define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
27IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x1000004a);
28
29#include <cmath>
30#include <vector>
31#include <limits>
32#include <algorithm>
33#include <complex>
34
35#ifndef IKFAST_ASSERT
36#include <stdexcept>
37#include <sstream>
38#include <iostream>
39
40#ifdef _MSC_VER
41#ifndef __PRETTY_FUNCTION__
42#define __PRETTY_FUNCTION__ __FUNCDNAME__
43#endif
44#endif
45
46#ifndef __PRETTY_FUNCTION__
47#define __PRETTY_FUNCTION__ __func__
48#endif
49
50#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()); } }
51
52#endif
53
54#if defined(_MSC_VER)
55#define IKFAST_ALIGNED16(x) __declspec(align(16)) x
56#else
57#define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
58#endif
59
60#define IK2PI ((IkReal)6.28318530717959)
61#define IKPI ((IkReal)3.14159265358979)
62#define IKPI_2 ((IkReal)1.57079632679490)
63
64#ifdef _MSC_VER
65#ifndef isnan
66#define isnan _isnan
67#endif
68#ifndef isinf
69#define isinf _isinf
70#endif
71//#ifndef isfinite
72//#define isfinite _isfinite
73//#endif
74#endif // _MSC_VER
75
76// lapack routines
77extern "C" {
78 void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
79 void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
80 void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
81 void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
82 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);
83 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);
84}
85
86using namespace std; // necessary to get std math routines
87
88#ifdef IKFAST_NAMESPACE
89namespace IKFAST_NAMESPACE {
90#endif
91
92inline float IKabs(float f) { return fabsf(f); }
93inline double IKabs(double f) { return fabs(f); }
94
95inline float IKsqr(float f) { return f*f; }
96inline double IKsqr(double f) { return f*f; }
97
98inline float IKlog(float f) { return logf(f); }
99inline double IKlog(double f) { return log(f); }
100
101// allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation
102#ifndef IKFAST_SINCOS_THRESH
103#define IKFAST_SINCOS_THRESH ((IkReal)1e-7)
104#endif
105
106// used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation
107#ifndef IKFAST_ATAN2_MAGTHRESH
108#define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7)
109#endif
110
111// minimum distance of separate solutions
112#ifndef IKFAST_SOLUTION_THRESH
113#define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
114#endif
115
116// there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate
117#ifndef IKFAST_EVALCOND_THRESH
118#define IKFAST_EVALCOND_THRESH ((IkReal)0.00001)
119#endif
120
121
122inline float IKasin(float f)
123{
124IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
125if( f <= -1 ) return float(-IKPI_2);
126else if( f >= 1 ) return float(IKPI_2);
127return asinf(f);
128}
129inline double IKasin(double f)
130{
131IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
132if( f <= -1 ) return -IKPI_2;
133else if( f >= 1 ) return IKPI_2;
134return asin(f);
135}
136
137// return positive value in [0,y)
138inline float IKfmod(float x, float y)
139{
140 while(x < 0) {
141 x += y;
142 }
143 return fmodf(x,y);
144}
145
146// return positive value in [0,y)
147inline double IKfmod(double x, double y)
148{
149 while(x < 0) {
150 x += y;
151 }
152 return fmod(x,y);
153}
154
155inline float IKacos(float f)
156{
157IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
158if( f <= -1 ) return float(IKPI);
159else if( f >= 1 ) return float(0);
160return acosf(f);
161}
162inline double IKacos(double f)
163{
164IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
165if( f <= -1 ) return IKPI;
166else if( f >= 1 ) return 0;
167return acos(f);
168}
169inline float IKsin(float f) { return sinf(f); }
170inline double IKsin(double f) { return sin(f); }
171inline float IKcos(float f) { return cosf(f); }
172inline double IKcos(double f) { return cos(f); }
173inline float IKtan(float f) { return tanf(f); }
174inline double IKtan(double f) { return tan(f); }
175inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
176inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
177inline float IKatan2Simple(float fy, float fx) {
178 return atan2f(fy,fx);
179}
180inline float IKatan2(float fy, float fx) {
181 if( isnan(fy) ) {
182 IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
183 return float(IKPI_2);
184 }
185 else if( isnan(fx) ) {
186 return 0;
187 }
188 return atan2f(fy,fx);
189}
190inline double IKatan2Simple(double fy, double fx) {
191 return atan2(fy,fx);
192}
193inline double IKatan2(double fy, double fx) {
194 if( isnan(fy) ) {
195 IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
196 return IKPI_2;
197 }
198 else if( isnan(fx) ) {
199 return 0;
200 }
201 return atan2(fy,fx);
202}
203
204template <typename T>
205struct CheckValue
206{
207 T value;
208 bool valid;
209};
210
211template <typename T>
212inline CheckValue<T> IKatan2WithCheck(T fy, T fx, T epsilon)
213{
214 CheckValue<T> ret;
215 ret.valid = false;
216 ret.value = 0;
217 if( !isnan(fy) && !isnan(fx) ) {
218 if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) {
219 ret.value = IKatan2Simple(fy,fx);
220 ret.valid = true;
221 }
222 }
223 return ret;
224}
225
226inline float IKsign(float f) {
227 if( f > 0 ) {
228 return float(1);
229 }
230 else if( f < 0 ) {
231 return float(-1);
232 }
233 return 0;
234}
235
236inline double IKsign(double f) {
237 if( f > 0 ) {
238 return 1.0;
239 }
240 else if( f < 0 ) {
241 return -1.0;
242 }
243 return 0;
244}
245
246template <typename T>
247inline CheckValue<T> IKPowWithIntegerCheck(T f, int n)
248{
249 CheckValue<T> ret;
250 ret.valid = true;
251 if( n == 0 ) {
252 ret.value = 1.0;
253 return ret;
254 }
255 else if( n == 1 )
256 {
257 ret.value = f;
258 return ret;
259 }
260 else if( n < 0 )
261 {
262 if( f == 0 )
263 {
264 ret.valid = false;
265 ret.value = (T)1.0e30;
266 return ret;
267 }
268 if( n == -1 ) {
269 ret.value = T(1.0)/f;
270 return ret;
271 }
272 }
273
274 int num = n > 0 ? n : -n;
275 if( num == 2 ) {
276 ret.value = f*f;
277 }
278 else if( num == 3 ) {
279 ret.value = f*f*f;
280 }
281 else {
282 ret.value = 1.0;
283 while(num>0) {
284 if( num & 1 ) {
285 ret.value *= f;
286 }
287 num >>= 1;
288 f *= f;
289 }
290 }
291
292 if( n < 0 ) {
293 ret.value = T(1.0)/ret.value;
294 }
295 return ret;
296}
297
298/// solves the forward kinematics equations.
299/// \param pfree is an array specifying the free joints of the chain.
300IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
301IkReal 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;
302x0=IKcos(j[0]);
303x1=IKcos(j[3]);
304x2=IKsin(j[0]);
305x3=IKsin(j[3]);
306x4=IKsin(j[4]);
307x5=IKsin(j[1]);
308x6=IKsin(j[2]);
309x7=IKcos(j[1]);
310x8=IKcos(j[2]);
311x9=IKcos(j[4]);
312x10=IKsin(j[5]);
313x11=IKcos(j[5]);
314x12=((0.134999999784)*x4);
315x13=((5.39999999136e-6)*x4);
316x14=((0.9999999992)*x4);
317x15=((1.271)*x0);
318x16=((1.271)*x2);
319x17=((5.39999999136e-6)*x0);
320x18=((0.175)*x0);
321x19=((3.9999999968e-5)*x4);
322x20=((5.39999999136e-6)*x9);
323x21=((0.175)*x2);
324x22=((0.134999999784)*x9);
325x23=((3.9999999968e-5)*x9);
326x24=((0.9999999992)*x9);
327x25=((1.0)*x2);
328x26=((5.39999999136e-6)*x1);
329x27=((1.095)*x5);
330x28=((2.159999996544e-10)*x0);
331x29=((1.0)*x0);
332x30=((2.159999996544e-10)*x2);
333x31=((2.159999996544e-10)*x1);
334x32=((5.39999999136e-6)*x2);
335x33=(x5*x6);
336x34=(x7*x8);
337x35=(x1*x9);
338x36=(x2*x3);
339x37=(x6*x7);
340x38=(x5*x8);
341x39=((1.0)*x34);
342x40=(x29*x33);
343x41=(x25*x33);
344x42=((((-1.0)*x39))+x33);
345x43=((((-1.0)*x33))+x39);
346x44=((((1.0)*x38))+(((1.0)*x37)));
347x45=((-1.0)*x44);
348x46=(x1*x42);
349x47=(x3*x43);
350x48=((((-1.0)*x40))+((x0*x34)));
351x49=((((-1.0)*x41))+((x2*x34)));
352x50=((((-1.0)*x29*x34))+x40);
353x51=((((-1.0)*x25*x34))+x41);
354x52=(x29*((x38+x37)));
355x53=((-1.0)*x52);
356x54=(x25*((x38+x37)));
357x55=((-1.0)*x54);
358x56=(x1*x55);
359x57=((((-1.0)*x25*x3))+((x1*x53)));
360x58=(((x3*x52))+(((-1.0)*x1*x25)));
361x59=(((x0*x3))+x56);
362x60=(((x0*x1))+((x3*x54)));
363x61=(x4*x57);
364x62=(((x19*x46))+((x23*x45))+((x14*x44))+((x24*x46)));
365x63=(((x14*x50))+((x23*x48))+((x19*x57))+((x24*x57)));
366x64=(((x14*x51))+((x23*x49))+((x19*x59))+((x24*x59)));
367eerot[0]=(((x11*x63))+((x10*x58)));
368eerot[1]=((((-1.0)*x10*x63))+((x11*x58)));
369eerot[2]=(((x14*x57))+(((-1.0)*x23*x57))+(((-1.0)*x19*x50))+((x24*x48)));
370IkReal x65=((1.0)*x33);
371eetrans[0]=(((x12*x57))+((x0*x27))+(((-1.0)*x15*x65))+((x18*x37))+((x18*x38))+(((-1.0)*x20*x57))+((x22*x48))+((x4*(((((-2.159999996544e-10)*x36))+((x31*x53))))))+((x15*x34))+((x9*((((x28*x34))+(((-1.0)*x28*x65))))))+x18+((x9*((((x26*x53))+(((-5.39999999136e-6)*x36))))))+(((-1.0)*x13*x50))+((x4*((((x17*x33))+(((-1.0)*x17*x34)))))));
372eerot[3]=(((x11*x64))+((x10*x60)));
373eerot[4]=((((-1.0)*x10*x64))+((x11*x60)));
374eerot[5]=(((x14*x59))+(((-1.0)*x23*x59))+(((-1.0)*x19*x51))+((x24*x49)));
375IkReal x66=((1.0)*x33);
376eetrans[1]=((((-1.0)*x16*x66))+((x12*x59))+((x4*((((x31*x55))+((x28*x3))))))+((x16*x34))+(((-1.0)*x20*x59))+((x4*((((x32*x33))+(((-1.0)*x32*x34))))))+((x22*x49))+((x21*x38))+((x21*x37))+((x9*(((((-1.0)*x30*x66))+((x30*x34))))))+((x2*x27))+x21+(((-1.0)*x13*x51))+((x9*((((x26*x55))+((x17*x3)))))));
377eerot[6]=(((x10*x47))+((x11*x62)));
378eerot[7]=((((-1.0)*x10*x62))+((x11*x47)));
379eerot[8]=(((x14*x46))+(((-1.0)*x19*x44))+((x24*x45))+(((-1.0)*x23*x46)));
380eetrans[2]=((0.495)+(((-0.175)*x33))+(((-1.0)*x20*x46))+(((0.175)*x34))+((x22*x45))+(((-1.271)*x38))+(((-1.271)*x37))+((x4*(((((5.39999999136e-6)*x38))+(((5.39999999136e-6)*x37))))))+((x1*x4*(((((-2.159999996544e-10)*x34))+(((2.159999996544e-10)*x33))))))+((x35*(((((5.39999999136e-6)*x33))+(((-5.39999999136e-6)*x34))))))+(((1.095)*x7))+((x12*x46))+((x9*(((((-2.159999996544e-10)*x37))+(((-2.159999996544e-10)*x38))))))+(((-1.0)*x13*x44)));
381}
382
383IKFAST_API int GetNumFreeParameters() { return 0; }
384IKFAST_API int* GetFreeParameters() { return NULL; }
385IKFAST_API int GetNumJoints() { return 6; }
386
387IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
388
389IKFAST_API int GetIkType() { return 0x67000001; }
390
391class IKSolver {
392public:
393IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,j5,cj5,sj5,htj5,j5mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_r10,r10,rxp1_0,new_r11,r11,rxp1_1,new_r12,r12,rxp1_2,new_r20,r20,rxp2_0,new_r21,r21,rxp2_1,new_r22,r22,rxp2_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp;
394unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5;
395
396IkReal j100, cj100, sj100;
397unsigned char _ij100[2], _nj100;
398bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
399j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; j5=numeric_limits<IkReal>::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1;
400for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
401 solutions.Clear();
402r00 = eerot[0*3+0];
403r01 = eerot[0*3+1];
404r02 = eerot[0*3+2];
405r10 = eerot[1*3+0];
406r11 = eerot[1*3+1];
407r12 = eerot[1*3+2];
408r20 = eerot[2*3+0];
409r21 = eerot[2*3+1];
410r22 = eerot[2*3+2];
411px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
412
413new_r00=r00;
414new_r01=r01;
415new_r02=r02;
416new_px=((((-0.134999999892)*r02))+px);
417new_r10=r10;
418new_r11=r11;
419new_r12=r12;
420new_py=((((-0.134999999892)*r12))+py);
421new_r20=r20;
422new_r21=r21;
423new_r22=r22;
424new_pz=((-0.495)+pz+(((-0.134999999892)*r22)));
425r00 = 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;
426IkReal x67=((1.0)*px);
427IkReal x68=((1.0)*pz);
428IkReal x69=((1.0)*py);
429pp=((px*px)+(py*py)+(pz*pz));
430npx=(((px*r00))+((py*r10))+((pz*r20)));
431npy=(((px*r01))+((py*r11))+((pz*r21)));
432npz=(((px*r02))+((py*r12))+((pz*r22)));
433rxp0_0=((((-1.0)*r20*x69))+((pz*r10)));
434rxp0_1=(((px*r20))+(((-1.0)*r00*x68)));
435rxp0_2=((((-1.0)*r10*x67))+((py*r00)));
436rxp1_0=((((-1.0)*r21*x69))+((pz*r11)));
437rxp1_1=(((px*r21))+(((-1.0)*r01*x68)));
438rxp1_2=((((-1.0)*r11*x67))+((py*r01)));
439rxp2_0=(((pz*r12))+(((-1.0)*r22*x69)));
440rxp2_1=(((px*r22))+(((-1.0)*r02*x68)));
441rxp2_2=((((-1.0)*r12*x67))+((py*r02)));
442{
443IkReal j0eval[1];
444j0eval[0]=((IKabs(px))+(IKabs(py)));
445if( IKabs(j0eval[0]) < 0.0000010000000000 )
446{
447continue; // no branches [j0, j1, j2]
448
449} else
450{
451{
452IkReal j0array[2], cj0array[2], sj0array[2];
453bool j0valid[2]={false};
454_nj0 = 2;
455CheckValue<IkReal> x71 = IKatan2WithCheck(IkReal(py),IkReal(((-1.0)*px)),IKFAST_ATAN2_MAGTHRESH);
456if(!x71.valid){
457continue;
458}
459IkReal x70=x71.value;
460j0array[0]=((-1.0)*x70);
461sj0array[0]=IKsin(j0array[0]);
462cj0array[0]=IKcos(j0array[0]);
463j0array[1]=((3.14159265358979)+(((-1.0)*x70)));
464sj0array[1]=IKsin(j0array[1]);
465cj0array[1]=IKcos(j0array[1]);
466if( j0array[0] > IKPI )
467{
468 j0array[0]-=IK2PI;
469}
470else if( j0array[0] < -IKPI )
471{ j0array[0]+=IK2PI;
472}
473j0valid[0] = true;
474if( j0array[1] > IKPI )
475{
476 j0array[1]-=IK2PI;
477}
478else if( j0array[1] < -IKPI )
479{ j0array[1]+=IK2PI;
480}
481j0valid[1] = true;
482for(int ij0 = 0; ij0 < 2; ++ij0)
483{
484if( !j0valid[ij0] )
485{
486 continue;
487}
488_ij0[0] = ij0; _ij0[1] = -1;
489for(int iij0 = ij0+1; iij0 < 2; ++iij0)
490{
491if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
492{
493 j0valid[iij0]=false; _ij0[1] = iij0; break;
494}
495}
496j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
497
498{
499IkReal j2array[2], cj2array[2], sj2array[2];
500bool j2valid[2]={false};
501_nj2 = 2;
502IkReal x72=px*px;
503IkReal x73=r10*r10;
504IkReal x74=r01*r01;
505IkReal x75=py*py;
506IkReal x76=r11*r11;
507IkReal x77=r00*r00;
508IkReal x78=r20*r20;
509IkReal x79=r21*r21;
510IkReal x80=pz*pz;
511IkReal x81=r12*r12;
512IkReal x82=r22*r22;
513IkReal x83=r02*r02;
514IkReal x84=((0.355903503251059)*x80);
515IkReal x85=((0.124566226137871)*cj0*px);
516IkReal x86=((0.355903503251059)*x72);
517IkReal x87=((0.355903503251059)*x75);
518IkReal x88=((0.124566226137871)*py*sj0);
519IkReal x89=(x74*x76);
520IkReal x90=(x77*x78);
521IkReal x91=(x76*x79);
522IkReal x92=(x81*x83);
523IkReal x93=(x82*x83);
524IkReal x94=(x81*x82);
525IkReal x95=(x74*x79);
526IkReal x96=(x73*x87);
527if( (((-1.00167830918099)+(((-1.0)*x81*x88))+((x77*x86))+((x87*x91))+((x79*x84))+(((-1.0)*x73*x88))+(((-1.0)*x83*x85))+((x78*x84))+((x82*x84))+((x81*x87))+((x78*x96))+((x86*x90))+((x86*x95))+(((-1.0)*x77*x85))+((x86*x89))+((x74*x86))+(((-0.711807006502117)*x78*x79*x80))+(((-1.0)*x87*x92))+(((-1.0)*x87*x94))+(((-1.0)*x86*x93))+(((-1.0)*x86*x92))+((x76*x87))+((x73*x77*x86))+x96+(((-1.0)*x74*x85))+(((-0.711807006502117)*x73*x75*x76))+(((-1.0)*x76*x88))+(((-1.0)*x84*x94))+(((-1.0)*x84*x93))+((x83*x86))+(((-0.711807006502117)*x72*x74*x77))+((x73*x78*x84))+((x84*x91))+((x84*x90))+((x84*x95))+((x77*x96))+((x87*x89)))) < -1-IKFAST_SINCOS_THRESH || (((-1.00167830918099)+(((-1.0)*x81*x88))+((x77*x86))+((x87*x91))+((x79*x84))+(((-1.0)*x73*x88))+(((-1.0)*x83*x85))+((x78*x84))+((x82*x84))+((x81*x87))+((x78*x96))+((x86*x90))+((x86*x95))+(((-1.0)*x77*x85))+((x86*x89))+((x74*x86))+(((-0.711807006502117)*x78*x79*x80))+(((-1.0)*x87*x92))+(((-1.0)*x87*x94))+(((-1.0)*x86*x93))+(((-1.0)*x86*x92))+((x76*x87))+((x73*x77*x86))+x96+(((-1.0)*x74*x85))+(((-0.711807006502117)*x73*x75*x76))+(((-1.0)*x76*x88))+(((-1.0)*x84*x94))+(((-1.0)*x84*x93))+((x83*x86))+(((-0.711807006502117)*x72*x74*x77))+((x73*x78*x84))+((x84*x91))+((x84*x90))+((x84*x95))+((x77*x96))+((x87*x89)))) > 1+IKFAST_SINCOS_THRESH )
528 continue;
529IkReal x97=IKasin(((-1.00167830918099)+(((-1.0)*x81*x88))+((x77*x86))+((x87*x91))+((x79*x84))+(((-1.0)*x73*x88))+(((-1.0)*x83*x85))+((x78*x84))+((x82*x84))+((x81*x87))+((x78*x96))+((x86*x90))+((x86*x95))+(((-1.0)*x77*x85))+((x86*x89))+((x74*x86))+(((-0.711807006502117)*x78*x79*x80))+(((-1.0)*x87*x92))+(((-1.0)*x87*x94))+(((-1.0)*x86*x93))+(((-1.0)*x86*x92))+((x76*x87))+((x73*x77*x86))+x96+(((-1.0)*x74*x85))+(((-0.711807006502117)*x73*x75*x76))+(((-1.0)*x76*x88))+(((-1.0)*x84*x94))+(((-1.0)*x84*x93))+((x83*x86))+(((-0.711807006502117)*x72*x74*x77))+((x73*x78*x84))+((x84*x91))+((x84*x90))+((x84*x95))+((x77*x96))+((x87*x89))));
530j2array[0]=((0.136826551321617)+(((-1.0)*x97)));
531sj2array[0]=IKsin(j2array[0]);
532cj2array[0]=IKcos(j2array[0]);
533j2array[1]=((3.27841920491141)+x97);
534sj2array[1]=IKsin(j2array[1]);
535cj2array[1]=IKcos(j2array[1]);
536if( j2array[0] > IKPI )
537{
538 j2array[0]-=IK2PI;
539}
540else if( j2array[0] < -IKPI )
541{ j2array[0]+=IK2PI;
542}
543j2valid[0] = true;
544if( j2array[1] > IKPI )
545{
546 j2array[1]-=IK2PI;
547}
548else if( j2array[1] < -IKPI )
549{ j2array[1]+=IK2PI;
550}
551j2valid[1] = true;
552for(int ij2 = 0; ij2 < 2; ++ij2)
553{
554if( !j2valid[ij2] )
555{
556 continue;
557}
558_ij2[0] = ij2; _ij2[1] = -1;
559for(int iij2 = ij2+1; iij2 < 2; ++iij2)
560{
561if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
562{
563 j2valid[iij2]=false; _ij2[1] = iij2; break;
564}
565}
566j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
567
568{
569IkReal j1eval[2];
570IkReal x98=(py*sj0);
571IkReal x99=((41.5020408163265)*cj2);
572IkReal x100=(pz*sj2);
573IkReal x101=((5.71428571428571)*sj2);
574IkReal x102=(cj2*pz);
575IkReal x103=(cj0*px);
576IkReal x104=((1.271)*cj2);
577IkReal x105=((0.175)*sj2);
578j1eval[0]=((((-35.7551020408163)*pz))+(((-1.0)*sj2))+(((41.5020408163265)*x100))+((x103*x99))+((x101*x98))+(((-5.71428571428571)*x102))+((x98*x99))+((x101*x103))+(((-7.26285714285714)*cj2)));
579j1eval[1]=IKsign(((((-1.095)*pz))+(((-0.175)*x102))+((x103*x105))+((x103*x104))+(((-0.030625)*sj2))+((x105*x98))+(((1.271)*x100))+((x104*x98))+(((-0.222425)*cj2))));
580if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 )
581{
582{
583IkReal j1eval[2];
584j1eval[0]=((7.42359034572733)+(((-7.26285714285714)*sj2))+cj2);
585j1eval[1]=IKsign(((2.845091)+(((0.38325)*cj2))+(((-2.78349)*sj2))));
586if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 )
587{
588{
589IkReal j1eval[2];
590IkReal x106=(py*sj0);
591IkReal x107=((0.175)*cj2);
592IkReal x108=((5.71428571428571)*cj2);
593IkReal x109=(cj0*px);
594IkReal x110=((1.271)*sj2);
595IkReal x111=(pz*sj2);
596IkReal x112=(cj2*pz);
597IkReal x113=((41.5020408163265)*sj2);
598j1eval[0]=((6.25714285714286)+(((-7.26285714285714)*sj2))+(((-35.7551020408163)*x109))+(((-35.7551020408163)*x106))+cj2+((x106*x113))+(((-5.71428571428571)*x111))+(((-41.5020408163265)*x112))+((x109*x113))+(((-1.0)*x106*x108))+(((-1.0)*x108*x109)));
599j1eval[1]=IKsign(((0.191625)+(((-0.175)*x111))+(((-1.271)*x112))+(((-1.095)*x106))+(((-1.095)*x109))+(((0.030625)*cj2))+((x106*x110))+(((-1.0)*x107*x109))+((x109*x110))+(((-1.0)*x106*x107))+(((-0.222425)*sj2))));
600if( IKabs(j1eval[0]) < 0.0000010000000000 || IKabs(j1eval[1]) < 0.0000010000000000 )
601{
602continue; // no branches [j1]
603
604} else
605{
606{
607IkReal j1array[1], cj1array[1], sj1array[1];
608bool j1valid[1]={false};
609_nj1 = 1;
610IkReal x114=cj2*cj2;
611IkReal x115=(cj2*sj2);
612IkReal x116=(py*sj0);
613IkReal x117=((1.271)*sj2);
614IkReal x118=((0.175)*cj2);
615IkReal x119=(cj0*px);
616IkReal x120=((0.175)*pz);
617IkReal x121=((1.0)*pz);
618CheckValue<IkReal> x122=IKPowWithIntegerCheck(IKsign(((0.191625)+(((-1.095)*x116))+(((-1.095)*x119))+(((-1.0)*x118*x119))+(((-1.0)*sj2*x120))+(((-1.271)*cj2*pz))+(((0.030625)*cj2))+(((-1.0)*x116*x118))+(((-0.222425)*sj2))+((x116*x117))+((x117*x119)))),-1);
619if(!x122.valid){
620continue;
621}
622CheckValue<IkReal> x123 = IKatan2WithCheck(IkReal(((-2.814466)+(((0.44485)*x115))+(((2.78349)*sj2))+(((-0.38325)*cj2))+(pz*pz)+(((1.584816)*x114)))),IkReal(((0.222425)+(((-0.191625)*sj2))+(((-1.0)*x119*x121))+(((-1.0)*x116*x121))+(((-1.391745)*cj2))+x120+(((1.584816)*x115))+(((-0.44485)*x114)))),IKFAST_ATAN2_MAGTHRESH);
623if(!x123.valid){
624continue;
625}
626j1array[0]=((-1.5707963267949)+(((1.5707963267949)*(x122.value)))+(x123.value));
627sj1array[0]=IKsin(j1array[0]);
628cj1array[0]=IKcos(j1array[0]);
629if( j1array[0] > IKPI )
630{
631 j1array[0]-=IK2PI;
632}
633else if( j1array[0] < -IKPI )
634{ j1array[0]+=IK2PI;
635}
636j1valid[0] = true;
637for(int ij1 = 0; ij1 < 1; ++ij1)
638{
639if( !j1valid[ij1] )
640{
641 continue;
642}
643_ij1[0] = ij1; _ij1[1] = -1;
644for(int iij1 = ij1+1; iij1 < 1; ++iij1)
645{
646if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
647{
648 j1valid[iij1]=false; _ij1[1] = iij1; break;
649}
650}
651j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
652{
653IkReal evalcond[5];
654IkReal x124=IKcos(j1);
655IkReal x125=IKsin(j1);
656IkReal x126=py*py;
657IkReal x127=r11*r11;
658IkReal x128=r21*r21;
659IkReal x129=r01*r01;
660IkReal x130=px*px;
661IkReal x131=pz*pz;
662IkReal x132=r10*r10;
663IkReal x133=r00*r00;
664IkReal x134=r20*r20;
665IkReal x135=r02*r02;
666IkReal x136=r22*r22;
667IkReal x137=r12*r12;
668IkReal x138=((1.271)*cj2);
669IkReal x139=(cj0*px);
670IkReal x140=((0.175)*cj2);
671IkReal x141=(py*sj0);
672IkReal x142=(sj2*x124);
673IkReal x143=((1.0)*x125);
674IkReal x144=((1.0)*x136);
675IkReal x145=(sj2*x125);
676IkReal x146=(x130*x133);
677IkReal x147=(x130*x135);
678IkReal x148=(x128*x131);
679IkReal x149=(x126*x137);
680IkReal x150=(x131*x134);
681IkReal x151=(x126*x132);
682IkReal x152=(x126*x127);
683IkReal x153=(x129*x130);
684evalcond[0]=(((x124*x141))+(((-1.0)*pz*x143))+(((-0.175)*sj2))+(((-1.0)*x138))+((x124*x139))+(((-0.175)*x124)));
685evalcond[1]=((((1.271)*x142))+(((-1.0)*x124*x140))+(((0.175)*x145))+((x125*x138))+pz+(((-1.095)*x124)));
686evalcond[2]=((1.095)+(((-1.0)*x139*x143))+x140+(((-1.0)*pz*x124))+(((-1.0)*x141*x143))+(((0.175)*x125))+(((-1.271)*sj2)));
687evalcond[3]=((-0.175)+(((1.271)*x145))+(((-1.0)*x125*x140))+(((-0.175)*x142))+(((-1.0)*x124*x138))+x141+x139+(((-1.095)*x125)));
688evalcond[4]=((-2.875716)+(((-2.0)*x129*x146))+(((-0.38325)*x125))+(((-0.44485)*cj2*x124))+(((-1.0)*x131*x137*x144))+((x128*x153))+((x128*x152))+(((2.78349)*sj2))+(((-0.38325)*cj2))+(((-1.0)*x144*x147))+(((-1.0)*x144*x149))+(((-2.0)*x134*x148))+(((-1.0)*x137*x147))+x153+x152+x151+x150+x146+x147+x148+x149+(((-0.06125)*x142))+((x129*x148))+((x127*x148))+((x131*x136))+((x129*x152))+(((-2.0)*x127*x151))+((x127*x153))+(((-1.0)*x131*x135*x144))+((x134*x146))+(((-0.06125)*cj2*x125))+((x134*x151))+((x132*x146))+((x133*x150))+((x133*x151))+((x132*x150))+(((-1.0)*x135*x149))+(((0.44485)*x145)));
689if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
690{
691continue;
692}
693}
694
695rotationfunction0(solutions);
696}
697}
698
699}
700
701}
702
703} else
704{
705{
706IkReal j1array[1], cj1array[1], sj1array[1];
707bool j1valid[1]={false};
708_nj1 = 1;
709IkReal x2707=((0.175)*cj2);
710IkReal x2708=(cj0*px);
711IkReal x2709=(py*sj0);
712IkReal x2710=((1.271)*pz);
713IkReal x2711=((0.175)*sj2);
714IkReal x2712=((1.271)*x2709);
715CheckValue<IkReal> x2713 = IKatan2WithCheck(IkReal(((-0.191625)+(((-0.030625)*cj2))+(((-1.0)*cj2*x2710))+(((-1.271)*sj2*x2708))+((x2707*x2708))+((x2707*x2709))+(((-1.0)*sj2*x2712))+(((-1.0)*pz*x2711))+(((0.222425)*sj2))+(((1.095)*x2708))+(((1.095)*x2709)))),IkReal((((x2708*x2711))+((cj2*x2712))+(((1.095)*pz))+((x2709*x2711))+(((1.271)*cj2*x2708))+((pz*x2707))+(((-1.0)*sj2*x2710))+(((-0.030625)*sj2))+(((-0.222425)*cj2)))),IKFAST_ATAN2_MAGTHRESH);
716if(!x2713.valid){
717continue;
718}
719CheckValue<IkReal> x2714=IKPowWithIntegerCheck(IKsign(((2.845091)+(((0.38325)*cj2))+(((-2.78349)*sj2)))),-1);
720if(!x2714.valid){
721continue;
722}
723j1array[0]=((-1.5707963267949)+(x2713.value)+(((1.5707963267949)*(x2714.value))));
724sj1array[0]=IKsin(j1array[0]);
725cj1array[0]=IKcos(j1array[0]);
726if( j1array[0] > IKPI )
727{
728 j1array[0]-=IK2PI;
729}
730else if( j1array[0] < -IKPI )
731{ j1array[0]+=IK2PI;
732}
733j1valid[0] = true;
734for(int ij1 = 0; ij1 < 1; ++ij1)
735{
736if( !j1valid[ij1] )
737{
738 continue;
739}
740_ij1[0] = ij1; _ij1[1] = -1;
741for(int iij1 = ij1+1; iij1 < 1; ++iij1)
742{
743if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
744{
745 j1valid[iij1]=false; _ij1[1] = iij1; break;
746}
747}
748j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
749{
750IkReal evalcond[5];
751IkReal x2715=IKcos(j1);
752IkReal x2716=IKsin(j1);
753IkReal x2717=py*py;
754IkReal x2718=r11*r11;
755IkReal x2719=r21*r21;
756IkReal x2720=r01*r01;
757IkReal x2721=px*px;
758IkReal x2722=pz*pz;
759IkReal x2723=r10*r10;
760IkReal x2724=r00*r00;
761IkReal x2725=r20*r20;
762IkReal x2726=r02*r02;
763IkReal x2727=r22*r22;
764IkReal x2728=r12*r12;
765IkReal x2729=((1.271)*cj2);
766IkReal x2730=(cj0*px);
767IkReal x2731=((0.175)*cj2);
768IkReal x2732=(py*sj0);
769IkReal x2733=(sj2*x2715);
770IkReal x2734=((1.0)*x2716);
771IkReal x2735=((1.0)*x2727);
772IkReal x2736=(sj2*x2716);
773IkReal x2737=(x2721*x2724);
774IkReal x2738=(x2721*x2726);
775IkReal x2739=(x2719*x2722);
776IkReal x2740=(x2717*x2728);
777IkReal x2741=(x2722*x2725);
778IkReal x2742=(x2717*x2723);
779IkReal x2743=(x2717*x2718);
780IkReal x2744=(x2720*x2721);
781evalcond[0]=((((-1.0)*pz*x2734))+((x2715*x2732))+((x2715*x2730))+(((-0.175)*sj2))+(((-1.0)*x2729))+(((-0.175)*x2715)));
782evalcond[1]=((((-1.095)*x2715))+(((-1.0)*x2715*x2731))+(((0.175)*x2736))+(((1.271)*x2733))+pz+((x2716*x2729)));
783evalcond[2]=((1.095)+x2731+(((-1.0)*x2730*x2734))+(((0.175)*x2716))+(((-1.0)*pz*x2715))+(((-1.271)*sj2))+(((-1.0)*x2732*x2734)));
784evalcond[3]=((-0.175)+x2730+x2732+(((-1.095)*x2716))+(((1.271)*x2736))+(((-1.0)*x2715*x2729))+(((-0.175)*x2733))+(((-1.0)*x2716*x2731)));
785evalcond[4]=((-2.875716)+(((-2.0)*x2725*x2739))+x2741+x2740+x2743+x2742+x2744+x2737+x2738+x2739+(((-2.0)*x2720*x2737))+(((-1.0)*x2726*x2740))+(((2.78349)*sj2))+(((-0.44485)*cj2*x2715))+(((-0.38325)*cj2))+(((-1.0)*x2722*x2726*x2735))+((x2725*x2737))+((x2723*x2741))+((x2720*x2739))+(((-0.06125)*cj2*x2716))+(((-0.06125)*x2733))+(((-1.0)*x2735*x2738))+(((-1.0)*x2735*x2740))+((x2718*x2739))+((x2723*x2737))+((x2724*x2741))+((x2724*x2742))+((x2720*x2743))+(((-1.0)*x2728*x2738))+(((-0.38325)*x2716))+((x2722*x2727))+((x2725*x2742))+(((-2.0)*x2718*x2742))+((x2719*x2744))+((x2719*x2743))+(((-1.0)*x2722*x2728*x2735))+(((0.44485)*x2736))+((x2718*x2744)));
786if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
787{
788continue;
789}
790}
791
792rotationfunction0(solutions);
793}
794}
795
796}
797
798}
799
800} else
801{
802{
803IkReal j1array[1], cj1array[1], sj1array[1];
804bool j1valid[1]={false};
805_nj1 = 1;
806IkReal x2745=cj2*cj2;
807IkReal x2746=(cj2*sj2);
808IkReal x2747=((0.175)*pz);
809IkReal x2748=((1.271)*cj2);
810IkReal x2749=(py*sj0);
811IkReal x2750=(cj0*px);
812IkReal x2751=((0.175)*sj2);
813IkReal x2752=((1.0)*pz);
814CheckValue<IkReal> x2753 = IKatan2WithCheck(IkReal(((-0.222425)+x2747+(((-1.584816)*x2746))+(((0.191625)*sj2))+(((-1.0)*x2750*x2752))+(((-1.0)*x2749*x2752))+(((1.391745)*cj2))+(((0.44485)*x2745)))),IkReal(((0.030625)+(((-1.0)*pz*x2752))+(((1.584816)*x2745))+(((0.44485)*x2746)))),IKFAST_ATAN2_MAGTHRESH);
815if(!x2753.valid){
816continue;
817}
818CheckValue<IkReal> x2754=IKPowWithIntegerCheck(IKsign((((x2749*x2751))+(((-1.095)*pz))+(((1.271)*pz*sj2))+((x2750*x2751))+(((-1.0)*cj2*x2747))+((x2748*x2749))+((x2748*x2750))+(((-0.030625)*sj2))+(((-0.222425)*cj2)))),-1);
819if(!x2754.valid){
820continue;
821}
822j1array[0]=((-1.5707963267949)+(x2753.value)+(((1.5707963267949)*(x2754.value))));
823sj1array[0]=IKsin(j1array[0]);
824cj1array[0]=IKcos(j1array[0]);
825if( j1array[0] > IKPI )
826{
827 j1array[0]-=IK2PI;
828}
829else if( j1array[0] < -IKPI )
830{ j1array[0]+=IK2PI;
831}
832j1valid[0] = true;
833for(int ij1 = 0; ij1 < 1; ++ij1)
834{
835if( !j1valid[ij1] )
836{
837 continue;
838}
839_ij1[0] = ij1; _ij1[1] = -1;
840for(int iij1 = ij1+1; iij1 < 1; ++iij1)
841{
842if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
843{
844 j1valid[iij1]=false; _ij1[1] = iij1; break;
845}
846}
847j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
848{
849IkReal evalcond[5];
850IkReal x2755=IKcos(j1);
851IkReal x2756=IKsin(j1);
852IkReal x2757=py*py;
853IkReal x2758=r11*r11;
854IkReal x2759=r21*r21;
855IkReal x2760=r01*r01;
856IkReal x2761=px*px;
857IkReal x2762=pz*pz;
858IkReal x2763=r10*r10;
859IkReal x2764=r00*r00;
860IkReal x2765=r20*r20;
861IkReal x2766=r02*r02;
862IkReal x2767=r22*r22;
863IkReal x2768=r12*r12;
864IkReal x2769=((1.271)*cj2);
865IkReal x2770=(cj0*px);
866IkReal x2771=((0.175)*cj2);
867IkReal x2772=(py*sj0);
868IkReal x2773=(sj2*x2755);
869IkReal x2774=((1.0)*x2756);
870IkReal x2775=((1.0)*x2767);
871IkReal x2776=(sj2*x2756);
872IkReal x2777=(x2761*x2764);
873IkReal x2778=(x2761*x2766);
874IkReal x2779=(x2759*x2762);
875IkReal x2780=(x2757*x2768);
876IkReal x2781=(x2762*x2765);
877IkReal x2782=(x2757*x2763);
878IkReal x2783=(x2757*x2758);
879IkReal x2784=(x2760*x2761);
880evalcond[0]=((((-0.175)*x2755))+(((-0.175)*sj2))+(((-1.0)*pz*x2774))+((x2755*x2770))+((x2755*x2772))+(((-1.0)*x2769)));
881evalcond[1]=(((x2756*x2769))+(((0.175)*x2776))+(((-1.095)*x2755))+pz+(((1.271)*x2773))+(((-1.0)*x2755*x2771)));
882evalcond[2]=((1.095)+x2771+(((-1.0)*pz*x2755))+(((-1.0)*x2770*x2774))+(((-1.0)*x2772*x2774))+(((0.175)*x2756))+(((-1.271)*sj2)));
883evalcond[3]=((-0.175)+x2770+x2772+(((-1.0)*x2755*x2769))+(((-1.0)*x2756*x2771))+(((-1.095)*x2756))+(((1.271)*x2776))+(((-0.175)*x2773)));
884evalcond[4]=((-2.875716)+((x2758*x2779))+x2778+x2779+x2777+x2784+x2781+x2780+x2783+x2782+((x2763*x2777))+(((-1.0)*x2766*x2780))+(((-1.0)*x2762*x2768*x2775))+(((-0.06125)*cj2*x2756))+(((-1.0)*x2762*x2766*x2775))+((x2765*x2782))+(((-2.0)*x2760*x2777))+((x2764*x2782))+((x2764*x2781))+(((2.78349)*sj2))+(((-0.06125)*x2773))+((x2760*x2783))+(((-0.38325)*cj2))+(((-1.0)*x2768*x2778))+((x2762*x2767))+((x2759*x2783))+((x2759*x2784))+(((-0.38325)*x2756))+((x2763*x2781))+((x2758*x2784))+(((-2.0)*x2758*x2782))+(((-1.0)*x2775*x2778))+(((-0.44485)*cj2*x2755))+(((-2.0)*x2765*x2779))+(((0.44485)*x2776))+((x2765*x2777))+((x2760*x2779))+(((-1.0)*x2775*x2780)));
885if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
886{
887continue;
888}
889}
890
891rotationfunction0(solutions);
892}
893}
894
895}
896
897}
898}
899}
900}
901}
902
903}
904
905}
906}
907return solutions.GetNumSolutions()>0;
908}
909inline void rotationfunction0(IkSolutionListBase<IkReal>& solutions) {
910for(int rotationiter = 0; rotationiter < 1; ++rotationiter) {
911IkReal x154=((1.0)*cj1);
912IkReal x155=((1.0)*sj1);
913IkReal x156=((1.0)*sj0);
914IkReal x157=((1.0)*sj2);
915IkReal x158=(((r10*sj0))+((cj0*r00)));
916IkReal x159=(((r11*sj0))+((cj0*r01)));
917IkReal x160=(((r12*sj0))+((cj0*r02)));
918IkReal x161=((((-1.0)*r20*x155))+((cj1*x158)));
919IkReal x162=(((cj1*x159))+(((-1.0)*r21*x155)));
920IkReal x163=(((cj1*x160))+(((-1.0)*r22*x155)));
921IkReal x164=((((-1.0)*x155*x158))+(((-1.0)*r20*x154)));
922IkReal x165=((((-1.0)*x155*x159))+(((-1.0)*r21*x154)));
923IkReal x166=((((-1.0)*x155*x160))+(((-1.0)*r22*x154)));
924new_r00=((((-1.0)*x157*x161))+((cj2*x164)));
925new_r01=((((-1.0)*r00*x156))+((cj0*r10)));
926new_r02=(((cj2*x161))+((sj2*x164)));
927new_r10=((((-1.0)*x157*x162))+((cj2*x165)));
928new_r11=((((-1.0)*r01*x156))+((cj0*r11)));
929new_r12=(((cj2*x162))+((sj2*x165)));
930new_r20=((((-1.0)*x157*x163))+((cj2*x166)));
931new_r21=((((-1.0)*r02*x156))+((cj0*r12)));
932new_r22=(((cj2*x163))+((sj2*x166)));
933{
934IkReal j4array[2], cj4array[2], sj4array[2];
935bool j4valid[2]={false};
936_nj4 = 2;
937if( (new_r22) < -1-IKFAST_SINCOS_THRESH || (new_r22) > 1+IKFAST_SINCOS_THRESH )
938 continue;
939IkReal x167=IKasin(new_r22);
940j4array[0]=((1.57083632679488)+(((-1.0)*x167)));
941sj4array[0]=IKsin(j4array[0]);
942cj4array[0]=IKcos(j4array[0]);
943j4array[1]=((4.71242898038467)+x167);
944sj4array[1]=IKsin(j4array[1]);
945cj4array[1]=IKcos(j4array[1]);
946if( j4array[0] > IKPI )
947{
948 j4array[0]-=IK2PI;
949}
950else if( j4array[0] < -IKPI )
951{ j4array[0]+=IK2PI;
952}
953j4valid[0] = true;
954if( j4array[1] > IKPI )
955{
956 j4array[1]-=IK2PI;
957}
958else if( j4array[1] < -IKPI )
959{ j4array[1]+=IK2PI;
960}
961j4valid[1] = true;
962for(int ij4 = 0; ij4 < 2; ++ij4)
963{
964if( !j4valid[ij4] )
965{
966 continue;
967}
968_ij4[0] = ij4; _ij4[1] = -1;
969for(int iij4 = ij4+1; iij4 < 2; ++iij4)
970{
971if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
972{
973 j4valid[iij4]=false; _ij4[1] = iij4; break;
974}
975}
976j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
977
978{
979IkReal j5eval[3];
980j5eval[0]=((((25000.0)*sj4))+(((-1.0)*cj4)));
981j5eval[1]=((IKabs(new_r12))+(IKabs(new_r02)));
982j5eval[2]=IKsign(((((-3.9999999968e-5)*cj4))+(((0.9999999992)*sj4))));
983if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
984{
985{
986IkReal j3eval[3];
987j3eval[0]=((((-25000.0)*sj4))+cj4);
988j3eval[1]=IKsign(((((-0.9999999992)*sj4))+(((3.9999999968e-5)*cj4))));
989j3eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
990if( IKabs(j3eval[0]) < 0.0000010000000000 || IKabs(j3eval[1]) < 0.0000010000000000 || IKabs(j3eval[2]) < 0.0000010000000000 )
991{
992{
993IkReal j5eval[3];
994IkReal x168=((625000000.5)*sj4);
995IkReal x169=((25000.00002)*cj4);
996IkReal x170=((new_r12*new_r12)+(new_r02*new_r02));
997j5eval[0]=x170;
998j5eval[1]=((IKabs((((new_r12*x168))+(((-1.0)*new_r12*x169)))))+(IKabs(((((-1.0)*new_r02*x168))+((new_r02*x169))))));
999j5eval[2]=IKsign(x170);
1000if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1001{
1002{
1003IkReal evalcond[5];
1004bool bgotonextstatement = true;
1005do
1006{
1007evalcond[0]=((new_r12*new_r12)+(new_r02*new_r02));
1008if( IKabs(evalcond[0]) < 0.0000050000000000 )
1009{
1010bgotonextstatement=false;
1011{
1012IkReal j5eval[1];
1013new_r12=0;
1014new_r02=0;
1015j5eval[0]=IKabs(((((-25000.0)*sj4))+cj4));
1016if( IKabs(j5eval[0]) < 0.0000000100000000 )
1017{
1018{
1019IkReal j5eval[1];
1020new_r12=0;
1021new_r02=0;
1022j5eval[0]=IKabs(((((-0.9999999992)*sj4))+(((3.9999999968e-5)*cj4))));
1023if( IKabs(j5eval[0]) < 0.0000000100000000 )
1024{
1025continue; // no branches [j3, j5]
1026
1027} else
1028{
1029IkReal op[2+1], zeror[2];
1030int numroots;
1031IkReal x171=((0.9999999992)*sj4);
1032IkReal x172=((3.9999999968e-5)*cj4);
1033op[0]=((((-1.0)*x171))+x172);
1034op[1]=0;
1035op[2]=((((-1.0)*x172))+x171);
1036polyroots2(op,zeror,numroots);
1037IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
1038int numsolutions = 0;
1039for(int ij5 = 0; ij5 < numroots; ++ij5)
1040{
1041IkReal htj5 = zeror[ij5];
1042tempj5array[0]=((2.0)*(atan(htj5)));
1043for(int kj5 = 0; kj5 < 1; ++kj5)
1044{
1045j5array[numsolutions] = tempj5array[kj5];
1046if( j5array[numsolutions] > IKPI )
1047{
1048 j5array[numsolutions]-=IK2PI;
1049}
1050else if( j5array[numsolutions] < -IKPI )
1051{
1052 j5array[numsolutions]+=IK2PI;
1053}
1054sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1055cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1056numsolutions++;
1057}
1058}
1059bool j5valid[2]={true,true};
1060_nj5 = 2;
1061for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1062 {
1063if( !j5valid[ij5] )
1064{
1065 continue;
1066}
1067 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1068htj5 = IKtan(j5/2);
1069
1070_ij5[0] = ij5; _ij5[1] = -1;
1071for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1072{
1073if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1074{
1075 j5valid[iij5]=false; _ij5[1] = iij5; break;
1076}
1077}
1078{
1079IkReal j3array[1], cj3array[1], sj3array[1];
1080bool j3valid[1]={false};
1081_nj3 = 1;
1082if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1083 continue;
1084j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1085sj3array[0]=IKsin(j3array[0]);
1086cj3array[0]=IKcos(j3array[0]);
1087if( j3array[0] > IKPI )
1088{
1089 j3array[0]-=IK2PI;
1090}
1091else if( j3array[0] < -IKPI )
1092{ j3array[0]+=IK2PI;
1093}
1094j3valid[0] = true;
1095for(int ij3 = 0; ij3 < 1; ++ij3)
1096{
1097if( !j3valid[ij3] )
1098{
1099 continue;
1100}
1101_ij3[0] = ij3; _ij3[1] = -1;
1102for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1103{
1104if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1105{
1106 j3valid[iij3]=false; _ij3[1] = iij3; break;
1107}
1108}
1109j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1110{
1111IkReal evalcond[10];
1112IkReal x173=IKsin(j3);
1113IkReal x174=IKcos(j3);
1114IkReal x175=(cj5*new_r01);
1115IkReal x176=((25000.00002)*sj4);
1116IkReal x177=(cj5*new_r00);
1117IkReal x178=((1.0)*sj5);
1118IkReal x179=((1.0)*x174);
1119IkReal x180=(sj5*x173);
1120IkReal x181=(cj5*x174);
1121IkReal x182=(cj5*x173);
1122evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x173);
1123evalcond[1]=((((-1.0)*x179))+((cj5*new_r11))+((new_r01*sj5)));
1124evalcond[2]=(x182+((sj5*x174*x176))+new_r10);
1125evalcond[3]=((((-1.0)*x174*x176))+(((-1.0)*new_r10*x178))+x177);
1126evalcond[4]=((((-1.0)*new_r11*x178))+x175+(((-1.0)*x173*x176)));
1127evalcond[5]=(x180+(((-1.0)*x176*x181))+new_r00);
1128evalcond[6]=((((-1.0)*cj5*x179))+((x176*x180))+new_r11);
1129evalcond[7]=((((-1.0)*x174*x178))+(((-1.0)*x176*x182))+new_r01);
1130evalcond[8]=(((x176*x177))+(((-1.0)*x179))+(((-1.0)*new_r10*sj5*x176)));
1131evalcond[9]=((((-1.0)*new_r11*sj5*x176))+(((-1.0)*x173))+((x175*x176)));
1132if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
1133{
1134continue;
1135}
1136}
1137
1138{
1139std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1140vinfos[0].jointtype = 1;
1141vinfos[0].foffset = j0;
1142vinfos[0].indices[0] = _ij0[0];
1143vinfos[0].indices[1] = _ij0[1];
1144vinfos[0].maxsolutions = _nj0;
1145vinfos[1].jointtype = 1;
1146vinfos[1].foffset = j1;
1147vinfos[1].indices[0] = _ij1[0];
1148vinfos[1].indices[1] = _ij1[1];
1149vinfos[1].maxsolutions = _nj1;
1150vinfos[2].jointtype = 1;
1151vinfos[2].foffset = j2;
1152vinfos[2].indices[0] = _ij2[0];
1153vinfos[2].indices[1] = _ij2[1];
1154vinfos[2].maxsolutions = _nj2;
1155vinfos[3].jointtype = 1;
1156vinfos[3].foffset = j3;
1157vinfos[3].indices[0] = _ij3[0];
1158vinfos[3].indices[1] = _ij3[1];
1159vinfos[3].maxsolutions = _nj3;
1160vinfos[4].jointtype = 1;
1161vinfos[4].foffset = j4;
1162vinfos[4].indices[0] = _ij4[0];
1163vinfos[4].indices[1] = _ij4[1];
1164vinfos[4].maxsolutions = _nj4;
1165vinfos[5].jointtype = 1;
1166vinfos[5].foffset = j5;
1167vinfos[5].indices[0] = _ij5[0];
1168vinfos[5].indices[1] = _ij5[1];
1169vinfos[5].maxsolutions = _nj5;
1170std::vector<int> vfree(0);
1171solutions.AddSolution(vinfos,vfree);
1172}
1173}
1174}
1175 }
1176
1177}
1178
1179}
1180
1181} else
1182{
1183IkReal op[2+1], zeror[2];
1184int numroots;
1185IkReal x183=((25000.0)*sj4);
1186op[0]=(cj4+(((-1.0)*x183)));
1187op[1]=0;
1188op[2]=(x183+(((-1.0)*cj4)));
1189polyroots2(op,zeror,numroots);
1190IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
1191int numsolutions = 0;
1192for(int ij5 = 0; ij5 < numroots; ++ij5)
1193{
1194IkReal htj5 = zeror[ij5];
1195tempj5array[0]=((2.0)*(atan(htj5)));
1196for(int kj5 = 0; kj5 < 1; ++kj5)
1197{
1198j5array[numsolutions] = tempj5array[kj5];
1199if( j5array[numsolutions] > IKPI )
1200{
1201 j5array[numsolutions]-=IK2PI;
1202}
1203else if( j5array[numsolutions] < -IKPI )
1204{
1205 j5array[numsolutions]+=IK2PI;
1206}
1207sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1208cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1209numsolutions++;
1210}
1211}
1212bool j5valid[2]={true,true};
1213_nj5 = 2;
1214for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1215 {
1216if( !j5valid[ij5] )
1217{
1218 continue;
1219}
1220 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1221htj5 = IKtan(j5/2);
1222
1223_ij5[0] = ij5; _ij5[1] = -1;
1224for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1225{
1226if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1227{
1228 j5valid[iij5]=false; _ij5[1] = iij5; break;
1229}
1230}
1231{
1232IkReal j3array[1], cj3array[1], sj3array[1];
1233bool j3valid[1]={false};
1234_nj3 = 1;
1235if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1236 continue;
1237j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1238sj3array[0]=IKsin(j3array[0]);
1239cj3array[0]=IKcos(j3array[0]);
1240if( j3array[0] > IKPI )
1241{
1242 j3array[0]-=IK2PI;
1243}
1244else if( j3array[0] < -IKPI )
1245{ j3array[0]+=IK2PI;
1246}
1247j3valid[0] = true;
1248for(int ij3 = 0; ij3 < 1; ++ij3)
1249{
1250if( !j3valid[ij3] )
1251{
1252 continue;
1253}
1254_ij3[0] = ij3; _ij3[1] = -1;
1255for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1256{
1257if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1258{
1259 j3valid[iij3]=false; _ij3[1] = iij3; break;
1260}
1261}
1262j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1263{
1264IkReal evalcond[10];
1265IkReal x184=IKsin(j3);
1266IkReal x185=IKcos(j3);
1267IkReal x186=(cj5*new_r01);
1268IkReal x187=((25000.00002)*sj4);
1269IkReal x188=(cj5*new_r00);
1270IkReal x189=((1.0)*sj5);
1271IkReal x190=((1.0)*x185);
1272IkReal x191=(sj5*x184);
1273IkReal x192=(cj5*x185);
1274IkReal x193=(cj5*x184);
1275evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x184);
1276evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x190)));
1277evalcond[2]=(x193+new_r10+((sj5*x185*x187)));
1278evalcond[3]=(x188+(((-1.0)*new_r10*x189))+(((-1.0)*x185*x187)));
1279evalcond[4]=(x186+(((-1.0)*new_r11*x189))+(((-1.0)*x184*x187)));
1280evalcond[5]=(x191+(((-1.0)*x187*x192))+new_r00);
1281evalcond[6]=(((x187*x191))+(((-1.0)*cj5*x190))+new_r11);
1282evalcond[7]=((((-1.0)*x187*x193))+(((-1.0)*x185*x189))+new_r01);
1283evalcond[8]=((((-1.0)*new_r10*sj5*x187))+((x187*x188))+(((-1.0)*x190)));
1284evalcond[9]=(((x186*x187))+(((-1.0)*x184))+(((-1.0)*new_r11*sj5*x187)));
1285if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
1286{
1287continue;
1288}
1289}
1290
1291{
1292std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1293vinfos[0].jointtype = 1;
1294vinfos[0].foffset = j0;
1295vinfos[0].indices[0] = _ij0[0];
1296vinfos[0].indices[1] = _ij0[1];
1297vinfos[0].maxsolutions = _nj0;
1298vinfos[1].jointtype = 1;
1299vinfos[1].foffset = j1;
1300vinfos[1].indices[0] = _ij1[0];
1301vinfos[1].indices[1] = _ij1[1];
1302vinfos[1].maxsolutions = _nj1;
1303vinfos[2].jointtype = 1;
1304vinfos[2].foffset = j2;
1305vinfos[2].indices[0] = _ij2[0];
1306vinfos[2].indices[1] = _ij2[1];
1307vinfos[2].maxsolutions = _nj2;
1308vinfos[3].jointtype = 1;
1309vinfos[3].foffset = j3;
1310vinfos[3].indices[0] = _ij3[0];
1311vinfos[3].indices[1] = _ij3[1];
1312vinfos[3].maxsolutions = _nj3;
1313vinfos[4].jointtype = 1;
1314vinfos[4].foffset = j4;
1315vinfos[4].indices[0] = _ij4[0];
1316vinfos[4].indices[1] = _ij4[1];
1317vinfos[4].maxsolutions = _nj4;
1318vinfos[5].jointtype = 1;
1319vinfos[5].foffset = j5;
1320vinfos[5].indices[0] = _ij5[0];
1321vinfos[5].indices[1] = _ij5[1];
1322vinfos[5].maxsolutions = _nj5;
1323std::vector<int> vfree(0);
1324solutions.AddSolution(vinfos,vfree);
1325}
1326}
1327}
1328 }
1329
1330}
1331
1332}
1333
1334}
1335} while(0);
1336if( bgotonextstatement )
1337{
1338bool bgotonextstatement = true;
1339do
1340{
1341evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((3.14155265358981)+j4)))), 6.28318530717959)));
1342evalcond[1]=new_r02;
1343evalcond[2]=new_r12;
1344evalcond[3]=new_r20;
1345evalcond[4]=new_r21;
1346if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
1347{
1348bgotonextstatement=false;
1349{
1350IkReal j5eval[1];
1351sj4=-4.0e-5;
1352cj4=-1.0;
1353j4=-3.14155264453703;
1354j5eval[0]=((((5.12e-8)*(IKabs(new_r10))))+(IKabs(((((8.0000000064)*new_r11))+(((8.0)*new_r00)))))+(IKabs(((((16.0000000128)*new_r11))+(((16.0000000512)*new_r00)))))+(IKabs(((((-8.0000000064)*new_r10))+(((8.0)*new_r01)))))+(((2.0)*(IKabs(((((16.0000000128)*new_r00))+(((16.0)*new_r11))))))));
1355if( IKabs(j5eval[0]) < 0.0000000100000000 )
1356{
1357continue; // no branches [j3, j5]
1358
1359} else
1360{
1361IkReal op[4+1], zeror[4];
1362int numroots;
1363IkReal j5evalpoly[1];
1364IkReal x194=((((8.0000000064)*new_r11))+(((8.0)*new_r00)));
1365op[0]=x194;
1366op[1]=((-2.56e-8)*new_r10);
1367op[2]=((((16.0000000128)*new_r11))+(((16.0000000512)*new_r00)));
1368op[3]=((2.56e-8)*new_r10);
1369op[4]=x194;
1370polyroots4(op,zeror,numroots);
1371IkReal j5array[4], cj5array[4], sj5array[4], tempj5array[1];
1372int numsolutions = 0;
1373for(int ij5 = 0; ij5 < numroots; ++ij5)
1374{
1375IkReal htj5 = zeror[ij5];
1376tempj5array[0]=((2.0)*(atan(htj5)));
1377for(int kj5 = 0; kj5 < 1; ++kj5)
1378{
1379j5array[numsolutions] = tempj5array[kj5];
1380if( j5array[numsolutions] > IKPI )
1381{
1382 j5array[numsolutions]-=IK2PI;
1383}
1384else if( j5array[numsolutions] < -IKPI )
1385{
1386 j5array[numsolutions]+=IK2PI;
1387}
1388sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1389cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1390numsolutions++;
1391}
1392}
1393bool j5valid[4]={true,true,true,true};
1394_nj5 = 4;
1395for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1396 {
1397if( !j5valid[ij5] )
1398{
1399 continue;
1400}
1401 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1402htj5 = IKtan(j5/2);
1403
1404IkReal x195=((8.0000000064)*new_r10);
1405IkReal x196=((8.0)*new_r01);
1406IkReal x197=((((16.0000000128)*new_r00))+(((16.0)*new_r11)));
1407j5evalpoly[0]=((((htj5*htj5*htj5*htj5)*(((((-1.0)*x195))+x196))))+(((-1.0)*x196))+x195+((htj5*x197))+((x197*(htj5*htj5*htj5))));
1408if( IKabs(j5evalpoly[0]) > 0.0000001000000000 )
1409{
1410 continue;
1411}
1412_ij5[0] = ij5; _ij5[1] = -1;
1413for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1414{
1415if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1416{
1417 j5valid[iij5]=false; _ij5[1] = iij5; break;
1418}
1419}
1420{
1421IkReal j3array[1], cj3array[1], sj3array[1];
1422bool j3valid[1]={false};
1423_nj3 = 1;
1424if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1425 continue;
1426j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1427sj3array[0]=IKsin(j3array[0]);
1428cj3array[0]=IKcos(j3array[0]);
1429if( j3array[0] > IKPI )
1430{
1431 j3array[0]-=IK2PI;
1432}
1433else if( j3array[0] < -IKPI )
1434{ j3array[0]+=IK2PI;
1435}
1436j3valid[0] = true;
1437for(int ij3 = 0; ij3 < 1; ++ij3)
1438{
1439if( !j3valid[ij3] )
1440{
1441 continue;
1442}
1443_ij3[0] = ij3; _ij3[1] = -1;
1444for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1445{
1446if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1447{
1448 j3valid[iij3]=false; _ij3[1] = iij3; break;
1449}
1450}
1451j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1452{
1453IkReal evalcond[10];
1454IkReal x198=IKcos(j3);
1455IkReal x199=IKsin(j3);
1456IkReal x200=((1.0000000008)*sj5);
1457IkReal x201=(cj5*new_r01);
1458IkReal x202=((1.0)*sj5);
1459IkReal x203=(cj5*new_r00);
1460IkReal x204=((1.0)*x198);
1461IkReal x205=((1.0000000008)*x199);
1462IkReal x206=((1.0000000008)*x198);
1463evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x199);
1464evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x204)));
1465evalcond[2]=(x206+x203+(((-1.0)*new_r10*x202)));
1466evalcond[3]=(x205+x201+(((-1.0)*new_r11*x202)));
1467evalcond[4]=(((cj5*x206))+new_r00+((sj5*x199)));
1468evalcond[5]=(((cj5*x199))+(((-1.0)*x198*x200))+new_r10);
1469evalcond[6]=(((cj5*x205))+(((-1.0)*x198*x202))+new_r01);
1470evalcond[7]=((((-1.0)*cj5*x204))+(((-1.0)*x199*x200))+new_r11);
1471evalcond[8]=(((new_r10*x200))+(((-1.0000000008)*x203))+(((-1.0)*x204)));
1472evalcond[9]=(((new_r11*x200))+(((-1.0)*x199))+(((-1.0000000008)*x201)));
1473if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
1474{
1475continue;
1476}
1477}
1478
1479{
1480std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1481vinfos[0].jointtype = 1;
1482vinfos[0].foffset = j0;
1483vinfos[0].indices[0] = _ij0[0];
1484vinfos[0].indices[1] = _ij0[1];
1485vinfos[0].maxsolutions = _nj0;
1486vinfos[1].jointtype = 1;
1487vinfos[1].foffset = j1;
1488vinfos[1].indices[0] = _ij1[0];
1489vinfos[1].indices[1] = _ij1[1];
1490vinfos[1].maxsolutions = _nj1;
1491vinfos[2].jointtype = 1;
1492vinfos[2].foffset = j2;
1493vinfos[2].indices[0] = _ij2[0];
1494vinfos[2].indices[1] = _ij2[1];
1495vinfos[2].maxsolutions = _nj2;
1496vinfos[3].jointtype = 1;
1497vinfos[3].foffset = j3;
1498vinfos[3].indices[0] = _ij3[0];
1499vinfos[3].indices[1] = _ij3[1];
1500vinfos[3].maxsolutions = _nj3;
1501vinfos[4].jointtype = 1;
1502vinfos[4].foffset = j4;
1503vinfos[4].indices[0] = _ij4[0];
1504vinfos[4].indices[1] = _ij4[1];
1505vinfos[4].maxsolutions = _nj4;
1506vinfos[5].jointtype = 1;
1507vinfos[5].foffset = j5;
1508vinfos[5].indices[0] = _ij5[0];
1509vinfos[5].indices[1] = _ij5[1];
1510vinfos[5].maxsolutions = _nj5;
1511std::vector<int> vfree(0);
1512solutions.AddSolution(vinfos,vfree);
1513}
1514}
1515}
1516 }
1517
1518}
1519
1520}
1521
1522}
1523} while(0);
1524if( bgotonextstatement )
1525{
1526bool bgotonextstatement = true;
1527do
1528{
1529evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.99999999786682e-5)+j4)))), 6.28318530717959)));
1530evalcond[1]=new_r02;
1531evalcond[2]=new_r12;
1532evalcond[3]=new_r20;
1533evalcond[4]=new_r21;
1534if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
1535{
1536bgotonextstatement=false;
1537{
1538IkReal j5eval[1];
1539sj4=4.0e-5;
1540cj4=1.0;
1541j4=4.0e-5;
1542j5eval[0]=((((5.12e-8)*(IKabs(new_r10))))+(IKabs(((((8.0000000064)*new_r10))+(((8.0)*new_r01)))))+(((2.0)*(IKabs(((((-16.0000000128)*new_r00))+(((16.0)*new_r11)))))))+(IKabs(((((-8.0000000064)*new_r11))+(((8.0)*new_r00)))))+(IKabs(((((16.0000000512)*new_r00))+(((-16.0000000128)*new_r11))))));
1543if( IKabs(j5eval[0]) < 0.0000000100000000 )
1544{
1545continue; // no branches [j3, j5]
1546
1547} else
1548{
1549IkReal op[4+1], zeror[4];
1550int numroots;
1551IkReal j5evalpoly[1];
1552IkReal x207=((((-8.0000000064)*new_r11))+(((8.0)*new_r00)));
1553op[0]=x207;
1554op[1]=((-2.56e-8)*new_r10);
1555op[2]=((((16.0000000512)*new_r00))+(((-16.0000000128)*new_r11)));
1556op[3]=((2.56e-8)*new_r10);
1557op[4]=x207;
1558polyroots4(op,zeror,numroots);
1559IkReal j5array[4], cj5array[4], sj5array[4], tempj5array[1];
1560int numsolutions = 0;
1561for(int ij5 = 0; ij5 < numroots; ++ij5)
1562{
1563IkReal htj5 = zeror[ij5];
1564tempj5array[0]=((2.0)*(atan(htj5)));
1565for(int kj5 = 0; kj5 < 1; ++kj5)
1566{
1567j5array[numsolutions] = tempj5array[kj5];
1568if( j5array[numsolutions] > IKPI )
1569{
1570 j5array[numsolutions]-=IK2PI;
1571}
1572else if( j5array[numsolutions] < -IKPI )
1573{
1574 j5array[numsolutions]+=IK2PI;
1575}
1576sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1577cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1578numsolutions++;
1579}
1580}
1581bool j5valid[4]={true,true,true,true};
1582_nj5 = 4;
1583for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1584 {
1585if( !j5valid[ij5] )
1586{
1587 continue;
1588}
1589 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1590htj5 = IKtan(j5/2);
1591
1592IkReal x208=((((-16.0000000128)*new_r00))+(((16.0)*new_r11)));
1593IkReal x209=((((8.0000000064)*new_r10))+(((8.0)*new_r01)));
1594j5evalpoly[0]=(((x208*(htj5*htj5*htj5)))+((htj5*x208))+(((-1.0)*x209))+((x209*(htj5*htj5*htj5*htj5))));
1595if( IKabs(j5evalpoly[0]) > 0.0000001000000000 )
1596{
1597 continue;
1598}
1599_ij5[0] = ij5; _ij5[1] = -1;
1600for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1601{
1602if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1603{
1604 j5valid[iij5]=false; _ij5[1] = iij5; break;
1605}
1606}
1607{
1608IkReal j3array[1], cj3array[1], sj3array[1];
1609bool j3valid[1]={false};
1610_nj3 = 1;
1611if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1612 continue;
1613j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1614sj3array[0]=IKsin(j3array[0]);
1615cj3array[0]=IKcos(j3array[0]);
1616if( j3array[0] > IKPI )
1617{
1618 j3array[0]-=IK2PI;
1619}
1620else if( j3array[0] < -IKPI )
1621{ j3array[0]+=IK2PI;
1622}
1623j3valid[0] = true;
1624for(int ij3 = 0; ij3 < 1; ++ij3)
1625{
1626if( !j3valid[ij3] )
1627{
1628 continue;
1629}
1630_ij3[0] = ij3; _ij3[1] = -1;
1631for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1632{
1633if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1634{
1635 j3valid[iij3]=false; _ij3[1] = iij3; break;
1636}
1637}
1638j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1639{
1640IkReal evalcond[10];
1641IkReal x210=IKcos(j3);
1642IkReal x211=IKsin(j3);
1643IkReal x212=((1.0000000008)*sj5);
1644IkReal x213=(cj5*new_r01);
1645IkReal x214=((1.0)*sj5);
1646IkReal x215=(cj5*new_r00);
1647IkReal x216=((1.0)*x210);
1648IkReal x217=((1.0000000008)*x211);
1649IkReal x218=((1.0000000008)*x210);
1650evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x211);
1651evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x216)));
1652evalcond[2]=((((-1.0)*new_r10*x214))+x215+(((-1.0)*x218)));
1653evalcond[3]=((((-1.0)*new_r11*x214))+x213+(((-1.0)*x217)));
1654evalcond[4]=(((sj5*x211))+(((-1.0)*cj5*x218))+new_r00);
1655evalcond[5]=(((x210*x212))+((cj5*x211))+new_r10);
1656evalcond[6]=((((-1.0)*x210*x214))+(((-1.0)*cj5*x217))+new_r01);
1657evalcond[7]=(((x211*x212))+(((-1.0)*cj5*x216))+new_r11);
1658evalcond[8]=((((1.0000000008)*x215))+(((-1.0)*new_r10*x212))+(((-1.0)*x216)));
1659evalcond[9]=((((1.0000000008)*x213))+(((-1.0)*new_r11*x212))+(((-1.0)*x211)));
1660if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
1661{
1662continue;
1663}
1664}
1665
1666{
1667std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1668vinfos[0].jointtype = 1;
1669vinfos[0].foffset = j0;
1670vinfos[0].indices[0] = _ij0[0];
1671vinfos[0].indices[1] = _ij0[1];
1672vinfos[0].maxsolutions = _nj0;
1673vinfos[1].jointtype = 1;
1674vinfos[1].foffset = j1;
1675vinfos[1].indices[0] = _ij1[0];
1676vinfos[1].indices[1] = _ij1[1];
1677vinfos[1].maxsolutions = _nj1;
1678vinfos[2].jointtype = 1;
1679vinfos[2].foffset = j2;
1680vinfos[2].indices[0] = _ij2[0];
1681vinfos[2].indices[1] = _ij2[1];
1682vinfos[2].maxsolutions = _nj2;
1683vinfos[3].jointtype = 1;
1684vinfos[3].foffset = j3;
1685vinfos[3].indices[0] = _ij3[0];
1686vinfos[3].indices[1] = _ij3[1];
1687vinfos[3].maxsolutions = _nj3;
1688vinfos[4].jointtype = 1;
1689vinfos[4].foffset = j4;
1690vinfos[4].indices[0] = _ij4[0];
1691vinfos[4].indices[1] = _ij4[1];
1692vinfos[4].maxsolutions = _nj4;
1693vinfos[5].jointtype = 1;
1694vinfos[5].foffset = j5;
1695vinfos[5].indices[0] = _ij5[0];
1696vinfos[5].indices[1] = _ij5[1];
1697vinfos[5].maxsolutions = _nj5;
1698std::vector<int> vfree(0);
1699solutions.AddSolution(vinfos,vfree);
1700}
1701}
1702}
1703 }
1704
1705}
1706
1707}
1708
1709}
1710} while(0);
1711if( bgotonextstatement )
1712{
1713bool bgotonextstatement = true;
1714do
1715{
1716evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.99999999786667e-5)+j4)))), 6.28318530717959)));
1717evalcond[1]=new_r02;
1718evalcond[2]=new_r12;
1719evalcond[3]=new_r20;
1720evalcond[4]=new_r21;
1721if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
1722{
1723bgotonextstatement=false;
1724{
1725IkReal j5eval[1];
1726sj4=4.0e-5;
1727cj4=1.0;
1728j4=4.0e-5;
1729j5eval[0]=((((5.12e-8)*(IKabs(new_r10))))+(IKabs(((((8.0000000064)*new_r10))+(((8.0)*new_r01)))))+(((2.0)*(IKabs(((((-16.0000000128)*new_r00))+(((16.0)*new_r11)))))))+(IKabs(((((-8.0000000064)*new_r11))+(((8.0)*new_r00)))))+(IKabs(((((16.0000000512)*new_r00))+(((-16.0000000128)*new_r11))))));
1730if( IKabs(j5eval[0]) < 0.0000000100000000 )
1731{
1732continue; // no branches [j3, j5]
1733
1734} else
1735{
1736IkReal op[4+1], zeror[4];
1737int numroots;
1738IkReal j5evalpoly[1];
1739IkReal x219=((((-8.0000000064)*new_r11))+(((8.0)*new_r00)));
1740op[0]=x219;
1741op[1]=((-2.56e-8)*new_r10);
1742op[2]=((((16.0000000512)*new_r00))+(((-16.0000000128)*new_r11)));
1743op[3]=((2.56e-8)*new_r10);
1744op[4]=x219;
1745polyroots4(op,zeror,numroots);
1746IkReal j5array[4], cj5array[4], sj5array[4], tempj5array[1];
1747int numsolutions = 0;
1748for(int ij5 = 0; ij5 < numroots; ++ij5)
1749{
1750IkReal htj5 = zeror[ij5];
1751tempj5array[0]=((2.0)*(atan(htj5)));
1752for(int kj5 = 0; kj5 < 1; ++kj5)
1753{
1754j5array[numsolutions] = tempj5array[kj5];
1755if( j5array[numsolutions] > IKPI )
1756{
1757 j5array[numsolutions]-=IK2PI;
1758}
1759else if( j5array[numsolutions] < -IKPI )
1760{
1761 j5array[numsolutions]+=IK2PI;
1762}
1763sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1764cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1765numsolutions++;
1766}
1767}
1768bool j5valid[4]={true,true,true,true};
1769_nj5 = 4;
1770for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1771 {
1772if( !j5valid[ij5] )
1773{
1774 continue;
1775}
1776 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1777htj5 = IKtan(j5/2);
1778
1779IkReal x220=((((-16.0000000128)*new_r00))+(((16.0)*new_r11)));
1780IkReal x221=((((8.0000000064)*new_r10))+(((8.0)*new_r01)));
1781j5evalpoly[0]=(((x220*(htj5*htj5*htj5)))+((x221*(htj5*htj5*htj5*htj5)))+(((-1.0)*x221))+((htj5*x220)));
1782if( IKabs(j5evalpoly[0]) > 0.0000001000000000 )
1783{
1784 continue;
1785}
1786_ij5[0] = ij5; _ij5[1] = -1;
1787for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1788{
1789if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1790{
1791 j5valid[iij5]=false; _ij5[1] = iij5; break;
1792}
1793}
1794{
1795IkReal j3array[1], cj3array[1], sj3array[1];
1796bool j3valid[1]={false};
1797_nj3 = 1;
1798if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1799 continue;
1800j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1801sj3array[0]=IKsin(j3array[0]);
1802cj3array[0]=IKcos(j3array[0]);
1803if( j3array[0] > IKPI )
1804{
1805 j3array[0]-=IK2PI;
1806}
1807else if( j3array[0] < -IKPI )
1808{ j3array[0]+=IK2PI;
1809}
1810j3valid[0] = true;
1811for(int ij3 = 0; ij3 < 1; ++ij3)
1812{
1813if( !j3valid[ij3] )
1814{
1815 continue;
1816}
1817_ij3[0] = ij3; _ij3[1] = -1;
1818for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1819{
1820if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1821{
1822 j3valid[iij3]=false; _ij3[1] = iij3; break;
1823}
1824}
1825j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1826{
1827IkReal evalcond[10];
1828IkReal x222=IKcos(j3);
1829IkReal x223=IKsin(j3);
1830IkReal x224=((1.0000000008)*sj5);
1831IkReal x225=(cj5*new_r01);
1832IkReal x226=((1.0)*sj5);
1833IkReal x227=(cj5*new_r00);
1834IkReal x228=((1.0)*x222);
1835IkReal x229=((1.0000000008)*x223);
1836IkReal x230=((1.0000000008)*x222);
1837evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x223);
1838evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x228)));
1839evalcond[2]=((((-1.0)*new_r10*x226))+(((-1.0)*x230))+x227);
1840evalcond[3]=((((-1.0)*new_r11*x226))+x225+(((-1.0)*x229)));
1841evalcond[4]=((((-1.0)*cj5*x230))+((sj5*x223))+new_r00);
1842evalcond[5]=(((x222*x224))+((cj5*x223))+new_r10);
1843evalcond[6]=((((-1.0)*cj5*x229))+(((-1.0)*x222*x226))+new_r01);
1844evalcond[7]=((((-1.0)*cj5*x228))+((x223*x224))+new_r11);
1845evalcond[8]=((((-1.0)*new_r10*x224))+(((1.0000000008)*x227))+(((-1.0)*x228)));
1846evalcond[9]=((((-1.0)*new_r11*x224))+(((1.0000000008)*x225))+(((-1.0)*x223)));
1847if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
1848{
1849continue;
1850}
1851}
1852
1853{
1854std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
1855vinfos[0].jointtype = 1;
1856vinfos[0].foffset = j0;
1857vinfos[0].indices[0] = _ij0[0];
1858vinfos[0].indices[1] = _ij0[1];
1859vinfos[0].maxsolutions = _nj0;
1860vinfos[1].jointtype = 1;
1861vinfos[1].foffset = j1;
1862vinfos[1].indices[0] = _ij1[0];
1863vinfos[1].indices[1] = _ij1[1];
1864vinfos[1].maxsolutions = _nj1;
1865vinfos[2].jointtype = 1;
1866vinfos[2].foffset = j2;
1867vinfos[2].indices[0] = _ij2[0];
1868vinfos[2].indices[1] = _ij2[1];
1869vinfos[2].maxsolutions = _nj2;
1870vinfos[3].jointtype = 1;
1871vinfos[3].foffset = j3;
1872vinfos[3].indices[0] = _ij3[0];
1873vinfos[3].indices[1] = _ij3[1];
1874vinfos[3].maxsolutions = _nj3;
1875vinfos[4].jointtype = 1;
1876vinfos[4].foffset = j4;
1877vinfos[4].indices[0] = _ij4[0];
1878vinfos[4].indices[1] = _ij4[1];
1879vinfos[4].maxsolutions = _nj4;
1880vinfos[5].jointtype = 1;
1881vinfos[5].foffset = j5;
1882vinfos[5].indices[0] = _ij5[0];
1883vinfos[5].indices[1] = _ij5[1];
1884vinfos[5].maxsolutions = _nj5;
1885std::vector<int> vfree(0);
1886solutions.AddSolution(vinfos,vfree);
1887}
1888}
1889}
1890 }
1891
1892}
1893
1894}
1895
1896}
1897} while(0);
1898if( bgotonextstatement )
1899{
1900bool bgotonextstatement = true;
1901do
1902{
1903evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14163265358977)+j4)))), 6.28318530717959)));
1904evalcond[1]=new_r02;
1905evalcond[2]=new_r12;
1906evalcond[3]=new_r20;
1907evalcond[4]=new_r21;
1908if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
1909{
1910bgotonextstatement=false;
1911{
1912IkReal j5eval[1];
1913sj4=-4.0e-5;
1914cj4=-1.0;
1915j4=3.14163265;
1916j5eval[0]=((((5.12e-8)*(IKabs(new_r10))))+(IKabs(((((8.0000000064)*new_r11))+(((8.0)*new_r00)))))+(IKabs(((((16.0000000128)*new_r11))+(((16.0000000512)*new_r00)))))+(IKabs(((((-8.0000000064)*new_r10))+(((8.0)*new_r01)))))+(((2.0)*(IKabs(((((16.0000000128)*new_r00))+(((16.0)*new_r11))))))));
1917if( IKabs(j5eval[0]) < 0.0000000100000000 )
1918{
1919continue; // no branches [j3, j5]
1920
1921} else
1922{
1923IkReal op[4+1], zeror[4];
1924int numroots;
1925IkReal j5evalpoly[1];
1926IkReal x231=((((8.0000000064)*new_r11))+(((8.0)*new_r00)));
1927op[0]=x231;
1928op[1]=((-2.56e-8)*new_r10);
1929op[2]=((((16.0000000128)*new_r11))+(((16.0000000512)*new_r00)));
1930op[3]=((2.56e-8)*new_r10);
1931op[4]=x231;
1932polyroots4(op,zeror,numroots);
1933IkReal j5array[4], cj5array[4], sj5array[4], tempj5array[1];
1934int numsolutions = 0;
1935for(int ij5 = 0; ij5 < numroots; ++ij5)
1936{
1937IkReal htj5 = zeror[ij5];
1938tempj5array[0]=((2.0)*(atan(htj5)));
1939for(int kj5 = 0; kj5 < 1; ++kj5)
1940{
1941j5array[numsolutions] = tempj5array[kj5];
1942if( j5array[numsolutions] > IKPI )
1943{
1944 j5array[numsolutions]-=IK2PI;
1945}
1946else if( j5array[numsolutions] < -IKPI )
1947{
1948 j5array[numsolutions]+=IK2PI;
1949}
1950sj5array[numsolutions] = IKsin(j5array[numsolutions]);
1951cj5array[numsolutions] = IKcos(j5array[numsolutions]);
1952numsolutions++;
1953}
1954}
1955bool j5valid[4]={true,true,true,true};
1956_nj5 = 4;
1957for(int ij5 = 0; ij5 < numsolutions; ++ij5)
1958 {
1959if( !j5valid[ij5] )
1960{
1961 continue;
1962}
1963 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1964htj5 = IKtan(j5/2);
1965
1966IkReal x232=((8.0000000064)*new_r10);
1967IkReal x233=((8.0)*new_r01);
1968IkReal x234=((((16.0000000128)*new_r00))+(((16.0)*new_r11)));
1969j5evalpoly[0]=((((htj5*htj5*htj5*htj5)*(((((-1.0)*x232))+x233))))+((htj5*x234))+(((-1.0)*x233))+x232+((x234*(htj5*htj5*htj5))));
1970if( IKabs(j5evalpoly[0]) > 0.0000001000000000 )
1971{
1972 continue;
1973}
1974_ij5[0] = ij5; _ij5[1] = -1;
1975for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
1976{
1977if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1978{
1979 j5valid[iij5]=false; _ij5[1] = iij5; break;
1980}
1981}
1982{
1983IkReal j3array[1], cj3array[1], sj3array[1];
1984bool j3valid[1]={false};
1985_nj3 = 1;
1986if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1987 continue;
1988j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
1989sj3array[0]=IKsin(j3array[0]);
1990cj3array[0]=IKcos(j3array[0]);
1991if( j3array[0] > IKPI )
1992{
1993 j3array[0]-=IK2PI;
1994}
1995else if( j3array[0] < -IKPI )
1996{ j3array[0]+=IK2PI;
1997}
1998j3valid[0] = true;
1999for(int ij3 = 0; ij3 < 1; ++ij3)
2000{
2001if( !j3valid[ij3] )
2002{
2003 continue;
2004}
2005_ij3[0] = ij3; _ij3[1] = -1;
2006for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2007{
2008if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2009{
2010 j3valid[iij3]=false; _ij3[1] = iij3; break;
2011}
2012}
2013j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2014{
2015IkReal evalcond[10];
2016IkReal x235=IKcos(j3);
2017IkReal x236=IKsin(j3);
2018IkReal x237=((1.0000000008)*sj5);
2019IkReal x238=(cj5*new_r01);
2020IkReal x239=((1.0)*sj5);
2021IkReal x240=(cj5*new_r00);
2022IkReal x241=((1.0)*x235);
2023IkReal x242=((1.0000000008)*x236);
2024IkReal x243=((1.0000000008)*x235);
2025evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x236);
2026evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x241)));
2027evalcond[2]=(x243+x240+(((-1.0)*new_r10*x239)));
2028evalcond[3]=(x238+x242+(((-1.0)*new_r11*x239)));
2029evalcond[4]=(((cj5*x243))+new_r00+((sj5*x236)));
2030evalcond[5]=((((-1.0)*x235*x237))+((cj5*x236))+new_r10);
2031evalcond[6]=((((-1.0)*x235*x239))+((cj5*x242))+new_r01);
2032evalcond[7]=((((-1.0)*cj5*x241))+(((-1.0)*x236*x237))+new_r11);
2033evalcond[8]=(((new_r10*x237))+(((-1.0000000008)*x240))+(((-1.0)*x241)));
2034evalcond[9]=(((new_r11*x237))+(((-1.0000000008)*x238))+(((-1.0)*x236)));
2035if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
2036{
2037continue;
2038}
2039}
2040
2041{
2042std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2043vinfos[0].jointtype = 1;
2044vinfos[0].foffset = j0;
2045vinfos[0].indices[0] = _ij0[0];
2046vinfos[0].indices[1] = _ij0[1];
2047vinfos[0].maxsolutions = _nj0;
2048vinfos[1].jointtype = 1;
2049vinfos[1].foffset = j1;
2050vinfos[1].indices[0] = _ij1[0];
2051vinfos[1].indices[1] = _ij1[1];
2052vinfos[1].maxsolutions = _nj1;
2053vinfos[2].jointtype = 1;
2054vinfos[2].foffset = j2;
2055vinfos[2].indices[0] = _ij2[0];
2056vinfos[2].indices[1] = _ij2[1];
2057vinfos[2].maxsolutions = _nj2;
2058vinfos[3].jointtype = 1;
2059vinfos[3].foffset = j3;
2060vinfos[3].indices[0] = _ij3[0];
2061vinfos[3].indices[1] = _ij3[1];
2062vinfos[3].maxsolutions = _nj3;
2063vinfos[4].jointtype = 1;
2064vinfos[4].foffset = j4;
2065vinfos[4].indices[0] = _ij4[0];
2066vinfos[4].indices[1] = _ij4[1];
2067vinfos[4].maxsolutions = _nj4;
2068vinfos[5].jointtype = 1;
2069vinfos[5].foffset = j5;
2070vinfos[5].indices[0] = _ij5[0];
2071vinfos[5].indices[1] = _ij5[1];
2072vinfos[5].maxsolutions = _nj5;
2073std::vector<int> vfree(0);
2074solutions.AddSolution(vinfos,vfree);
2075}
2076}
2077}
2078 }
2079
2080}
2081
2082}
2083
2084}
2085} while(0);
2086if( bgotonextstatement )
2087{
2088bool bgotonextstatement = true;
2089do
2090{
2091evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02)));
2092if( IKabs(evalcond[0]) < 0.0000050000000000 )
2093{
2094bgotonextstatement=false;
2095{
2096IkReal j3eval[1];
2097new_r02=0;
2098new_r12=0;
2099new_r20=0;
2100new_r21=0;
2101j3eval[0]=IKabs(((((-3.9999999968e-5)*cj4))+(((0.9999999992)*sj4))));
2102if( IKabs(j3eval[0]) < 0.0000000100000000 )
2103{
2104{
2105IkReal j5eval[1];
2106new_r02=0;
2107new_r12=0;
2108new_r20=0;
2109new_r21=0;
2110IkReal x244=((625000000.5)*sj4);
2111IkReal x245=((25000.00002)*cj4);
2112j5eval[0]=((IKabs(((((-1.0)*new_r00*x244))+((new_r00*x245)))))+(IKabs(((((-1.0)*new_r10*x245))+((new_r10*x244))))));
2113if( IKabs(j5eval[0]) < 0.0000010000000000 )
2114{
2115{
2116IkReal j5eval[1];
2117new_r02=0;
2118new_r12=0;
2119new_r20=0;
2120new_r21=0;
2121IkReal x246=((625000000.5)*sj4);
2122IkReal x247=((25000.00002)*cj4);
2123j5eval[0]=((IKabs(((((-1.0)*new_r01*x246))+((new_r01*x247)))))+(IKabs(((((-1.0)*new_r11*x247))+((new_r11*x246))))));
2124if( IKabs(j5eval[0]) < 0.0000010000000000 )
2125{
2126continue; // no branches [j3, j5]
2127
2128} else
2129{
2130{
2131IkReal j5array[2], cj5array[2], sj5array[2];
2132bool j5valid[2]={false};
2133_nj5 = 2;
2134IkReal x248=((3.9999999968e-5)*cj4);
2135IkReal x249=((0.9999999992)*sj4);
2136CheckValue<IkReal> x251 = IKatan2WithCheck(IkReal(((((-1.0)*new_r01*x249))+((new_r01*x248)))),IkReal(((((-1.0)*new_r11*x248))+((new_r11*x249)))),IKFAST_ATAN2_MAGTHRESH);
2137if(!x251.valid){
2138continue;
2139}
2140IkReal x250=x251.value;
2141j5array[0]=((-1.0)*x250);
2142sj5array[0]=IKsin(j5array[0]);
2143cj5array[0]=IKcos(j5array[0]);
2144j5array[1]=((3.14159265358979)+(((-1.0)*x250)));
2145sj5array[1]=IKsin(j5array[1]);
2146cj5array[1]=IKcos(j5array[1]);
2147if( j5array[0] > IKPI )
2148{
2149 j5array[0]-=IK2PI;
2150}
2151else if( j5array[0] < -IKPI )
2152{ j5array[0]+=IK2PI;
2153}
2154j5valid[0] = true;
2155if( j5array[1] > IKPI )
2156{
2157 j5array[1]-=IK2PI;
2158}
2159else if( j5array[1] < -IKPI )
2160{ j5array[1]+=IK2PI;
2161}
2162j5valid[1] = true;
2163for(int ij5 = 0; ij5 < 2; ++ij5)
2164{
2165if( !j5valid[ij5] )
2166{
2167 continue;
2168}
2169_ij5[0] = ij5; _ij5[1] = -1;
2170for(int iij5 = ij5+1; iij5 < 2; ++iij5)
2171{
2172if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2173{
2174 j5valid[iij5]=false; _ij5[1] = iij5; break;
2175}
2176}
2177j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2178{
2179IkReal evalcond[3];
2180IkReal x252=IKcos(j5);
2181IkReal x253=IKsin(j5);
2182IkReal x254=((0.9999999992)*sj4);
2183IkReal x255=((3.9999999968e-5)*cj4);
2184IkReal x256=(new_r00*x252);
2185IkReal x257=(x253*x255);
2186evalcond[0]=((((-1.0)*x252*x255))+((x252*x254)));
2187evalcond[1]=(x257+(((-1.0)*x253*x254)));
2188evalcond[2]=((((-1.0)*new_r10*x257))+(((-1.0)*x254*x256))+((new_r10*x253*x254))+((x255*x256)));
2189if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
2190{
2191continue;
2192}
2193}
2194
2195{
2196IkReal j3array[1], cj3array[1], sj3array[1];
2197bool j3valid[1]={false};
2198_nj3 = 1;
2199if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
2200 continue;
2201j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
2202sj3array[0]=IKsin(j3array[0]);
2203cj3array[0]=IKcos(j3array[0]);
2204if( j3array[0] > IKPI )
2205{
2206 j3array[0]-=IK2PI;
2207}
2208else if( j3array[0] < -IKPI )
2209{ j3array[0]+=IK2PI;
2210}
2211j3valid[0] = true;
2212for(int ij3 = 0; ij3 < 1; ++ij3)
2213{
2214if( !j3valid[ij3] )
2215{
2216 continue;
2217}
2218_ij3[0] = ij3; _ij3[1] = -1;
2219for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2220{
2221if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2222{
2223 j3valid[iij3]=false; _ij3[1] = iij3; break;
2224}
2225}
2226j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2227{
2228IkReal evalcond[12];
2229IkReal x258=IKsin(j3);
2230IkReal x259=IKcos(j3);
2231IkReal x260=(cj5*new_r01);
2232IkReal x261=((25000.00002)*sj4);
2233IkReal x262=((3.9999999968e-5)*cj4);
2234IkReal x263=((0.9999999992)*sj4);
2235IkReal x264=(cj5*new_r00);
2236IkReal x265=((1.0)*sj5);
2237IkReal x266=((1.0)*x259);
2238IkReal x267=(sj5*x258);
2239IkReal x268=(cj5*x259);
2240IkReal x269=(cj5*x258);
2241evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x258);
2242evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x266)));
2243evalcond[2]=(x269+new_r10+((sj5*x259*x261)));
2244evalcond[3]=((((-1.0)*x259*x261))+x264+(((-1.0)*new_r10*x265)));
2245evalcond[4]=((((-1.0)*x258*x261))+x260+(((-1.0)*new_r11*x265)));
2246evalcond[5]=(x267+(((-1.0)*x261*x268))+new_r00);
2247evalcond[6]=((((-1.0)*cj5*x266))+((x261*x267))+new_r11);
2248evalcond[7]=((((-1.0)*x259*x265))+(((-1.0)*x261*x269))+new_r01);
2249evalcond[8]=(((x259*x262))+(((-1.0)*x259*x263)));
2250evalcond[9]=(((x258*x262))+(((-1.0)*x258*x263)));
2251evalcond[10]=((((-1.0)*new_r10*sj5*x261))+((x261*x264))+(((-1.0)*x266)));
2252evalcond[11]=(((x260*x261))+(((-1.0)*new_r11*sj5*x261))+(((-1.0)*x258)));
2253if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
2254{
2255continue;
2256}
2257}
2258
2259{
2260std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2261vinfos[0].jointtype = 1;
2262vinfos[0].foffset = j0;
2263vinfos[0].indices[0] = _ij0[0];
2264vinfos[0].indices[1] = _ij0[1];
2265vinfos[0].maxsolutions = _nj0;
2266vinfos[1].jointtype = 1;
2267vinfos[1].foffset = j1;
2268vinfos[1].indices[0] = _ij1[0];
2269vinfos[1].indices[1] = _ij1[1];
2270vinfos[1].maxsolutions = _nj1;
2271vinfos[2].jointtype = 1;
2272vinfos[2].foffset = j2;
2273vinfos[2].indices[0] = _ij2[0];
2274vinfos[2].indices[1] = _ij2[1];
2275vinfos[2].maxsolutions = _nj2;
2276vinfos[3].jointtype = 1;
2277vinfos[3].foffset = j3;
2278vinfos[3].indices[0] = _ij3[0];
2279vinfos[3].indices[1] = _ij3[1];
2280vinfos[3].maxsolutions = _nj3;
2281vinfos[4].jointtype = 1;
2282vinfos[4].foffset = j4;
2283vinfos[4].indices[0] = _ij4[0];
2284vinfos[4].indices[1] = _ij4[1];
2285vinfos[4].maxsolutions = _nj4;
2286vinfos[5].jointtype = 1;
2287vinfos[5].foffset = j5;
2288vinfos[5].indices[0] = _ij5[0];
2289vinfos[5].indices[1] = _ij5[1];
2290vinfos[5].maxsolutions = _nj5;
2291std::vector<int> vfree(0);
2292solutions.AddSolution(vinfos,vfree);
2293}
2294}
2295}
2296}
2297}
2298
2299}
2300
2301}
2302
2303} else
2304{
2305{
2306IkReal j5array[2], cj5array[2], sj5array[2];
2307bool j5valid[2]={false};
2308_nj5 = 2;
2309IkReal x270=((3.9999999968e-5)*cj4);
2310IkReal x271=((0.9999999992)*sj4);
2311CheckValue<IkReal> x273 = IKatan2WithCheck(IkReal(((((-1.0)*new_r00*x271))+((new_r00*x270)))),IkReal(((((-1.0)*new_r10*x270))+((new_r10*x271)))),IKFAST_ATAN2_MAGTHRESH);
2312if(!x273.valid){
2313continue;
2314}
2315IkReal x272=x273.value;
2316j5array[0]=((-1.0)*x272);
2317sj5array[0]=IKsin(j5array[0]);
2318cj5array[0]=IKcos(j5array[0]);
2319j5array[1]=((3.14159265358979)+(((-1.0)*x272)));
2320sj5array[1]=IKsin(j5array[1]);
2321cj5array[1]=IKcos(j5array[1]);
2322if( j5array[0] > IKPI )
2323{
2324 j5array[0]-=IK2PI;
2325}
2326else if( j5array[0] < -IKPI )
2327{ j5array[0]+=IK2PI;
2328}
2329j5valid[0] = true;
2330if( j5array[1] > IKPI )
2331{
2332 j5array[1]-=IK2PI;
2333}
2334else if( j5array[1] < -IKPI )
2335{ j5array[1]+=IK2PI;
2336}
2337j5valid[1] = true;
2338for(int ij5 = 0; ij5 < 2; ++ij5)
2339{
2340if( !j5valid[ij5] )
2341{
2342 continue;
2343}
2344_ij5[0] = ij5; _ij5[1] = -1;
2345for(int iij5 = ij5+1; iij5 < 2; ++iij5)
2346{
2347if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2348{
2349 j5valid[iij5]=false; _ij5[1] = iij5; break;
2350}
2351}
2352j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2353{
2354IkReal evalcond[3];
2355IkReal x274=IKcos(j5);
2356IkReal x275=IKsin(j5);
2357IkReal x276=((0.9999999992)*sj4);
2358IkReal x277=((3.9999999968e-5)*cj4);
2359IkReal x278=(new_r11*x275);
2360IkReal x279=(new_r01*x274);
2361evalcond[0]=((((-1.0)*x274*x277))+((x274*x276)));
2362evalcond[1]=(((x275*x277))+(((-1.0)*x275*x276)));
2363evalcond[2]=((((-1.0)*x277*x278))+((x277*x279))+((x276*x278))+(((-1.0)*x276*x279)));
2364if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
2365{
2366continue;
2367}
2368}
2369
2370{
2371IkReal j3array[1], cj3array[1], sj3array[1];
2372bool j3valid[1]={false};
2373_nj3 = 1;
2374if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
2375 continue;
2376j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
2377sj3array[0]=IKsin(j3array[0]);
2378cj3array[0]=IKcos(j3array[0]);
2379if( j3array[0] > IKPI )
2380{
2381 j3array[0]-=IK2PI;
2382}
2383else if( j3array[0] < -IKPI )
2384{ j3array[0]+=IK2PI;
2385}
2386j3valid[0] = true;
2387for(int ij3 = 0; ij3 < 1; ++ij3)
2388{
2389if( !j3valid[ij3] )
2390{
2391 continue;
2392}
2393_ij3[0] = ij3; _ij3[1] = -1;
2394for(int iij3 = ij3+1; iij3 < 1; ++iij3)
2395{
2396if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2397{
2398 j3valid[iij3]=false; _ij3[1] = iij3; break;
2399}
2400}
2401j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2402{
2403IkReal evalcond[12];
2404IkReal x280=IKsin(j3);
2405IkReal x281=IKcos(j3);
2406IkReal x282=(cj5*new_r01);
2407IkReal x283=((25000.00002)*sj4);
2408IkReal x284=((3.9999999968e-5)*cj4);
2409IkReal x285=((0.9999999992)*sj4);
2410IkReal x286=(cj5*new_r00);
2411IkReal x287=((1.0)*sj5);
2412IkReal x288=((1.0)*x281);
2413IkReal x289=(sj5*x280);
2414IkReal x290=(cj5*x281);
2415IkReal x291=(cj5*x280);
2416evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x280);
2417evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x288)));
2418evalcond[2]=(x291+((sj5*x281*x283))+new_r10);
2419evalcond[3]=((((-1.0)*x281*x283))+x286+(((-1.0)*new_r10*x287)));
2420evalcond[4]=((((-1.0)*x280*x283))+x282+(((-1.0)*new_r11*x287)));
2421evalcond[5]=(x289+(((-1.0)*x283*x290))+new_r00);
2422evalcond[6]=((((-1.0)*cj5*x288))+new_r11+((x283*x289)));
2423evalcond[7]=((((-1.0)*x281*x287))+(((-1.0)*x283*x291))+new_r01);
2424evalcond[8]=((((-1.0)*x281*x285))+((x281*x284)));
2425evalcond[9]=((((-1.0)*x280*x285))+((x280*x284)));
2426evalcond[10]=((((-1.0)*new_r10*sj5*x283))+(((-1.0)*x288))+((x283*x286)));
2427evalcond[11]=((((-1.0)*x280))+(((-1.0)*new_r11*sj5*x283))+((x282*x283)));
2428if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
2429{
2430continue;
2431}
2432}
2433
2434{
2435std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2436vinfos[0].jointtype = 1;
2437vinfos[0].foffset = j0;
2438vinfos[0].indices[0] = _ij0[0];
2439vinfos[0].indices[1] = _ij0[1];
2440vinfos[0].maxsolutions = _nj0;
2441vinfos[1].jointtype = 1;
2442vinfos[1].foffset = j1;
2443vinfos[1].indices[0] = _ij1[0];
2444vinfos[1].indices[1] = _ij1[1];
2445vinfos[1].maxsolutions = _nj1;
2446vinfos[2].jointtype = 1;
2447vinfos[2].foffset = j2;
2448vinfos[2].indices[0] = _ij2[0];
2449vinfos[2].indices[1] = _ij2[1];
2450vinfos[2].maxsolutions = _nj2;
2451vinfos[3].jointtype = 1;
2452vinfos[3].foffset = j3;
2453vinfos[3].indices[0] = _ij3[0];
2454vinfos[3].indices[1] = _ij3[1];
2455vinfos[3].maxsolutions = _nj3;
2456vinfos[4].jointtype = 1;
2457vinfos[4].foffset = j4;
2458vinfos[4].indices[0] = _ij4[0];
2459vinfos[4].indices[1] = _ij4[1];
2460vinfos[4].maxsolutions = _nj4;
2461vinfos[5].jointtype = 1;
2462vinfos[5].foffset = j5;
2463vinfos[5].indices[0] = _ij5[0];
2464vinfos[5].indices[1] = _ij5[1];
2465vinfos[5].maxsolutions = _nj5;
2466std::vector<int> vfree(0);
2467solutions.AddSolution(vinfos,vfree);
2468}
2469}
2470}
2471}
2472}
2473
2474}
2475
2476}
2477
2478} else
2479{
2480IkReal op[2+1], zeror[2];
2481int numroots;
2482IkReal x292=((3.9999999968e-5)*cj4);
2483IkReal x293=((0.9999999992)*sj4);
2484op[0]=((((-1.0)*x292))+x293);
2485op[1]=0;
2486op[2]=((((-1.0)*x293))+x292);
2487polyroots2(op,zeror,numroots);
2488IkReal j3array[2], cj3array[2], sj3array[2], tempj3array[1];
2489int numsolutions = 0;
2490for(int ij3 = 0; ij3 < numroots; ++ij3)
2491{
2492IkReal htj3 = zeror[ij3];
2493tempj3array[0]=((2.0)*(atan(htj3)));
2494for(int kj3 = 0; kj3 < 1; ++kj3)
2495{
2496j3array[numsolutions] = tempj3array[kj3];
2497if( j3array[numsolutions] > IKPI )
2498{
2499 j3array[numsolutions]-=IK2PI;
2500}
2501else if( j3array[numsolutions] < -IKPI )
2502{
2503 j3array[numsolutions]+=IK2PI;
2504}
2505sj3array[numsolutions] = IKsin(j3array[numsolutions]);
2506cj3array[numsolutions] = IKcos(j3array[numsolutions]);
2507numsolutions++;
2508}
2509}
2510bool j3valid[2]={true,true};
2511_nj3 = 2;
2512for(int ij3 = 0; ij3 < numsolutions; ++ij3)
2513 {
2514if( !j3valid[ij3] )
2515{
2516 continue;
2517}
2518 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
2519htj3 = IKtan(j3/2);
2520
2521_ij3[0] = ij3; _ij3[1] = -1;
2522for(int iij3 = ij3+1; iij3 < numsolutions; ++iij3)
2523{
2524if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
2525{
2526 j3valid[iij3]=false; _ij3[1] = iij3; break;
2527}
2528}
2529{
2530IkReal j5eval[3];
2531new_r02=0;
2532new_r12=0;
2533new_r20=0;
2534new_r21=0;
2535IkReal x294=((1.0)*new_r00);
2536IkReal x295=((((-1.0)*new_r11*x294))+((new_r01*new_r10)));
2537j5eval[0]=x295;
2538j5eval[1]=IKsign(x295);
2539j5eval[2]=((IKabs((((new_r11*sj3))+((cj3*new_r10)))))+(IKabs(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x294))))));
2540if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
2541{
2542{
2543IkReal j5eval[2];
2544new_r02=0;
2545new_r12=0;
2546new_r20=0;
2547new_r21=0;
2548IkReal x296=cj3*cj3;
2549IkReal x297=new_r00*new_r00;
2550IkReal x298=cj4*cj4;
2551IkReal x299=((625000001.0)*x296*x298);
2552j5eval[0]=((((-1.0)*x297*x299))+x299+x297+(((-625000001.0)*x296))+(((625000000.0)*x296*x297)));
2553j5eval[1]=((((-25000.00002)*cj3*new_r10*sj4))+((new_r00*sj3)));
2554if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
2555{
2556{
2557IkReal j5eval[2];
2558new_r02=0;
2559new_r12=0;
2560new_r20=0;
2561new_r21=0;
2562j5eval[0]=(((new_r10*sj3))+(((25000.00002)*cj3*new_r00*sj4)));
2563j5eval[1]=new_r00;
2564if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
2565{
2566{
2567IkReal evalcond[3];
2568bool bgotonextstatement = true;
2569do
2570{
2571evalcond[0]=((IKabs(((-3.14159265358979)+(IKfmod(((3.14159265358979)+j4), 6.28318530717959)))))+(IKabs(((-3.14159265358979)+(IKfmod(((3.14159265358979)+j3), 6.28318530717959))))));
2572evalcond[1]=new_r00;
2573evalcond[2]=new_r10;
2574if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
2575{
2576bgotonextstatement=false;
2577{
2578IkReal j5array[1], cj5array[1], sj5array[1];
2579bool j5valid[1]={false};
2580_nj5 = 1;
2581if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
2582 continue;
2583j5array[0]=IKatan2(new_r01, new_r11);
2584sj5array[0]=IKsin(j5array[0]);
2585cj5array[0]=IKcos(j5array[0]);
2586if( j5array[0] > IKPI )
2587{
2588 j5array[0]-=IK2PI;
2589}
2590else if( j5array[0] < -IKPI )
2591{ j5array[0]+=IK2PI;
2592}
2593j5valid[0] = true;
2594for(int ij5 = 0; ij5 < 1; ++ij5)
2595{
2596if( !j5valid[ij5] )
2597{
2598 continue;
2599}
2600_ij5[0] = ij5; _ij5[1] = -1;
2601for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2602{
2603if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2604{
2605 j5valid[iij5]=false; _ij5[1] = iij5; break;
2606}
2607}
2608j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2609{
2610IkReal evalcond[7];
2611IkReal x300=IKcos(j5);
2612IkReal x301=IKsin(j5);
2613IkReal x302=(new_r01*x300);
2614IkReal x303=((3.9999999968e-5)*x301);
2615IkReal x304=((1.0)*x301);
2616evalcond[0]=(new_r01+(((-1.0)*x304)));
2617evalcond[1]=((((-1.0)*x300))+new_r11);
2618evalcond[2]=((-3.9999999968e-5)*x300);
2619evalcond[3]=x303;
2620evalcond[4]=((-1.0)+((new_r01*x301))+((new_r11*x300)));
2621evalcond[5]=(x302+(((-1.0)*new_r11*x304)));
2622evalcond[6]=((((3.9999999968e-5)*x302))+(((-1.0)*new_r11*x303)));
2623if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
2624{
2625continue;
2626}
2627}
2628
2629{
2630std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2631vinfos[0].jointtype = 1;
2632vinfos[0].foffset = j0;
2633vinfos[0].indices[0] = _ij0[0];
2634vinfos[0].indices[1] = _ij0[1];
2635vinfos[0].maxsolutions = _nj0;
2636vinfos[1].jointtype = 1;
2637vinfos[1].foffset = j1;
2638vinfos[1].indices[0] = _ij1[0];
2639vinfos[1].indices[1] = _ij1[1];
2640vinfos[1].maxsolutions = _nj1;
2641vinfos[2].jointtype = 1;
2642vinfos[2].foffset = j2;
2643vinfos[2].indices[0] = _ij2[0];
2644vinfos[2].indices[1] = _ij2[1];
2645vinfos[2].maxsolutions = _nj2;
2646vinfos[3].jointtype = 1;
2647vinfos[3].foffset = j3;
2648vinfos[3].indices[0] = _ij3[0];
2649vinfos[3].indices[1] = _ij3[1];
2650vinfos[3].maxsolutions = _nj3;
2651vinfos[4].jointtype = 1;
2652vinfos[4].foffset = j4;
2653vinfos[4].indices[0] = _ij4[0];
2654vinfos[4].indices[1] = _ij4[1];
2655vinfos[4].maxsolutions = _nj4;
2656vinfos[5].jointtype = 1;
2657vinfos[5].foffset = j5;
2658vinfos[5].indices[0] = _ij5[0];
2659vinfos[5].indices[1] = _ij5[1];
2660vinfos[5].maxsolutions = _nj5;
2661std::vector<int> vfree(0);
2662solutions.AddSolution(vinfos,vfree);
2663}
2664}
2665}
2666
2667}
2668} while(0);
2669if( bgotonextstatement )
2670{
2671bool bgotonextstatement = true;
2672do
2673{
2674evalcond[0]=((IKabs(((-3.14159265358979)+(IKfmod(j3, 6.28318530717959)))))+(IKabs(((-3.14159265358979)+(IKfmod(((3.14159265358979)+j4), 6.28318530717959))))));
2675evalcond[1]=new_r00;
2676evalcond[2]=new_r10;
2677if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
2678{
2679bgotonextstatement=false;
2680{
2681IkReal j5array[1], cj5array[1], sj5array[1];
2682bool j5valid[1]={false};
2683_nj5 = 1;
2684if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
2685 continue;
2686j5array[0]=IKatan2(((-1.0)*new_r01), ((-1.0)*new_r11));
2687sj5array[0]=IKsin(j5array[0]);
2688cj5array[0]=IKcos(j5array[0]);
2689if( j5array[0] > IKPI )
2690{
2691 j5array[0]-=IK2PI;
2692}
2693else if( j5array[0] < -IKPI )
2694{ j5array[0]+=IK2PI;
2695}
2696j5valid[0] = true;
2697for(int ij5 = 0; ij5 < 1; ++ij5)
2698{
2699if( !j5valid[ij5] )
2700{
2701 continue;
2702}
2703_ij5[0] = ij5; _ij5[1] = -1;
2704for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2705{
2706if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2707{
2708 j5valid[iij5]=false; _ij5[1] = iij5; break;
2709}
2710}
2711j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2712{
2713IkReal evalcond[7];
2714IkReal x305=IKcos(j5);
2715IkReal x306=IKsin(j5);
2716IkReal x307=(new_r01*x305);
2717IkReal x308=((3.9999999968e-5)*x306);
2718evalcond[0]=(x306+new_r01);
2719evalcond[1]=(x305+new_r11);
2720evalcond[2]=((-3.9999999968e-5)*x305);
2721evalcond[3]=x308;
2722evalcond[4]=((1.0)+((new_r01*x306))+((new_r11*x305)));
2723evalcond[5]=(x307+(((-1.0)*new_r11*x306)));
2724evalcond[6]=((((3.9999999968e-5)*x307))+(((-1.0)*new_r11*x308)));
2725if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
2726{
2727continue;
2728}
2729}
2730
2731{
2732std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2733vinfos[0].jointtype = 1;
2734vinfos[0].foffset = j0;
2735vinfos[0].indices[0] = _ij0[0];
2736vinfos[0].indices[1] = _ij0[1];
2737vinfos[0].maxsolutions = _nj0;
2738vinfos[1].jointtype = 1;
2739vinfos[1].foffset = j1;
2740vinfos[1].indices[0] = _ij1[0];
2741vinfos[1].indices[1] = _ij1[1];
2742vinfos[1].maxsolutions = _nj1;
2743vinfos[2].jointtype = 1;
2744vinfos[2].foffset = j2;
2745vinfos[2].indices[0] = _ij2[0];
2746vinfos[2].indices[1] = _ij2[1];
2747vinfos[2].maxsolutions = _nj2;
2748vinfos[3].jointtype = 1;
2749vinfos[3].foffset = j3;
2750vinfos[3].indices[0] = _ij3[0];
2751vinfos[3].indices[1] = _ij3[1];
2752vinfos[3].maxsolutions = _nj3;
2753vinfos[4].jointtype = 1;
2754vinfos[4].foffset = j4;
2755vinfos[4].indices[0] = _ij4[0];
2756vinfos[4].indices[1] = _ij4[1];
2757vinfos[4].maxsolutions = _nj4;
2758vinfos[5].jointtype = 1;
2759vinfos[5].foffset = j5;
2760vinfos[5].indices[0] = _ij5[0];
2761vinfos[5].indices[1] = _ij5[1];
2762vinfos[5].maxsolutions = _nj5;
2763std::vector<int> vfree(0);
2764solutions.AddSolution(vinfos,vfree);
2765}
2766}
2767}
2768
2769}
2770} while(0);
2771if( bgotonextstatement )
2772{
2773bool bgotonextstatement = true;
2774do
2775{
2776evalcond[0]=((IKabs(((-3.14159265358979)+(IKfmod(j4, 6.28318530717959)))))+(IKabs(((-3.14159265358979)+(IKfmod(((3.14159265358979)+j3), 6.28318530717959))))));
2777evalcond[1]=new_r00;
2778evalcond[2]=new_r10;
2779if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
2780{
2781bgotonextstatement=false;
2782{
2783IkReal j5array[1], cj5array[1], sj5array[1];
2784bool j5valid[1]={false};
2785_nj5 = 1;
2786if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
2787 continue;
2788j5array[0]=IKatan2(new_r01, new_r11);
2789sj5array[0]=IKsin(j5array[0]);
2790cj5array[0]=IKcos(j5array[0]);
2791if( j5array[0] > IKPI )
2792{
2793 j5array[0]-=IK2PI;
2794}
2795else if( j5array[0] < -IKPI )
2796{ j5array[0]+=IK2PI;
2797}
2798j5valid[0] = true;
2799for(int ij5 = 0; ij5 < 1; ++ij5)
2800{
2801if( !j5valid[ij5] )
2802{
2803 continue;
2804}
2805_ij5[0] = ij5; _ij5[1] = -1;
2806for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2807{
2808if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2809{
2810 j5valid[iij5]=false; _ij5[1] = iij5; break;
2811}
2812}
2813j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2814{
2815IkReal evalcond[7];
2816IkReal x309=IKcos(j5);
2817IkReal x310=IKsin(j5);
2818IkReal x311=((3.9999999968e-5)*x309);
2819IkReal x312=(new_r11*x310);
2820evalcond[0]=((((-1.0)*x310))+new_r01);
2821evalcond[1]=((((-1.0)*x309))+new_r11);
2822evalcond[2]=x311;
2823evalcond[3]=((-3.9999999968e-5)*x310);
2824evalcond[4]=((-1.0)+((new_r11*x309))+((new_r01*x310)));
2825evalcond[5]=(((new_r01*x309))+(((-1.0)*x312)));
2826evalcond[6]=((((3.9999999968e-5)*x312))+(((-1.0)*new_r01*x311)));
2827if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
2828{
2829continue;
2830}
2831}
2832
2833{
2834std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2835vinfos[0].jointtype = 1;
2836vinfos[0].foffset = j0;
2837vinfos[0].indices[0] = _ij0[0];
2838vinfos[0].indices[1] = _ij0[1];
2839vinfos[0].maxsolutions = _nj0;
2840vinfos[1].jointtype = 1;
2841vinfos[1].foffset = j1;
2842vinfos[1].indices[0] = _ij1[0];
2843vinfos[1].indices[1] = _ij1[1];
2844vinfos[1].maxsolutions = _nj1;
2845vinfos[2].jointtype = 1;
2846vinfos[2].foffset = j2;
2847vinfos[2].indices[0] = _ij2[0];
2848vinfos[2].indices[1] = _ij2[1];
2849vinfos[2].maxsolutions = _nj2;
2850vinfos[3].jointtype = 1;
2851vinfos[3].foffset = j3;
2852vinfos[3].indices[0] = _ij3[0];
2853vinfos[3].indices[1] = _ij3[1];
2854vinfos[3].maxsolutions = _nj3;
2855vinfos[4].jointtype = 1;
2856vinfos[4].foffset = j4;
2857vinfos[4].indices[0] = _ij4[0];
2858vinfos[4].indices[1] = _ij4[1];
2859vinfos[4].maxsolutions = _nj4;
2860vinfos[5].jointtype = 1;
2861vinfos[5].foffset = j5;
2862vinfos[5].indices[0] = _ij5[0];
2863vinfos[5].indices[1] = _ij5[1];
2864vinfos[5].maxsolutions = _nj5;
2865std::vector<int> vfree(0);
2866solutions.AddSolution(vinfos,vfree);
2867}
2868}
2869}
2870
2871}
2872} while(0);
2873if( bgotonextstatement )
2874{
2875bool bgotonextstatement = true;
2876do
2877{
2878evalcond[0]=((IKabs(((-3.14159265358979)+(IKfmod(j3, 6.28318530717959)))))+(IKabs(((-3.14159265358979)+(IKfmod(j4, 6.28318530717959))))));
2879evalcond[1]=new_r00;
2880evalcond[2]=new_r10;
2881if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
2882{
2883bgotonextstatement=false;
2884{
2885IkReal j5array[1], cj5array[1], sj5array[1];
2886bool j5valid[1]={false};
2887_nj5 = 1;
2888if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
2889 continue;
2890j5array[0]=IKatan2(((-1.0)*new_r01), ((-1.0)*new_r11));
2891sj5array[0]=IKsin(j5array[0]);
2892cj5array[0]=IKcos(j5array[0]);
2893if( j5array[0] > IKPI )
2894{
2895 j5array[0]-=IK2PI;
2896}
2897else if( j5array[0] < -IKPI )
2898{ j5array[0]+=IK2PI;
2899}
2900j5valid[0] = true;
2901for(int ij5 = 0; ij5 < 1; ++ij5)
2902{
2903if( !j5valid[ij5] )
2904{
2905 continue;
2906}
2907_ij5[0] = ij5; _ij5[1] = -1;
2908for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2909{
2910if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2911{
2912 j5valid[iij5]=false; _ij5[1] = iij5; break;
2913}
2914}
2915j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2916{
2917IkReal evalcond[7];
2918IkReal x313=IKcos(j5);
2919IkReal x314=IKsin(j5);
2920IkReal x315=((3.9999999968e-5)*x313);
2921IkReal x316=(new_r11*x314);
2922evalcond[0]=(x314+new_r01);
2923evalcond[1]=(x313+new_r11);
2924evalcond[2]=x315;
2925evalcond[3]=((-3.9999999968e-5)*x314);
2926evalcond[4]=((1.0)+((new_r01*x314))+((new_r11*x313)));
2927evalcond[5]=(((new_r01*x313))+(((-1.0)*x316)));
2928evalcond[6]=((((3.9999999968e-5)*x316))+(((-1.0)*new_r01*x315)));
2929if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
2930{
2931continue;
2932}
2933}
2934
2935{
2936std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2937vinfos[0].jointtype = 1;
2938vinfos[0].foffset = j0;
2939vinfos[0].indices[0] = _ij0[0];
2940vinfos[0].indices[1] = _ij0[1];
2941vinfos[0].maxsolutions = _nj0;
2942vinfos[1].jointtype = 1;
2943vinfos[1].foffset = j1;
2944vinfos[1].indices[0] = _ij1[0];
2945vinfos[1].indices[1] = _ij1[1];
2946vinfos[1].maxsolutions = _nj1;
2947vinfos[2].jointtype = 1;
2948vinfos[2].foffset = j2;
2949vinfos[2].indices[0] = _ij2[0];
2950vinfos[2].indices[1] = _ij2[1];
2951vinfos[2].maxsolutions = _nj2;
2952vinfos[3].jointtype = 1;
2953vinfos[3].foffset = j3;
2954vinfos[3].indices[0] = _ij3[0];
2955vinfos[3].indices[1] = _ij3[1];
2956vinfos[3].maxsolutions = _nj3;
2957vinfos[4].jointtype = 1;
2958vinfos[4].foffset = j4;
2959vinfos[4].indices[0] = _ij4[0];
2960vinfos[4].indices[1] = _ij4[1];
2961vinfos[4].maxsolutions = _nj4;
2962vinfos[5].jointtype = 1;
2963vinfos[5].foffset = j5;
2964vinfos[5].indices[0] = _ij5[0];
2965vinfos[5].indices[1] = _ij5[1];
2966vinfos[5].maxsolutions = _nj5;
2967std::vector<int> vfree(0);
2968solutions.AddSolution(vinfos,vfree);
2969}
2970}
2971}
2972
2973}
2974} while(0);
2975if( bgotonextstatement )
2976{
2977bool bgotonextstatement = true;
2978do
2979{
2980if( 1 )
2981{
2982bgotonextstatement=false;
2983continue; // branch miss [j5]
2984
2985}
2986} while(0);
2987if( bgotonextstatement )
2988{
2989}
2990}
2991}
2992}
2993}
2994}
2995
2996} else
2997{
2998{
2999IkReal j5array[1], cj5array[1], sj5array[1];
3000bool j5valid[1]={false};
3001_nj5 = 1;
3002CheckValue<IkReal> x321=IKPowWithIntegerCheck(new_r00,-1);
3003if(!x321.valid){
3004continue;
3005}
3006IkReal x317=x321.value;
3007IkReal x318=cj3*cj3;
3008CheckValue<IkReal> x322=IKPowWithIntegerCheck((((new_r10*sj3))+(((25000.00002)*cj3*new_r00*sj4))),-1);
3009if(!x322.valid){
3010continue;
3011}
3012IkReal x319=x322.value;
3013IkReal x320=((1.0)*new_r10*x319);
3014CheckValue<IkReal> x323=IKPowWithIntegerCheck(x317,-2);
3015if(!x323.valid){
3016continue;
3017}
3018if( IKabs(((((-1.0)*x317*x318*x320))+(((-1.0)*new_r00*x320))+(((-1.0)*sj3*x317))+((new_r10*x317*x319)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x319*(((-1.0)+x318+(x323.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x317*x318*x320))+(((-1.0)*new_r00*x320))+(((-1.0)*sj3*x317))+((new_r10*x317*x319))))+IKsqr((x319*(((-1.0)+x318+(x323.value)))))-1) <= IKFAST_SINCOS_THRESH )
3019 continue;
3020j5array[0]=IKatan2(((((-1.0)*x317*x318*x320))+(((-1.0)*new_r00*x320))+(((-1.0)*sj3*x317))+((new_r10*x317*x319))), (x319*(((-1.0)+x318+(x323.value)))));
3021sj5array[0]=IKsin(j5array[0]);
3022cj5array[0]=IKcos(j5array[0]);
3023if( j5array[0] > IKPI )
3024{
3025 j5array[0]-=IK2PI;
3026}
3027else if( j5array[0] < -IKPI )
3028{ j5array[0]+=IK2PI;
3029}
3030j5valid[0] = true;
3031for(int ij5 = 0; ij5 < 1; ++ij5)
3032{
3033if( !j5valid[ij5] )
3034{
3035 continue;
3036}
3037_ij5[0] = ij5; _ij5[1] = -1;
3038for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3039{
3040if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3041{
3042 j5valid[iij5]=false; _ij5[1] = iij5; break;
3043}
3044}
3045j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3046{
3047IkReal evalcond[14];
3048IkReal x324=IKcos(j5);
3049IkReal x325=IKsin(j5);
3050IkReal x326=((1.0)*cj3);
3051IkReal x327=((25000.00002)*sj4);
3052IkReal x328=((3.9999999968e-5)*cj4);
3053IkReal x329=((0.9999999992)*sj4);
3054IkReal x330=(new_r11*x325);
3055IkReal x331=(new_r01*x324);
3056IkReal x332=(new_r00*x324);
3057IkReal x333=(sj3*x325);
3058IkReal x334=(new_r10*x325);
3059IkReal x335=(sj3*x324);
3060evalcond[0]=(((new_r00*x325))+sj3+((new_r10*x324)));
3061evalcond[1]=(((new_r01*x325))+(((-1.0)*x326))+((new_r11*x324)));
3062evalcond[2]=(((cj3*x325*x327))+x335+new_r10);
3063evalcond[3]=((((-1.0)*cj3*x324*x327))+x333+new_r00);
3064evalcond[4]=(((x327*x333))+new_r11+(((-1.0)*x324*x326)));
3065evalcond[5]=((((-1.0)*x325*x326))+new_r01+(((-1.0)*x327*x335)));
3066evalcond[6]=(((x324*x329))+(((-1.0)*x324*x328)));
3067evalcond[7]=(((x325*x328))+(((-1.0)*x325*x329)));
3068evalcond[8]=((((-1.0)*cj3*x327))+x332+(((-1.0)*x334)));
3069evalcond[9]=(x331+(((-1.0)*x330))+(((-1.0)*sj3*x327)));
3070evalcond[10]=((((-1.0)*x326))+((x327*x332))+(((-1.0)*x327*x334)));
3071evalcond[11]=((((-1.0)*sj3))+((x327*x331))+(((-1.0)*x327*x330)));
3072evalcond[12]=((((-1.0)*x329*x332))+(((-1.0)*x328*x334))+((x329*x334))+((x328*x332)));
3073evalcond[13]=((((-1.0)*x329*x331))+(((-1.0)*x328*x330))+((x329*x330))+((x328*x331)));
3074if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH )
3075{
3076continue;
3077}
3078}
3079
3080{
3081std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3082vinfos[0].jointtype = 1;
3083vinfos[0].foffset = j0;
3084vinfos[0].indices[0] = _ij0[0];
3085vinfos[0].indices[1] = _ij0[1];
3086vinfos[0].maxsolutions = _nj0;
3087vinfos[1].jointtype = 1;
3088vinfos[1].foffset = j1;
3089vinfos[1].indices[0] = _ij1[0];
3090vinfos[1].indices[1] = _ij1[1];
3091vinfos[1].maxsolutions = _nj1;
3092vinfos[2].jointtype = 1;
3093vinfos[2].foffset = j2;
3094vinfos[2].indices[0] = _ij2[0];
3095vinfos[2].indices[1] = _ij2[1];
3096vinfos[2].maxsolutions = _nj2;
3097vinfos[3].jointtype = 1;
3098vinfos[3].foffset = j3;
3099vinfos[3].indices[0] = _ij3[0];
3100vinfos[3].indices[1] = _ij3[1];
3101vinfos[3].maxsolutions = _nj3;
3102vinfos[4].jointtype = 1;
3103vinfos[4].foffset = j4;
3104vinfos[4].indices[0] = _ij4[0];
3105vinfos[4].indices[1] = _ij4[1];
3106vinfos[4].maxsolutions = _nj4;
3107vinfos[5].jointtype = 1;
3108vinfos[5].foffset = j5;
3109vinfos[5].indices[0] = _ij5[0];
3110vinfos[5].indices[1] = _ij5[1];
3111vinfos[5].maxsolutions = _nj5;
3112std::vector<int> vfree(0);
3113solutions.AddSolution(vinfos,vfree);
3114}
3115}
3116}
3117
3118}
3119
3120}
3121
3122} else
3123{
3124{
3125IkReal j5array[1], cj5array[1], sj5array[1];
3126bool j5valid[1]={false};
3127_nj5 = 1;
3128IkReal x336=new_r10*new_r10;
3129IkReal x337=cj3*cj3;
3130IkReal x338=new_r00*new_r00;
3131IkReal x339=(new_r00*sj3);
3132IkReal x340=((1.0)*new_r00);
3133IkReal x341=((25000.00002)*cj3*sj4);
3134IkReal x342=(new_r10*x341);
3135IkReal x343=((625000001.0)*x336*x337);
3136CheckValue<IkReal> x344=IKPowWithIntegerCheck((x338+(((-1.0)*x337*x338))+(((-1.0)*x343))+((x343*(cj4*cj4)))),-1);
3137if(!x344.valid){
3138continue;
3139}
3140CheckValue<IkReal> x345=IKPowWithIntegerCheck((x339+(((-1.0)*x342))),-1);
3141if(!x345.valid){
3142continue;
3143}
3144if( IKabs(((x344.value)*((((x342*(new_r10*new_r10)))+(((-1.0)*x339*(sj3*sj3)))+((x336*x339))+(((-1.0)*x342))+((x342*(cj3*cj3))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x345.value)*(((((-1.0)*new_r10*x340))+((sj3*x341)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x344.value)*((((x342*(new_r10*new_r10)))+(((-1.0)*x339*(sj3*sj3)))+((x336*x339))+(((-1.0)*x342))+((x342*(cj3*cj3)))))))+IKsqr(((x345.value)*(((((-1.0)*new_r10*x340))+((sj3*x341))))))-1) <= IKFAST_SINCOS_THRESH )
3145 continue;
3146j5array[0]=IKatan2(((x344.value)*((((x342*(new_r10*new_r10)))+(((-1.0)*x339*(sj3*sj3)))+((x336*x339))+(((-1.0)*x342))+((x342*(cj3*cj3)))))), ((x345.value)*(((((-1.0)*new_r10*x340))+((sj3*x341))))));
3147sj5array[0]=IKsin(j5array[0]);
3148cj5array[0]=IKcos(j5array[0]);
3149if( j5array[0] > IKPI )
3150{
3151 j5array[0]-=IK2PI;
3152}
3153else if( j5array[0] < -IKPI )
3154{ j5array[0]+=IK2PI;
3155}
3156j5valid[0] = true;
3157for(int ij5 = 0; ij5 < 1; ++ij5)
3158{
3159if( !j5valid[ij5] )
3160{
3161 continue;
3162}
3163_ij5[0] = ij5; _ij5[1] = -1;
3164for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3165{
3166if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3167{
3168 j5valid[iij5]=false; _ij5[1] = iij5; break;
3169}
3170}
3171j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3172{
3173IkReal evalcond[14];
3174IkReal x346=IKcos(j5);
3175IkReal x347=IKsin(j5);
3176IkReal x348=((1.0)*cj3);
3177IkReal x349=((25000.00002)*sj4);
3178IkReal x350=((3.9999999968e-5)*cj4);
3179IkReal x351=((0.9999999992)*sj4);
3180IkReal x352=(new_r11*x347);
3181IkReal x353=(new_r01*x346);
3182IkReal x354=(new_r00*x346);
3183IkReal x355=(sj3*x347);
3184IkReal x356=(new_r10*x347);
3185IkReal x357=(sj3*x346);
3186evalcond[0]=(sj3+((new_r00*x347))+((new_r10*x346)));
3187evalcond[1]=(((new_r11*x346))+((new_r01*x347))+(((-1.0)*x348)));
3188evalcond[2]=(x357+new_r10+((cj3*x347*x349)));
3189evalcond[3]=((((-1.0)*cj3*x346*x349))+x355+new_r00);
3190evalcond[4]=(((x349*x355))+(((-1.0)*x346*x348))+new_r11);
3191evalcond[5]=((((-1.0)*x349*x357))+(((-1.0)*x347*x348))+new_r01);
3192evalcond[6]=(((x346*x351))+(((-1.0)*x346*x350)));
3193evalcond[7]=(((x347*x350))+(((-1.0)*x347*x351)));
3194evalcond[8]=((((-1.0)*cj3*x349))+(((-1.0)*x356))+x354);
3195evalcond[9]=((((-1.0)*x352))+x353+(((-1.0)*sj3*x349)));
3196evalcond[10]=((((-1.0)*x349*x356))+((x349*x354))+(((-1.0)*x348)));
3197evalcond[11]=((((-1.0)*sj3))+(((-1.0)*x349*x352))+((x349*x353)));
3198evalcond[12]=(((x351*x356))+((x350*x354))+(((-1.0)*x351*x354))+(((-1.0)*x350*x356)));
3199evalcond[13]=(((x351*x352))+((x350*x353))+(((-1.0)*x351*x353))+(((-1.0)*x350*x352)));
3200if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH )
3201{
3202continue;
3203}
3204}
3205
3206{
3207std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3208vinfos[0].jointtype = 1;
3209vinfos[0].foffset = j0;
3210vinfos[0].indices[0] = _ij0[0];
3211vinfos[0].indices[1] = _ij0[1];
3212vinfos[0].maxsolutions = _nj0;
3213vinfos[1].jointtype = 1;
3214vinfos[1].foffset = j1;
3215vinfos[1].indices[0] = _ij1[0];
3216vinfos[1].indices[1] = _ij1[1];
3217vinfos[1].maxsolutions = _nj1;
3218vinfos[2].jointtype = 1;
3219vinfos[2].foffset = j2;
3220vinfos[2].indices[0] = _ij2[0];
3221vinfos[2].indices[1] = _ij2[1];
3222vinfos[2].maxsolutions = _nj2;
3223vinfos[3].jointtype = 1;
3224vinfos[3].foffset = j3;
3225vinfos[3].indices[0] = _ij3[0];
3226vinfos[3].indices[1] = _ij3[1];
3227vinfos[3].maxsolutions = _nj3;
3228vinfos[4].jointtype = 1;
3229vinfos[4].foffset = j4;
3230vinfos[4].indices[0] = _ij4[0];
3231vinfos[4].indices[1] = _ij4[1];
3232vinfos[4].maxsolutions = _nj4;
3233vinfos[5].jointtype = 1;
3234vinfos[5].foffset = j5;
3235vinfos[5].indices[0] = _ij5[0];
3236vinfos[5].indices[1] = _ij5[1];
3237vinfos[5].maxsolutions = _nj5;
3238std::vector<int> vfree(0);
3239solutions.AddSolution(vinfos,vfree);
3240}
3241}
3242}
3243
3244}
3245
3246}
3247
3248} else
3249{
3250{
3251IkReal j5array[1], cj5array[1], sj5array[1];
3252bool j5valid[1]={false};
3253_nj5 = 1;
3254IkReal x358=((1.0)*new_r00);
3255CheckValue<IkReal> x359 = IKatan2WithCheck(IkReal((((new_r11*sj3))+((cj3*new_r10)))),IkReal(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x358)))),IKFAST_ATAN2_MAGTHRESH);
3256if(!x359.valid){
3257continue;
3258}
3259CheckValue<IkReal> x360=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x358)))),-1);
3260if(!x360.valid){
3261continue;
3262}
3263j5array[0]=((-1.5707963267949)+(x359.value)+(((1.5707963267949)*(x360.value))));
3264sj5array[0]=IKsin(j5array[0]);
3265cj5array[0]=IKcos(j5array[0]);
3266if( j5array[0] > IKPI )
3267{
3268 j5array[0]-=IK2PI;
3269}
3270else if( j5array[0] < -IKPI )
3271{ j5array[0]+=IK2PI;
3272}
3273j5valid[0] = true;
3274for(int ij5 = 0; ij5 < 1; ++ij5)
3275{
3276if( !j5valid[ij5] )
3277{
3278 continue;
3279}
3280_ij5[0] = ij5; _ij5[1] = -1;
3281for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3282{
3283if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3284{
3285 j5valid[iij5]=false; _ij5[1] = iij5; break;
3286}
3287}
3288j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3289{
3290IkReal evalcond[14];
3291IkReal x361=IKcos(j5);
3292IkReal x362=IKsin(j5);
3293IkReal x363=((1.0)*cj3);
3294IkReal x364=((25000.00002)*sj4);
3295IkReal x365=((3.9999999968e-5)*cj4);
3296IkReal x366=((0.9999999992)*sj4);
3297IkReal x367=(new_r11*x362);
3298IkReal x368=(new_r01*x361);
3299IkReal x369=(new_r00*x361);
3300IkReal x370=(sj3*x362);
3301IkReal x371=(new_r10*x362);
3302IkReal x372=(sj3*x361);
3303evalcond[0]=(sj3+((new_r00*x362))+((new_r10*x361)));
3304evalcond[1]=((((-1.0)*x363))+((new_r01*x362))+((new_r11*x361)));
3305evalcond[2]=(((cj3*x362*x364))+x372+new_r10);
3306evalcond[3]=(x370+(((-1.0)*cj3*x361*x364))+new_r00);
3307evalcond[4]=((((-1.0)*x361*x363))+((x364*x370))+new_r11);
3308evalcond[5]=((((-1.0)*x362*x363))+new_r01+(((-1.0)*x364*x372)));
3309evalcond[6]=(((x361*x366))+(((-1.0)*x361*x365)));
3310evalcond[7]=((((-1.0)*x362*x366))+((x362*x365)));
3311evalcond[8]=((((-1.0)*x371))+x369+(((-1.0)*cj3*x364)));
3312evalcond[9]=((((-1.0)*x367))+(((-1.0)*sj3*x364))+x368);
3313evalcond[10]=(((x364*x369))+(((-1.0)*x363))+(((-1.0)*x364*x371)));
3314evalcond[11]=((((-1.0)*sj3))+((x364*x368))+(((-1.0)*x364*x367)));
3315evalcond[12]=(((x365*x369))+((x366*x371))+(((-1.0)*x366*x369))+(((-1.0)*x365*x371)));
3316evalcond[13]=(((x366*x367))+((x365*x368))+(((-1.0)*x366*x368))+(((-1.0)*x365*x367)));
3317if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH )
3318{
3319continue;
3320}
3321}
3322
3323{
3324std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3325vinfos[0].jointtype = 1;
3326vinfos[0].foffset = j0;
3327vinfos[0].indices[0] = _ij0[0];
3328vinfos[0].indices[1] = _ij0[1];
3329vinfos[0].maxsolutions = _nj0;
3330vinfos[1].jointtype = 1;
3331vinfos[1].foffset = j1;
3332vinfos[1].indices[0] = _ij1[0];
3333vinfos[1].indices[1] = _ij1[1];
3334vinfos[1].maxsolutions = _nj1;
3335vinfos[2].jointtype = 1;
3336vinfos[2].foffset = j2;
3337vinfos[2].indices[0] = _ij2[0];
3338vinfos[2].indices[1] = _ij2[1];
3339vinfos[2].maxsolutions = _nj2;
3340vinfos[3].jointtype = 1;
3341vinfos[3].foffset = j3;
3342vinfos[3].indices[0] = _ij3[0];
3343vinfos[3].indices[1] = _ij3[1];
3344vinfos[3].maxsolutions = _nj3;
3345vinfos[4].jointtype = 1;
3346vinfos[4].foffset = j4;
3347vinfos[4].indices[0] = _ij4[0];
3348vinfos[4].indices[1] = _ij4[1];
3349vinfos[4].maxsolutions = _nj4;
3350vinfos[5].jointtype = 1;
3351vinfos[5].foffset = j5;
3352vinfos[5].indices[0] = _ij5[0];
3353vinfos[5].indices[1] = _ij5[1];
3354vinfos[5].maxsolutions = _nj5;
3355std::vector<int> vfree(0);
3356solutions.AddSolution(vinfos,vfree);
3357}
3358}
3359}
3360
3361}
3362
3363}
3364 }
3365
3366}
3367
3368}
3369
3370}
3371} while(0);
3372if( bgotonextstatement )
3373{
3374bool bgotonextstatement = true;
3375do
3376{
3377if( 1 )
3378{
3379bgotonextstatement=false;
3380continue; // branch miss [j3, j5]
3381
3382}
3383} while(0);
3384if( bgotonextstatement )
3385{
3386}
3387}
3388}
3389}
3390}
3391}
3392}
3393}
3394
3395} else
3396{
3397{
3398IkReal j5array[1], cj5array[1], sj5array[1];
3399bool j5valid[1]={false};
3400_nj5 = 1;
3401IkReal x373=((0.9999999992)*sj4);
3402IkReal x374=((3.9999999968e-5)*cj4);
3403CheckValue<IkReal> x375=IKPowWithIntegerCheck(IKsign(((new_r12*new_r12)+(new_r02*new_r02))),-1);
3404if(!x375.valid){
3405continue;
3406}
3407CheckValue<IkReal> x376 = IKatan2WithCheck(IkReal((((new_r12*x373))+(((-1.0)*new_r12*x374)))),IkReal((((new_r02*x374))+(((-1.0)*new_r02*x373)))),IKFAST_ATAN2_MAGTHRESH);
3408if(!x376.valid){
3409continue;
3410}
3411j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x375.value)))+(x376.value));
3412sj5array[0]=IKsin(j5array[0]);
3413cj5array[0]=IKcos(j5array[0]);
3414if( j5array[0] > IKPI )
3415{
3416 j5array[0]-=IK2PI;
3417}
3418else if( j5array[0] < -IKPI )
3419{ j5array[0]+=IK2PI;
3420}
3421j5valid[0] = true;
3422for(int ij5 = 0; ij5 < 1; ++ij5)
3423{
3424if( !j5valid[ij5] )
3425{
3426 continue;
3427}
3428_ij5[0] = ij5; _ij5[1] = -1;
3429for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3430{
3431if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3432{
3433 j5valid[iij5]=false; _ij5[1] = iij5; break;
3434}
3435}
3436j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3437{
3438IkReal evalcond[8];
3439IkReal x377=IKcos(j5);
3440IkReal x378=IKsin(j5);
3441IkReal x379=((0.9999999992)*cj4);
3442IkReal x380=((3.9999999968e-5)*cj4);
3443IkReal x381=((0.9999999992)*sj4);
3444IkReal x382=((3.9999999968e-5)*sj4);
3445IkReal x383=(new_r12*x378);
3446IkReal x384=(new_r02*x377);
3447IkReal x385=(new_r01*x377);
3448IkReal x386=(new_r11*x378);
3449IkReal x387=(new_r00*x377);
3450IkReal x388=(new_r10*x378);
3451evalcond[0]=(((new_r12*x377))+((new_r02*x378)));
3452evalcond[1]=(((x377*x381))+new_r02+(((-1.0)*x377*x380)));
3453evalcond[2]=(((x378*x380))+(((-1.0)*x378*x381))+new_r12);
3454evalcond[3]=(x384+x381+(((-1.0)*x383))+(((-1.0)*x380)));
3455evalcond[4]=((((-1.0)*x380*x388))+((new_r20*x379))+(((-1.0)*x381*x387))+((new_r20*x382))+((x380*x387))+((x381*x388)));
3456evalcond[5]=((((-1.0)*x380*x386))+(((-1.0)*x381*x385))+((new_r21*x379))+((x380*x385))+((x381*x386))+((new_r21*x382)));
3457evalcond[6]=((((-1.0)*x379*x383))+((new_r22*x381))+((x382*x384))+((x379*x384))+(((-1.0)*new_r22*x380))+(((-1.0)*x382*x383)));
3458evalcond[7]=((-1.0)+(((-1.0)*x380*x383))+(((-1.0)*x381*x384))+((new_r22*x382))+((x380*x384))+((x381*x383))+((new_r22*x379)));
3459if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
3460{
3461continue;
3462}
3463}
3464
3465{
3466IkReal j3array[1], cj3array[1], sj3array[1];
3467bool j3valid[1]={false};
3468_nj3 = 1;
3469if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
3470 continue;
3471j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
3472sj3array[0]=IKsin(j3array[0]);
3473cj3array[0]=IKcos(j3array[0]);
3474if( j3array[0] > IKPI )
3475{
3476 j3array[0]-=IK2PI;
3477}
3478else if( j3array[0] < -IKPI )
3479{ j3array[0]+=IK2PI;
3480}
3481j3valid[0] = true;
3482for(int ij3 = 0; ij3 < 1; ++ij3)
3483{
3484if( !j3valid[ij3] )
3485{
3486 continue;
3487}
3488_ij3[0] = ij3; _ij3[1] = -1;
3489for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3490{
3491if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3492{
3493 j3valid[iij3]=false; _ij3[1] = iij3; break;
3494}
3495}
3496j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3497{
3498IkReal evalcond[12];
3499IkReal x389=IKcos(j3);
3500IkReal x390=IKsin(j3);
3501IkReal x391=((0.9999999992)*cj4);
3502IkReal x392=((3.9999999968e-5)*cj4);
3503IkReal x393=(cj5*new_r01);
3504IkReal x394=((0.9999999992)*sj4);
3505IkReal x395=(cj5*new_r00);
3506IkReal x396=((3.9999999968e-5)*sj4);
3507IkReal x397=(new_r10*sj5);
3508IkReal x398=(new_r11*sj5);
3509IkReal x399=((1.0)*x389);
3510IkReal x400=(cj5*x390);
3511IkReal x401=(sj5*x389);
3512IkReal x402=(sj5*x390);
3513IkReal x403=(cj5*x389);
3514IkReal x404=(x389*x396);
3515evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x390);
3516evalcond[1]=((((-1.0)*x399))+((cj5*new_r11))+((new_r01*sj5)));
3517evalcond[2]=((((-1.0)*x389*x394))+new_r20+((x389*x392)));
3518evalcond[3]=((((-1.0)*x390*x394))+new_r21+((x390*x392)));
3519evalcond[4]=((((-1.0)*x397))+(((-1.0)*x389*x391))+x395+(((-1.0)*x404)));
3520evalcond[5]=((((-1.0)*x398))+x393+(((-1.0)*x390*x396))+(((-1.0)*x390*x391)));
3521evalcond[6]=((((-1.0)*x391*x403))+x402+new_r00+(((-1.0)*x396*x403)));
3522evalcond[7]=(x400+new_r10+((x396*x401))+((x391*x401)));
3523evalcond[8]=((((-1.0)*sj5*x399))+(((-1.0)*x391*x400))+new_r01+(((-1.0)*x396*x400)));
3524evalcond[9]=((((-1.0)*cj5*x399))+new_r11+((x396*x402))+((x391*x402)));
3525evalcond[10]=((((-1.0)*x399))+((x395*x396))+((new_r20*x394))+(((-1.0)*x391*x397))+((x391*x395))+(((-1.0)*x396*x397))+(((-1.0)*new_r20*x392)));
3526evalcond[11]=((((-1.0)*x390))+(((-1.0)*new_r21*x392))+(((-1.0)*x391*x398))+((x391*x393))+((new_r21*x394))+(((-1.0)*x396*x398))+((x393*x396)));
3527if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
3528{
3529continue;
3530}
3531}
3532
3533{
3534std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3535vinfos[0].jointtype = 1;
3536vinfos[0].foffset = j0;
3537vinfos[0].indices[0] = _ij0[0];
3538vinfos[0].indices[1] = _ij0[1];
3539vinfos[0].maxsolutions = _nj0;
3540vinfos[1].jointtype = 1;
3541vinfos[1].foffset = j1;
3542vinfos[1].indices[0] = _ij1[0];
3543vinfos[1].indices[1] = _ij1[1];
3544vinfos[1].maxsolutions = _nj1;
3545vinfos[2].jointtype = 1;
3546vinfos[2].foffset = j2;
3547vinfos[2].indices[0] = _ij2[0];
3548vinfos[2].indices[1] = _ij2[1];
3549vinfos[2].maxsolutions = _nj2;
3550vinfos[3].jointtype = 1;
3551vinfos[3].foffset = j3;
3552vinfos[3].indices[0] = _ij3[0];
3553vinfos[3].indices[1] = _ij3[1];
3554vinfos[3].maxsolutions = _nj3;
3555vinfos[4].jointtype = 1;
3556vinfos[4].foffset = j4;
3557vinfos[4].indices[0] = _ij4[0];
3558vinfos[4].indices[1] = _ij4[1];
3559vinfos[4].maxsolutions = _nj4;
3560vinfos[5].jointtype = 1;
3561vinfos[5].foffset = j5;
3562vinfos[5].indices[0] = _ij5[0];
3563vinfos[5].indices[1] = _ij5[1];
3564vinfos[5].maxsolutions = _nj5;
3565std::vector<int> vfree(0);
3566solutions.AddSolution(vinfos,vfree);
3567}
3568}
3569}
3570}
3571}
3572
3573}
3574
3575}
3576
3577} else
3578{
3579{
3580IkReal j3array[1], cj3array[1], sj3array[1];
3581bool j3valid[1]={false};
3582_nj3 = 1;
3583CheckValue<IkReal> x405 = IKatan2WithCheck(IkReal(((-1.0)*new_r21)),IkReal(((-1.0)*new_r20)),IKFAST_ATAN2_MAGTHRESH);
3584if(!x405.valid){
3585continue;
3586}
3587CheckValue<IkReal> x406=IKPowWithIntegerCheck(IKsign(((((-0.9999999992)*sj4))+(((3.9999999968e-5)*cj4)))),-1);
3588if(!x406.valid){
3589continue;
3590}
3591j3array[0]=((-1.5707963267949)+(x405.value)+(((1.5707963267949)*(x406.value))));
3592sj3array[0]=IKsin(j3array[0]);
3593cj3array[0]=IKcos(j3array[0]);
3594if( j3array[0] > IKPI )
3595{
3596 j3array[0]-=IK2PI;
3597}
3598else if( j3array[0] < -IKPI )
3599{ j3array[0]+=IK2PI;
3600}
3601j3valid[0] = true;
3602for(int ij3 = 0; ij3 < 1; ++ij3)
3603{
3604if( !j3valid[ij3] )
3605{
3606 continue;
3607}
3608_ij3[0] = ij3; _ij3[1] = -1;
3609for(int iij3 = ij3+1; iij3 < 1; ++iij3)
3610{
3611if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
3612{
3613 j3valid[iij3]=false; _ij3[1] = iij3; break;
3614}
3615}
3616j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
3617{
3618IkReal evalcond[2];
3619IkReal x407=IKcos(j3);
3620IkReal x408=IKsin(j3);
3621IkReal x409=((0.9999999992)*sj4);
3622IkReal x410=((3.9999999968e-5)*cj4);
3623evalcond[0]=(((x407*x410))+(((-1.0)*x407*x409))+new_r20);
3624evalcond[1]=(((x408*x410))+new_r21+(((-1.0)*x408*x409)));
3625if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
3626{
3627continue;
3628}
3629}
3630
3631{
3632IkReal j5eval[3];
3633IkReal x411=((((-1.0)*new_r00*new_r12))+((new_r02*new_r10)));
3634j5eval[0]=x411;
3635j5eval[1]=((IKabs((new_r12*sj3)))+(IKabs((new_r02*sj3))));
3636j5eval[2]=IKsign(x411);
3637if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
3638{
3639{
3640IkReal j5eval[3];
3641IkReal x412=(((new_r01*new_r12))+(((-1.0)*new_r02*new_r11)));
3642j5eval[0]=x412;
3643j5eval[1]=IKsign(x412);
3644j5eval[2]=((IKabs((cj3*new_r02)))+(IKabs((cj3*new_r12))));
3645if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
3646{
3647{
3648IkReal j5eval[3];
3649j5eval[0]=((((25000.0)*sj4))+(((-1.0)*cj4)));
3650j5eval[1]=((IKabs(new_r12))+(IKabs(new_r02)));
3651j5eval[2]=IKsign(((((-3.9999999968e-5)*cj4))+(((0.9999999992)*sj4))));
3652if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
3653{
3654{
3655IkReal evalcond[5];
3656bool bgotonextstatement = true;
3657do
3658{
3659evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.99999999786667e-5)+j4)))), 6.28318530717959)));
3660evalcond[1]=new_r02;
3661evalcond[2]=new_r12;
3662evalcond[3]=new_r20;
3663evalcond[4]=new_r21;
3664if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
3665{
3666bgotonextstatement=false;
3667{
3668IkReal j5eval[3];
3669sj4=4.0e-5;
3670cj4=1.0;
3671j4=4.0e-5;
3672IkReal x413=((1.0)*new_r00);
3673IkReal x414=(((new_r01*new_r10))+(((-1.0)*new_r11*x413)));
3674j5eval[0]=x414;
3675j5eval[1]=IKsign(x414);
3676j5eval[2]=((IKabs((((new_r11*sj3))+((cj3*new_r10)))))+(IKabs(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x413))))));
3677if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
3678{
3679{
3680IkReal j5eval[2];
3681sj4=4.0e-5;
3682cj4=1.0;
3683j4=4.0e-5;
3684IkReal x415=new_r00*new_r00;
3685IkReal x416=cj3*cj3;
3686j5eval[0]=((((-1.0)*x415*x416))+x415+(((-1.0000000016)*x416*(new_r10*new_r10))));
3687j5eval[1]=((((-1.0000000008)*cj3*new_r10))+((new_r00*sj3)));
3688if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
3689{
3690{
3691IkReal j5eval[2];
3692sj4=4.0e-5;
3693cj4=1.0;
3694j4=4.0e-5;
3695j5eval[0]=new_r00;
3696j5eval[1]=((((-1.0000000008)*new_r00*sj3))+((cj3*new_r10)));
3697if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
3698{
3699{
3700IkReal evalcond[1];
3701bool bgotonextstatement = true;
3702do
3703{
3704IkReal x417=((-1.0000000008)*new_r00);
3705IkReal x419 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
3706if(IKabs(x419)==0){
3707continue;
3708}
3709IkReal x418=pow(x419,-0.5);
3710CheckValue<IkReal> x420 = IKatan2WithCheck(IkReal(new_r10),IkReal(x417),IKFAST_ATAN2_MAGTHRESH);
3711if(!x420.valid){
3712continue;
3713}
3714IkReal gconst6=((-1.0)*(x420.value));
3715IkReal gconst7=((-1.0)*new_r10*x418);
3716IkReal gconst8=(x417*x418);
3717CheckValue<IkReal> x421 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
3718if(!x421.valid){
3719continue;
3720}
3721evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x421.value)+j3)))), 6.28318530717959)));
3722if( IKabs(evalcond[0]) < 0.0000050000000000 )
3723{
3724bgotonextstatement=false;
3725{
3726IkReal j5eval[3];
3727IkReal x422=((-1.0000000008)*new_r00);
3728IkReal x423=x418;
3729sj4=4.0e-5;
3730cj4=1.0;
3731j4=4.0e-5;
3732sj3=gconst7;
3733cj3=gconst8;
3734CheckValue<IkReal> x424 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
3735if(!x424.valid){
3736continue;
3737}
3738j3=((-1.0)*(x424.value));
3739CheckValue<IkReal> x425 = IKatan2WithCheck(IkReal(new_r10),IkReal(x422),IKFAST_ATAN2_MAGTHRESH);
3740if(!x425.valid){
3741continue;
3742}
3743IkReal gconst6=((-1.0)*(x425.value));
3744IkReal gconst7=((-1.0)*new_r10*x423);
3745IkReal gconst8=(x422*x423);
3746IkReal x426=new_r00*new_r00;
3747IkReal x427=(new_r01*new_r10);
3748IkReal x428=(x427+(((-1.0)*new_r00*new_r11)));
3749IkReal x431 = ((((625000000.0)*(new_r10*new_r10)))+(((625000001.0)*x426)));
3750if(IKabs(x431)==0){
3751continue;
3752}
3753IkReal x429=pow(x431,-0.5);
3754IkReal x430=(new_r10*x429);
3755j5eval[0]=x428;
3756j5eval[1]=IKsign(x428);
3757j5eval[2]=((IKabs(((((-25000.00002)*new_r00*x430))+(((-25000.0)*new_r11*x430)))))+(IKabs(((((25000.00002)*x426*x429))+(((25000.0)*x427*x429))))));
3758if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
3759{
3760{
3761IkReal j5eval[2];
3762IkReal x432=((-1.0000000008)*new_r00);
3763IkReal x433=x418;
3764sj4=4.0e-5;
3765cj4=1.0;
3766j4=4.0e-5;
3767sj3=gconst7;
3768cj3=gconst8;
3769CheckValue<IkReal> x434 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
3770if(!x434.valid){
3771continue;
3772}
3773j3=((-1.0)*(x434.value));
3774CheckValue<IkReal> x435 = IKatan2WithCheck(IkReal(new_r10),IkReal(x432),IKFAST_ATAN2_MAGTHRESH);
3775if(!x435.valid){
3776continue;
3777}
3778IkReal gconst6=((-1.0)*(x435.value));
3779IkReal gconst7=((-1.0)*new_r10*x433);
3780IkReal gconst8=(x432*x433);
3781IkReal x436=new_r00*new_r00;
3782IkReal x437=new_r10*new_r10;
3783IkReal x438=((((1.0000000016)*x436))+x437);
3784CheckValue<IkReal> x439=IKPowWithIntegerCheck(x438,-1);
3785if(!x439.valid){
3786continue;
3787}
3788j5eval[0]=((-3.20000000256e-9)*x436*x437*(x439.value));
3789IkReal x440 = x438;
3790if(IKabs(x440)==0){
3791continue;
3792}
3793j5eval[1]=((1.6e-9)*new_r00*new_r10*(pow(x440,-0.5)));
3794if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
3795{
3796{
3797IkReal j5eval[1];
3798IkReal x441=((-1.0000000008)*new_r00);
3799IkReal x442=x418;
3800sj4=4.0e-5;
3801cj4=1.0;
3802j4=4.0e-5;
3803sj3=gconst7;
3804cj3=gconst8;
3805CheckValue<IkReal> x443 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
3806if(!x443.valid){
3807continue;
3808}
3809j3=((-1.0)*(x443.value));
3810CheckValue<IkReal> x444 = IKatan2WithCheck(IkReal(new_r10),IkReal(x441),IKFAST_ATAN2_MAGTHRESH);
3811if(!x444.valid){
3812continue;
3813}
3814IkReal gconst6=((-1.0)*(x444.value));
3815IkReal gconst7=((-1.0)*new_r10*x442);
3816IkReal gconst8=(x441*x442);
3817j5eval[0]=new_r00;
3818if( IKabs(j5eval[0]) < 0.0000010000000000 )
3819{
3820{
3821IkReal evalcond[1];
3822bool bgotonextstatement = true;
3823do
3824{
3825evalcond[0]=IKabs(new_r00);
3826if( IKabs(evalcond[0]) < 0.0000050000000000 )
3827{
3828bgotonextstatement=false;
3829{
3830IkReal j5eval[1];
3831CheckValue<IkReal> x446 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
3832if(!x446.valid){
3833continue;
3834}
3835IkReal x445=((-1.0)*(x446.value));
3836sj4=4.0e-5;
3837cj4=1.0;
3838j4=4.0e-5;
3839sj3=gconst7;
3840cj3=gconst8;
3841j3=x445;
3842new_r00=0;
3843IkReal gconst6=x445;
3844IkReal x447 = new_r10*new_r10;
3845if(IKabs(x447)==0){
3846continue;
3847}
3848IkReal gconst7=((-1.0)*new_r10*(pow(x447,-0.5)));
3849IkReal gconst8=0;
3850j5eval[0]=new_r10;
3851if( IKabs(j5eval[0]) < 0.0000010000000000 )
3852{
3853{
3854IkReal j5array[1], cj5array[1], sj5array[1];
3855bool j5valid[1]={false};
3856_nj5 = 1;
3857CheckValue<IkReal> x449=IKPowWithIntegerCheck(gconst7,-1);
3858if(!x449.valid){
3859continue;
3860}
3861IkReal x448=x449.value;
3862if( IKabs(((-0.9999999992)*new_r11*x448)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x448)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*x448))+IKsqr(((-1.0)*new_r10*x448))-1) <= IKFAST_SINCOS_THRESH )
3863 continue;
3864j5array[0]=IKatan2(((-0.9999999992)*new_r11*x448), ((-1.0)*new_r10*x448));
3865sj5array[0]=IKsin(j5array[0]);
3866cj5array[0]=IKcos(j5array[0]);
3867if( j5array[0] > IKPI )
3868{
3869 j5array[0]-=IK2PI;
3870}
3871else if( j5array[0] < -IKPI )
3872{ j5array[0]+=IK2PI;
3873}
3874j5valid[0] = true;
3875for(int ij5 = 0; ij5 < 1; ++ij5)
3876{
3877if( !j5valid[ij5] )
3878{
3879 continue;
3880}
3881_ij5[0] = ij5; _ij5[1] = -1;
3882for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3883{
3884if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3885{
3886 j5valid[iij5]=false; _ij5[1] = iij5; break;
3887}
3888}
3889j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3890{
3891IkReal evalcond[10];
3892IkReal x450=IKsin(j5);
3893IkReal x451=IKcos(j5);
3894IkReal x452=((1.0000000008)*gconst7);
3895IkReal x453=(new_r11*x450);
3896IkReal x454=(new_r10*x450);
3897IkReal x455=(new_r01*x451);
3898evalcond[0]=(gconst7*x450);
3899evalcond[1]=((-1.0)*x454);
3900evalcond[2]=(((new_r10*x451))+gconst7);
3901evalcond[3]=(((gconst7*x451))+new_r10);
3902evalcond[4]=((-1.0000000008)*x454);
3903evalcond[5]=(((new_r11*x451))+((new_r01*x450)));
3904evalcond[6]=((((-1.0)*x451*x452))+new_r01);
3905evalcond[7]=(((x450*x452))+new_r11);
3906evalcond[8]=((((-1.0)*x453))+(((-1.0)*x452))+x455);
3907evalcond[9]=((((-1.0)*gconst7))+(((1.0000000008)*x455))+(((-1.0000000008)*x453)));
3908if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
3909{
3910continue;
3911}
3912}
3913
3914{
3915std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3916vinfos[0].jointtype = 1;
3917vinfos[0].foffset = j0;
3918vinfos[0].indices[0] = _ij0[0];
3919vinfos[0].indices[1] = _ij0[1];
3920vinfos[0].maxsolutions = _nj0;
3921vinfos[1].jointtype = 1;
3922vinfos[1].foffset = j1;
3923vinfos[1].indices[0] = _ij1[0];
3924vinfos[1].indices[1] = _ij1[1];
3925vinfos[1].maxsolutions = _nj1;
3926vinfos[2].jointtype = 1;
3927vinfos[2].foffset = j2;
3928vinfos[2].indices[0] = _ij2[0];
3929vinfos[2].indices[1] = _ij2[1];
3930vinfos[2].maxsolutions = _nj2;
3931vinfos[3].jointtype = 1;
3932vinfos[3].foffset = j3;
3933vinfos[3].indices[0] = _ij3[0];
3934vinfos[3].indices[1] = _ij3[1];
3935vinfos[3].maxsolutions = _nj3;
3936vinfos[4].jointtype = 1;
3937vinfos[4].foffset = j4;
3938vinfos[4].indices[0] = _ij4[0];
3939vinfos[4].indices[1] = _ij4[1];
3940vinfos[4].maxsolutions = _nj4;
3941vinfos[5].jointtype = 1;
3942vinfos[5].foffset = j5;
3943vinfos[5].indices[0] = _ij5[0];
3944vinfos[5].indices[1] = _ij5[1];
3945vinfos[5].maxsolutions = _nj5;
3946std::vector<int> vfree(0);
3947solutions.AddSolution(vinfos,vfree);
3948}
3949}
3950}
3951
3952} else
3953{
3954{
3955IkReal j5array[1], cj5array[1], sj5array[1];
3956bool j5valid[1]={false};
3957_nj5 = 1;
3958CheckValue<IkReal> x456=IKPowWithIntegerCheck(gconst7,-1);
3959if(!x456.valid){
3960continue;
3961}
3962CheckValue<IkReal> x457=IKPowWithIntegerCheck(new_r10,-1);
3963if(!x457.valid){
3964continue;
3965}
3966if( IKabs(((-0.9999999992)*new_r11*(x456.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst7*(x457.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*(x456.value)))+IKsqr(((-1.0)*gconst7*(x457.value)))-1) <= IKFAST_SINCOS_THRESH )
3967 continue;
3968j5array[0]=IKatan2(((-0.9999999992)*new_r11*(x456.value)), ((-1.0)*gconst7*(x457.value)));
3969sj5array[0]=IKsin(j5array[0]);
3970cj5array[0]=IKcos(j5array[0]);
3971if( j5array[0] > IKPI )
3972{
3973 j5array[0]-=IK2PI;
3974}
3975else if( j5array[0] < -IKPI )
3976{ j5array[0]+=IK2PI;
3977}
3978j5valid[0] = true;
3979for(int ij5 = 0; ij5 < 1; ++ij5)
3980{
3981if( !j5valid[ij5] )
3982{
3983 continue;
3984}
3985_ij5[0] = ij5; _ij5[1] = -1;
3986for(int iij5 = ij5+1; iij5 < 1; ++iij5)
3987{
3988if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
3989{
3990 j5valid[iij5]=false; _ij5[1] = iij5; break;
3991}
3992}
3993j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
3994{
3995IkReal evalcond[10];
3996IkReal x458=IKsin(j5);
3997IkReal x459=IKcos(j5);
3998IkReal x460=((1.0000000008)*gconst7);
3999IkReal x461=(new_r11*x458);
4000IkReal x462=(new_r10*x458);
4001IkReal x463=(new_r01*x459);
4002evalcond[0]=(gconst7*x458);
4003evalcond[1]=((-1.0)*x462);
4004evalcond[2]=(((new_r10*x459))+gconst7);
4005evalcond[3]=(((gconst7*x459))+new_r10);
4006evalcond[4]=((-1.0000000008)*x462);
4007evalcond[5]=(((new_r11*x459))+((new_r01*x458)));
4008evalcond[6]=((((-1.0)*x459*x460))+new_r01);
4009evalcond[7]=(new_r11+((x458*x460)));
4010evalcond[8]=((((-1.0)*x461))+(((-1.0)*x460))+x463);
4011evalcond[9]=((((-1.0)*gconst7))+(((1.0000000008)*x463))+(((-1.0000000008)*x461)));
4012if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
4013{
4014continue;
4015}
4016}
4017
4018{
4019std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4020vinfos[0].jointtype = 1;
4021vinfos[0].foffset = j0;
4022vinfos[0].indices[0] = _ij0[0];
4023vinfos[0].indices[1] = _ij0[1];
4024vinfos[0].maxsolutions = _nj0;
4025vinfos[1].jointtype = 1;
4026vinfos[1].foffset = j1;
4027vinfos[1].indices[0] = _ij1[0];
4028vinfos[1].indices[1] = _ij1[1];
4029vinfos[1].maxsolutions = _nj1;
4030vinfos[2].jointtype = 1;
4031vinfos[2].foffset = j2;
4032vinfos[2].indices[0] = _ij2[0];
4033vinfos[2].indices[1] = _ij2[1];
4034vinfos[2].maxsolutions = _nj2;
4035vinfos[3].jointtype = 1;
4036vinfos[3].foffset = j3;
4037vinfos[3].indices[0] = _ij3[0];
4038vinfos[3].indices[1] = _ij3[1];
4039vinfos[3].maxsolutions = _nj3;
4040vinfos[4].jointtype = 1;
4041vinfos[4].foffset = j4;
4042vinfos[4].indices[0] = _ij4[0];
4043vinfos[4].indices[1] = _ij4[1];
4044vinfos[4].maxsolutions = _nj4;
4045vinfos[5].jointtype = 1;
4046vinfos[5].foffset = j5;
4047vinfos[5].indices[0] = _ij5[0];
4048vinfos[5].indices[1] = _ij5[1];
4049vinfos[5].maxsolutions = _nj5;
4050std::vector<int> vfree(0);
4051solutions.AddSolution(vinfos,vfree);
4052}
4053}
4054}
4055
4056}
4057
4058}
4059
4060}
4061} while(0);
4062if( bgotonextstatement )
4063{
4064bool bgotonextstatement = true;
4065do
4066{
4067evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
4068if( IKabs(evalcond[0]) < 0.0000050000000000 )
4069{
4070bgotonextstatement=false;
4071{
4072IkReal j5eval[3];
4073IkReal x464=((-1.0000000008)*new_r00);
4074IkReal x466 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
4075if(IKabs(x466)==0){
4076continue;
4077}
4078IkReal x465=pow(x466,-0.5);
4079sj4=4.0e-5;
4080cj4=1.0;
4081j4=4.0e-5;
4082sj3=gconst7;
4083cj3=gconst8;
4084CheckValue<IkReal> x467 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
4085if(!x467.valid){
4086continue;
4087}
4088j3=((-1.0)*(x467.value));
4089new_r11=0;
4090new_r01=0;
4091new_r22=0;
4092new_r20=0;
4093CheckValue<IkReal> x468 = IKatan2WithCheck(IkReal(new_r10),IkReal(x464),IKFAST_ATAN2_MAGTHRESH);
4094if(!x468.valid){
4095continue;
4096}
4097IkReal gconst6=((-1.0)*(x468.value));
4098IkReal gconst7=((-1.0)*new_r10*x465);
4099IkReal gconst8=(x464*x465);
4100IkReal x469=new_r10*new_r10;
4101CheckValue<IkReal> x473=IKPowWithIntegerCheck(((-625000001.0)+x469),-1);
4102if(!x473.valid){
4103continue;
4104}
4105IkReal x470=x473.value;
4106if((((625000001.0)+(((-1.0)*x469)))) < -0.00001)
4107continue;
4108IkReal x471=IKsqrt(((625000001.0)+(((-1.0)*x469))));
4109IkReal x472=(x470*x471);
4110j5eval[0]=-1.0;
4111j5eval[1]=-1.0;
4112IkReal x474 = ((1.0000000016)+(((-1.6e-9)*x469)));
4113if(IKabs(x474)==0){
4114continue;
4115}
4116j5eval[2]=((IKabs(((((-625000001.0)*x472))+(((1250000001.0)*x469*x472)))))+(((50000.00004)*(IKabs((new_r00*new_r10*(pow(x474,-0.5))))))));
4117if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
4118{
4119{
4120IkReal j5eval[1];
4121IkReal x475=((-1.0000000008)*new_r00);
4122IkReal x477 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
4123if(IKabs(x477)==0){
4124continue;
4125}
4126IkReal x476=pow(x477,-0.5);
4127sj4=4.0e-5;
4128cj4=1.0;
4129j4=4.0e-5;
4130sj3=gconst7;
4131cj3=gconst8;
4132CheckValue<IkReal> x478 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
4133if(!x478.valid){
4134continue;
4135}
4136j3=((-1.0)*(x478.value));
4137new_r11=0;
4138new_r01=0;
4139new_r22=0;
4140new_r20=0;
4141CheckValue<IkReal> x479 = IKatan2WithCheck(IkReal(new_r10),IkReal(x475),IKFAST_ATAN2_MAGTHRESH);
4142if(!x479.valid){
4143continue;
4144}
4145IkReal gconst6=((-1.0)*(x479.value));
4146IkReal gconst7=((-1.0)*new_r10*x476);
4147IkReal gconst8=(x475*x476);
4148IkReal x480=new_r10*new_r10;
4149CheckValue<IkReal> x483=IKPowWithIntegerCheck(((1.0000000016)+(((-1.6e-9)*x480))),-1);
4150if(!x483.valid){
4151continue;
4152}
4153IkReal x481=x483.value;
4154IkReal x482=((625000001.0)*x481);
4155IkReal x484=((1.0)+(((-1.0)*x480)));
4156j5eval[0]=IKsign((((x482*(x480*x480)))+(((-1.0)*x482*(x484*x484)))));
4157if( IKabs(j5eval[0]) < 0.0000010000000000 )
4158{
4159{
4160IkReal j5eval[2];
4161IkReal x485=((-1.0000000008)*new_r00);
4162IkReal x487 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
4163if(IKabs(x487)==0){
4164continue;
4165}
4166IkReal x486=pow(x487,-0.5);
4167sj4=4.0e-5;
4168cj4=1.0;
4169j4=4.0e-5;
4170sj3=gconst7;
4171cj3=gconst8;
4172CheckValue<IkReal> x488 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
4173if(!x488.valid){
4174continue;
4175}
4176j3=((-1.0)*(x488.value));
4177new_r11=0;
4178new_r01=0;
4179new_r22=0;
4180new_r20=0;
4181CheckValue<IkReal> x489 = IKatan2WithCheck(IkReal(new_r10),IkReal(x485),IKFAST_ATAN2_MAGTHRESH);
4182if(!x489.valid){
4183continue;
4184}
4185IkReal gconst6=((-1.0)*(x489.value));
4186IkReal gconst7=((-1.0)*new_r10*x486);
4187IkReal gconst8=(x485*x486);
4188IkReal x490=new_r10*new_r10;
4189IkReal x491=((1.0000000016)+(((-1.6e-9)*x490)));
4190CheckValue<IkReal> x492=IKPowWithIntegerCheck(x491,-1);
4191if(!x492.valid){
4192continue;
4193}
4194j5eval[0]=((-3.20000000256e-9)*x490*(x492.value)*(((1.0)+(((-1.0)*x490)))));
4195IkReal x493 = x491;
4196if(IKabs(x493)==0){
4197continue;
4198}
4199j5eval[1]=((1.6e-9)*new_r00*new_r10*(pow(x493,-0.5)));
4200if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
4201{
4202continue; // 3 cases reached
4203
4204} else
4205{
4206{
4207IkReal j5array[1], cj5array[1], sj5array[1];
4208bool j5valid[1]={false};
4209_nj5 = 1;
4210IkReal x494=gconst7*gconst7;
4211IkReal x495=new_r10*new_r10;
4212IkReal x496=((625000000.0)*new_r00);
4213IkReal x497=((625000000.5)*gconst8);
4214IkReal x498=((25000.00002)*gconst8);
4215IkReal x499=((25000.0)*new_r00);
4216CheckValue<IkReal> x500=IKPowWithIntegerCheck(((((-625000001.0)*x495*(gconst8*gconst8)))+((new_r00*x494*x496))),-1);
4217if(!x500.valid){
4218continue;
4219}
4220CheckValue<IkReal> x501=IKPowWithIntegerCheck(((((-1.0)*new_r10*x498))+((gconst7*x499))),-1);
4221if(!x501.valid){
4222continue;
4223}
4224if( IKabs(((x500.value)*(((((-1.0)*x496*(gconst7*gconst7*gconst7)))+(((-1.0)*new_r10*x494*x497))+((x497*(new_r10*new_r10*new_r10)))+((gconst7*x495*x496)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x501.value)*(((((-1.0)*new_r10*x499))+((gconst7*x498)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x500.value)*(((((-1.0)*x496*(gconst7*gconst7*gconst7)))+(((-1.0)*new_r10*x494*x497))+((x497*(new_r10*new_r10*new_r10)))+((gconst7*x495*x496))))))+IKsqr(((x501.value)*(((((-1.0)*new_r10*x499))+((gconst7*x498))))))-1) <= IKFAST_SINCOS_THRESH )
4225 continue;
4226j5array[0]=IKatan2(((x500.value)*(((((-1.0)*x496*(gconst7*gconst7*gconst7)))+(((-1.0)*new_r10*x494*x497))+((x497*(new_r10*new_r10*new_r10)))+((gconst7*x495*x496))))), ((x501.value)*(((((-1.0)*new_r10*x499))+((gconst7*x498))))));
4227sj5array[0]=IKsin(j5array[0]);
4228cj5array[0]=IKcos(j5array[0]);
4229if( j5array[0] > IKPI )
4230{
4231 j5array[0]-=IK2PI;
4232}
4233else if( j5array[0] < -IKPI )
4234{ j5array[0]+=IK2PI;
4235}
4236j5valid[0] = true;
4237for(int ij5 = 0; ij5 < 1; ++ij5)
4238{
4239if( !j5valid[ij5] )
4240{
4241 continue;
4242}
4243_ij5[0] = ij5; _ij5[1] = -1;
4244for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4245{
4246if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4247{
4248 j5valid[iij5]=false; _ij5[1] = iij5; break;
4249}
4250}
4251j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4252{
4253IkReal evalcond[7];
4254IkReal x502=IKsin(j5);
4255IkReal x503=IKcos(j5);
4256IkReal x504=((1.0)*gconst8);
4257IkReal x505=((1.0000000008)*gconst8);
4258IkReal x506=(gconst7*x503);
4259IkReal x507=(new_r00*x503);
4260IkReal x508=((1.0000000008)*x502);
4261evalcond[0]=(gconst7+((new_r10*x503))+((new_r00*x502)));
4262evalcond[1]=(((gconst7*x502))+(((-1.0)*x503*x505))+new_r00);
4263evalcond[2]=(x506+((x502*x505))+new_r10);
4264evalcond[3]=((((-1.0)*x502*x504))+(((-1.0000000008)*x506)));
4265evalcond[4]=(((gconst7*x508))+(((-1.0)*x503*x504)));
4266evalcond[5]=((((-1.0)*new_r10*x502))+(((-1.0)*x505))+x507);
4267evalcond[6]=((((-1.0)*x504))+(((1.0000000008)*x507))+(((-1.0)*new_r10*x508)));
4268if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
4269{
4270continue;
4271}
4272}
4273
4274{
4275std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4276vinfos[0].jointtype = 1;
4277vinfos[0].foffset = j0;
4278vinfos[0].indices[0] = _ij0[0];
4279vinfos[0].indices[1] = _ij0[1];
4280vinfos[0].maxsolutions = _nj0;
4281vinfos[1].jointtype = 1;
4282vinfos[1].foffset = j1;
4283vinfos[1].indices[0] = _ij1[0];
4284vinfos[1].indices[1] = _ij1[1];
4285vinfos[1].maxsolutions = _nj1;
4286vinfos[2].jointtype = 1;
4287vinfos[2].foffset = j2;
4288vinfos[2].indices[0] = _ij2[0];
4289vinfos[2].indices[1] = _ij2[1];
4290vinfos[2].maxsolutions = _nj2;
4291vinfos[3].jointtype = 1;
4292vinfos[3].foffset = j3;
4293vinfos[3].indices[0] = _ij3[0];
4294vinfos[3].indices[1] = _ij3[1];
4295vinfos[3].maxsolutions = _nj3;
4296vinfos[4].jointtype = 1;
4297vinfos[4].foffset = j4;
4298vinfos[4].indices[0] = _ij4[0];
4299vinfos[4].indices[1] = _ij4[1];
4300vinfos[4].maxsolutions = _nj4;
4301vinfos[5].jointtype = 1;
4302vinfos[5].foffset = j5;
4303vinfos[5].indices[0] = _ij5[0];
4304vinfos[5].indices[1] = _ij5[1];
4305vinfos[5].maxsolutions = _nj5;
4306std::vector<int> vfree(0);
4307solutions.AddSolution(vinfos,vfree);
4308}
4309}
4310}
4311
4312}
4313
4314}
4315
4316} else
4317{
4318{
4319IkReal j5array[1], cj5array[1], sj5array[1];
4320bool j5valid[1]={false};
4321_nj5 = 1;
4322IkReal x509=gconst8*gconst8;
4323IkReal x510=gconst7*gconst7;
4324IkReal x511=((625000000.0)*x509);
4325IkReal x512=((625000000.5)*gconst8*x510);
4326CheckValue<IkReal> x513 = IKatan2WithCheck(IkReal((((gconst7*new_r00*x511))+(((-1.0)*new_r10*x512)))),IkReal((((new_r00*x512))+(((-625000001.0)*new_r10*(gconst7*gconst7*gconst7))))),IKFAST_ATAN2_MAGTHRESH);
4327if(!x513.valid){
4328continue;
4329}
4330CheckValue<IkReal> x514=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x510*(new_r10*new_r10)))+(((-1.0)*x511*(new_r00*new_r00))))),-1);
4331if(!x514.valid){
4332continue;
4333}
4334j5array[0]=((-1.5707963267949)+(x513.value)+(((1.5707963267949)*(x514.value))));
4335sj5array[0]=IKsin(j5array[0]);
4336cj5array[0]=IKcos(j5array[0]);
4337if( j5array[0] > IKPI )
4338{
4339 j5array[0]-=IK2PI;
4340}
4341else if( j5array[0] < -IKPI )
4342{ j5array[0]+=IK2PI;
4343}
4344j5valid[0] = true;
4345for(int ij5 = 0; ij5 < 1; ++ij5)
4346{
4347if( !j5valid[ij5] )
4348{
4349 continue;
4350}
4351_ij5[0] = ij5; _ij5[1] = -1;
4352for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4353{
4354if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4355{
4356 j5valid[iij5]=false; _ij5[1] = iij5; break;
4357}
4358}
4359j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4360{
4361IkReal evalcond[7];
4362IkReal x515=IKsin(j5);
4363IkReal x516=IKcos(j5);
4364IkReal x517=((1.0)*gconst8);
4365IkReal x518=((1.0000000008)*gconst8);
4366IkReal x519=(gconst7*x516);
4367IkReal x520=(new_r00*x516);
4368IkReal x521=((1.0000000008)*x515);
4369evalcond[0]=(((new_r00*x515))+((new_r10*x516))+gconst7);
4370evalcond[1]=((((-1.0)*x516*x518))+((gconst7*x515))+new_r00);
4371evalcond[2]=(x519+((x515*x518))+new_r10);
4372evalcond[3]=((((-1.0000000008)*x519))+(((-1.0)*x515*x517)));
4373evalcond[4]=(((gconst7*x521))+(((-1.0)*x516*x517)));
4374evalcond[5]=((((-1.0)*new_r10*x515))+x520+(((-1.0)*x518)));
4375evalcond[6]=((((1.0000000008)*x520))+(((-1.0)*new_r10*x521))+(((-1.0)*x517)));
4376if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
4377{
4378continue;
4379}
4380}
4381
4382{
4383std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4384vinfos[0].jointtype = 1;
4385vinfos[0].foffset = j0;
4386vinfos[0].indices[0] = _ij0[0];
4387vinfos[0].indices[1] = _ij0[1];
4388vinfos[0].maxsolutions = _nj0;
4389vinfos[1].jointtype = 1;
4390vinfos[1].foffset = j1;
4391vinfos[1].indices[0] = _ij1[0];
4392vinfos[1].indices[1] = _ij1[1];
4393vinfos[1].maxsolutions = _nj1;
4394vinfos[2].jointtype = 1;
4395vinfos[2].foffset = j2;
4396vinfos[2].indices[0] = _ij2[0];
4397vinfos[2].indices[1] = _ij2[1];
4398vinfos[2].maxsolutions = _nj2;
4399vinfos[3].jointtype = 1;
4400vinfos[3].foffset = j3;
4401vinfos[3].indices[0] = _ij3[0];
4402vinfos[3].indices[1] = _ij3[1];
4403vinfos[3].maxsolutions = _nj3;
4404vinfos[4].jointtype = 1;
4405vinfos[4].foffset = j4;
4406vinfos[4].indices[0] = _ij4[0];
4407vinfos[4].indices[1] = _ij4[1];
4408vinfos[4].maxsolutions = _nj4;
4409vinfos[5].jointtype = 1;
4410vinfos[5].foffset = j5;
4411vinfos[5].indices[0] = _ij5[0];
4412vinfos[5].indices[1] = _ij5[1];
4413vinfos[5].maxsolutions = _nj5;
4414std::vector<int> vfree(0);
4415solutions.AddSolution(vinfos,vfree);
4416}
4417}
4418}
4419
4420}
4421
4422}
4423
4424} else
4425{
4426{
4427IkReal j5array[1], cj5array[1], sj5array[1];
4428bool j5valid[1]={false};
4429_nj5 = 1;
4430IkReal x522=((25000.00002)*gconst8);
4431IkReal x523=((25000.0)*gconst7);
4432CheckValue<IkReal> x524=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
4433if(!x524.valid){
4434continue;
4435}
4436CheckValue<IkReal> x525 = IKatan2WithCheck(IkReal((((new_r10*x522))+((new_r00*x523)))),IkReal(((((-1.0)*new_r00*x522))+((new_r10*x523)))),IKFAST_ATAN2_MAGTHRESH);
4437if(!x525.valid){
4438continue;
4439}
4440j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x524.value)))+(x525.value));
4441sj5array[0]=IKsin(j5array[0]);
4442cj5array[0]=IKcos(j5array[0]);
4443if( j5array[0] > IKPI )
4444{
4445 j5array[0]-=IK2PI;
4446}
4447else if( j5array[0] < -IKPI )
4448{ j5array[0]+=IK2PI;
4449}
4450j5valid[0] = true;
4451for(int ij5 = 0; ij5 < 1; ++ij5)
4452{
4453if( !j5valid[ij5] )
4454{
4455 continue;
4456}
4457_ij5[0] = ij5; _ij5[1] = -1;
4458for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4459{
4460if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4461{
4462 j5valid[iij5]=false; _ij5[1] = iij5; break;
4463}
4464}
4465j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4466{
4467IkReal evalcond[7];
4468IkReal x526=IKsin(j5);
4469IkReal x527=IKcos(j5);
4470IkReal x528=((1.0)*gconst8);
4471IkReal x529=((1.0000000008)*gconst8);
4472IkReal x530=(gconst7*x527);
4473IkReal x531=(new_r00*x527);
4474IkReal x532=((1.0000000008)*x526);
4475evalcond[0]=(gconst7+((new_r10*x527))+((new_r00*x526)));
4476evalcond[1]=((((-1.0)*x527*x529))+((gconst7*x526))+new_r00);
4477evalcond[2]=(((x526*x529))+x530+new_r10);
4478evalcond[3]=((((-1.0)*x526*x528))+(((-1.0000000008)*x530)));
4479evalcond[4]=((((-1.0)*x527*x528))+((gconst7*x532)));
4480evalcond[5]=((((-1.0)*x529))+x531+(((-1.0)*new_r10*x526)));
4481evalcond[6]=((((1.0000000008)*x531))+(((-1.0)*x528))+(((-1.0)*new_r10*x532)));
4482if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
4483{
4484continue;
4485}
4486}
4487
4488{
4489std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4490vinfos[0].jointtype = 1;
4491vinfos[0].foffset = j0;
4492vinfos[0].indices[0] = _ij0[0];
4493vinfos[0].indices[1] = _ij0[1];
4494vinfos[0].maxsolutions = _nj0;
4495vinfos[1].jointtype = 1;
4496vinfos[1].foffset = j1;
4497vinfos[1].indices[0] = _ij1[0];
4498vinfos[1].indices[1] = _ij1[1];
4499vinfos[1].maxsolutions = _nj1;
4500vinfos[2].jointtype = 1;
4501vinfos[2].foffset = j2;
4502vinfos[2].indices[0] = _ij2[0];
4503vinfos[2].indices[1] = _ij2[1];
4504vinfos[2].maxsolutions = _nj2;
4505vinfos[3].jointtype = 1;
4506vinfos[3].foffset = j3;
4507vinfos[3].indices[0] = _ij3[0];
4508vinfos[3].indices[1] = _ij3[1];
4509vinfos[3].maxsolutions = _nj3;
4510vinfos[4].jointtype = 1;
4511vinfos[4].foffset = j4;
4512vinfos[4].indices[0] = _ij4[0];
4513vinfos[4].indices[1] = _ij4[1];
4514vinfos[4].maxsolutions = _nj4;
4515vinfos[5].jointtype = 1;
4516vinfos[5].foffset = j5;
4517vinfos[5].indices[0] = _ij5[0];
4518vinfos[5].indices[1] = _ij5[1];
4519vinfos[5].maxsolutions = _nj5;
4520std::vector<int> vfree(0);
4521solutions.AddSolution(vinfos,vfree);
4522}
4523}
4524}
4525
4526}
4527
4528}
4529
4530}
4531} while(0);
4532if( bgotonextstatement )
4533{
4534bool bgotonextstatement = true;
4535do
4536{
4537evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
4538if( IKabs(evalcond[0]) < 0.0000050000000000 )
4539{
4540bgotonextstatement=false;
4541{
4542IkReal j5array[1], cj5array[1], sj5array[1];
4543bool j5valid[1]={false};
4544_nj5 = 1;
4545CheckValue<IkReal> x534=IKPowWithIntegerCheck(gconst8,-1);
4546if(!x534.valid){
4547continue;
4548}
4549IkReal x533=x534.value;
4550if( IKabs((new_r01*x533)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r00*x533)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x533))+IKsqr(((0.9999999992)*new_r00*x533))-1) <= IKFAST_SINCOS_THRESH )
4551 continue;
4552j5array[0]=IKatan2((new_r01*x533), ((0.9999999992)*new_r00*x533));
4553sj5array[0]=IKsin(j5array[0]);
4554cj5array[0]=IKcos(j5array[0]);
4555if( j5array[0] > IKPI )
4556{
4557 j5array[0]-=IK2PI;
4558}
4559else if( j5array[0] < -IKPI )
4560{ j5array[0]+=IK2PI;
4561}
4562j5valid[0] = true;
4563for(int ij5 = 0; ij5 < 1; ++ij5)
4564{
4565if( !j5valid[ij5] )
4566{
4567 continue;
4568}
4569_ij5[0] = ij5; _ij5[1] = -1;
4570for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4571{
4572if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4573{
4574 j5valid[iij5]=false; _ij5[1] = iij5; break;
4575}
4576}
4577j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4578{
4579IkReal evalcond[10];
4580IkReal x535=IKcos(j5);
4581IkReal x536=IKsin(j5);
4582IkReal x537=((1.0)*gconst8);
4583IkReal x538=((1.0000000008)*gconst8);
4584IkReal x539=(new_r00*x535);
4585IkReal x540=(gconst8*x535);
4586IkReal x541=(new_r01*x535);
4587evalcond[0]=(new_r00*x536);
4588evalcond[1]=x541;
4589evalcond[2]=((-1.0)*x540);
4590evalcond[3]=(new_r01+(((-1.0)*x536*x537)));
4591evalcond[4]=(((new_r01*x536))+(((-1.0)*x537)));
4592evalcond[5]=(x536*x538);
4593evalcond[6]=((1.0000000008)*x541);
4594evalcond[7]=((((-1.0)*x535*x538))+new_r00);
4595evalcond[8]=((((-1.0)*x538))+x539);
4596evalcond[9]=((((1.0000000008)*x539))+(((-1.0)*x537)));
4597if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
4598{
4599continue;
4600}
4601}
4602
4603{
4604std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4605vinfos[0].jointtype = 1;
4606vinfos[0].foffset = j0;
4607vinfos[0].indices[0] = _ij0[0];
4608vinfos[0].indices[1] = _ij0[1];
4609vinfos[0].maxsolutions = _nj0;
4610vinfos[1].jointtype = 1;
4611vinfos[1].foffset = j1;
4612vinfos[1].indices[0] = _ij1[0];
4613vinfos[1].indices[1] = _ij1[1];
4614vinfos[1].maxsolutions = _nj1;
4615vinfos[2].jointtype = 1;
4616vinfos[2].foffset = j2;
4617vinfos[2].indices[0] = _ij2[0];
4618vinfos[2].indices[1] = _ij2[1];
4619vinfos[2].maxsolutions = _nj2;
4620vinfos[3].jointtype = 1;
4621vinfos[3].foffset = j3;
4622vinfos[3].indices[0] = _ij3[0];
4623vinfos[3].indices[1] = _ij3[1];
4624vinfos[3].maxsolutions = _nj3;
4625vinfos[4].jointtype = 1;
4626vinfos[4].foffset = j4;
4627vinfos[4].indices[0] = _ij4[0];
4628vinfos[4].indices[1] = _ij4[1];
4629vinfos[4].maxsolutions = _nj4;
4630vinfos[5].jointtype = 1;
4631vinfos[5].foffset = j5;
4632vinfos[5].indices[0] = _ij5[0];
4633vinfos[5].indices[1] = _ij5[1];
4634vinfos[5].maxsolutions = _nj5;
4635std::vector<int> vfree(0);
4636solutions.AddSolution(vinfos,vfree);
4637}
4638}
4639}
4640
4641}
4642} while(0);
4643if( bgotonextstatement )
4644{
4645bool bgotonextstatement = true;
4646do
4647{
4648if( 1 )
4649{
4650bgotonextstatement=false;
4651continue; // branch miss [j5]
4652
4653}
4654} while(0);
4655if( bgotonextstatement )
4656{
4657}
4658}
4659}
4660}
4661}
4662
4663} else
4664{
4665{
4666IkReal j5array[1], cj5array[1], sj5array[1];
4667bool j5valid[1]={false};
4668_nj5 = 1;
4669CheckValue<IkReal> x546=IKPowWithIntegerCheck(new_r00,-1);
4670if(!x546.valid){
4671continue;
4672}
4673IkReal x542=x546.value;
4674IkReal x543=gconst7*gconst7;
4675IkReal x544=((25000.0)*new_r10);
4676CheckValue<IkReal> x547=IKPowWithIntegerCheck(((((25000.00002)*gconst8*new_r00))+((gconst7*x544))),-1);
4677if(!x547.valid){
4678continue;
4679}
4680IkReal x545=x547.value;
4681CheckValue<IkReal> x548=IKPowWithIntegerCheck(x542,-2);
4682if(!x548.valid){
4683continue;
4684}
4685if( IKabs((((x542*x543*x544*x545))+(((-1.0)*gconst7*x542))+(((-1.0)*new_r00*x544*x545)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x545*(((((25000.0)*(x548.value)))+(((-25000.0)*x543)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((x542*x543*x544*x545))+(((-1.0)*gconst7*x542))+(((-1.0)*new_r00*x544*x545))))+IKsqr((x545*(((((25000.0)*(x548.value)))+(((-25000.0)*x543))))))-1) <= IKFAST_SINCOS_THRESH )
4686 continue;
4687j5array[0]=IKatan2((((x542*x543*x544*x545))+(((-1.0)*gconst7*x542))+(((-1.0)*new_r00*x544*x545))), (x545*(((((25000.0)*(x548.value)))+(((-25000.0)*x543))))));
4688sj5array[0]=IKsin(j5array[0]);
4689cj5array[0]=IKcos(j5array[0]);
4690if( j5array[0] > IKPI )
4691{
4692 j5array[0]-=IK2PI;
4693}
4694else if( j5array[0] < -IKPI )
4695{ j5array[0]+=IK2PI;
4696}
4697j5valid[0] = true;
4698for(int ij5 = 0; ij5 < 1; ++ij5)
4699{
4700if( !j5valid[ij5] )
4701{
4702 continue;
4703}
4704_ij5[0] = ij5; _ij5[1] = -1;
4705for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4706{
4707if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4708{
4709 j5valid[iij5]=false; _ij5[1] = iij5; break;
4710}
4711}
4712j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4713{
4714IkReal evalcond[10];
4715IkReal x549=IKcos(j5);
4716IkReal x550=IKsin(j5);
4717IkReal x551=((1.0)*gconst8);
4718IkReal x552=((1.0000000008)*gconst7);
4719IkReal x553=((1.0000000008)*gconst8);
4720IkReal x554=(new_r11*x550);
4721IkReal x555=(new_r01*x549);
4722IkReal x556=(new_r00*x549);
4723IkReal x557=(new_r10*x550);
4724evalcond[0]=(gconst7+((new_r10*x549))+((new_r00*x550)));
4725evalcond[1]=(((new_r11*x549))+(((-1.0)*x551))+((new_r01*x550)));
4726evalcond[2]=(((gconst7*x550))+(((-1.0)*x549*x553))+new_r00);
4727evalcond[3]=(((gconst7*x549))+((x550*x553))+new_r10);
4728evalcond[4]=((((-1.0)*x550*x551))+(((-1.0)*x549*x552))+new_r01);
4729evalcond[5]=(((x550*x552))+(((-1.0)*x549*x551))+new_r11);
4730evalcond[6]=((((-1.0)*x557))+(((-1.0)*x553))+x556);
4731evalcond[7]=((((-1.0)*x554))+(((-1.0)*x552))+x555);
4732evalcond[8]=((((-1.0000000008)*x557))+(((-1.0)*x551))+(((1.0000000008)*x556)));
4733evalcond[9]=((((-1.0)*gconst7))+(((-1.0000000008)*x554))+(((1.0000000008)*x555)));
4734if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
4735{
4736continue;
4737}
4738}
4739
4740{
4741std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4742vinfos[0].jointtype = 1;
4743vinfos[0].foffset = j0;
4744vinfos[0].indices[0] = _ij0[0];
4745vinfos[0].indices[1] = _ij0[1];
4746vinfos[0].maxsolutions = _nj0;
4747vinfos[1].jointtype = 1;
4748vinfos[1].foffset = j1;
4749vinfos[1].indices[0] = _ij1[0];
4750vinfos[1].indices[1] = _ij1[1];
4751vinfos[1].maxsolutions = _nj1;
4752vinfos[2].jointtype = 1;
4753vinfos[2].foffset = j2;
4754vinfos[2].indices[0] = _ij2[0];
4755vinfos[2].indices[1] = _ij2[1];
4756vinfos[2].maxsolutions = _nj2;
4757vinfos[3].jointtype = 1;
4758vinfos[3].foffset = j3;
4759vinfos[3].indices[0] = _ij3[0];
4760vinfos[3].indices[1] = _ij3[1];
4761vinfos[3].maxsolutions = _nj3;
4762vinfos[4].jointtype = 1;
4763vinfos[4].foffset = j4;
4764vinfos[4].indices[0] = _ij4[0];
4765vinfos[4].indices[1] = _ij4[1];
4766vinfos[4].maxsolutions = _nj4;
4767vinfos[5].jointtype = 1;
4768vinfos[5].foffset = j5;
4769vinfos[5].indices[0] = _ij5[0];
4770vinfos[5].indices[1] = _ij5[1];
4771vinfos[5].maxsolutions = _nj5;
4772std::vector<int> vfree(0);
4773solutions.AddSolution(vinfos,vfree);
4774}
4775}
4776}
4777
4778}
4779
4780}
4781
4782} else
4783{
4784{
4785IkReal j5array[1], cj5array[1], sj5array[1];
4786bool j5valid[1]={false};
4787_nj5 = 1;
4788IkReal x558=gconst7*gconst7;
4789IkReal x559=new_r10*new_r10;
4790IkReal x560=((625000000.0)*new_r00);
4791IkReal x561=((625000000.5)*gconst8);
4792IkReal x562=((25000.00002)*gconst8);
4793IkReal x563=((25000.0)*new_r00);
4794CheckValue<IkReal> x564=IKPowWithIntegerCheck(((((-625000001.0)*x559*(gconst8*gconst8)))+((new_r00*x558*x560))),-1);
4795if(!x564.valid){
4796continue;
4797}
4798CheckValue<IkReal> x565=IKPowWithIntegerCheck((((gconst7*x563))+(((-1.0)*new_r10*x562))),-1);
4799if(!x565.valid){
4800continue;
4801}
4802if( IKabs(((x564.value)*((((x561*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x558*x561))+((gconst7*x559*x560))+(((-1.0)*x560*(gconst7*gconst7*gconst7))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x565.value)*((((gconst7*x562))+(((-1.0)*new_r10*x563)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x564.value)*((((x561*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x558*x561))+((gconst7*x559*x560))+(((-1.0)*x560*(gconst7*gconst7*gconst7)))))))+IKsqr(((x565.value)*((((gconst7*x562))+(((-1.0)*new_r10*x563))))))-1) <= IKFAST_SINCOS_THRESH )
4803 continue;
4804j5array[0]=IKatan2(((x564.value)*((((x561*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x558*x561))+((gconst7*x559*x560))+(((-1.0)*x560*(gconst7*gconst7*gconst7)))))), ((x565.value)*((((gconst7*x562))+(((-1.0)*new_r10*x563))))));
4805sj5array[0]=IKsin(j5array[0]);
4806cj5array[0]=IKcos(j5array[0]);
4807if( j5array[0] > IKPI )
4808{
4809 j5array[0]-=IK2PI;
4810}
4811else if( j5array[0] < -IKPI )
4812{ j5array[0]+=IK2PI;
4813}
4814j5valid[0] = true;
4815for(int ij5 = 0; ij5 < 1; ++ij5)
4816{
4817if( !j5valid[ij5] )
4818{
4819 continue;
4820}
4821_ij5[0] = ij5; _ij5[1] = -1;
4822for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4823{
4824if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4825{
4826 j5valid[iij5]=false; _ij5[1] = iij5; break;
4827}
4828}
4829j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4830{
4831IkReal evalcond[10];
4832IkReal x566=IKcos(j5);
4833IkReal x567=IKsin(j5);
4834IkReal x568=((1.0)*gconst8);
4835IkReal x569=((1.0000000008)*gconst7);
4836IkReal x570=((1.0000000008)*gconst8);
4837IkReal x571=(new_r11*x567);
4838IkReal x572=(new_r01*x566);
4839IkReal x573=(new_r00*x566);
4840IkReal x574=(new_r10*x567);
4841evalcond[0]=(gconst7+((new_r00*x567))+((new_r10*x566)));
4842evalcond[1]=(((new_r01*x567))+((new_r11*x566))+(((-1.0)*x568)));
4843evalcond[2]=((((-1.0)*x566*x570))+new_r00+((gconst7*x567)));
4844evalcond[3]=(((x567*x570))+new_r10+((gconst7*x566)));
4845evalcond[4]=((((-1.0)*x566*x569))+(((-1.0)*x567*x568))+new_r01);
4846evalcond[5]=((((-1.0)*x566*x568))+((x567*x569))+new_r11);
4847evalcond[6]=((((-1.0)*x574))+(((-1.0)*x570))+x573);
4848evalcond[7]=((((-1.0)*x571))+x572+(((-1.0)*x569)));
4849evalcond[8]=((((-1.0000000008)*x574))+(((1.0000000008)*x573))+(((-1.0)*x568)));
4850evalcond[9]=((((-1.0000000008)*x571))+(((1.0000000008)*x572))+(((-1.0)*gconst7)));
4851if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
4852{
4853continue;
4854}
4855}
4856
4857{
4858std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4859vinfos[0].jointtype = 1;
4860vinfos[0].foffset = j0;
4861vinfos[0].indices[0] = _ij0[0];
4862vinfos[0].indices[1] = _ij0[1];
4863vinfos[0].maxsolutions = _nj0;
4864vinfos[1].jointtype = 1;
4865vinfos[1].foffset = j1;
4866vinfos[1].indices[0] = _ij1[0];
4867vinfos[1].indices[1] = _ij1[1];
4868vinfos[1].maxsolutions = _nj1;
4869vinfos[2].jointtype = 1;
4870vinfos[2].foffset = j2;
4871vinfos[2].indices[0] = _ij2[0];
4872vinfos[2].indices[1] = _ij2[1];
4873vinfos[2].maxsolutions = _nj2;
4874vinfos[3].jointtype = 1;
4875vinfos[3].foffset = j3;
4876vinfos[3].indices[0] = _ij3[0];
4877vinfos[3].indices[1] = _ij3[1];
4878vinfos[3].maxsolutions = _nj3;
4879vinfos[4].jointtype = 1;
4880vinfos[4].foffset = j4;
4881vinfos[4].indices[0] = _ij4[0];
4882vinfos[4].indices[1] = _ij4[1];
4883vinfos[4].maxsolutions = _nj4;
4884vinfos[5].jointtype = 1;
4885vinfos[5].foffset = j5;
4886vinfos[5].indices[0] = _ij5[0];
4887vinfos[5].indices[1] = _ij5[1];
4888vinfos[5].maxsolutions = _nj5;
4889std::vector<int> vfree(0);
4890solutions.AddSolution(vinfos,vfree);
4891}
4892}
4893}
4894
4895}
4896
4897}
4898
4899} else
4900{
4901{
4902IkReal j5array[1], cj5array[1], sj5array[1];
4903bool j5valid[1]={false};
4904_nj5 = 1;
4905IkReal x575=((1.0)*new_r00);
4906CheckValue<IkReal> x576 = IKatan2WithCheck(IkReal((((gconst8*new_r10))+((gconst7*new_r11)))),IkReal(((((-1.0)*gconst7*new_r01))+(((-1.0)*gconst8*x575)))),IKFAST_ATAN2_MAGTHRESH);
4907if(!x576.valid){
4908continue;
4909}
4910CheckValue<IkReal> x577=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x575))+((new_r01*new_r10)))),-1);
4911if(!x577.valid){
4912continue;
4913}
4914j5array[0]=((-1.5707963267949)+(x576.value)+(((1.5707963267949)*(x577.value))));
4915sj5array[0]=IKsin(j5array[0]);
4916cj5array[0]=IKcos(j5array[0]);
4917if( j5array[0] > IKPI )
4918{
4919 j5array[0]-=IK2PI;
4920}
4921else if( j5array[0] < -IKPI )
4922{ j5array[0]+=IK2PI;
4923}
4924j5valid[0] = true;
4925for(int ij5 = 0; ij5 < 1; ++ij5)
4926{
4927if( !j5valid[ij5] )
4928{
4929 continue;
4930}
4931_ij5[0] = ij5; _ij5[1] = -1;
4932for(int iij5 = ij5+1; iij5 < 1; ++iij5)
4933{
4934if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
4935{
4936 j5valid[iij5]=false; _ij5[1] = iij5; break;
4937}
4938}
4939j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
4940{
4941IkReal evalcond[10];
4942IkReal x578=IKcos(j5);
4943IkReal x579=IKsin(j5);
4944IkReal x580=((1.0)*gconst8);
4945IkReal x581=((1.0000000008)*gconst7);
4946IkReal x582=((1.0000000008)*gconst8);
4947IkReal x583=(new_r11*x579);
4948IkReal x584=(new_r01*x578);
4949IkReal x585=(new_r00*x578);
4950IkReal x586=(new_r10*x579);
4951evalcond[0]=(((new_r00*x579))+((new_r10*x578))+gconst7);
4952evalcond[1]=(((new_r11*x578))+((new_r01*x579))+(((-1.0)*x580)));
4953evalcond[2]=((((-1.0)*x578*x582))+((gconst7*x579))+new_r00);
4954evalcond[3]=(((x579*x582))+((gconst7*x578))+new_r10);
4955evalcond[4]=((((-1.0)*x578*x581))+(((-1.0)*x579*x580))+new_r01);
4956evalcond[5]=(((x579*x581))+(((-1.0)*x578*x580))+new_r11);
4957evalcond[6]=((((-1.0)*x586))+x585+(((-1.0)*x582)));
4958evalcond[7]=((((-1.0)*x583))+x584+(((-1.0)*x581)));
4959evalcond[8]=((((1.0000000008)*x585))+(((-1.0)*x580))+(((-1.0000000008)*x586)));
4960evalcond[9]=((((1.0000000008)*x584))+(((-1.0)*gconst7))+(((-1.0000000008)*x583)));
4961if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
4962{
4963continue;
4964}
4965}
4966
4967{
4968std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4969vinfos[0].jointtype = 1;
4970vinfos[0].foffset = j0;
4971vinfos[0].indices[0] = _ij0[0];
4972vinfos[0].indices[1] = _ij0[1];
4973vinfos[0].maxsolutions = _nj0;
4974vinfos[1].jointtype = 1;
4975vinfos[1].foffset = j1;
4976vinfos[1].indices[0] = _ij1[0];
4977vinfos[1].indices[1] = _ij1[1];
4978vinfos[1].maxsolutions = _nj1;
4979vinfos[2].jointtype = 1;
4980vinfos[2].foffset = j2;
4981vinfos[2].indices[0] = _ij2[0];
4982vinfos[2].indices[1] = _ij2[1];
4983vinfos[2].maxsolutions = _nj2;
4984vinfos[3].jointtype = 1;
4985vinfos[3].foffset = j3;
4986vinfos[3].indices[0] = _ij3[0];
4987vinfos[3].indices[1] = _ij3[1];
4988vinfos[3].maxsolutions = _nj3;
4989vinfos[4].jointtype = 1;
4990vinfos[4].foffset = j4;
4991vinfos[4].indices[0] = _ij4[0];
4992vinfos[4].indices[1] = _ij4[1];
4993vinfos[4].maxsolutions = _nj4;
4994vinfos[5].jointtype = 1;
4995vinfos[5].foffset = j5;
4996vinfos[5].indices[0] = _ij5[0];
4997vinfos[5].indices[1] = _ij5[1];
4998vinfos[5].maxsolutions = _nj5;
4999std::vector<int> vfree(0);
5000solutions.AddSolution(vinfos,vfree);
5001}
5002}
5003}
5004
5005}
5006
5007}
5008
5009}
5010} while(0);
5011if( bgotonextstatement )
5012{
5013bool bgotonextstatement = true;
5014do
5015{
5016IkReal x588 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
5017if(IKabs(x588)==0){
5018continue;
5019}
5020IkReal x587=pow(x588,-0.5);
5021CheckValue<IkReal> x589 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5022if(!x589.valid){
5023continue;
5024}
5025IkReal gconst9=((3.14159265358979)+(((-1.0)*(x589.value))));
5026IkReal gconst10=((1.0)*new_r10*x587);
5027IkReal gconst11=((1.0000000008)*new_r00*x587);
5028CheckValue<IkReal> x590 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5029if(!x590.valid){
5030continue;
5031}
5032evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x590.value)+j3)))), 6.28318530717959)));
5033if( IKabs(evalcond[0]) < 0.0000050000000000 )
5034{
5035bgotonextstatement=false;
5036{
5037IkReal j5eval[2];
5038IkReal x591=x587;
5039sj4=4.0e-5;
5040cj4=1.0;
5041j4=4.0e-5;
5042sj3=gconst10;
5043cj3=gconst11;
5044CheckValue<IkReal> x592 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5045if(!x592.valid){
5046continue;
5047}
5048j3=((3.14159265)+(((-1.0)*(x592.value))));
5049CheckValue<IkReal> x593 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5050if(!x593.valid){
5051continue;
5052}
5053IkReal gconst9=((3.14159265358979)+(((-1.0)*(x593.value))));
5054IkReal gconst10=((1.0)*new_r10*x591);
5055IkReal gconst11=((1.0000000008)*new_r00*x591);
5056IkReal x594=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
5057j5eval[0]=x594;
5058j5eval[1]=IKsign(x594);
5059if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
5060{
5061{
5062IkReal j5eval[2];
5063IkReal x595=x587;
5064sj4=4.0e-5;
5065cj4=1.0;
5066j4=4.0e-5;
5067sj3=gconst10;
5068cj3=gconst11;
5069CheckValue<IkReal> x596 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5070if(!x596.valid){
5071continue;
5072}
5073j3=((3.14159265)+(((-1.0)*(x596.value))));
5074CheckValue<IkReal> x597 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5075if(!x597.valid){
5076continue;
5077}
5078IkReal gconst9=((3.14159265358979)+(((-1.0)*(x597.value))));
5079IkReal gconst10=((1.0)*new_r10*x595);
5080IkReal gconst11=((1.0000000008)*new_r00*x595);
5081IkReal x598=new_r00*new_r00;
5082IkReal x599=new_r10*new_r10;
5083IkReal x600=((((1.0000000016)*x598))+x599);
5084CheckValue<IkReal> x601=IKPowWithIntegerCheck(x600,-1);
5085if(!x601.valid){
5086continue;
5087}
5088j5eval[0]=((-3.20000004272458e-9)*x598*x599*(x601.value));
5089IkReal x602 = x600;
5090if(IKabs(x602)==0){
5091continue;
5092}
5093j5eval[1]=((-1.60000013238459e-9)*new_r00*new_r10*(pow(x602,-0.5)));
5094if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
5095{
5096{
5097IkReal j5eval[1];
5098IkReal x603=x587;
5099sj4=4.0e-5;
5100cj4=1.0;
5101j4=4.0e-5;
5102sj3=gconst10;
5103cj3=gconst11;
5104CheckValue<IkReal> x604 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5105if(!x604.valid){
5106continue;
5107}
5108j3=((3.14159265)+(((-1.0)*(x604.value))));
5109CheckValue<IkReal> x605 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5110if(!x605.valid){
5111continue;
5112}
5113IkReal gconst9=((3.14159265358979)+(((-1.0)*(x605.value))));
5114IkReal gconst10=((1.0)*new_r10*x603);
5115IkReal gconst11=((1.0000000008)*new_r00*x603);
5116j5eval[0]=new_r00;
5117if( IKabs(j5eval[0]) < 0.0000010000000000 )
5118{
5119{
5120IkReal evalcond[1];
5121bool bgotonextstatement = true;
5122do
5123{
5124evalcond[0]=IKabs(new_r00);
5125if( IKabs(evalcond[0]) < 0.0000050000000000 )
5126{
5127bgotonextstatement=false;
5128{
5129IkReal j5eval[1];
5130CheckValue<IkReal> x607 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
5131if(!x607.valid){
5132continue;
5133}
5134IkReal x606=((1.0)*(x607.value));
5135sj4=4.0e-5;
5136cj4=1.0;
5137j4=4.0e-5;
5138sj3=gconst10;
5139cj3=gconst11;
5140j3=((3.14159265)+(((-1.0)*x606)));
5141new_r00=0;
5142IkReal gconst9=((3.14159265358979)+(((-1.0)*x606)));
5143IkReal x608 = new_r10*new_r10;
5144if(IKabs(x608)==0){
5145continue;
5146}
5147IkReal gconst10=((1.0)*new_r10*(pow(x608,-0.5)));
5148IkReal gconst11=0;
5149j5eval[0]=new_r10;
5150if( IKabs(j5eval[0]) < 0.0000010000000000 )
5151{
5152{
5153IkReal j5array[1], cj5array[1], sj5array[1];
5154bool j5valid[1]={false};
5155_nj5 = 1;
5156CheckValue<IkReal> x610=IKPowWithIntegerCheck(gconst10,-1);
5157if(!x610.valid){
5158continue;
5159}
5160IkReal x609=x610.value;
5161if( IKabs(((-0.9999999992)*new_r11*x609)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x609)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*x609))+IKsqr(((-1.0)*new_r10*x609))-1) <= IKFAST_SINCOS_THRESH )
5162 continue;
5163j5array[0]=IKatan2(((-0.9999999992)*new_r11*x609), ((-1.0)*new_r10*x609));
5164sj5array[0]=IKsin(j5array[0]);
5165cj5array[0]=IKcos(j5array[0]);
5166if( j5array[0] > IKPI )
5167{
5168 j5array[0]-=IK2PI;
5169}
5170else if( j5array[0] < -IKPI )
5171{ j5array[0]+=IK2PI;
5172}
5173j5valid[0] = true;
5174for(int ij5 = 0; ij5 < 1; ++ij5)
5175{
5176if( !j5valid[ij5] )
5177{
5178 continue;
5179}
5180_ij5[0] = ij5; _ij5[1] = -1;
5181for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5182{
5183if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5184{
5185 j5valid[iij5]=false; _ij5[1] = iij5; break;
5186}
5187}
5188j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5189{
5190IkReal evalcond[10];
5191IkReal x611=IKsin(j5);
5192IkReal x612=IKcos(j5);
5193IkReal x613=(gconst10*x612);
5194IkReal x614=(gconst10*x611);
5195IkReal x615=(new_r01*x612);
5196IkReal x616=(new_r11*x611);
5197IkReal x617=(new_r10*x611);
5198evalcond[0]=x614;
5199evalcond[1]=((-1.0)*x617);
5200evalcond[2]=(gconst10+((new_r10*x612)));
5201evalcond[3]=(x613+new_r10);
5202evalcond[4]=((-1.0000000008)*x617);
5203evalcond[5]=(((new_r11*x612))+((new_r01*x611)));
5204evalcond[6]=((((-1.0000000008)*x613))+new_r01);
5205evalcond[7]=(new_r11+(((1.0000000008)*x614)));
5206evalcond[8]=((((-1.0000000008)*gconst10))+(((-1.0)*x616))+x615);
5207evalcond[9]=((((-1.0000000008)*x616))+(((-1.0)*gconst10))+(((1.0000000008)*x615)));
5208if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
5209{
5210continue;
5211}
5212}
5213
5214{
5215std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5216vinfos[0].jointtype = 1;
5217vinfos[0].foffset = j0;
5218vinfos[0].indices[0] = _ij0[0];
5219vinfos[0].indices[1] = _ij0[1];
5220vinfos[0].maxsolutions = _nj0;
5221vinfos[1].jointtype = 1;
5222vinfos[1].foffset = j1;
5223vinfos[1].indices[0] = _ij1[0];
5224vinfos[1].indices[1] = _ij1[1];
5225vinfos[1].maxsolutions = _nj1;
5226vinfos[2].jointtype = 1;
5227vinfos[2].foffset = j2;
5228vinfos[2].indices[0] = _ij2[0];
5229vinfos[2].indices[1] = _ij2[1];
5230vinfos[2].maxsolutions = _nj2;
5231vinfos[3].jointtype = 1;
5232vinfos[3].foffset = j3;
5233vinfos[3].indices[0] = _ij3[0];
5234vinfos[3].indices[1] = _ij3[1];
5235vinfos[3].maxsolutions = _nj3;
5236vinfos[4].jointtype = 1;
5237vinfos[4].foffset = j4;
5238vinfos[4].indices[0] = _ij4[0];
5239vinfos[4].indices[1] = _ij4[1];
5240vinfos[4].maxsolutions = _nj4;
5241vinfos[5].jointtype = 1;
5242vinfos[5].foffset = j5;
5243vinfos[5].indices[0] = _ij5[0];
5244vinfos[5].indices[1] = _ij5[1];
5245vinfos[5].maxsolutions = _nj5;
5246std::vector<int> vfree(0);
5247solutions.AddSolution(vinfos,vfree);
5248}
5249}
5250}
5251
5252} else
5253{
5254{
5255IkReal j5array[1], cj5array[1], sj5array[1];
5256bool j5valid[1]={false};
5257_nj5 = 1;
5258CheckValue<IkReal> x618=IKPowWithIntegerCheck(gconst10,-1);
5259if(!x618.valid){
5260continue;
5261}
5262CheckValue<IkReal> x619=IKPowWithIntegerCheck(new_r10,-1);
5263if(!x619.valid){
5264continue;
5265}
5266if( IKabs(((-0.9999999992)*new_r11*(x618.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst10*(x619.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*(x618.value)))+IKsqr(((-1.0)*gconst10*(x619.value)))-1) <= IKFAST_SINCOS_THRESH )
5267 continue;
5268j5array[0]=IKatan2(((-0.9999999992)*new_r11*(x618.value)), ((-1.0)*gconst10*(x619.value)));
5269sj5array[0]=IKsin(j5array[0]);
5270cj5array[0]=IKcos(j5array[0]);
5271if( j5array[0] > IKPI )
5272{
5273 j5array[0]-=IK2PI;
5274}
5275else if( j5array[0] < -IKPI )
5276{ j5array[0]+=IK2PI;
5277}
5278j5valid[0] = true;
5279for(int ij5 = 0; ij5 < 1; ++ij5)
5280{
5281if( !j5valid[ij5] )
5282{
5283 continue;
5284}
5285_ij5[0] = ij5; _ij5[1] = -1;
5286for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5287{
5288if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5289{
5290 j5valid[iij5]=false; _ij5[1] = iij5; break;
5291}
5292}
5293j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5294{
5295IkReal evalcond[10];
5296IkReal x620=IKsin(j5);
5297IkReal x621=IKcos(j5);
5298IkReal x622=(gconst10*x621);
5299IkReal x623=(gconst10*x620);
5300IkReal x624=(new_r01*x621);
5301IkReal x625=(new_r11*x620);
5302IkReal x626=(new_r10*x620);
5303evalcond[0]=x623;
5304evalcond[1]=((-1.0)*x626);
5305evalcond[2]=(gconst10+((new_r10*x621)));
5306evalcond[3]=(x622+new_r10);
5307evalcond[4]=((-1.0000000008)*x626);
5308evalcond[5]=(((new_r01*x620))+((new_r11*x621)));
5309evalcond[6]=((((-1.0000000008)*x622))+new_r01);
5310evalcond[7]=((((1.0000000008)*x623))+new_r11);
5311evalcond[8]=((((-1.0000000008)*gconst10))+x624+(((-1.0)*x625)));
5312evalcond[9]=((((1.0000000008)*x624))+(((-1.0000000008)*x625))+(((-1.0)*gconst10)));
5313if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
5314{
5315continue;
5316}
5317}
5318
5319{
5320std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5321vinfos[0].jointtype = 1;
5322vinfos[0].foffset = j0;
5323vinfos[0].indices[0] = _ij0[0];
5324vinfos[0].indices[1] = _ij0[1];
5325vinfos[0].maxsolutions = _nj0;
5326vinfos[1].jointtype = 1;
5327vinfos[1].foffset = j1;
5328vinfos[1].indices[0] = _ij1[0];
5329vinfos[1].indices[1] = _ij1[1];
5330vinfos[1].maxsolutions = _nj1;
5331vinfos[2].jointtype = 1;
5332vinfos[2].foffset = j2;
5333vinfos[2].indices[0] = _ij2[0];
5334vinfos[2].indices[1] = _ij2[1];
5335vinfos[2].maxsolutions = _nj2;
5336vinfos[3].jointtype = 1;
5337vinfos[3].foffset = j3;
5338vinfos[3].indices[0] = _ij3[0];
5339vinfos[3].indices[1] = _ij3[1];
5340vinfos[3].maxsolutions = _nj3;
5341vinfos[4].jointtype = 1;
5342vinfos[4].foffset = j4;
5343vinfos[4].indices[0] = _ij4[0];
5344vinfos[4].indices[1] = _ij4[1];
5345vinfos[4].maxsolutions = _nj4;
5346vinfos[5].jointtype = 1;
5347vinfos[5].foffset = j5;
5348vinfos[5].indices[0] = _ij5[0];
5349vinfos[5].indices[1] = _ij5[1];
5350vinfos[5].maxsolutions = _nj5;
5351std::vector<int> vfree(0);
5352solutions.AddSolution(vinfos,vfree);
5353}
5354}
5355}
5356
5357}
5358
5359}
5360
5361}
5362} while(0);
5363if( bgotonextstatement )
5364{
5365bool bgotonextstatement = true;
5366do
5367{
5368evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
5369if( IKabs(evalcond[0]) < 0.0000050000000000 )
5370{
5371bgotonextstatement=false;
5372{
5373IkReal j5eval[3];
5374IkReal x628 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
5375if(IKabs(x628)==0){
5376continue;
5377}
5378IkReal x627=pow(x628,-0.5);
5379sj4=4.0e-5;
5380cj4=1.0;
5381j4=4.0e-5;
5382sj3=gconst10;
5383cj3=gconst11;
5384CheckValue<IkReal> x629 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5385if(!x629.valid){
5386continue;
5387}
5388j3=((3.14159265)+(((-1.0)*(x629.value))));
5389new_r11=0;
5390new_r01=0;
5391new_r22=0;
5392new_r20=0;
5393CheckValue<IkReal> x630 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5394if(!x630.valid){
5395continue;
5396}
5397IkReal gconst9=((3.14159265358979)+(((-1.0)*(x630.value))));
5398IkReal gconst10=((1.0)*new_r10*x627);
5399IkReal gconst11=((1.0000000008)*new_r00*x627);
5400IkReal x631=new_r10*new_r10;
5401CheckValue<IkReal> x635=IKPowWithIntegerCheck(((-3.90625000625e+17)+(((625000000.0)*x631))),-1);
5402if(!x635.valid){
5403continue;
5404}
5405IkReal x632=x635.value;
5406if((((625000001.0)+(((-1.0)*x631)))) < -0.00001)
5407continue;
5408IkReal x633=IKsqrt(((625000001.0)+(((-1.0)*x631))));
5409IkReal x634=(x632*x633);
5410j5eval[0]=-1.0;
5411j5eval[1]=-1.0;
5412IkReal x636 = ((1.0000000016)+(((-1.6e-9)*x631)));
5413if(IKabs(x636)==0){
5414continue;
5415}
5416j5eval[2]=((IKabs(((((-7.81250000625e+17)*x631*x634))+(((3.90625000625e+17)*x634)))))+(IKabs(((50000.00004)*new_r00*new_r10*(pow(x636,-0.5))))));
5417if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
5418{
5419{
5420IkReal j5eval[1];
5421IkReal x638 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
5422if(IKabs(x638)==0){
5423continue;
5424}
5425IkReal x637=pow(x638,-0.5);
5426sj4=4.0e-5;
5427cj4=1.0;
5428j4=4.0e-5;
5429sj3=gconst10;
5430cj3=gconst11;
5431CheckValue<IkReal> x639 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5432if(!x639.valid){
5433continue;
5434}
5435j3=((3.14159265)+(((-1.0)*(x639.value))));
5436new_r11=0;
5437new_r01=0;
5438new_r22=0;
5439new_r20=0;
5440CheckValue<IkReal> x640 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5441if(!x640.valid){
5442continue;
5443}
5444IkReal gconst9=((3.14159265358979)+(((-1.0)*(x640.value))));
5445IkReal gconst10=((1.0)*new_r10*x637);
5446IkReal gconst11=((1.0000000008)*new_r00*x637);
5447IkReal x641=new_r10*new_r10;
5448CheckValue<IkReal> x643=IKPowWithIntegerCheck(((1.0000000016)+(((-1.6e-9)*x641))),-1);
5449if(!x643.valid){
5450continue;
5451}
5452IkReal x642=x643.value;
5453IkReal x644=((1.0)+(((-1.0)*x641)));
5454j5eval[0]=IKsign(((((625000001.0)*x642*(x641*x641)))+(((-625000001.0)*x642*(x644*x644)))));
5455if( IKabs(j5eval[0]) < 0.0000010000000000 )
5456{
5457{
5458IkReal j5eval[2];
5459IkReal x646 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
5460if(IKabs(x646)==0){
5461continue;
5462}
5463IkReal x645=pow(x646,-0.5);
5464sj4=4.0e-5;
5465cj4=1.0;
5466j4=4.0e-5;
5467sj3=gconst10;
5468cj3=gconst11;
5469CheckValue<IkReal> x647 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5470if(!x647.valid){
5471continue;
5472}
5473j3=((3.14159265)+(((-1.0)*(x647.value))));
5474new_r11=0;
5475new_r01=0;
5476new_r22=0;
5477new_r20=0;
5478CheckValue<IkReal> x648 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5479if(!x648.valid){
5480continue;
5481}
5482IkReal gconst9=((3.14159265358979)+(((-1.0)*(x648.value))));
5483IkReal gconst10=((1.0)*new_r10*x645);
5484IkReal gconst11=((1.0000000008)*new_r00*x645);
5485IkReal x649=new_r10*new_r10;
5486IkReal x650=((1.0000000016)+(((-1.6e-9)*x649)));
5487CheckValue<IkReal> x651=IKPowWithIntegerCheck(x650,-1);
5488if(!x651.valid){
5489continue;
5490}
5491j5eval[0]=((-3.20000004272458e-9)*x649*(x651.value)*(((1.0)+(((-1.0)*x649)))));
5492IkReal x652 = x650;
5493if(IKabs(x652)==0){
5494continue;
5495}
5496j5eval[1]=((-1.60000013238459e-9)*new_r00*new_r10*(pow(x652,-0.5)));
5497if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
5498{
5499continue; // 3 cases reached
5500
5501} else
5502{
5503{
5504IkReal j5array[1], cj5array[1], sj5array[1];
5505bool j5valid[1]={false};
5506_nj5 = 1;
5507IkReal x653=gconst10*gconst10;
5508IkReal x654=new_r10*new_r10;
5509IkReal x655=((25000.00002)*gconst11);
5510IkReal x656=(gconst10*new_r00);
5511IkReal x657=((625000000.5)*gconst11);
5512CheckValue<IkReal> x658=IKPowWithIntegerCheck(((((625000000.0)*x653*(new_r00*new_r00)))+(((-625000001.0)*x654*(gconst11*gconst11)))),-1);
5513if(!x658.valid){
5514continue;
5515}
5516CheckValue<IkReal> x659=IKPowWithIntegerCheck(((((-1.0)*new_r10*x655))+(((25000.0)*x656))),-1);
5517if(!x659.valid){
5518continue;
5519}
5520if( IKabs(((x658.value)*((((x657*(new_r10*new_r10*new_r10)))+(((625000000.0)*x654*x656))+(((-625000000.0)*x656*(gconst10*gconst10)))+(((-1.0)*new_r10*x653*x657)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x659.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x655)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x658.value)*((((x657*(new_r10*new_r10*new_r10)))+(((625000000.0)*x654*x656))+(((-625000000.0)*x656*(gconst10*gconst10)))+(((-1.0)*new_r10*x653*x657))))))+IKsqr(((x659.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x655))))))-1) <= IKFAST_SINCOS_THRESH )
5521 continue;
5522j5array[0]=IKatan2(((x658.value)*((((x657*(new_r10*new_r10*new_r10)))+(((625000000.0)*x654*x656))+(((-625000000.0)*x656*(gconst10*gconst10)))+(((-1.0)*new_r10*x653*x657))))), ((x659.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x655))))));
5523sj5array[0]=IKsin(j5array[0]);
5524cj5array[0]=IKcos(j5array[0]);
5525if( j5array[0] > IKPI )
5526{
5527 j5array[0]-=IK2PI;
5528}
5529else if( j5array[0] < -IKPI )
5530{ j5array[0]+=IK2PI;
5531}
5532j5valid[0] = true;
5533for(int ij5 = 0; ij5 < 1; ++ij5)
5534{
5535if( !j5valid[ij5] )
5536{
5537 continue;
5538}
5539_ij5[0] = ij5; _ij5[1] = -1;
5540for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5541{
5542if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5543{
5544 j5valid[iij5]=false; _ij5[1] = iij5; break;
5545}
5546}
5547j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5548{
5549IkReal evalcond[7];
5550IkReal x660=IKsin(j5);
5551IkReal x661=IKcos(j5);
5552IkReal x662=(gconst11*x661);
5553IkReal x663=((1.0000000008)*x660);
5554IkReal x664=(gconst10*x661);
5555IkReal x665=((1.0)*x660);
5556IkReal x666=(new_r00*x661);
5557evalcond[0]=(gconst10+((new_r10*x661))+((new_r00*x660)));
5558evalcond[1]=((((-1.0000000008)*x662))+new_r00+((gconst10*x660)));
5559evalcond[2]=(x664+new_r10+((gconst11*x663)));
5560evalcond[3]=((((-1.0000000008)*x664))+(((-1.0)*gconst11*x665)));
5561evalcond[4]=((((-1.0)*x662))+((gconst10*x663)));
5562evalcond[5]=((((-1.0)*new_r10*x665))+(((-1.0000000008)*gconst11))+x666);
5563evalcond[6]=((((1.0000000008)*x666))+(((-1.0)*new_r10*x663))+(((-1.0)*gconst11)));
5564if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
5565{
5566continue;
5567}
5568}
5569
5570{
5571std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5572vinfos[0].jointtype = 1;
5573vinfos[0].foffset = j0;
5574vinfos[0].indices[0] = _ij0[0];
5575vinfos[0].indices[1] = _ij0[1];
5576vinfos[0].maxsolutions = _nj0;
5577vinfos[1].jointtype = 1;
5578vinfos[1].foffset = j1;
5579vinfos[1].indices[0] = _ij1[0];
5580vinfos[1].indices[1] = _ij1[1];
5581vinfos[1].maxsolutions = _nj1;
5582vinfos[2].jointtype = 1;
5583vinfos[2].foffset = j2;
5584vinfos[2].indices[0] = _ij2[0];
5585vinfos[2].indices[1] = _ij2[1];
5586vinfos[2].maxsolutions = _nj2;
5587vinfos[3].jointtype = 1;
5588vinfos[3].foffset = j3;
5589vinfos[3].indices[0] = _ij3[0];
5590vinfos[3].indices[1] = _ij3[1];
5591vinfos[3].maxsolutions = _nj3;
5592vinfos[4].jointtype = 1;
5593vinfos[4].foffset = j4;
5594vinfos[4].indices[0] = _ij4[0];
5595vinfos[4].indices[1] = _ij4[1];
5596vinfos[4].maxsolutions = _nj4;
5597vinfos[5].jointtype = 1;
5598vinfos[5].foffset = j5;
5599vinfos[5].indices[0] = _ij5[0];
5600vinfos[5].indices[1] = _ij5[1];
5601vinfos[5].maxsolutions = _nj5;
5602std::vector<int> vfree(0);
5603solutions.AddSolution(vinfos,vfree);
5604}
5605}
5606}
5607
5608}
5609
5610}
5611
5612} else
5613{
5614{
5615IkReal j5array[1], cj5array[1], sj5array[1];
5616bool j5valid[1]={false};
5617_nj5 = 1;
5618IkReal x667=gconst10*gconst10;
5619IkReal x668=gconst11*gconst11;
5620IkReal x669=((625000000.0)*x668);
5621IkReal x670=((625000000.5)*gconst11*x667);
5622CheckValue<IkReal> x671 = IKatan2WithCheck(IkReal((((gconst10*new_r00*x669))+(((-1.0)*new_r10*x670)))),IkReal((((new_r00*x670))+(((-625000001.0)*new_r10*(gconst10*gconst10*gconst10))))),IKFAST_ATAN2_MAGTHRESH);
5623if(!x671.valid){
5624continue;
5625}
5626CheckValue<IkReal> x672=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x667*(new_r10*new_r10)))+(((-1.0)*x669*(new_r00*new_r00))))),-1);
5627if(!x672.valid){
5628continue;
5629}
5630j5array[0]=((-1.5707963267949)+(x671.value)+(((1.5707963267949)*(x672.value))));
5631sj5array[0]=IKsin(j5array[0]);
5632cj5array[0]=IKcos(j5array[0]);
5633if( j5array[0] > IKPI )
5634{
5635 j5array[0]-=IK2PI;
5636}
5637else if( j5array[0] < -IKPI )
5638{ j5array[0]+=IK2PI;
5639}
5640j5valid[0] = true;
5641for(int ij5 = 0; ij5 < 1; ++ij5)
5642{
5643if( !j5valid[ij5] )
5644{
5645 continue;
5646}
5647_ij5[0] = ij5; _ij5[1] = -1;
5648for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5649{
5650if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5651{
5652 j5valid[iij5]=false; _ij5[1] = iij5; break;
5653}
5654}
5655j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5656{
5657IkReal evalcond[7];
5658IkReal x673=IKsin(j5);
5659IkReal x674=IKcos(j5);
5660IkReal x675=(gconst11*x674);
5661IkReal x676=((1.0000000008)*x673);
5662IkReal x677=(gconst10*x674);
5663IkReal x678=((1.0)*x673);
5664IkReal x679=(new_r00*x674);
5665evalcond[0]=(((new_r00*x673))+((new_r10*x674))+gconst10);
5666evalcond[1]=(((gconst10*x673))+new_r00+(((-1.0000000008)*x675)));
5667evalcond[2]=(((gconst11*x676))+x677+new_r10);
5668evalcond[3]=((((-1.0)*gconst11*x678))+(((-1.0000000008)*x677)));
5669evalcond[4]=(((gconst10*x676))+(((-1.0)*x675)));
5670evalcond[5]=((((-1.0000000008)*gconst11))+x679+(((-1.0)*new_r10*x678)));
5671evalcond[6]=((((1.0000000008)*x679))+(((-1.0)*gconst11))+(((-1.0)*new_r10*x676)));
5672if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
5673{
5674continue;
5675}
5676}
5677
5678{
5679std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5680vinfos[0].jointtype = 1;
5681vinfos[0].foffset = j0;
5682vinfos[0].indices[0] = _ij0[0];
5683vinfos[0].indices[1] = _ij0[1];
5684vinfos[0].maxsolutions = _nj0;
5685vinfos[1].jointtype = 1;
5686vinfos[1].foffset = j1;
5687vinfos[1].indices[0] = _ij1[0];
5688vinfos[1].indices[1] = _ij1[1];
5689vinfos[1].maxsolutions = _nj1;
5690vinfos[2].jointtype = 1;
5691vinfos[2].foffset = j2;
5692vinfos[2].indices[0] = _ij2[0];
5693vinfos[2].indices[1] = _ij2[1];
5694vinfos[2].maxsolutions = _nj2;
5695vinfos[3].jointtype = 1;
5696vinfos[3].foffset = j3;
5697vinfos[3].indices[0] = _ij3[0];
5698vinfos[3].indices[1] = _ij3[1];
5699vinfos[3].maxsolutions = _nj3;
5700vinfos[4].jointtype = 1;
5701vinfos[4].foffset = j4;
5702vinfos[4].indices[0] = _ij4[0];
5703vinfos[4].indices[1] = _ij4[1];
5704vinfos[4].maxsolutions = _nj4;
5705vinfos[5].jointtype = 1;
5706vinfos[5].foffset = j5;
5707vinfos[5].indices[0] = _ij5[0];
5708vinfos[5].indices[1] = _ij5[1];
5709vinfos[5].maxsolutions = _nj5;
5710std::vector<int> vfree(0);
5711solutions.AddSolution(vinfos,vfree);
5712}
5713}
5714}
5715
5716}
5717
5718}
5719
5720} else
5721{
5722{
5723IkReal j5array[1], cj5array[1], sj5array[1];
5724bool j5valid[1]={false};
5725_nj5 = 1;
5726IkReal x680=((25000.00002)*gconst11);
5727IkReal x681=((25000.0)*gconst10);
5728CheckValue<IkReal> x682=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
5729if(!x682.valid){
5730continue;
5731}
5732CheckValue<IkReal> x683 = IKatan2WithCheck(IkReal((((new_r00*x681))+((new_r10*x680)))),IkReal((((new_r10*x681))+(((-1.0)*new_r00*x680)))),IKFAST_ATAN2_MAGTHRESH);
5733if(!x683.valid){
5734continue;
5735}
5736j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x682.value)))+(x683.value));
5737sj5array[0]=IKsin(j5array[0]);
5738cj5array[0]=IKcos(j5array[0]);
5739if( j5array[0] > IKPI )
5740{
5741 j5array[0]-=IK2PI;
5742}
5743else if( j5array[0] < -IKPI )
5744{ j5array[0]+=IK2PI;
5745}
5746j5valid[0] = true;
5747for(int ij5 = 0; ij5 < 1; ++ij5)
5748{
5749if( !j5valid[ij5] )
5750{
5751 continue;
5752}
5753_ij5[0] = ij5; _ij5[1] = -1;
5754for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5755{
5756if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5757{
5758 j5valid[iij5]=false; _ij5[1] = iij5; break;
5759}
5760}
5761j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5762{
5763IkReal evalcond[7];
5764IkReal x684=IKsin(j5);
5765IkReal x685=IKcos(j5);
5766IkReal x686=(gconst11*x685);
5767IkReal x687=((1.0000000008)*x684);
5768IkReal x688=(gconst10*x685);
5769IkReal x689=((1.0)*x684);
5770IkReal x690=(new_r00*x685);
5771evalcond[0]=(gconst10+((new_r00*x684))+((new_r10*x685)));
5772evalcond[1]=(((gconst10*x684))+(((-1.0000000008)*x686))+new_r00);
5773evalcond[2]=(((gconst11*x687))+x688+new_r10);
5774evalcond[3]=((((-1.0)*gconst11*x689))+(((-1.0000000008)*x688)));
5775evalcond[4]=(((gconst10*x687))+(((-1.0)*x686)));
5776evalcond[5]=((((-1.0)*new_r10*x689))+(((-1.0000000008)*gconst11))+x690);
5777evalcond[6]=((((-1.0)*new_r10*x687))+(((1.0000000008)*x690))+(((-1.0)*gconst11)));
5778if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
5779{
5780continue;
5781}
5782}
5783
5784{
5785std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5786vinfos[0].jointtype = 1;
5787vinfos[0].foffset = j0;
5788vinfos[0].indices[0] = _ij0[0];
5789vinfos[0].indices[1] = _ij0[1];
5790vinfos[0].maxsolutions = _nj0;
5791vinfos[1].jointtype = 1;
5792vinfos[1].foffset = j1;
5793vinfos[1].indices[0] = _ij1[0];
5794vinfos[1].indices[1] = _ij1[1];
5795vinfos[1].maxsolutions = _nj1;
5796vinfos[2].jointtype = 1;
5797vinfos[2].foffset = j2;
5798vinfos[2].indices[0] = _ij2[0];
5799vinfos[2].indices[1] = _ij2[1];
5800vinfos[2].maxsolutions = _nj2;
5801vinfos[3].jointtype = 1;
5802vinfos[3].foffset = j3;
5803vinfos[3].indices[0] = _ij3[0];
5804vinfos[3].indices[1] = _ij3[1];
5805vinfos[3].maxsolutions = _nj3;
5806vinfos[4].jointtype = 1;
5807vinfos[4].foffset = j4;
5808vinfos[4].indices[0] = _ij4[0];
5809vinfos[4].indices[1] = _ij4[1];
5810vinfos[4].maxsolutions = _nj4;
5811vinfos[5].jointtype = 1;
5812vinfos[5].foffset = j5;
5813vinfos[5].indices[0] = _ij5[0];
5814vinfos[5].indices[1] = _ij5[1];
5815vinfos[5].maxsolutions = _nj5;
5816std::vector<int> vfree(0);
5817solutions.AddSolution(vinfos,vfree);
5818}
5819}
5820}
5821
5822}
5823
5824}
5825
5826}
5827} while(0);
5828if( bgotonextstatement )
5829{
5830bool bgotonextstatement = true;
5831do
5832{
5833evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
5834if( IKabs(evalcond[0]) < 0.0000050000000000 )
5835{
5836bgotonextstatement=false;
5837{
5838IkReal j5array[1], cj5array[1], sj5array[1];
5839bool j5valid[1]={false};
5840_nj5 = 1;
5841CheckValue<IkReal> x692=IKPowWithIntegerCheck(gconst11,-1);
5842if(!x692.valid){
5843continue;
5844}
5845IkReal x691=x692.value;
5846if( IKabs((new_r01*x691)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r00*x691)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x691))+IKsqr(((0.9999999992)*new_r00*x691))-1) <= IKFAST_SINCOS_THRESH )
5847 continue;
5848j5array[0]=IKatan2((new_r01*x691), ((0.9999999992)*new_r00*x691));
5849sj5array[0]=IKsin(j5array[0]);
5850cj5array[0]=IKcos(j5array[0]);
5851if( j5array[0] > IKPI )
5852{
5853 j5array[0]-=IK2PI;
5854}
5855else if( j5array[0] < -IKPI )
5856{ j5array[0]+=IK2PI;
5857}
5858j5valid[0] = true;
5859for(int ij5 = 0; ij5 < 1; ++ij5)
5860{
5861if( !j5valid[ij5] )
5862{
5863 continue;
5864}
5865_ij5[0] = ij5; _ij5[1] = -1;
5866for(int iij5 = ij5+1; iij5 < 1; ++iij5)
5867{
5868if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
5869{
5870 j5valid[iij5]=false; _ij5[1] = iij5; break;
5871}
5872}
5873j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
5874{
5875IkReal evalcond[10];
5876IkReal x693=IKcos(j5);
5877IkReal x694=IKsin(j5);
5878IkReal x695=((1.0)*gconst11);
5879IkReal x696=((1.0000000008)*gconst11);
5880IkReal x697=(new_r00*x693);
5881IkReal x698=(new_r01*x693);
5882evalcond[0]=(new_r00*x694);
5883evalcond[1]=x698;
5884evalcond[2]=((-1.0)*gconst11*x693);
5885evalcond[3]=((((-1.0)*x694*x695))+new_r01);
5886evalcond[4]=((((-1.0)*x695))+((new_r01*x694)));
5887evalcond[5]=(x694*x696);
5888evalcond[6]=((1.0000000008)*x698);
5889evalcond[7]=((((-1.0)*x693*x696))+new_r00);
5890evalcond[8]=(x697+(((-1.0)*x696)));
5891evalcond[9]=((((-1.0)*x695))+(((1.0000000008)*x697)));
5892if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
5893{
5894continue;
5895}
5896}
5897
5898{
5899std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5900vinfos[0].jointtype = 1;
5901vinfos[0].foffset = j0;
5902vinfos[0].indices[0] = _ij0[0];
5903vinfos[0].indices[1] = _ij0[1];
5904vinfos[0].maxsolutions = _nj0;
5905vinfos[1].jointtype = 1;
5906vinfos[1].foffset = j1;
5907vinfos[1].indices[0] = _ij1[0];
5908vinfos[1].indices[1] = _ij1[1];
5909vinfos[1].maxsolutions = _nj1;
5910vinfos[2].jointtype = 1;
5911vinfos[2].foffset = j2;
5912vinfos[2].indices[0] = _ij2[0];
5913vinfos[2].indices[1] = _ij2[1];
5914vinfos[2].maxsolutions = _nj2;
5915vinfos[3].jointtype = 1;
5916vinfos[3].foffset = j3;
5917vinfos[3].indices[0] = _ij3[0];
5918vinfos[3].indices[1] = _ij3[1];
5919vinfos[3].maxsolutions = _nj3;
5920vinfos[4].jointtype = 1;
5921vinfos[4].foffset = j4;
5922vinfos[4].indices[0] = _ij4[0];
5923vinfos[4].indices[1] = _ij4[1];
5924vinfos[4].maxsolutions = _nj4;
5925vinfos[5].jointtype = 1;
5926vinfos[5].foffset = j5;
5927vinfos[5].indices[0] = _ij5[0];
5928vinfos[5].indices[1] = _ij5[1];
5929vinfos[5].maxsolutions = _nj5;
5930std::vector<int> vfree(0);
5931solutions.AddSolution(vinfos,vfree);
5932}
5933}
5934}
5935
5936}
5937} while(0);
5938if( bgotonextstatement )
5939{
5940bool bgotonextstatement = true;
5941do
5942{
5943if( 1 )
5944{
5945bgotonextstatement=false;
5946continue; // branch miss [j5]
5947
5948}
5949} while(0);
5950if( bgotonextstatement )
5951{
5952}
5953}
5954}
5955}
5956}
5957
5958} else
5959{
5960{
5961IkReal j5array[1], cj5array[1], sj5array[1];
5962bool j5valid[1]={false};
5963_nj5 = 1;
5964CheckValue<IkReal> x704=IKPowWithIntegerCheck(new_r00,-1);
5965if(!x704.valid){
5966continue;
5967}
5968IkReal x699=x704.value;
5969IkReal x700=gconst10*gconst10;
5970IkReal x701=((25000.0)*new_r10);
5971IkReal x702=((25000.0)*x700);
5972CheckValue<IkReal> x705=IKPowWithIntegerCheck((((gconst10*x701))+(((25000.00002)*gconst11*new_r00))),-1);
5973if(!x705.valid){
5974continue;
5975}
5976IkReal x703=x705.value;
5977CheckValue<IkReal> x706=IKPowWithIntegerCheck(x699,-2);
5978if(!x706.valid){
5979continue;
5980}
5981if( IKabs((((x699*x700*x701*x703))+(((-1.0)*new_r00*x701*x703))+(((-1.0)*gconst10*x699)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x703*(((((25000.0)*(x706.value)))+(((-1.0)*x702)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((x699*x700*x701*x703))+(((-1.0)*new_r00*x701*x703))+(((-1.0)*gconst10*x699))))+IKsqr((x703*(((((25000.0)*(x706.value)))+(((-1.0)*x702))))))-1) <= IKFAST_SINCOS_THRESH )
5982 continue;
5983j5array[0]=IKatan2((((x699*x700*x701*x703))+(((-1.0)*new_r00*x701*x703))+(((-1.0)*gconst10*x699))), (x703*(((((25000.0)*(x706.value)))+(((-1.0)*x702))))));
5984sj5array[0]=IKsin(j5array[0]);
5985cj5array[0]=IKcos(j5array[0]);
5986if( j5array[0] > IKPI )
5987{
5988 j5array[0]-=IK2PI;
5989}
5990else if( j5array[0] < -IKPI )
5991{ j5array[0]+=IK2PI;
5992}
5993j5valid[0] = true;
5994for(int ij5 = 0; ij5 < 1; ++ij5)
5995{
5996if( !j5valid[ij5] )
5997{
5998 continue;
5999}
6000_ij5[0] = ij5; _ij5[1] = -1;
6001for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6002{
6003if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6004{
6005 j5valid[iij5]=false; _ij5[1] = iij5; break;
6006}
6007}
6008j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6009{
6010IkReal evalcond[10];
6011IkReal x707=IKcos(j5);
6012IkReal x708=IKsin(j5);
6013IkReal x709=((1.0)*gconst11);
6014IkReal x710=((1.0000000008)*gconst11);
6015IkReal x711=((1.0000000008)*gconst10);
6016IkReal x712=(new_r11*x708);
6017IkReal x713=(new_r01*x707);
6018IkReal x714=(new_r00*x707);
6019IkReal x715=(gconst10*x707);
6020IkReal x716=(new_r10*x708);
6021evalcond[0]=(((new_r00*x708))+gconst10+((new_r10*x707)));
6022evalcond[1]=(((new_r01*x708))+(((-1.0)*x709))+((new_r11*x707)));
6023evalcond[2]=((((-1.0)*x707*x710))+((gconst10*x708))+new_r00);
6024evalcond[3]=(x715+new_r10+((x708*x710)));
6025evalcond[4]=((((-1.0)*x707*x711))+new_r01+(((-1.0)*x708*x709)));
6026evalcond[5]=((((-1.0)*x707*x709))+new_r11+((x708*x711)));
6027evalcond[6]=((((-1.0)*x716))+(((-1.0)*x710))+x714);
6028evalcond[7]=((((-1.0)*x712))+(((-1.0)*x711))+x713);
6029evalcond[8]=((((1.0000000008)*x714))+(((-1.0)*x709))+(((-1.0000000008)*x716)));
6030evalcond[9]=((((1.0000000008)*x713))+(((-1.0000000008)*x712))+(((-1.0)*gconst10)));
6031if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
6032{
6033continue;
6034}
6035}
6036
6037{
6038std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6039vinfos[0].jointtype = 1;
6040vinfos[0].foffset = j0;
6041vinfos[0].indices[0] = _ij0[0];
6042vinfos[0].indices[1] = _ij0[1];
6043vinfos[0].maxsolutions = _nj0;
6044vinfos[1].jointtype = 1;
6045vinfos[1].foffset = j1;
6046vinfos[1].indices[0] = _ij1[0];
6047vinfos[1].indices[1] = _ij1[1];
6048vinfos[1].maxsolutions = _nj1;
6049vinfos[2].jointtype = 1;
6050vinfos[2].foffset = j2;
6051vinfos[2].indices[0] = _ij2[0];
6052vinfos[2].indices[1] = _ij2[1];
6053vinfos[2].maxsolutions = _nj2;
6054vinfos[3].jointtype = 1;
6055vinfos[3].foffset = j3;
6056vinfos[3].indices[0] = _ij3[0];
6057vinfos[3].indices[1] = _ij3[1];
6058vinfos[3].maxsolutions = _nj3;
6059vinfos[4].jointtype = 1;
6060vinfos[4].foffset = j4;
6061vinfos[4].indices[0] = _ij4[0];
6062vinfos[4].indices[1] = _ij4[1];
6063vinfos[4].maxsolutions = _nj4;
6064vinfos[5].jointtype = 1;
6065vinfos[5].foffset = j5;
6066vinfos[5].indices[0] = _ij5[0];
6067vinfos[5].indices[1] = _ij5[1];
6068vinfos[5].maxsolutions = _nj5;
6069std::vector<int> vfree(0);
6070solutions.AddSolution(vinfos,vfree);
6071}
6072}
6073}
6074
6075}
6076
6077}
6078
6079} else
6080{
6081{
6082IkReal j5array[1], cj5array[1], sj5array[1];
6083bool j5valid[1]={false};
6084_nj5 = 1;
6085IkReal x717=gconst10*gconst10;
6086IkReal x718=new_r10*new_r10;
6087IkReal x719=((25000.00002)*gconst11);
6088IkReal x720=(gconst10*new_r00);
6089IkReal x721=((625000000.5)*gconst11);
6090CheckValue<IkReal> x722=IKPowWithIntegerCheck(((((625000000.0)*x717*(new_r00*new_r00)))+(((-625000001.0)*x718*(gconst11*gconst11)))),-1);
6091if(!x722.valid){
6092continue;
6093}
6094CheckValue<IkReal> x723=IKPowWithIntegerCheck(((((25000.0)*x720))+(((-1.0)*new_r10*x719))),-1);
6095if(!x723.valid){
6096continue;
6097}
6098if( IKabs(((x722.value)*(((((625000000.0)*x718*x720))+((x721*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x717*x721))+(((-625000000.0)*x720*(gconst10*gconst10))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x723.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x719)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x722.value)*(((((625000000.0)*x718*x720))+((x721*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x717*x721))+(((-625000000.0)*x720*(gconst10*gconst10)))))))+IKsqr(((x723.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x719))))))-1) <= IKFAST_SINCOS_THRESH )
6099 continue;
6100j5array[0]=IKatan2(((x722.value)*(((((625000000.0)*x718*x720))+((x721*(new_r10*new_r10*new_r10)))+(((-1.0)*new_r10*x717*x721))+(((-625000000.0)*x720*(gconst10*gconst10)))))), ((x723.value)*(((((-25000.0)*new_r00*new_r10))+((gconst10*x719))))));
6101sj5array[0]=IKsin(j5array[0]);
6102cj5array[0]=IKcos(j5array[0]);
6103if( j5array[0] > IKPI )
6104{
6105 j5array[0]-=IK2PI;
6106}
6107else if( j5array[0] < -IKPI )
6108{ j5array[0]+=IK2PI;
6109}
6110j5valid[0] = true;
6111for(int ij5 = 0; ij5 < 1; ++ij5)
6112{
6113if( !j5valid[ij5] )
6114{
6115 continue;
6116}
6117_ij5[0] = ij5; _ij5[1] = -1;
6118for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6119{
6120if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6121{
6122 j5valid[iij5]=false; _ij5[1] = iij5; break;
6123}
6124}
6125j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6126{
6127IkReal evalcond[10];
6128IkReal x724=IKcos(j5);
6129IkReal x725=IKsin(j5);
6130IkReal x726=((1.0)*gconst11);
6131IkReal x727=((1.0000000008)*gconst11);
6132IkReal x728=((1.0000000008)*gconst10);
6133IkReal x729=(new_r11*x725);
6134IkReal x730=(new_r01*x724);
6135IkReal x731=(new_r00*x724);
6136IkReal x732=(gconst10*x724);
6137IkReal x733=(new_r10*x725);
6138evalcond[0]=(((new_r00*x725))+gconst10+((new_r10*x724)));
6139evalcond[1]=(((new_r01*x725))+(((-1.0)*x726))+((new_r11*x724)));
6140evalcond[2]=((((-1.0)*x724*x727))+((gconst10*x725))+new_r00);
6141evalcond[3]=(((x725*x727))+x732+new_r10);
6142evalcond[4]=((((-1.0)*x724*x728))+(((-1.0)*x725*x726))+new_r01);
6143evalcond[5]=((((-1.0)*x724*x726))+((x725*x728))+new_r11);
6144evalcond[6]=((((-1.0)*x733))+(((-1.0)*x727))+x731);
6145evalcond[7]=((((-1.0)*x728))+(((-1.0)*x729))+x730);
6146evalcond[8]=((((1.0000000008)*x731))+(((-1.0)*x726))+(((-1.0000000008)*x733)));
6147evalcond[9]=((((1.0000000008)*x730))+(((-1.0000000008)*x729))+(((-1.0)*gconst10)));
6148if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
6149{
6150continue;
6151}
6152}
6153
6154{
6155std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6156vinfos[0].jointtype = 1;
6157vinfos[0].foffset = j0;
6158vinfos[0].indices[0] = _ij0[0];
6159vinfos[0].indices[1] = _ij0[1];
6160vinfos[0].maxsolutions = _nj0;
6161vinfos[1].jointtype = 1;
6162vinfos[1].foffset = j1;
6163vinfos[1].indices[0] = _ij1[0];
6164vinfos[1].indices[1] = _ij1[1];
6165vinfos[1].maxsolutions = _nj1;
6166vinfos[2].jointtype = 1;
6167vinfos[2].foffset = j2;
6168vinfos[2].indices[0] = _ij2[0];
6169vinfos[2].indices[1] = _ij2[1];
6170vinfos[2].maxsolutions = _nj2;
6171vinfos[3].jointtype = 1;
6172vinfos[3].foffset = j3;
6173vinfos[3].indices[0] = _ij3[0];
6174vinfos[3].indices[1] = _ij3[1];
6175vinfos[3].maxsolutions = _nj3;
6176vinfos[4].jointtype = 1;
6177vinfos[4].foffset = j4;
6178vinfos[4].indices[0] = _ij4[0];
6179vinfos[4].indices[1] = _ij4[1];
6180vinfos[4].maxsolutions = _nj4;
6181vinfos[5].jointtype = 1;
6182vinfos[5].foffset = j5;
6183vinfos[5].indices[0] = _ij5[0];
6184vinfos[5].indices[1] = _ij5[1];
6185vinfos[5].maxsolutions = _nj5;
6186std::vector<int> vfree(0);
6187solutions.AddSolution(vinfos,vfree);
6188}
6189}
6190}
6191
6192}
6193
6194}
6195
6196} else
6197{
6198{
6199IkReal j5array[1], cj5array[1], sj5array[1];
6200bool j5valid[1]={false};
6201_nj5 = 1;
6202IkReal x734=((1.0)*new_r00);
6203CheckValue<IkReal> x735=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x734)))),-1);
6204if(!x735.valid){
6205continue;
6206}
6207CheckValue<IkReal> x736 = IKatan2WithCheck(IkReal((((gconst10*new_r11))+((gconst11*new_r10)))),IkReal(((((-1.0)*gconst11*x734))+(((-1.0)*gconst10*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
6208if(!x736.valid){
6209continue;
6210}
6211j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x735.value)))+(x736.value));
6212sj5array[0]=IKsin(j5array[0]);
6213cj5array[0]=IKcos(j5array[0]);
6214if( j5array[0] > IKPI )
6215{
6216 j5array[0]-=IK2PI;
6217}
6218else if( j5array[0] < -IKPI )
6219{ j5array[0]+=IK2PI;
6220}
6221j5valid[0] = true;
6222for(int ij5 = 0; ij5 < 1; ++ij5)
6223{
6224if( !j5valid[ij5] )
6225{
6226 continue;
6227}
6228_ij5[0] = ij5; _ij5[1] = -1;
6229for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6230{
6231if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6232{
6233 j5valid[iij5]=false; _ij5[1] = iij5; break;
6234}
6235}
6236j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6237{
6238IkReal evalcond[10];
6239IkReal x737=IKcos(j5);
6240IkReal x738=IKsin(j5);
6241IkReal x739=((1.0)*gconst11);
6242IkReal x740=((1.0000000008)*gconst11);
6243IkReal x741=((1.0000000008)*gconst10);
6244IkReal x742=(new_r11*x738);
6245IkReal x743=(new_r01*x737);
6246IkReal x744=(new_r00*x737);
6247IkReal x745=(gconst10*x737);
6248IkReal x746=(new_r10*x738);
6249evalcond[0]=(gconst10+((new_r00*x738))+((new_r10*x737)));
6250evalcond[1]=(((new_r01*x738))+(((-1.0)*x739))+((new_r11*x737)));
6251evalcond[2]=((((-1.0)*x737*x740))+((gconst10*x738))+new_r00);
6252evalcond[3]=(((x738*x740))+x745+new_r10);
6253evalcond[4]=((((-1.0)*x737*x741))+new_r01+(((-1.0)*x738*x739)));
6254evalcond[5]=(((x738*x741))+(((-1.0)*x737*x739))+new_r11);
6255evalcond[6]=((((-1.0)*x746))+x744+(((-1.0)*x740)));
6256evalcond[7]=((((-1.0)*x742))+x743+(((-1.0)*x741)));
6257evalcond[8]=((((-1.0000000008)*x746))+(((-1.0)*x739))+(((1.0000000008)*x744)));
6258evalcond[9]=((((-1.0000000008)*x742))+(((1.0000000008)*x743))+(((-1.0)*gconst10)));
6259if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
6260{
6261continue;
6262}
6263}
6264
6265{
6266std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6267vinfos[0].jointtype = 1;
6268vinfos[0].foffset = j0;
6269vinfos[0].indices[0] = _ij0[0];
6270vinfos[0].indices[1] = _ij0[1];
6271vinfos[0].maxsolutions = _nj0;
6272vinfos[1].jointtype = 1;
6273vinfos[1].foffset = j1;
6274vinfos[1].indices[0] = _ij1[0];
6275vinfos[1].indices[1] = _ij1[1];
6276vinfos[1].maxsolutions = _nj1;
6277vinfos[2].jointtype = 1;
6278vinfos[2].foffset = j2;
6279vinfos[2].indices[0] = _ij2[0];
6280vinfos[2].indices[1] = _ij2[1];
6281vinfos[2].maxsolutions = _nj2;
6282vinfos[3].jointtype = 1;
6283vinfos[3].foffset = j3;
6284vinfos[3].indices[0] = _ij3[0];
6285vinfos[3].indices[1] = _ij3[1];
6286vinfos[3].maxsolutions = _nj3;
6287vinfos[4].jointtype = 1;
6288vinfos[4].foffset = j4;
6289vinfos[4].indices[0] = _ij4[0];
6290vinfos[4].indices[1] = _ij4[1];
6291vinfos[4].maxsolutions = _nj4;
6292vinfos[5].jointtype = 1;
6293vinfos[5].foffset = j5;
6294vinfos[5].indices[0] = _ij5[0];
6295vinfos[5].indices[1] = _ij5[1];
6296vinfos[5].maxsolutions = _nj5;
6297std::vector<int> vfree(0);
6298solutions.AddSolution(vinfos,vfree);
6299}
6300}
6301}
6302
6303}
6304
6305}
6306
6307}
6308} while(0);
6309if( bgotonextstatement )
6310{
6311bool bgotonextstatement = true;
6312do
6313{
6314IkReal x747=new_r00*new_r00;
6315CheckValue<IkReal> x748=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x747))),-1);
6316if(!x748.valid){
6317continue;
6318}
6319if((((-1.0)*x747*(x748.value))) < -0.00001)
6320continue;
6321IkReal gconst12=IKsqrt(((-1.0)*x747*(x748.value)));
6322evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst12)))))), 6.28318530717959)));
6323if( IKabs(evalcond[0]) < 0.0000050000000000 )
6324{
6325bgotonextstatement=false;
6326{
6327IkReal j5eval[2];
6328IkReal x749=new_r00*new_r00;
6329sj4=4.0e-5;
6330cj4=1.0;
6331j4=4.0e-5;
6332if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6333continue;
6334sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6335cj3=gconst12;
6336if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6337 continue;
6338j3=IKacos(gconst12);
6339CheckValue<IkReal> x750=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x749))),-1);
6340if(!x750.valid){
6341continue;
6342}
6343if((((-1.0)*x749*(x750.value))) < -0.00001)
6344continue;
6345IkReal gconst12=IKsqrt(((-1.0)*x749*(x750.value)));
6346IkReal x751=(new_r00*new_r01);
6347IkReal x752=(new_r10*new_r11);
6348j5eval[0]=(x751+x752);
6349j5eval[1]=IKsign(((((25000.0)*x752))+(((25000.0)*x751))));
6350if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
6351{
6352{
6353IkReal j5eval[2];
6354IkReal x753=new_r00*new_r00;
6355sj4=4.0e-5;
6356cj4=1.0;
6357j4=4.0e-5;
6358if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6359continue;
6360sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6361cj3=gconst12;
6362if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6363 continue;
6364j3=IKacos(gconst12);
6365CheckValue<IkReal> x754=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x753))),-1);
6366if(!x754.valid){
6367continue;
6368}
6369if((((-1.0)*x753*(x754.value))) < -0.00001)
6370continue;
6371IkReal gconst12=IKsqrt(((-1.0)*x753*(x754.value)));
6372IkReal x755=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
6373j5eval[0]=x755;
6374j5eval[1]=IKsign(x755);
6375if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
6376{
6377{
6378IkReal j5eval[1];
6379IkReal x756=new_r00*new_r00;
6380sj4=4.0e-5;
6381cj4=1.0;
6382j4=4.0e-5;
6383if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6384continue;
6385sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6386cj3=gconst12;
6387if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6388 continue;
6389j3=IKacos(gconst12);
6390CheckValue<IkReal> x757=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x756))),-1);
6391if(!x757.valid){
6392continue;
6393}
6394if((((-1.0)*x756*(x757.value))) < -0.00001)
6395continue;
6396IkReal gconst12=IKsqrt(((-1.0)*x756*(x757.value)));
6397j5eval[0]=new_r01;
6398if( IKabs(j5eval[0]) < 0.0000010000000000 )
6399{
6400{
6401IkReal evalcond[1];
6402bool bgotonextstatement = true;
6403do
6404{
6405evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
6406if( IKabs(evalcond[0]) < 0.0000050000000000 )
6407{
6408bgotonextstatement=false;
6409{
6410IkReal j5eval[2];
6411IkReal x758=new_r10*new_r10;
6412sj4=4.0e-5;
6413cj4=1.0;
6414j4=4.0e-5;
6415if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6416continue;
6417sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6418cj3=gconst12;
6419if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6420 continue;
6421j3=IKacos(gconst12);
6422new_r11=0;
6423new_r01=0;
6424new_r22=0;
6425new_r20=0;
6426CheckValue<IkReal> x759=IKPowWithIntegerCheck(((-1.0)+(((-1.6e-9)*x758))),-1);
6427if(!x759.valid){
6428continue;
6429}
6430if((((x759.value)*(((-1.0)+(((1.0)*x758)))))) < -0.00001)
6431continue;
6432IkReal gconst12=IKsqrt(((x759.value)*(((-1.0)+(((1.0)*x758))))));
6433j5eval[0]=-1.0;
6434j5eval[1]=-1.0;
6435if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
6436{
6437{
6438IkReal j5array[1], cj5array[1], sj5array[1];
6439bool j5valid[1]={false};
6440_nj5 = 1;
6441IkReal x760=gconst12*gconst12;
6442IkReal x761=new_r00*new_r00;
6443IkReal x762=(gconst12*new_r10);
6444IkReal x763=((1.0)+(((-1.0)*x760)));
6445IkReal x764=((3.90625000625e+17)*x760);
6446if((x763) < -0.00001)
6447continue;
6448IkReal x765=IKsqrt(x763);
6449IkReal x766=(new_r00*x765);
6450CheckValue<IkReal> x767=IKPowWithIntegerCheck(((((-1.0)*x764*(new_r10*new_r10)))+(((3.90625e+17)*x761*(pow(x763,1.0))))),-1);
6451if(!x767.valid){
6452continue;
6453}
6454CheckValue<IkReal> x768=IKPowWithIntegerCheck(((((-25000.00002)*x762))+(((25000.0)*x766))),-1);
6455if(!x768.valid){
6456continue;
6457}
6458if( IKabs(((x767.value)*(((((-3.906250003125e+17)*x761*x762))+(((3.906250009375e+17)*x762*(gconst12*gconst12)))+(((-3.90625e+17)*x766*(new_r00*new_r00)))+((x764*x766)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x768.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst12*x765)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x767.value)*(((((-3.906250003125e+17)*x761*x762))+(((3.906250009375e+17)*x762*(gconst12*gconst12)))+(((-3.90625e+17)*x766*(new_r00*new_r00)))+((x764*x766))))))+IKsqr(((x768.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst12*x765))))))-1) <= IKFAST_SINCOS_THRESH )
6459 continue;
6460j5array[0]=IKatan2(((x767.value)*(((((-3.906250003125e+17)*x761*x762))+(((3.906250009375e+17)*x762*(gconst12*gconst12)))+(((-3.90625e+17)*x766*(new_r00*new_r00)))+((x764*x766))))), ((x768.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst12*x765))))));
6461sj5array[0]=IKsin(j5array[0]);
6462cj5array[0]=IKcos(j5array[0]);
6463if( j5array[0] > IKPI )
6464{
6465 j5array[0]-=IK2PI;
6466}
6467else if( j5array[0] < -IKPI )
6468{ j5array[0]+=IK2PI;
6469}
6470j5valid[0] = true;
6471for(int ij5 = 0; ij5 < 1; ++ij5)
6472{
6473if( !j5valid[ij5] )
6474{
6475 continue;
6476}
6477_ij5[0] = ij5; _ij5[1] = -1;
6478for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6479{
6480if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6481{
6482 j5valid[iij5]=false; _ij5[1] = iij5; break;
6483}
6484}
6485j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6486{
6487IkReal evalcond[7];
6488IkReal x769=IKcos(j5);
6489IkReal x770=IKsin(j5);
6490IkReal x771=((1.0)*gconst12);
6491IkReal x772=((1.0000000008)*gconst12);
6492IkReal x773=((1.0000000008)*x770);
6493IkReal x774=(new_r00*x769);
6494if((((1.0)+(((-1.0)*gconst12*x771)))) < -0.00001)
6495continue;
6496IkReal x775=IKsqrt(((1.0)+(((-1.0)*gconst12*x771))));
6497IkReal x776=(x769*x775);
6498evalcond[0]=((((-1.0)*new_r10*x770))+x774+(((-1.0)*x772)));
6499evalcond[1]=(((new_r10*x769))+((new_r00*x770))+x775);
6500evalcond[2]=((((-1.0)*new_r10*x773))+(((1.0000000008)*x774))+(((-1.0)*x771)));
6501evalcond[3]=(((x770*x775))+(((-1.0)*x769*x772))+new_r00);
6502evalcond[4]=(((x770*x772))+x776+new_r10);
6503evalcond[5]=((((-1.0000000008)*x776))+(((-1.0)*x770*x771)));
6504evalcond[6]=(((x773*x775))+(((-1.0)*x769*x771)));
6505if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
6506{
6507continue;
6508}
6509}
6510
6511{
6512std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6513vinfos[0].jointtype = 1;
6514vinfos[0].foffset = j0;
6515vinfos[0].indices[0] = _ij0[0];
6516vinfos[0].indices[1] = _ij0[1];
6517vinfos[0].maxsolutions = _nj0;
6518vinfos[1].jointtype = 1;
6519vinfos[1].foffset = j1;
6520vinfos[1].indices[0] = _ij1[0];
6521vinfos[1].indices[1] = _ij1[1];
6522vinfos[1].maxsolutions = _nj1;
6523vinfos[2].jointtype = 1;
6524vinfos[2].foffset = j2;
6525vinfos[2].indices[0] = _ij2[0];
6526vinfos[2].indices[1] = _ij2[1];
6527vinfos[2].maxsolutions = _nj2;
6528vinfos[3].jointtype = 1;
6529vinfos[3].foffset = j3;
6530vinfos[3].indices[0] = _ij3[0];
6531vinfos[3].indices[1] = _ij3[1];
6532vinfos[3].maxsolutions = _nj3;
6533vinfos[4].jointtype = 1;
6534vinfos[4].foffset = j4;
6535vinfos[4].indices[0] = _ij4[0];
6536vinfos[4].indices[1] = _ij4[1];
6537vinfos[4].maxsolutions = _nj4;
6538vinfos[5].jointtype = 1;
6539vinfos[5].foffset = j5;
6540vinfos[5].indices[0] = _ij5[0];
6541vinfos[5].indices[1] = _ij5[1];
6542vinfos[5].maxsolutions = _nj5;
6543std::vector<int> vfree(0);
6544solutions.AddSolution(vinfos,vfree);
6545}
6546}
6547}
6548
6549} else
6550{
6551{
6552IkReal j5array[1], cj5array[1], sj5array[1];
6553bool j5valid[1]={false};
6554_nj5 = 1;
6555if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6556continue;
6557IkReal x777=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6558IkReal x778=((25000.0)*x777);
6559CheckValue<IkReal> x779=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
6560if(!x779.valid){
6561continue;
6562}
6563CheckValue<IkReal> x780 = IKatan2WithCheck(IkReal(((((25000.00002)*gconst12*new_r10))+((new_r00*x778)))),IkReal(((((-25000.00002)*gconst12*new_r00))+((new_r10*x778)))),IKFAST_ATAN2_MAGTHRESH);
6564if(!x780.valid){
6565continue;
6566}
6567j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x779.value)))+(x780.value));
6568sj5array[0]=IKsin(j5array[0]);
6569cj5array[0]=IKcos(j5array[0]);
6570if( j5array[0] > IKPI )
6571{
6572 j5array[0]-=IK2PI;
6573}
6574else if( j5array[0] < -IKPI )
6575{ j5array[0]+=IK2PI;
6576}
6577j5valid[0] = true;
6578for(int ij5 = 0; ij5 < 1; ++ij5)
6579{
6580if( !j5valid[ij5] )
6581{
6582 continue;
6583}
6584_ij5[0] = ij5; _ij5[1] = -1;
6585for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6586{
6587if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6588{
6589 j5valid[iij5]=false; _ij5[1] = iij5; break;
6590}
6591}
6592j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6593{
6594IkReal evalcond[7];
6595IkReal x781=IKcos(j5);
6596IkReal x782=IKsin(j5);
6597IkReal x783=((1.0)*gconst12);
6598IkReal x784=((1.0000000008)*gconst12);
6599IkReal x785=((1.0000000008)*x782);
6600IkReal x786=(new_r00*x781);
6601IkReal x787=x777;
6602IkReal x788=(x781*x787);
6603evalcond[0]=((((-1.0)*x784))+x786+(((-1.0)*new_r10*x782)));
6604evalcond[1]=(((new_r10*x781))+((new_r00*x782))+x787);
6605evalcond[2]=((((-1.0)*x783))+(((-1.0)*new_r10*x785))+(((1.0000000008)*x786)));
6606evalcond[3]=(((x782*x787))+(((-1.0)*x781*x784))+new_r00);
6607evalcond[4]=(((x782*x784))+x788+new_r10);
6608evalcond[5]=((((-1.0)*x782*x783))+(((-1.0000000008)*x788)));
6609evalcond[6]=(((x785*x787))+(((-1.0)*x781*x783)));
6610if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
6611{
6612continue;
6613}
6614}
6615
6616{
6617std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6618vinfos[0].jointtype = 1;
6619vinfos[0].foffset = j0;
6620vinfos[0].indices[0] = _ij0[0];
6621vinfos[0].indices[1] = _ij0[1];
6622vinfos[0].maxsolutions = _nj0;
6623vinfos[1].jointtype = 1;
6624vinfos[1].foffset = j1;
6625vinfos[1].indices[0] = _ij1[0];
6626vinfos[1].indices[1] = _ij1[1];
6627vinfos[1].maxsolutions = _nj1;
6628vinfos[2].jointtype = 1;
6629vinfos[2].foffset = j2;
6630vinfos[2].indices[0] = _ij2[0];
6631vinfos[2].indices[1] = _ij2[1];
6632vinfos[2].maxsolutions = _nj2;
6633vinfos[3].jointtype = 1;
6634vinfos[3].foffset = j3;
6635vinfos[3].indices[0] = _ij3[0];
6636vinfos[3].indices[1] = _ij3[1];
6637vinfos[3].maxsolutions = _nj3;
6638vinfos[4].jointtype = 1;
6639vinfos[4].foffset = j4;
6640vinfos[4].indices[0] = _ij4[0];
6641vinfos[4].indices[1] = _ij4[1];
6642vinfos[4].maxsolutions = _nj4;
6643vinfos[5].jointtype = 1;
6644vinfos[5].foffset = j5;
6645vinfos[5].indices[0] = _ij5[0];
6646vinfos[5].indices[1] = _ij5[1];
6647vinfos[5].maxsolutions = _nj5;
6648std::vector<int> vfree(0);
6649solutions.AddSolution(vinfos,vfree);
6650}
6651}
6652}
6653
6654}
6655
6656}
6657
6658}
6659} while(0);
6660if( bgotonextstatement )
6661{
6662bool bgotonextstatement = true;
6663do
6664{
6665evalcond[0]=IKabs(new_r01);
6666if( IKabs(evalcond[0]) < 0.0000050000000000 )
6667{
6668bgotonextstatement=false;
6669{
6670IkReal j5eval[3];
6671IkReal x789=new_r00*new_r00;
6672sj4=4.0e-5;
6673cj4=1.0;
6674j4=4.0e-5;
6675if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6676continue;
6677sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6678cj3=gconst12;
6679if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6680 continue;
6681j3=IKacos(gconst12);
6682new_r01=0;
6683CheckValue<IkReal> x790=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x789))),-1);
6684if(!x790.valid){
6685continue;
6686}
6687if((((-1.0)*x789*(x790.value))) < -0.00001)
6688continue;
6689IkReal gconst12=IKsqrt(((-1.0)*x789*(x790.value)));
6690IkReal x791=new_r10*new_r10;
6691IkReal x792=new_r00*new_r00;
6692IkReal x793=((1.0)*x792);
6693j5eval[0]=new_r11;
6694j5eval[1]=IKsign(new_r11);
6695CheckValue<IkReal> x794=IKPowWithIntegerCheck(((((625000000.0)*x792))+(((625000001.0)*x791))),-1);
6696if(!x794.valid){
6697continue;
6698}
6699CheckValue<IkReal> x795=IKPowWithIntegerCheck(((((-1.0000000016)*x791))+(((-1.0)*x792))),-1);
6700if(!x795.valid){
6701continue;
6702}
6703j5eval[2]=((((625000002.0)*(pow(x791,1.0))*(pow(x794.value,1.0))))+(((-1.0)*x793*(x795.value))));
6704if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
6705{
6706{
6707IkReal j5eval[2];
6708IkReal x796=new_r00*new_r00;
6709sj4=4.0e-5;
6710cj4=1.0;
6711j4=4.0e-5;
6712if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6713continue;
6714sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6715cj3=gconst12;
6716if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6717 continue;
6718j3=IKacos(gconst12);
6719new_r01=0;
6720CheckValue<IkReal> x797=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x796))),-1);
6721if(!x797.valid){
6722continue;
6723}
6724if((((-1.0)*x796*(x797.value))) < -0.00001)
6725continue;
6726IkReal gconst12=IKsqrt(((-1.0)*x796*(x797.value)));
6727j5eval[0]=new_r10;
6728j5eval[1]=new_r11;
6729if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
6730{
6731{
6732IkReal j5eval[2];
6733IkReal x798=new_r00*new_r00;
6734sj4=4.0e-5;
6735cj4=1.0;
6736j4=4.0e-5;
6737if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6738continue;
6739sj3=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
6740cj3=gconst12;
6741if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
6742 continue;
6743j3=IKacos(gconst12);
6744new_r01=0;
6745CheckValue<IkReal> x799=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x798))),-1);
6746if(!x799.valid){
6747continue;
6748}
6749if((((-1.0)*x798*(x799.value))) < -0.00001)
6750continue;
6751IkReal gconst12=IKsqrt(((-1.0)*x798*(x799.value)));
6752j5eval[0]=new_r00;
6753j5eval[1]=new_r11;
6754if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
6755{
6756continue; // 3 cases reached
6757
6758} else
6759{
6760{
6761IkReal j5array[1], cj5array[1], sj5array[1];
6762bool j5valid[1]={false};
6763_nj5 = 1;
6764CheckValue<IkReal> x801=IKPowWithIntegerCheck(new_r11,-1);
6765if(!x801.valid){
6766continue;
6767}
6768IkReal x800=x801.value;
6769CheckValue<IkReal> x802=IKPowWithIntegerCheck(new_r00,-1);
6770if(!x802.valid){
6771continue;
6772}
6773if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
6774continue;
6775if( IKabs((x800*(x802.value)*(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r10)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst12*x800)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x800*(x802.value)*(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r10))))))+IKsqr((gconst12*x800))-1) <= IKFAST_SINCOS_THRESH )
6776 continue;
6777j5array[0]=IKatan2((x800*(x802.value)*(((((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+(((-1.0)*gconst12*new_r10))))), (gconst12*x800));
6778sj5array[0]=IKsin(j5array[0]);
6779cj5array[0]=IKcos(j5array[0]);
6780if( j5array[0] > IKPI )
6781{
6782 j5array[0]-=IK2PI;
6783}
6784else if( j5array[0] < -IKPI )
6785{ j5array[0]+=IK2PI;
6786}
6787j5valid[0] = true;
6788for(int ij5 = 0; ij5 < 1; ++ij5)
6789{
6790if( !j5valid[ij5] )
6791{
6792 continue;
6793}
6794_ij5[0] = ij5; _ij5[1] = -1;
6795for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6796{
6797if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6798{
6799 j5valid[iij5]=false; _ij5[1] = iij5; break;
6800}
6801}
6802j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6803{
6804IkReal evalcond[10];
6805IkReal x803=IKcos(j5);
6806IkReal x804=IKsin(j5);
6807IkReal x805=((1.0)*gconst12);
6808IkReal x806=(gconst12*x803);
6809IkReal x807=(new_r11*x804);
6810IkReal x808=(new_r00*x803);
6811IkReal x809=(gconst12*x804);
6812IkReal x810=(new_r10*x804);
6813if((((1.0)+(((-1.0)*gconst12*x805)))) < -0.00001)
6814continue;
6815IkReal x811=IKsqrt(((1.0)+(((-1.0)*gconst12*x805))));
6816IkReal x812=(x804*x811);
6817IkReal x813=(x803*x811);
6818evalcond[0]=(((new_r11*x803))+(((-1.0)*x805)));
6819evalcond[1]=((((-1.0000000008)*gconst12))+(((-1.0)*x810))+x808);
6820evalcond[2]=(((new_r00*x804))+((new_r10*x803))+x811);
6821evalcond[3]=((((-1.0)*x807))+(((-1.0000000008)*x811)));
6822evalcond[4]=((((-1.0000000008)*x807))+(((-1.0)*x811)));
6823evalcond[5]=((((1.0000000008)*x808))+(((-1.0)*x805))+(((-1.0000000008)*x810)));
6824evalcond[6]=((((-1.0000000008)*x806))+new_r00+x812);
6825evalcond[7]=((((1.0000000008)*x809))+new_r10+x813);
6826evalcond[8]=((((-1.0)*x804*x805))+(((-1.0000000008)*x813)));
6827evalcond[9]=((((1.0000000008)*x812))+(((-1.0)*x803*x805))+new_r11);
6828if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
6829{
6830continue;
6831}
6832}
6833
6834{
6835std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6836vinfos[0].jointtype = 1;
6837vinfos[0].foffset = j0;
6838vinfos[0].indices[0] = _ij0[0];
6839vinfos[0].indices[1] = _ij0[1];
6840vinfos[0].maxsolutions = _nj0;
6841vinfos[1].jointtype = 1;
6842vinfos[1].foffset = j1;
6843vinfos[1].indices[0] = _ij1[0];
6844vinfos[1].indices[1] = _ij1[1];
6845vinfos[1].maxsolutions = _nj1;
6846vinfos[2].jointtype = 1;
6847vinfos[2].foffset = j2;
6848vinfos[2].indices[0] = _ij2[0];
6849vinfos[2].indices[1] = _ij2[1];
6850vinfos[2].maxsolutions = _nj2;
6851vinfos[3].jointtype = 1;
6852vinfos[3].foffset = j3;
6853vinfos[3].indices[0] = _ij3[0];
6854vinfos[3].indices[1] = _ij3[1];
6855vinfos[3].maxsolutions = _nj3;
6856vinfos[4].jointtype = 1;
6857vinfos[4].foffset = j4;
6858vinfos[4].indices[0] = _ij4[0];
6859vinfos[4].indices[1] = _ij4[1];
6860vinfos[4].maxsolutions = _nj4;
6861vinfos[5].jointtype = 1;
6862vinfos[5].foffset = j5;
6863vinfos[5].indices[0] = _ij5[0];
6864vinfos[5].indices[1] = _ij5[1];
6865vinfos[5].maxsolutions = _nj5;
6866std::vector<int> vfree(0);
6867solutions.AddSolution(vinfos,vfree);
6868}
6869}
6870}
6871
6872}
6873
6874}
6875
6876} else
6877{
6878{
6879IkReal j5array[1], cj5array[1], sj5array[1];
6880bool j5valid[1]={false};
6881_nj5 = 1;
6882CheckValue<IkReal> x815=IKPowWithIntegerCheck(new_r11,-1);
6883if(!x815.valid){
6884continue;
6885}
6886IkReal x814=x815.value;
6887CheckValue<IkReal> x816=IKPowWithIntegerCheck(new_r10,-1);
6888if(!x816.valid){
6889continue;
6890}
6891if( IKabs(((4.0e-5)*x814*(x816.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst12*x814)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((4.0e-5)*x814*(x816.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11))))))+IKsqr((gconst12*x814))-1) <= IKFAST_SINCOS_THRESH )
6892 continue;
6893j5array[0]=IKatan2(((4.0e-5)*x814*(x816.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11))))), (gconst12*x814));
6894sj5array[0]=IKsin(j5array[0]);
6895cj5array[0]=IKcos(j5array[0]);
6896if( j5array[0] > IKPI )
6897{
6898 j5array[0]-=IK2PI;
6899}
6900else if( j5array[0] < -IKPI )
6901{ j5array[0]+=IK2PI;
6902}
6903j5valid[0] = true;
6904for(int ij5 = 0; ij5 < 1; ++ij5)
6905{
6906if( !j5valid[ij5] )
6907{
6908 continue;
6909}
6910_ij5[0] = ij5; _ij5[1] = -1;
6911for(int iij5 = ij5+1; iij5 < 1; ++iij5)
6912{
6913if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
6914{
6915 j5valid[iij5]=false; _ij5[1] = iij5; break;
6916}
6917}
6918j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
6919{
6920IkReal evalcond[10];
6921IkReal x817=IKcos(j5);
6922IkReal x818=IKsin(j5);
6923IkReal x819=((1.0)*gconst12);
6924IkReal x820=(gconst12*x817);
6925IkReal x821=(new_r11*x818);
6926IkReal x822=(new_r00*x817);
6927IkReal x823=(gconst12*x818);
6928IkReal x824=(new_r10*x818);
6929if((((1.0)+(((-1.0)*gconst12*x819)))) < -0.00001)
6930continue;
6931IkReal x825=IKsqrt(((1.0)+(((-1.0)*gconst12*x819))));
6932IkReal x826=(x818*x825);
6933IkReal x827=(x817*x825);
6934evalcond[0]=(((new_r11*x817))+(((-1.0)*x819)));
6935evalcond[1]=((((-1.0000000008)*gconst12))+(((-1.0)*x824))+x822);
6936evalcond[2]=(((new_r00*x818))+((new_r10*x817))+x825);
6937evalcond[3]=((((-1.0)*x821))+(((-1.0000000008)*x825)));
6938evalcond[4]=((((-1.0)*x825))+(((-1.0000000008)*x821)));
6939evalcond[5]=((((1.0000000008)*x822))+(((-1.0)*x819))+(((-1.0000000008)*x824)));
6940evalcond[6]=(new_r00+x826+(((-1.0000000008)*x820)));
6941evalcond[7]=((((1.0000000008)*x823))+new_r10+x827);
6942evalcond[8]=((((-1.0)*x818*x819))+(((-1.0000000008)*x827)));
6943evalcond[9]=((((-1.0)*x817*x819))+(((1.0000000008)*x826))+new_r11);
6944if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
6945{
6946continue;
6947}
6948}
6949
6950{
6951std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6952vinfos[0].jointtype = 1;
6953vinfos[0].foffset = j0;
6954vinfos[0].indices[0] = _ij0[0];
6955vinfos[0].indices[1] = _ij0[1];
6956vinfos[0].maxsolutions = _nj0;
6957vinfos[1].jointtype = 1;
6958vinfos[1].foffset = j1;
6959vinfos[1].indices[0] = _ij1[0];
6960vinfos[1].indices[1] = _ij1[1];
6961vinfos[1].maxsolutions = _nj1;
6962vinfos[2].jointtype = 1;
6963vinfos[2].foffset = j2;
6964vinfos[2].indices[0] = _ij2[0];
6965vinfos[2].indices[1] = _ij2[1];
6966vinfos[2].maxsolutions = _nj2;
6967vinfos[3].jointtype = 1;
6968vinfos[3].foffset = j3;
6969vinfos[3].indices[0] = _ij3[0];
6970vinfos[3].indices[1] = _ij3[1];
6971vinfos[3].maxsolutions = _nj3;
6972vinfos[4].jointtype = 1;
6973vinfos[4].foffset = j4;
6974vinfos[4].indices[0] = _ij4[0];
6975vinfos[4].indices[1] = _ij4[1];
6976vinfos[4].maxsolutions = _nj4;
6977vinfos[5].jointtype = 1;
6978vinfos[5].foffset = j5;
6979vinfos[5].indices[0] = _ij5[0];
6980vinfos[5].indices[1] = _ij5[1];
6981vinfos[5].maxsolutions = _nj5;
6982std::vector<int> vfree(0);
6983solutions.AddSolution(vinfos,vfree);
6984}
6985}
6986}
6987
6988}
6989
6990}
6991
6992} else
6993{
6994{
6995IkReal j5array[1], cj5array[1], sj5array[1];
6996bool j5valid[1]={false};
6997_nj5 = 1;
6998CheckValue<IkReal> x828=IKPowWithIntegerCheck(IKsign(new_r11),-1);
6999if(!x828.valid){
7000continue;
7001}
7002if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7003continue;
7004CheckValue<IkReal> x829 = IKatan2WithCheck(IkReal(((-1.0000000008)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))))),IkReal(gconst12),IKFAST_ATAN2_MAGTHRESH);
7005if(!x829.valid){
7006continue;
7007}
7008j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x828.value)))+(x829.value));
7009sj5array[0]=IKsin(j5array[0]);
7010cj5array[0]=IKcos(j5array[0]);
7011if( j5array[0] > IKPI )
7012{
7013 j5array[0]-=IK2PI;
7014}
7015else if( j5array[0] < -IKPI )
7016{ j5array[0]+=IK2PI;
7017}
7018j5valid[0] = true;
7019for(int ij5 = 0; ij5 < 1; ++ij5)
7020{
7021if( !j5valid[ij5] )
7022{
7023 continue;
7024}
7025_ij5[0] = ij5; _ij5[1] = -1;
7026for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7027{
7028if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7029{
7030 j5valid[iij5]=false; _ij5[1] = iij5; break;
7031}
7032}
7033j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7034{
7035IkReal evalcond[10];
7036IkReal x830=IKcos(j5);
7037IkReal x831=IKsin(j5);
7038IkReal x832=((1.0)*gconst12);
7039IkReal x833=(gconst12*x830);
7040IkReal x834=(new_r11*x831);
7041IkReal x835=(new_r00*x830);
7042IkReal x836=(gconst12*x831);
7043IkReal x837=(new_r10*x831);
7044if((((1.0)+(((-1.0)*gconst12*x832)))) < -0.00001)
7045continue;
7046IkReal x838=IKsqrt(((1.0)+(((-1.0)*gconst12*x832))));
7047IkReal x839=(x831*x838);
7048IkReal x840=(x830*x838);
7049evalcond[0]=(((new_r11*x830))+(((-1.0)*x832)));
7050evalcond[1]=((((-1.0000000008)*gconst12))+(((-1.0)*x837))+x835);
7051evalcond[2]=(((new_r00*x831))+x838+((new_r10*x830)));
7052evalcond[3]=((((-1.0)*x834))+(((-1.0000000008)*x838)));
7053evalcond[4]=((((-1.0)*x838))+(((-1.0000000008)*x834)));
7054evalcond[5]=((((1.0000000008)*x835))+(((-1.0)*x832))+(((-1.0000000008)*x837)));
7055evalcond[6]=((((-1.0000000008)*x833))+new_r00+x839);
7056evalcond[7]=((((1.0000000008)*x836))+new_r10+x840);
7057evalcond[8]=((((-1.0000000008)*x840))+(((-1.0)*x831*x832)));
7058evalcond[9]=((((1.0000000008)*x839))+(((-1.0)*x830*x832))+new_r11);
7059if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
7060{
7061continue;
7062}
7063}
7064
7065{
7066std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7067vinfos[0].jointtype = 1;
7068vinfos[0].foffset = j0;
7069vinfos[0].indices[0] = _ij0[0];
7070vinfos[0].indices[1] = _ij0[1];
7071vinfos[0].maxsolutions = _nj0;
7072vinfos[1].jointtype = 1;
7073vinfos[1].foffset = j1;
7074vinfos[1].indices[0] = _ij1[0];
7075vinfos[1].indices[1] = _ij1[1];
7076vinfos[1].maxsolutions = _nj1;
7077vinfos[2].jointtype = 1;
7078vinfos[2].foffset = j2;
7079vinfos[2].indices[0] = _ij2[0];
7080vinfos[2].indices[1] = _ij2[1];
7081vinfos[2].maxsolutions = _nj2;
7082vinfos[3].jointtype = 1;
7083vinfos[3].foffset = j3;
7084vinfos[3].indices[0] = _ij3[0];
7085vinfos[3].indices[1] = _ij3[1];
7086vinfos[3].maxsolutions = _nj3;
7087vinfos[4].jointtype = 1;
7088vinfos[4].foffset = j4;
7089vinfos[4].indices[0] = _ij4[0];
7090vinfos[4].indices[1] = _ij4[1];
7091vinfos[4].maxsolutions = _nj4;
7092vinfos[5].jointtype = 1;
7093vinfos[5].foffset = j5;
7094vinfos[5].indices[0] = _ij5[0];
7095vinfos[5].indices[1] = _ij5[1];
7096vinfos[5].maxsolutions = _nj5;
7097std::vector<int> vfree(0);
7098solutions.AddSolution(vinfos,vfree);
7099}
7100}
7101}
7102
7103}
7104
7105}
7106
7107}
7108} while(0);
7109if( bgotonextstatement )
7110{
7111bool bgotonextstatement = true;
7112do
7113{
7114evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
7115if( IKabs(evalcond[0]) < 0.0000050000000000 )
7116{
7117bgotonextstatement=false;
7118{
7119IkReal j5array[2], cj5array[2], sj5array[2];
7120bool j5valid[2]={false};
7121_nj5 = 2;
7122cj5array[0]=((-1.0)*new_r10);
7123if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
7124{
7125 j5valid[0] = j5valid[1] = true;
7126 j5array[0] = IKacos(cj5array[0]);
7127 sj5array[0] = IKsin(j5array[0]);
7128 cj5array[1] = cj5array[0];
7129 j5array[1] = -j5array[0];
7130 sj5array[1] = -sj5array[0];
7131}
7132else if( isnan(cj5array[0]) )
7133{
7134 // probably any value will work
7135 j5valid[0] = true;
7136 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
7137}
7138for(int ij5 = 0; ij5 < 2; ++ij5)
7139{
7140if( !j5valid[ij5] )
7141{
7142 continue;
7143}
7144_ij5[0] = ij5; _ij5[1] = -1;
7145for(int iij5 = ij5+1; iij5 < 2; ++iij5)
7146{
7147if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7148{
7149 j5valid[iij5]=false; _ij5[1] = iij5; break;
7150}
7151}
7152j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7153{
7154IkReal evalcond[9];
7155IkReal x841=IKsin(j5);
7156IkReal x842=IKcos(j5);
7157IkReal x843=(new_r10*x841);
7158IkReal x844=((1.0000000008)*x842);
7159evalcond[0]=x841;
7160evalcond[1]=(new_r01*x841);
7161evalcond[2]=((-1.0)*x843);
7162evalcond[3]=((1.0)+((new_r10*x842)));
7163evalcond[4]=((1.0000000008)*x841);
7164evalcond[5]=((-1.0000000008)*x843);
7165evalcond[6]=((((-1.0)*x844))+new_r01);
7166evalcond[7]=((-1.0000000008)+((new_r01*x842)));
7167evalcond[8]=((-1.0)+((new_r01*x844)));
7168if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
7169{
7170continue;
7171}
7172}
7173
7174{
7175std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7176vinfos[0].jointtype = 1;
7177vinfos[0].foffset = j0;
7178vinfos[0].indices[0] = _ij0[0];
7179vinfos[0].indices[1] = _ij0[1];
7180vinfos[0].maxsolutions = _nj0;
7181vinfos[1].jointtype = 1;
7182vinfos[1].foffset = j1;
7183vinfos[1].indices[0] = _ij1[0];
7184vinfos[1].indices[1] = _ij1[1];
7185vinfos[1].maxsolutions = _nj1;
7186vinfos[2].jointtype = 1;
7187vinfos[2].foffset = j2;
7188vinfos[2].indices[0] = _ij2[0];
7189vinfos[2].indices[1] = _ij2[1];
7190vinfos[2].maxsolutions = _nj2;
7191vinfos[3].jointtype = 1;
7192vinfos[3].foffset = j3;
7193vinfos[3].indices[0] = _ij3[0];
7194vinfos[3].indices[1] = _ij3[1];
7195vinfos[3].maxsolutions = _nj3;
7196vinfos[4].jointtype = 1;
7197vinfos[4].foffset = j4;
7198vinfos[4].indices[0] = _ij4[0];
7199vinfos[4].indices[1] = _ij4[1];
7200vinfos[4].maxsolutions = _nj4;
7201vinfos[5].jointtype = 1;
7202vinfos[5].foffset = j5;
7203vinfos[5].indices[0] = _ij5[0];
7204vinfos[5].indices[1] = _ij5[1];
7205vinfos[5].maxsolutions = _nj5;
7206std::vector<int> vfree(0);
7207solutions.AddSolution(vinfos,vfree);
7208}
7209}
7210}
7211
7212}
7213} while(0);
7214if( bgotonextstatement )
7215{
7216bool bgotonextstatement = true;
7217do
7218{
7219evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
7220if( IKabs(evalcond[0]) < 0.0000050000000000 )
7221{
7222bgotonextstatement=false;
7223{
7224IkReal j5array[1], cj5array[1], sj5array[1];
7225bool j5valid[1]={false};
7226_nj5 = 1;
7227if( IKabs(((-0.9999999992)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11))+IKsqr(((0.9999999992)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
7228 continue;
7229j5array[0]=IKatan2(((-0.9999999992)*new_r11), ((0.9999999992)*new_r01));
7230sj5array[0]=IKsin(j5array[0]);
7231cj5array[0]=IKcos(j5array[0]);
7232if( j5array[0] > IKPI )
7233{
7234 j5array[0]-=IK2PI;
7235}
7236else if( j5array[0] < -IKPI )
7237{ j5array[0]+=IK2PI;
7238}
7239j5valid[0] = true;
7240for(int ij5 = 0; ij5 < 1; ++ij5)
7241{
7242if( !j5valid[ij5] )
7243{
7244 continue;
7245}
7246_ij5[0] = ij5; _ij5[1] = -1;
7247for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7248{
7249if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7250{
7251 j5valid[iij5]=false; _ij5[1] = iij5; break;
7252}
7253}
7254j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7255{
7256IkReal evalcond[7];
7257IkReal x845=IKcos(j5);
7258IkReal x846=IKsin(j5);
7259IkReal x847=((1.0000000008)*x846);
7260IkReal x848=((1.0000000008)*x845);
7261evalcond[0]=x846;
7262evalcond[1]=x845;
7263evalcond[2]=((((-1.0)*x848))+new_r01);
7264evalcond[3]=(new_r11+x847);
7265evalcond[4]=(((new_r01*x846))+((new_r11*x845)));
7266evalcond[5]=((-1.0000000008)+((new_r01*x845))+(((-1.0)*new_r11*x846)));
7267evalcond[6]=((-1.0)+(((-1.0)*new_r11*x847))+((new_r01*x848)));
7268if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
7269{
7270continue;
7271}
7272}
7273
7274{
7275std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7276vinfos[0].jointtype = 1;
7277vinfos[0].foffset = j0;
7278vinfos[0].indices[0] = _ij0[0];
7279vinfos[0].indices[1] = _ij0[1];
7280vinfos[0].maxsolutions = _nj0;
7281vinfos[1].jointtype = 1;
7282vinfos[1].foffset = j1;
7283vinfos[1].indices[0] = _ij1[0];
7284vinfos[1].indices[1] = _ij1[1];
7285vinfos[1].maxsolutions = _nj1;
7286vinfos[2].jointtype = 1;
7287vinfos[2].foffset = j2;
7288vinfos[2].indices[0] = _ij2[0];
7289vinfos[2].indices[1] = _ij2[1];
7290vinfos[2].maxsolutions = _nj2;
7291vinfos[3].jointtype = 1;
7292vinfos[3].foffset = j3;
7293vinfos[3].indices[0] = _ij3[0];
7294vinfos[3].indices[1] = _ij3[1];
7295vinfos[3].maxsolutions = _nj3;
7296vinfos[4].jointtype = 1;
7297vinfos[4].foffset = j4;
7298vinfos[4].indices[0] = _ij4[0];
7299vinfos[4].indices[1] = _ij4[1];
7300vinfos[4].maxsolutions = _nj4;
7301vinfos[5].jointtype = 1;
7302vinfos[5].foffset = j5;
7303vinfos[5].indices[0] = _ij5[0];
7304vinfos[5].indices[1] = _ij5[1];
7305vinfos[5].maxsolutions = _nj5;
7306std::vector<int> vfree(0);
7307solutions.AddSolution(vinfos,vfree);
7308}
7309}
7310}
7311
7312}
7313} while(0);
7314if( bgotonextstatement )
7315{
7316bool bgotonextstatement = true;
7317do
7318{
7319if( 1 )
7320{
7321bgotonextstatement=false;
7322continue; // branch miss [j5]
7323
7324}
7325} while(0);
7326if( bgotonextstatement )
7327{
7328}
7329}
7330}
7331}
7332}
7333}
7334
7335} else
7336{
7337{
7338IkReal j5array[1], cj5array[1], sj5array[1];
7339bool j5valid[1]={false};
7340_nj5 = 1;
7341CheckValue<IkReal> x855=IKPowWithIntegerCheck(new_r01,-1);
7342if(!x855.valid){
7343continue;
7344}
7345IkReal x849=x855.value;
7346IkReal x850=(gconst12*x849);
7347if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7348continue;
7349IkReal x851=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
7350IkReal x852=((25000.0)*x851);
7351CheckValue<IkReal> x856=IKPowWithIntegerCheck(((((25000.00002)*gconst12*new_r01))+((new_r11*x852))),-1);
7352if(!x856.valid){
7353continue;
7354}
7355IkReal x853=x856.value;
7356IkReal x854=((25000.0)*new_r11*x853);
7357if( IKabs(((((-1.0)*new_r00*x854))+x850+(((-1.0)*new_r11*x850*x852*x853)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x853*((((gconst12*x852))+(((25000.0)*new_r00*new_r01)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*x854))+x850+(((-1.0)*new_r11*x850*x852*x853))))+IKsqr((x853*((((gconst12*x852))+(((25000.0)*new_r00*new_r01))))))-1) <= IKFAST_SINCOS_THRESH )
7358 continue;
7359j5array[0]=IKatan2(((((-1.0)*new_r00*x854))+x850+(((-1.0)*new_r11*x850*x852*x853))), (x853*((((gconst12*x852))+(((25000.0)*new_r00*new_r01))))));
7360sj5array[0]=IKsin(j5array[0]);
7361cj5array[0]=IKcos(j5array[0]);
7362if( j5array[0] > IKPI )
7363{
7364 j5array[0]-=IK2PI;
7365}
7366else if( j5array[0] < -IKPI )
7367{ j5array[0]+=IK2PI;
7368}
7369j5valid[0] = true;
7370for(int ij5 = 0; ij5 < 1; ++ij5)
7371{
7372if( !j5valid[ij5] )
7373{
7374 continue;
7375}
7376_ij5[0] = ij5; _ij5[1] = -1;
7377for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7378{
7379if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7380{
7381 j5valid[iij5]=false; _ij5[1] = iij5; break;
7382}
7383}
7384j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7385{
7386IkReal evalcond[10];
7387IkReal x857=IKcos(j5);
7388IkReal x858=IKsin(j5);
7389IkReal x859=((1.0)*gconst12);
7390IkReal x860=(gconst12*x857);
7391IkReal x861=(new_r11*x858);
7392IkReal x862=(new_r01*x857);
7393IkReal x863=(new_r00*x857);
7394IkReal x864=(gconst12*x858);
7395IkReal x865=(new_r10*x858);
7396IkReal x866=x851;
7397IkReal x867=(x858*x866);
7398IkReal x868=(x857*x866);
7399evalcond[0]=((((-1.0)*x859))+((new_r11*x857))+((new_r01*x858)));
7400evalcond[1]=((((-1.0)*x865))+(((-1.0000000008)*gconst12))+x863);
7401evalcond[2]=(((new_r10*x857))+x866+((new_r00*x858)));
7402evalcond[3]=((((-1.0000000008)*x865))+(((1.0000000008)*x863))+(((-1.0)*x859)));
7403evalcond[4]=((((-1.0000000008)*x860))+new_r00+x867);
7404evalcond[5]=((((1.0000000008)*x864))+new_r10+x868);
7405evalcond[6]=((((-1.0000000008)*x868))+(((-1.0)*x858*x859))+new_r01);
7406evalcond[7]=((((1.0000000008)*x867))+new_r11+(((-1.0)*x857*x859)));
7407evalcond[8]=((((-1.0000000008)*x866))+(((-1.0)*x861))+x862);
7408evalcond[9]=((((-1.0000000008)*x861))+(((1.0000000008)*x862))+(((-1.0)*x866)));
7409if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
7410{
7411continue;
7412}
7413}
7414
7415{
7416std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7417vinfos[0].jointtype = 1;
7418vinfos[0].foffset = j0;
7419vinfos[0].indices[0] = _ij0[0];
7420vinfos[0].indices[1] = _ij0[1];
7421vinfos[0].maxsolutions = _nj0;
7422vinfos[1].jointtype = 1;
7423vinfos[1].foffset = j1;
7424vinfos[1].indices[0] = _ij1[0];
7425vinfos[1].indices[1] = _ij1[1];
7426vinfos[1].maxsolutions = _nj1;
7427vinfos[2].jointtype = 1;
7428vinfos[2].foffset = j2;
7429vinfos[2].indices[0] = _ij2[0];
7430vinfos[2].indices[1] = _ij2[1];
7431vinfos[2].maxsolutions = _nj2;
7432vinfos[3].jointtype = 1;
7433vinfos[3].foffset = j3;
7434vinfos[3].indices[0] = _ij3[0];
7435vinfos[3].indices[1] = _ij3[1];
7436vinfos[3].maxsolutions = _nj3;
7437vinfos[4].jointtype = 1;
7438vinfos[4].foffset = j4;
7439vinfos[4].indices[0] = _ij4[0];
7440vinfos[4].indices[1] = _ij4[1];
7441vinfos[4].maxsolutions = _nj4;
7442vinfos[5].jointtype = 1;
7443vinfos[5].foffset = j5;
7444vinfos[5].indices[0] = _ij5[0];
7445vinfos[5].indices[1] = _ij5[1];
7446vinfos[5].maxsolutions = _nj5;
7447std::vector<int> vfree(0);
7448solutions.AddSolution(vinfos,vfree);
7449}
7450}
7451}
7452
7453}
7454
7455}
7456
7457} else
7458{
7459{
7460IkReal j5array[1], cj5array[1], sj5array[1];
7461bool j5valid[1]={false};
7462_nj5 = 1;
7463if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7464continue;
7465IkReal x869=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
7466CheckValue<IkReal> x870 = IKatan2WithCheck(IkReal((((new_r11*x869))+((gconst12*new_r10)))),IkReal(((((-1.0)*gconst12*new_r00))+(((-1.0)*new_r01*x869)))),IKFAST_ATAN2_MAGTHRESH);
7467if(!x870.valid){
7468continue;
7469}
7470CheckValue<IkReal> x871=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
7471if(!x871.valid){
7472continue;
7473}
7474j5array[0]=((-1.5707963267949)+(x870.value)+(((1.5707963267949)*(x871.value))));
7475sj5array[0]=IKsin(j5array[0]);
7476cj5array[0]=IKcos(j5array[0]);
7477if( j5array[0] > IKPI )
7478{
7479 j5array[0]-=IK2PI;
7480}
7481else if( j5array[0] < -IKPI )
7482{ j5array[0]+=IK2PI;
7483}
7484j5valid[0] = true;
7485for(int ij5 = 0; ij5 < 1; ++ij5)
7486{
7487if( !j5valid[ij5] )
7488{
7489 continue;
7490}
7491_ij5[0] = ij5; _ij5[1] = -1;
7492for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7493{
7494if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7495{
7496 j5valid[iij5]=false; _ij5[1] = iij5; break;
7497}
7498}
7499j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7500{
7501IkReal evalcond[10];
7502IkReal x872=IKcos(j5);
7503IkReal x873=IKsin(j5);
7504IkReal x874=((1.0)*gconst12);
7505IkReal x875=(gconst12*x872);
7506IkReal x876=(new_r11*x873);
7507IkReal x877=(new_r01*x872);
7508IkReal x878=(new_r00*x872);
7509IkReal x879=(gconst12*x873);
7510IkReal x880=(new_r10*x873);
7511IkReal x881=x869;
7512IkReal x882=(x873*x881);
7513IkReal x883=(x872*x881);
7514evalcond[0]=(((new_r01*x873))+((new_r11*x872))+(((-1.0)*x874)));
7515evalcond[1]=((((-1.0)*x880))+(((-1.0000000008)*gconst12))+x878);
7516evalcond[2]=(((new_r00*x873))+((new_r10*x872))+x881);
7517evalcond[3]=((((1.0000000008)*x878))+(((-1.0000000008)*x880))+(((-1.0)*x874)));
7518evalcond[4]=((((-1.0000000008)*x875))+new_r00+x882);
7519evalcond[5]=((((1.0000000008)*x879))+new_r10+x883);
7520evalcond[6]=((((-1.0)*x873*x874))+new_r01+(((-1.0000000008)*x883)));
7521evalcond[7]=((((-1.0)*x872*x874))+(((1.0000000008)*x882))+new_r11);
7522evalcond[8]=((((-1.0)*x876))+x877+(((-1.0000000008)*x881)));
7523evalcond[9]=((((-1.0000000008)*x876))+(((1.0000000008)*x877))+(((-1.0)*x881)));
7524if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
7525{
7526continue;
7527}
7528}
7529
7530{
7531std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7532vinfos[0].jointtype = 1;
7533vinfos[0].foffset = j0;
7534vinfos[0].indices[0] = _ij0[0];
7535vinfos[0].indices[1] = _ij0[1];
7536vinfos[0].maxsolutions = _nj0;
7537vinfos[1].jointtype = 1;
7538vinfos[1].foffset = j1;
7539vinfos[1].indices[0] = _ij1[0];
7540vinfos[1].indices[1] = _ij1[1];
7541vinfos[1].maxsolutions = _nj1;
7542vinfos[2].jointtype = 1;
7543vinfos[2].foffset = j2;
7544vinfos[2].indices[0] = _ij2[0];
7545vinfos[2].indices[1] = _ij2[1];
7546vinfos[2].maxsolutions = _nj2;
7547vinfos[3].jointtype = 1;
7548vinfos[3].foffset = j3;
7549vinfos[3].indices[0] = _ij3[0];
7550vinfos[3].indices[1] = _ij3[1];
7551vinfos[3].maxsolutions = _nj3;
7552vinfos[4].jointtype = 1;
7553vinfos[4].foffset = j4;
7554vinfos[4].indices[0] = _ij4[0];
7555vinfos[4].indices[1] = _ij4[1];
7556vinfos[4].maxsolutions = _nj4;
7557vinfos[5].jointtype = 1;
7558vinfos[5].foffset = j5;
7559vinfos[5].indices[0] = _ij5[0];
7560vinfos[5].indices[1] = _ij5[1];
7561vinfos[5].maxsolutions = _nj5;
7562std::vector<int> vfree(0);
7563solutions.AddSolution(vinfos,vfree);
7564}
7565}
7566}
7567
7568}
7569
7570}
7571
7572} else
7573{
7574{
7575IkReal j5array[1], cj5array[1], sj5array[1];
7576bool j5valid[1]={false};
7577_nj5 = 1;
7578IkReal x884=((25000.00002)*gconst12);
7579IkReal x885=((25000.0)*new_r10);
7580IkReal x886=((25000.0)*new_r00);
7581CheckValue<IkReal> x887=IKPowWithIntegerCheck(IKsign((((new_r01*x886))+((new_r11*x885)))),-1);
7582if(!x887.valid){
7583continue;
7584}
7585CheckValue<IkReal> x888 = IKatan2WithCheck(IkReal(((((-1.0)*new_r11*x884))+((gconst12*x886)))),IkReal((((new_r01*x884))+((gconst12*x885)))),IKFAST_ATAN2_MAGTHRESH);
7586if(!x888.valid){
7587continue;
7588}
7589j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x887.value)))+(x888.value));
7590sj5array[0]=IKsin(j5array[0]);
7591cj5array[0]=IKcos(j5array[0]);
7592if( j5array[0] > IKPI )
7593{
7594 j5array[0]-=IK2PI;
7595}
7596else if( j5array[0] < -IKPI )
7597{ j5array[0]+=IK2PI;
7598}
7599j5valid[0] = true;
7600for(int ij5 = 0; ij5 < 1; ++ij5)
7601{
7602if( !j5valid[ij5] )
7603{
7604 continue;
7605}
7606_ij5[0] = ij5; _ij5[1] = -1;
7607for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7608{
7609if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7610{
7611 j5valid[iij5]=false; _ij5[1] = iij5; break;
7612}
7613}
7614j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7615{
7616IkReal evalcond[10];
7617IkReal x889=IKcos(j5);
7618IkReal x890=IKsin(j5);
7619IkReal x891=((1.0)*gconst12);
7620IkReal x892=(gconst12*x889);
7621IkReal x893=(new_r11*x890);
7622IkReal x894=(new_r01*x889);
7623IkReal x895=(new_r00*x889);
7624IkReal x896=(gconst12*x890);
7625IkReal x897=(new_r10*x890);
7626if((((1.0)+(((-1.0)*gconst12*x891)))) < -0.00001)
7627continue;
7628IkReal x898=IKsqrt(((1.0)+(((-1.0)*gconst12*x891))));
7629IkReal x899=(x890*x898);
7630IkReal x900=(x889*x898);
7631evalcond[0]=(((new_r11*x889))+((new_r01*x890))+(((-1.0)*x891)));
7632evalcond[1]=((((-1.0)*x897))+(((-1.0000000008)*gconst12))+x895);
7633evalcond[2]=(((new_r10*x889))+((new_r00*x890))+x898);
7634evalcond[3]=((((1.0000000008)*x895))+(((-1.0)*x891))+(((-1.0000000008)*x897)));
7635evalcond[4]=(new_r00+x899+(((-1.0000000008)*x892)));
7636evalcond[5]=((((1.0000000008)*x896))+new_r10+x900);
7637evalcond[6]=(new_r01+(((-1.0000000008)*x900))+(((-1.0)*x890*x891)));
7638evalcond[7]=((((1.0000000008)*x899))+(((-1.0)*x889*x891))+new_r11);
7639evalcond[8]=((((-1.0)*x893))+x894+(((-1.0000000008)*x898)));
7640evalcond[9]=((((1.0000000008)*x894))+(((-1.0)*x898))+(((-1.0000000008)*x893)));
7641if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
7642{
7643continue;
7644}
7645}
7646
7647{
7648std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7649vinfos[0].jointtype = 1;
7650vinfos[0].foffset = j0;
7651vinfos[0].indices[0] = _ij0[0];
7652vinfos[0].indices[1] = _ij0[1];
7653vinfos[0].maxsolutions = _nj0;
7654vinfos[1].jointtype = 1;
7655vinfos[1].foffset = j1;
7656vinfos[1].indices[0] = _ij1[0];
7657vinfos[1].indices[1] = _ij1[1];
7658vinfos[1].maxsolutions = _nj1;
7659vinfos[2].jointtype = 1;
7660vinfos[2].foffset = j2;
7661vinfos[2].indices[0] = _ij2[0];
7662vinfos[2].indices[1] = _ij2[1];
7663vinfos[2].maxsolutions = _nj2;
7664vinfos[3].jointtype = 1;
7665vinfos[3].foffset = j3;
7666vinfos[3].indices[0] = _ij3[0];
7667vinfos[3].indices[1] = _ij3[1];
7668vinfos[3].maxsolutions = _nj3;
7669vinfos[4].jointtype = 1;
7670vinfos[4].foffset = j4;
7671vinfos[4].indices[0] = _ij4[0];
7672vinfos[4].indices[1] = _ij4[1];
7673vinfos[4].maxsolutions = _nj4;
7674vinfos[5].jointtype = 1;
7675vinfos[5].foffset = j5;
7676vinfos[5].indices[0] = _ij5[0];
7677vinfos[5].indices[1] = _ij5[1];
7678vinfos[5].maxsolutions = _nj5;
7679std::vector<int> vfree(0);
7680solutions.AddSolution(vinfos,vfree);
7681}
7682}
7683}
7684
7685}
7686
7687}
7688
7689}
7690} while(0);
7691if( bgotonextstatement )
7692{
7693bool bgotonextstatement = true;
7694do
7695{
7696IkReal x901=new_r00*new_r00;
7697CheckValue<IkReal> x902=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x901))),-1);
7698if(!x902.valid){
7699continue;
7700}
7701if((((-1.0)*x901*(x902.value))) < -0.00001)
7702continue;
7703IkReal gconst12=IKsqrt(((-1.0)*x901*(x902.value)));
7704evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst12)))))), 6.28318530717959)));
7705if( IKabs(evalcond[0]) < 0.0000050000000000 )
7706{
7707bgotonextstatement=false;
7708{
7709IkReal j5eval[2];
7710IkReal x903=new_r00*new_r00;
7711sj4=4.0e-5;
7712cj4=1.0;
7713j4=4.0e-5;
7714if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7715continue;
7716sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7717cj3=gconst12;
7718if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7719 continue;
7720j3=((-1.0)*(IKacos(gconst12)));
7721CheckValue<IkReal> x904=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x903))),-1);
7722if(!x904.valid){
7723continue;
7724}
7725if((((-1.0)*x903*(x904.value))) < -0.00001)
7726continue;
7727IkReal gconst12=IKsqrt(((-1.0)*x903*(x904.value)));
7728IkReal x905=(new_r00*new_r01);
7729IkReal x906=(new_r10*new_r11);
7730j5eval[0]=(x905+x906);
7731j5eval[1]=IKsign(((((25000.0)*x906))+(((25000.0)*x905))));
7732if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
7733{
7734{
7735IkReal j5eval[2];
7736IkReal x907=new_r00*new_r00;
7737sj4=4.0e-5;
7738cj4=1.0;
7739j4=4.0e-5;
7740if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7741continue;
7742sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7743cj3=gconst12;
7744if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7745 continue;
7746j3=((-1.0)*(IKacos(gconst12)));
7747CheckValue<IkReal> x908=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x907))),-1);
7748if(!x908.valid){
7749continue;
7750}
7751if((((-1.0)*x907*(x908.value))) < -0.00001)
7752continue;
7753IkReal gconst12=IKsqrt(((-1.0)*x907*(x908.value)));
7754IkReal x909=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
7755j5eval[0]=x909;
7756j5eval[1]=IKsign(x909);
7757if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
7758{
7759{
7760IkReal j5eval[1];
7761IkReal x910=new_r00*new_r00;
7762sj4=4.0e-5;
7763cj4=1.0;
7764j4=4.0e-5;
7765if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7766continue;
7767sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7768cj3=gconst12;
7769if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7770 continue;
7771j3=((-1.0)*(IKacos(gconst12)));
7772CheckValue<IkReal> x911=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x910))),-1);
7773if(!x911.valid){
7774continue;
7775}
7776if((((-1.0)*x910*(x911.value))) < -0.00001)
7777continue;
7778IkReal gconst12=IKsqrt(((-1.0)*x910*(x911.value)));
7779j5eval[0]=new_r01;
7780if( IKabs(j5eval[0]) < 0.0000010000000000 )
7781{
7782{
7783IkReal evalcond[1];
7784bool bgotonextstatement = true;
7785do
7786{
7787evalcond[0]=IKabs(new_r01);
7788if( IKabs(evalcond[0]) < 0.0000050000000000 )
7789{
7790bgotonextstatement=false;
7791{
7792IkReal j5eval[1];
7793IkReal x912=new_r00*new_r00;
7794sj4=4.0e-5;
7795cj4=1.0;
7796j4=4.0e-5;
7797if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7798continue;
7799sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7800cj3=gconst12;
7801if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7802 continue;
7803j3=((-1.0)*(IKacos(gconst12)));
7804new_r01=0;
7805CheckValue<IkReal> x913=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x912))),-1);
7806if(!x913.valid){
7807continue;
7808}
7809if((((-1.0)*x912*(x913.value))) < -0.00001)
7810continue;
7811IkReal gconst12=IKsqrt(((-1.0)*x912*(x913.value)));
7812j5eval[0]=new_r11;
7813if( IKabs(j5eval[0]) < 0.0000010000000000 )
7814{
7815{
7816IkReal j5eval[2];
7817IkReal x914=new_r00*new_r00;
7818sj4=4.0e-5;
7819cj4=1.0;
7820j4=4.0e-5;
7821if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7822continue;
7823sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7824cj3=gconst12;
7825if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7826 continue;
7827j3=((-1.0)*(IKacos(gconst12)));
7828new_r01=0;
7829CheckValue<IkReal> x915=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x914))),-1);
7830if(!x915.valid){
7831continue;
7832}
7833if((((-1.0)*x914*(x915.value))) < -0.00001)
7834continue;
7835IkReal gconst12=IKsqrt(((-1.0)*x914*(x915.value)));
7836j5eval[0]=new_r10;
7837j5eval[1]=new_r11;
7838if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
7839{
7840{
7841IkReal j5eval[2];
7842IkReal x916=new_r00*new_r00;
7843sj4=4.0e-5;
7844cj4=1.0;
7845j4=4.0e-5;
7846if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7847continue;
7848sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))));
7849cj3=gconst12;
7850if( (gconst12) < -1-IKFAST_SINCOS_THRESH || (gconst12) > 1+IKFAST_SINCOS_THRESH )
7851 continue;
7852j3=((-1.0)*(IKacos(gconst12)));
7853new_r01=0;
7854CheckValue<IkReal> x917=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x916))),-1);
7855if(!x917.valid){
7856continue;
7857}
7858if((((-1.0)*x916*(x917.value))) < -0.00001)
7859continue;
7860IkReal gconst12=IKsqrt(((-1.0)*x916*(x917.value)));
7861j5eval[0]=new_r00;
7862j5eval[1]=new_r11;
7863if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
7864{
7865continue; // 3 cases reached
7866
7867} else
7868{
7869{
7870IkReal j5array[1], cj5array[1], sj5array[1];
7871bool j5valid[1]={false};
7872_nj5 = 1;
7873CheckValue<IkReal> x919=IKPowWithIntegerCheck(new_r11,-1);
7874if(!x919.valid){
7875continue;
7876}
7877IkReal x918=x919.value;
7878CheckValue<IkReal> x920=IKPowWithIntegerCheck(new_r00,-1);
7879if(!x920.valid){
7880continue;
7881}
7882if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
7883continue;
7884if( IKabs((x918*(x920.value)*(((((-1.0)*gconst12*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst12*x918)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x918*(x920.value)*(((((-1.0)*gconst12*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))))))+IKsqr((gconst12*x918))-1) <= IKFAST_SINCOS_THRESH )
7885 continue;
7886j5array[0]=IKatan2((x918*(x920.value)*(((((-1.0)*gconst12*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))))), (gconst12*x918));
7887sj5array[0]=IKsin(j5array[0]);
7888cj5array[0]=IKcos(j5array[0]);
7889if( j5array[0] > IKPI )
7890{
7891 j5array[0]-=IK2PI;
7892}
7893else if( j5array[0] < -IKPI )
7894{ j5array[0]+=IK2PI;
7895}
7896j5valid[0] = true;
7897for(int ij5 = 0; ij5 < 1; ++ij5)
7898{
7899if( !j5valid[ij5] )
7900{
7901 continue;
7902}
7903_ij5[0] = ij5; _ij5[1] = -1;
7904for(int iij5 = ij5+1; iij5 < 1; ++iij5)
7905{
7906if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
7907{
7908 j5valid[iij5]=false; _ij5[1] = iij5; break;
7909}
7910}
7911j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
7912{
7913IkReal evalcond[10];
7914IkReal x921=IKcos(j5);
7915IkReal x922=IKsin(j5);
7916IkReal x923=((1.0)*gconst12);
7917IkReal x924=(gconst12*x921);
7918IkReal x925=(new_r11*x922);
7919IkReal x926=(new_r00*x921);
7920IkReal x927=(gconst12*x922);
7921IkReal x928=(new_r10*x922);
7922if((((1.0)+(((-1.0)*gconst12*x923)))) < -0.00001)
7923continue;
7924IkReal x929=IKsqrt(((1.0)+(((-1.0)*gconst12*x923))));
7925IkReal x930=((1.0)*x929);
7926IkReal x931=((1.0000000008)*x929);
7927evalcond[0]=((((-1.0)*x923))+((new_r11*x921)));
7928evalcond[1]=((((-1.0000000008)*gconst12))+(((-1.0)*x928))+x926);
7929evalcond[2]=((((-1.0000000008)*x925))+x929);
7930evalcond[3]=((((-1.0)*x925))+x931);
7931evalcond[4]=(((new_r00*x922))+((new_r10*x921))+(((-1.0)*x930)));
7932evalcond[5]=((((-1.0)*x923))+(((-1.0000000008)*x928))+(((1.0000000008)*x926)));
7933evalcond[6]=(((x921*x931))+(((-1.0)*x922*x923)));
7934evalcond[7]=((((-1.0000000008)*x924))+new_r00+(((-1.0)*x922*x930)));
7935evalcond[8]=((((1.0000000008)*x927))+(((-1.0)*x921*x930))+new_r10);
7936evalcond[9]=((((-1.0)*x921*x923))+new_r11+(((-1.0)*x922*x931)));
7937if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
7938{
7939continue;
7940}
7941}
7942
7943{
7944std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7945vinfos[0].jointtype = 1;
7946vinfos[0].foffset = j0;
7947vinfos[0].indices[0] = _ij0[0];
7948vinfos[0].indices[1] = _ij0[1];
7949vinfos[0].maxsolutions = _nj0;
7950vinfos[1].jointtype = 1;
7951vinfos[1].foffset = j1;
7952vinfos[1].indices[0] = _ij1[0];
7953vinfos[1].indices[1] = _ij1[1];
7954vinfos[1].maxsolutions = _nj1;
7955vinfos[2].jointtype = 1;
7956vinfos[2].foffset = j2;
7957vinfos[2].indices[0] = _ij2[0];
7958vinfos[2].indices[1] = _ij2[1];
7959vinfos[2].maxsolutions = _nj2;
7960vinfos[3].jointtype = 1;
7961vinfos[3].foffset = j3;
7962vinfos[3].indices[0] = _ij3[0];
7963vinfos[3].indices[1] = _ij3[1];
7964vinfos[3].maxsolutions = _nj3;
7965vinfos[4].jointtype = 1;
7966vinfos[4].foffset = j4;
7967vinfos[4].indices[0] = _ij4[0];
7968vinfos[4].indices[1] = _ij4[1];
7969vinfos[4].maxsolutions = _nj4;
7970vinfos[5].jointtype = 1;
7971vinfos[5].foffset = j5;
7972vinfos[5].indices[0] = _ij5[0];
7973vinfos[5].indices[1] = _ij5[1];
7974vinfos[5].maxsolutions = _nj5;
7975std::vector<int> vfree(0);
7976solutions.AddSolution(vinfos,vfree);
7977}
7978}
7979}
7980
7981}
7982
7983}
7984
7985} else
7986{
7987{
7988IkReal j5array[1], cj5array[1], sj5array[1];
7989bool j5valid[1]={false};
7990_nj5 = 1;
7991CheckValue<IkReal> x933=IKPowWithIntegerCheck(new_r11,-1);
7992if(!x933.valid){
7993continue;
7994}
7995IkReal x932=x933.value;
7996CheckValue<IkReal> x934=IKPowWithIntegerCheck(new_r10,-1);
7997if(!x934.valid){
7998continue;
7999}
8000if( IKabs(((4.0e-5)*x932*(x934.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst12*x932)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((4.0e-5)*x932*(x934.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11))))))+IKsqr((gconst12*x932))-1) <= IKFAST_SINCOS_THRESH )
8001 continue;
8002j5array[0]=IKatan2(((4.0e-5)*x932*(x934.value)*(((((25000.0)*gconst12*new_r00))+(((-25000.00002)*gconst12*new_r11))))), (gconst12*x932));
8003sj5array[0]=IKsin(j5array[0]);
8004cj5array[0]=IKcos(j5array[0]);
8005if( j5array[0] > IKPI )
8006{
8007 j5array[0]-=IK2PI;
8008}
8009else if( j5array[0] < -IKPI )
8010{ j5array[0]+=IK2PI;
8011}
8012j5valid[0] = true;
8013for(int ij5 = 0; ij5 < 1; ++ij5)
8014{
8015if( !j5valid[ij5] )
8016{
8017 continue;
8018}
8019_ij5[0] = ij5; _ij5[1] = -1;
8020for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8021{
8022if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8023{
8024 j5valid[iij5]=false; _ij5[1] = iij5; break;
8025}
8026}
8027j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8028{
8029IkReal evalcond[10];
8030IkReal x935=IKcos(j5);
8031IkReal x936=IKsin(j5);
8032IkReal x937=((1.0)*gconst12);
8033IkReal x938=(gconst12*x935);
8034IkReal x939=(new_r11*x936);
8035IkReal x940=(new_r00*x935);
8036IkReal x941=(gconst12*x936);
8037IkReal x942=(new_r10*x936);
8038if((((1.0)+(((-1.0)*gconst12*x937)))) < -0.00001)
8039continue;
8040IkReal x943=IKsqrt(((1.0)+(((-1.0)*gconst12*x937))));
8041IkReal x944=((1.0)*x943);
8042IkReal x945=((1.0000000008)*x943);
8043evalcond[0]=(((new_r11*x935))+(((-1.0)*x937)));
8044evalcond[1]=((((-1.0)*x942))+(((-1.0000000008)*gconst12))+x940);
8045evalcond[2]=((((-1.0000000008)*x939))+x943);
8046evalcond[3]=((((-1.0)*x939))+x945);
8047evalcond[4]=((((-1.0)*x944))+((new_r00*x936))+((new_r10*x935)));
8048evalcond[5]=((((1.0000000008)*x940))+(((-1.0000000008)*x942))+(((-1.0)*x937)));
8049evalcond[6]=(((x935*x945))+(((-1.0)*x936*x937)));
8050evalcond[7]=((((-1.0000000008)*x938))+(((-1.0)*x936*x944))+new_r00);
8051evalcond[8]=((((1.0000000008)*x941))+new_r10+(((-1.0)*x935*x944)));
8052evalcond[9]=((((-1.0)*x935*x937))+(((-1.0)*x936*x945))+new_r11);
8053if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
8054{
8055continue;
8056}
8057}
8058
8059{
8060std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8061vinfos[0].jointtype = 1;
8062vinfos[0].foffset = j0;
8063vinfos[0].indices[0] = _ij0[0];
8064vinfos[0].indices[1] = _ij0[1];
8065vinfos[0].maxsolutions = _nj0;
8066vinfos[1].jointtype = 1;
8067vinfos[1].foffset = j1;
8068vinfos[1].indices[0] = _ij1[0];
8069vinfos[1].indices[1] = _ij1[1];
8070vinfos[1].maxsolutions = _nj1;
8071vinfos[2].jointtype = 1;
8072vinfos[2].foffset = j2;
8073vinfos[2].indices[0] = _ij2[0];
8074vinfos[2].indices[1] = _ij2[1];
8075vinfos[2].maxsolutions = _nj2;
8076vinfos[3].jointtype = 1;
8077vinfos[3].foffset = j3;
8078vinfos[3].indices[0] = _ij3[0];
8079vinfos[3].indices[1] = _ij3[1];
8080vinfos[3].maxsolutions = _nj3;
8081vinfos[4].jointtype = 1;
8082vinfos[4].foffset = j4;
8083vinfos[4].indices[0] = _ij4[0];
8084vinfos[4].indices[1] = _ij4[1];
8085vinfos[4].maxsolutions = _nj4;
8086vinfos[5].jointtype = 1;
8087vinfos[5].foffset = j5;
8088vinfos[5].indices[0] = _ij5[0];
8089vinfos[5].indices[1] = _ij5[1];
8090vinfos[5].maxsolutions = _nj5;
8091std::vector<int> vfree(0);
8092solutions.AddSolution(vinfos,vfree);
8093}
8094}
8095}
8096
8097}
8098
8099}
8100
8101} else
8102{
8103{
8104IkReal j5array[1], cj5array[1], sj5array[1];
8105bool j5valid[1]={false};
8106_nj5 = 1;
8107CheckValue<IkReal> x947=IKPowWithIntegerCheck(new_r11,-1);
8108if(!x947.valid){
8109continue;
8110}
8111IkReal x946=x947.value;
8112if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
8113continue;
8114if( IKabs(((0.9999999992)*x946*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst12*x946)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*x946*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))))+IKsqr((gconst12*x946))-1) <= IKFAST_SINCOS_THRESH )
8115 continue;
8116j5array[0]=IKatan2(((0.9999999992)*x946*(IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12))))))), (gconst12*x946));
8117sj5array[0]=IKsin(j5array[0]);
8118cj5array[0]=IKcos(j5array[0]);
8119if( j5array[0] > IKPI )
8120{
8121 j5array[0]-=IK2PI;
8122}
8123else if( j5array[0] < -IKPI )
8124{ j5array[0]+=IK2PI;
8125}
8126j5valid[0] = true;
8127for(int ij5 = 0; ij5 < 1; ++ij5)
8128{
8129if( !j5valid[ij5] )
8130{
8131 continue;
8132}
8133_ij5[0] = ij5; _ij5[1] = -1;
8134for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8135{
8136if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8137{
8138 j5valid[iij5]=false; _ij5[1] = iij5; break;
8139}
8140}
8141j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8142{
8143IkReal evalcond[10];
8144IkReal x948=IKcos(j5);
8145IkReal x949=IKsin(j5);
8146IkReal x950=((1.0)*gconst12);
8147IkReal x951=(gconst12*x948);
8148IkReal x952=(new_r11*x949);
8149IkReal x953=(new_r00*x948);
8150IkReal x954=(gconst12*x949);
8151IkReal x955=(new_r10*x949);
8152if((((1.0)+(((-1.0)*gconst12*x950)))) < -0.00001)
8153continue;
8154IkReal x956=IKsqrt(((1.0)+(((-1.0)*gconst12*x950))));
8155IkReal x957=((1.0)*x956);
8156IkReal x958=((1.0000000008)*x956);
8157evalcond[0]=(((new_r11*x948))+(((-1.0)*x950)));
8158evalcond[1]=((((-1.0)*x955))+(((-1.0000000008)*gconst12))+x953);
8159evalcond[2]=((((-1.0000000008)*x952))+x956);
8160evalcond[3]=((((-1.0)*x952))+x958);
8161evalcond[4]=(((new_r00*x949))+((new_r10*x948))+(((-1.0)*x957)));
8162evalcond[5]=((((1.0000000008)*x953))+(((-1.0000000008)*x955))+(((-1.0)*x950)));
8163evalcond[6]=(((x948*x958))+(((-1.0)*x949*x950)));
8164evalcond[7]=((((-1.0000000008)*x951))+(((-1.0)*x949*x957))+new_r00);
8165evalcond[8]=((((1.0000000008)*x954))+new_r10+(((-1.0)*x948*x957)));
8166evalcond[9]=((((-1.0)*x949*x958))+new_r11+(((-1.0)*x948*x950)));
8167if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
8168{
8169continue;
8170}
8171}
8172
8173{
8174std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8175vinfos[0].jointtype = 1;
8176vinfos[0].foffset = j0;
8177vinfos[0].indices[0] = _ij0[0];
8178vinfos[0].indices[1] = _ij0[1];
8179vinfos[0].maxsolutions = _nj0;
8180vinfos[1].jointtype = 1;
8181vinfos[1].foffset = j1;
8182vinfos[1].indices[0] = _ij1[0];
8183vinfos[1].indices[1] = _ij1[1];
8184vinfos[1].maxsolutions = _nj1;
8185vinfos[2].jointtype = 1;
8186vinfos[2].foffset = j2;
8187vinfos[2].indices[0] = _ij2[0];
8188vinfos[2].indices[1] = _ij2[1];
8189vinfos[2].maxsolutions = _nj2;
8190vinfos[3].jointtype = 1;
8191vinfos[3].foffset = j3;
8192vinfos[3].indices[0] = _ij3[0];
8193vinfos[3].indices[1] = _ij3[1];
8194vinfos[3].maxsolutions = _nj3;
8195vinfos[4].jointtype = 1;
8196vinfos[4].foffset = j4;
8197vinfos[4].indices[0] = _ij4[0];
8198vinfos[4].indices[1] = _ij4[1];
8199vinfos[4].maxsolutions = _nj4;
8200vinfos[5].jointtype = 1;
8201vinfos[5].foffset = j5;
8202vinfos[5].indices[0] = _ij5[0];
8203vinfos[5].indices[1] = _ij5[1];
8204vinfos[5].maxsolutions = _nj5;
8205std::vector<int> vfree(0);
8206solutions.AddSolution(vinfos,vfree);
8207}
8208}
8209}
8210
8211}
8212
8213}
8214
8215}
8216} while(0);
8217if( bgotonextstatement )
8218{
8219bool bgotonextstatement = true;
8220do
8221{
8222evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
8223if( IKabs(evalcond[0]) < 0.0000050000000000 )
8224{
8225bgotonextstatement=false;
8226{
8227IkReal j5array[2], cj5array[2], sj5array[2];
8228bool j5valid[2]={false};
8229_nj5 = 2;
8230cj5array[0]=new_r10;
8231if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
8232{
8233 j5valid[0] = j5valid[1] = true;
8234 j5array[0] = IKacos(cj5array[0]);
8235 sj5array[0] = IKsin(j5array[0]);
8236 cj5array[1] = cj5array[0];
8237 j5array[1] = -j5array[0];
8238 sj5array[1] = -sj5array[0];
8239}
8240else if( isnan(cj5array[0]) )
8241{
8242 // probably any value will work
8243 j5valid[0] = true;
8244 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
8245}
8246for(int ij5 = 0; ij5 < 2; ++ij5)
8247{
8248if( !j5valid[ij5] )
8249{
8250 continue;
8251}
8252_ij5[0] = ij5; _ij5[1] = -1;
8253for(int iij5 = ij5+1; iij5 < 2; ++iij5)
8254{
8255if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8256{
8257 j5valid[iij5]=false; _ij5[1] = iij5; break;
8258}
8259}
8260j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8261{
8262IkReal evalcond[9];
8263IkReal x959=IKsin(j5);
8264IkReal x960=IKcos(j5);
8265IkReal x961=((1.0000000008)*x960);
8266IkReal x962=((-1.0000000008)*x959);
8267IkReal x963=((-1.0)*x959);
8268evalcond[0]=(new_r01*x959);
8269evalcond[1]=x963;
8270evalcond[2]=(new_r10*x963);
8271evalcond[3]=((-1.0)+((new_r10*x960)));
8272evalcond[4]=x962;
8273evalcond[5]=(new_r10*x962);
8274evalcond[6]=(new_r01+x961);
8275evalcond[7]=((1.0000000008)+((new_r01*x960)));
8276evalcond[8]=((1.0)+((new_r01*x961)));
8277if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
8278{
8279continue;
8280}
8281}
8282
8283{
8284std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8285vinfos[0].jointtype = 1;
8286vinfos[0].foffset = j0;
8287vinfos[0].indices[0] = _ij0[0];
8288vinfos[0].indices[1] = _ij0[1];
8289vinfos[0].maxsolutions = _nj0;
8290vinfos[1].jointtype = 1;
8291vinfos[1].foffset = j1;
8292vinfos[1].indices[0] = _ij1[0];
8293vinfos[1].indices[1] = _ij1[1];
8294vinfos[1].maxsolutions = _nj1;
8295vinfos[2].jointtype = 1;
8296vinfos[2].foffset = j2;
8297vinfos[2].indices[0] = _ij2[0];
8298vinfos[2].indices[1] = _ij2[1];
8299vinfos[2].maxsolutions = _nj2;
8300vinfos[3].jointtype = 1;
8301vinfos[3].foffset = j3;
8302vinfos[3].indices[0] = _ij3[0];
8303vinfos[3].indices[1] = _ij3[1];
8304vinfos[3].maxsolutions = _nj3;
8305vinfos[4].jointtype = 1;
8306vinfos[4].foffset = j4;
8307vinfos[4].indices[0] = _ij4[0];
8308vinfos[4].indices[1] = _ij4[1];
8309vinfos[4].maxsolutions = _nj4;
8310vinfos[5].jointtype = 1;
8311vinfos[5].foffset = j5;
8312vinfos[5].indices[0] = _ij5[0];
8313vinfos[5].indices[1] = _ij5[1];
8314vinfos[5].maxsolutions = _nj5;
8315std::vector<int> vfree(0);
8316solutions.AddSolution(vinfos,vfree);
8317}
8318}
8319}
8320
8321}
8322} while(0);
8323if( bgotonextstatement )
8324{
8325bool bgotonextstatement = true;
8326do
8327{
8328evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
8329if( IKabs(evalcond[0]) < 0.0000050000000000 )
8330{
8331bgotonextstatement=false;
8332{
8333IkReal j5array[1], cj5array[1], sj5array[1];
8334bool j5valid[1]={false};
8335_nj5 = 1;
8336if( IKabs(((0.9999999992)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11))+IKsqr(((-0.9999999992)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
8337 continue;
8338j5array[0]=IKatan2(((0.9999999992)*new_r11), ((-0.9999999992)*new_r01));
8339sj5array[0]=IKsin(j5array[0]);
8340cj5array[0]=IKcos(j5array[0]);
8341if( j5array[0] > IKPI )
8342{
8343 j5array[0]-=IK2PI;
8344}
8345else if( j5array[0] < -IKPI )
8346{ j5array[0]+=IK2PI;
8347}
8348j5valid[0] = true;
8349for(int ij5 = 0; ij5 < 1; ++ij5)
8350{
8351if( !j5valid[ij5] )
8352{
8353 continue;
8354}
8355_ij5[0] = ij5; _ij5[1] = -1;
8356for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8357{
8358if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8359{
8360 j5valid[iij5]=false; _ij5[1] = iij5; break;
8361}
8362}
8363j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8364{
8365IkReal evalcond[7];
8366IkReal x964=IKcos(j5);
8367IkReal x965=IKsin(j5);
8368IkReal x966=((1.0000000008)*x965);
8369IkReal x967=((1.0000000008)*x964);
8370evalcond[0]=((-1.0)*x965);
8371evalcond[1]=((-1.0)*x964);
8372evalcond[2]=(new_r01+x967);
8373evalcond[3]=(new_r11+(((-1.0)*x966)));
8374evalcond[4]=(((new_r11*x964))+((new_r01*x965)));
8375evalcond[5]=((1.0000000008)+((new_r01*x964))+(((-1.0)*new_r11*x965)));
8376evalcond[6]=((1.0)+((new_r01*x967))+(((-1.0)*new_r11*x966)));
8377if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
8378{
8379continue;
8380}
8381}
8382
8383{
8384std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8385vinfos[0].jointtype = 1;
8386vinfos[0].foffset = j0;
8387vinfos[0].indices[0] = _ij0[0];
8388vinfos[0].indices[1] = _ij0[1];
8389vinfos[0].maxsolutions = _nj0;
8390vinfos[1].jointtype = 1;
8391vinfos[1].foffset = j1;
8392vinfos[1].indices[0] = _ij1[0];
8393vinfos[1].indices[1] = _ij1[1];
8394vinfos[1].maxsolutions = _nj1;
8395vinfos[2].jointtype = 1;
8396vinfos[2].foffset = j2;
8397vinfos[2].indices[0] = _ij2[0];
8398vinfos[2].indices[1] = _ij2[1];
8399vinfos[2].maxsolutions = _nj2;
8400vinfos[3].jointtype = 1;
8401vinfos[3].foffset = j3;
8402vinfos[3].indices[0] = _ij3[0];
8403vinfos[3].indices[1] = _ij3[1];
8404vinfos[3].maxsolutions = _nj3;
8405vinfos[4].jointtype = 1;
8406vinfos[4].foffset = j4;
8407vinfos[4].indices[0] = _ij4[0];
8408vinfos[4].indices[1] = _ij4[1];
8409vinfos[4].maxsolutions = _nj4;
8410vinfos[5].jointtype = 1;
8411vinfos[5].foffset = j5;
8412vinfos[5].indices[0] = _ij5[0];
8413vinfos[5].indices[1] = _ij5[1];
8414vinfos[5].maxsolutions = _nj5;
8415std::vector<int> vfree(0);
8416solutions.AddSolution(vinfos,vfree);
8417}
8418}
8419}
8420
8421}
8422} while(0);
8423if( bgotonextstatement )
8424{
8425bool bgotonextstatement = true;
8426do
8427{
8428if( 1 )
8429{
8430bgotonextstatement=false;
8431continue; // branch miss [j5]
8432
8433}
8434} while(0);
8435if( bgotonextstatement )
8436{
8437}
8438}
8439}
8440}
8441}
8442
8443} else
8444{
8445{
8446IkReal j5array[1], cj5array[1], sj5array[1];
8447bool j5valid[1]={false};
8448_nj5 = 1;
8449CheckValue<IkReal> x975=IKPowWithIntegerCheck(new_r01,-1);
8450if(!x975.valid){
8451continue;
8452}
8453IkReal x968=x975.value;
8454IkReal x969=(gconst12*x968);
8455IkReal x970=((25000.0)*new_r00);
8456if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
8457continue;
8458IkReal x971=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
8459IkReal x972=((25000.0)*new_r11*x971);
8460CheckValue<IkReal> x976=IKPowWithIntegerCheck(((((25000.00002)*gconst12*new_r01))+(((-1.0)*x972))),-1);
8461if(!x976.valid){
8462continue;
8463}
8464IkReal x973=x976.value;
8465IkReal x974=((25000.0)*new_r11*x973);
8466CheckValue<IkReal> x977=IKPowWithIntegerCheck(((((25000.00002)*gconst12*new_r01))+(((-25000.0)*new_r11*x971))),-1);
8467if(!x977.valid){
8468continue;
8469}
8470if( IKabs(((((-1.0)*new_r11*x970*x973))+((x969*x972*(x977.value)))+x969)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x973*((((new_r01*x970))+(((-25000.0)*gconst12*x971)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r11*x970*x973))+((x969*x972*(x977.value)))+x969))+IKsqr((x973*((((new_r01*x970))+(((-25000.0)*gconst12*x971))))))-1) <= IKFAST_SINCOS_THRESH )
8471 continue;
8472j5array[0]=IKatan2(((((-1.0)*new_r11*x970*x973))+((x969*x972*(x977.value)))+x969), (x973*((((new_r01*x970))+(((-25000.0)*gconst12*x971))))));
8473sj5array[0]=IKsin(j5array[0]);
8474cj5array[0]=IKcos(j5array[0]);
8475if( j5array[0] > IKPI )
8476{
8477 j5array[0]-=IK2PI;
8478}
8479else if( j5array[0] < -IKPI )
8480{ j5array[0]+=IK2PI;
8481}
8482j5valid[0] = true;
8483for(int ij5 = 0; ij5 < 1; ++ij5)
8484{
8485if( !j5valid[ij5] )
8486{
8487 continue;
8488}
8489_ij5[0] = ij5; _ij5[1] = -1;
8490for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8491{
8492if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8493{
8494 j5valid[iij5]=false; _ij5[1] = iij5; break;
8495}
8496}
8497j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8498{
8499IkReal evalcond[10];
8500IkReal x978=IKcos(j5);
8501IkReal x979=IKsin(j5);
8502IkReal x980=((1.0)*gconst12);
8503IkReal x981=(gconst12*x978);
8504IkReal x982=(new_r11*x979);
8505IkReal x983=(new_r01*x978);
8506IkReal x984=(new_r00*x978);
8507IkReal x985=(gconst12*x979);
8508IkReal x986=(new_r10*x979);
8509IkReal x987=x971;
8510IkReal x988=((1.0)*x987);
8511IkReal x989=((1.0000000008)*x987);
8512evalcond[0]=((((-1.0)*x980))+((new_r01*x979))+((new_r11*x978)));
8513evalcond[1]=((((-1.0)*x986))+(((-1.0000000008)*gconst12))+x984);
8514evalcond[2]=((((-1.0)*x988))+((new_r10*x978))+((new_r00*x979)));
8515evalcond[3]=((((-1.0)*x980))+(((-1.0000000008)*x986))+(((1.0000000008)*x984)));
8516evalcond[4]=((((-1.0000000008)*x981))+new_r00+(((-1.0)*x979*x988)));
8517evalcond[5]=((((-1.0)*x978*x988))+new_r10+(((1.0000000008)*x985)));
8518evalcond[6]=(new_r01+(((-1.0)*x979*x980))+((x978*x989)));
8519evalcond[7]=((((-1.0)*x978*x980))+new_r11+(((-1.0)*x979*x989)));
8520evalcond[8]=((((-1.0)*x982))+x989+x983);
8521evalcond[9]=((((-1.0000000008)*x982))+(((1.0000000008)*x983))+x987);
8522if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
8523{
8524continue;
8525}
8526}
8527
8528{
8529std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8530vinfos[0].jointtype = 1;
8531vinfos[0].foffset = j0;
8532vinfos[0].indices[0] = _ij0[0];
8533vinfos[0].indices[1] = _ij0[1];
8534vinfos[0].maxsolutions = _nj0;
8535vinfos[1].jointtype = 1;
8536vinfos[1].foffset = j1;
8537vinfos[1].indices[0] = _ij1[0];
8538vinfos[1].indices[1] = _ij1[1];
8539vinfos[1].maxsolutions = _nj1;
8540vinfos[2].jointtype = 1;
8541vinfos[2].foffset = j2;
8542vinfos[2].indices[0] = _ij2[0];
8543vinfos[2].indices[1] = _ij2[1];
8544vinfos[2].maxsolutions = _nj2;
8545vinfos[3].jointtype = 1;
8546vinfos[3].foffset = j3;
8547vinfos[3].indices[0] = _ij3[0];
8548vinfos[3].indices[1] = _ij3[1];
8549vinfos[3].maxsolutions = _nj3;
8550vinfos[4].jointtype = 1;
8551vinfos[4].foffset = j4;
8552vinfos[4].indices[0] = _ij4[0];
8553vinfos[4].indices[1] = _ij4[1];
8554vinfos[4].maxsolutions = _nj4;
8555vinfos[5].jointtype = 1;
8556vinfos[5].foffset = j5;
8557vinfos[5].indices[0] = _ij5[0];
8558vinfos[5].indices[1] = _ij5[1];
8559vinfos[5].maxsolutions = _nj5;
8560std::vector<int> vfree(0);
8561solutions.AddSolution(vinfos,vfree);
8562}
8563}
8564}
8565
8566}
8567
8568}
8569
8570} else
8571{
8572{
8573IkReal j5array[1], cj5array[1], sj5array[1];
8574bool j5valid[1]={false};
8575_nj5 = 1;
8576IkReal x990=((1.0)*new_r11);
8577if((((1.0)+(((-1.0)*(gconst12*gconst12))))) < -0.00001)
8578continue;
8579IkReal x991=IKsqrt(((1.0)+(((-1.0)*(gconst12*gconst12)))));
8580CheckValue<IkReal> x992=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*x990))+((new_r01*new_r10)))),-1);
8581if(!x992.valid){
8582continue;
8583}
8584CheckValue<IkReal> x993 = IKatan2WithCheck(IkReal(((((-1.0)*x990*x991))+((gconst12*new_r10)))),IkReal(((((-1.0)*gconst12*new_r00))+((new_r01*x991)))),IKFAST_ATAN2_MAGTHRESH);
8585if(!x993.valid){
8586continue;
8587}
8588j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x992.value)))+(x993.value));
8589sj5array[0]=IKsin(j5array[0]);
8590cj5array[0]=IKcos(j5array[0]);
8591if( j5array[0] > IKPI )
8592{
8593 j5array[0]-=IK2PI;
8594}
8595else if( j5array[0] < -IKPI )
8596{ j5array[0]+=IK2PI;
8597}
8598j5valid[0] = true;
8599for(int ij5 = 0; ij5 < 1; ++ij5)
8600{
8601if( !j5valid[ij5] )
8602{
8603 continue;
8604}
8605_ij5[0] = ij5; _ij5[1] = -1;
8606for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8607{
8608if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8609{
8610 j5valid[iij5]=false; _ij5[1] = iij5; break;
8611}
8612}
8613j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8614{
8615IkReal evalcond[10];
8616IkReal x994=IKcos(j5);
8617IkReal x995=IKsin(j5);
8618IkReal x996=((1.0)*gconst12);
8619IkReal x997=(gconst12*x994);
8620IkReal x998=(new_r11*x995);
8621IkReal x999=(new_r01*x994);
8622IkReal x1000=(new_r00*x994);
8623IkReal x1001=(gconst12*x995);
8624IkReal x1002=(new_r10*x995);
8625IkReal x1003=x991;
8626IkReal x1004=((1.0)*x1003);
8627IkReal x1005=((1.0000000008)*x1003);
8628evalcond[0]=(((new_r11*x994))+(((-1.0)*x996))+((new_r01*x995)));
8629evalcond[1]=((((-1.0)*x1002))+x1000+(((-1.0000000008)*gconst12)));
8630evalcond[2]=((((-1.0)*x1004))+((new_r10*x994))+((new_r00*x995)));
8631evalcond[3]=((((-1.0000000008)*x1002))+(((1.0000000008)*x1000))+(((-1.0)*x996)));
8632evalcond[4]=((((-1.0000000008)*x997))+(((-1.0)*x1004*x995))+new_r00);
8633evalcond[5]=((((1.0000000008)*x1001))+(((-1.0)*x1004*x994))+new_r10);
8634evalcond[6]=((((-1.0)*x995*x996))+new_r01+((x1005*x994)));
8635evalcond[7]=((((-1.0)*x994*x996))+new_r11+(((-1.0)*x1005*x995)));
8636evalcond[8]=((((-1.0)*x998))+x1005+x999);
8637evalcond[9]=(x1003+(((-1.0000000008)*x998))+(((1.0000000008)*x999)));
8638if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
8639{
8640continue;
8641}
8642}
8643
8644{
8645std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8646vinfos[0].jointtype = 1;
8647vinfos[0].foffset = j0;
8648vinfos[0].indices[0] = _ij0[0];
8649vinfos[0].indices[1] = _ij0[1];
8650vinfos[0].maxsolutions = _nj0;
8651vinfos[1].jointtype = 1;
8652vinfos[1].foffset = j1;
8653vinfos[1].indices[0] = _ij1[0];
8654vinfos[1].indices[1] = _ij1[1];
8655vinfos[1].maxsolutions = _nj1;
8656vinfos[2].jointtype = 1;
8657vinfos[2].foffset = j2;
8658vinfos[2].indices[0] = _ij2[0];
8659vinfos[2].indices[1] = _ij2[1];
8660vinfos[2].maxsolutions = _nj2;
8661vinfos[3].jointtype = 1;
8662vinfos[3].foffset = j3;
8663vinfos[3].indices[0] = _ij3[0];
8664vinfos[3].indices[1] = _ij3[1];
8665vinfos[3].maxsolutions = _nj3;
8666vinfos[4].jointtype = 1;
8667vinfos[4].foffset = j4;
8668vinfos[4].indices[0] = _ij4[0];
8669vinfos[4].indices[1] = _ij4[1];
8670vinfos[4].maxsolutions = _nj4;
8671vinfos[5].jointtype = 1;
8672vinfos[5].foffset = j5;
8673vinfos[5].indices[0] = _ij5[0];
8674vinfos[5].indices[1] = _ij5[1];
8675vinfos[5].maxsolutions = _nj5;
8676std::vector<int> vfree(0);
8677solutions.AddSolution(vinfos,vfree);
8678}
8679}
8680}
8681
8682}
8683
8684}
8685
8686} else
8687{
8688{
8689IkReal j5array[1], cj5array[1], sj5array[1];
8690bool j5valid[1]={false};
8691_nj5 = 1;
8692IkReal x1006=((25000.00002)*gconst12);
8693IkReal x1007=((25000.0)*new_r10);
8694IkReal x1008=((25000.0)*new_r00);
8695CheckValue<IkReal> x1009=IKPowWithIntegerCheck(IKsign((((new_r11*x1007))+((new_r01*x1008)))),-1);
8696if(!x1009.valid){
8697continue;
8698}
8699CheckValue<IkReal> x1010 = IKatan2WithCheck(IkReal((((gconst12*x1008))+(((-1.0)*new_r11*x1006)))),IkReal((((gconst12*x1007))+((new_r01*x1006)))),IKFAST_ATAN2_MAGTHRESH);
8700if(!x1010.valid){
8701continue;
8702}
8703j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1009.value)))+(x1010.value));
8704sj5array[0]=IKsin(j5array[0]);
8705cj5array[0]=IKcos(j5array[0]);
8706if( j5array[0] > IKPI )
8707{
8708 j5array[0]-=IK2PI;
8709}
8710else if( j5array[0] < -IKPI )
8711{ j5array[0]+=IK2PI;
8712}
8713j5valid[0] = true;
8714for(int ij5 = 0; ij5 < 1; ++ij5)
8715{
8716if( !j5valid[ij5] )
8717{
8718 continue;
8719}
8720_ij5[0] = ij5; _ij5[1] = -1;
8721for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8722{
8723if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8724{
8725 j5valid[iij5]=false; _ij5[1] = iij5; break;
8726}
8727}
8728j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8729{
8730IkReal evalcond[10];
8731IkReal x1011=IKcos(j5);
8732IkReal x1012=IKsin(j5);
8733IkReal x1013=((1.0)*gconst12);
8734IkReal x1014=(gconst12*x1011);
8735IkReal x1015=(new_r11*x1012);
8736IkReal x1016=(new_r01*x1011);
8737IkReal x1017=(new_r00*x1011);
8738IkReal x1018=(gconst12*x1012);
8739IkReal x1019=(new_r10*x1012);
8740if((((1.0)+(((-1.0)*gconst12*x1013)))) < -0.00001)
8741continue;
8742IkReal x1020=IKsqrt(((1.0)+(((-1.0)*gconst12*x1013))));
8743IkReal x1021=((1.0)*x1020);
8744IkReal x1022=((1.0000000008)*x1020);
8745evalcond[0]=(((new_r11*x1011))+(((-1.0)*x1013))+((new_r01*x1012)));
8746evalcond[1]=(x1017+(((-1.0000000008)*gconst12))+(((-1.0)*x1019)));
8747evalcond[2]=(((new_r10*x1011))+(((-1.0)*x1021))+((new_r00*x1012)));
8748evalcond[3]=((((-1.0000000008)*x1019))+(((-1.0)*x1013))+(((1.0000000008)*x1017)));
8749evalcond[4]=((((-1.0000000008)*x1014))+new_r00+(((-1.0)*x1012*x1021)));
8750evalcond[5]=((((1.0000000008)*x1018))+new_r10+(((-1.0)*x1011*x1021)));
8751evalcond[6]=((((-1.0)*x1012*x1013))+((x1011*x1022))+new_r01);
8752evalcond[7]=((((-1.0)*x1011*x1013))+new_r11+(((-1.0)*x1012*x1022)));
8753evalcond[8]=(x1016+x1022+(((-1.0)*x1015)));
8754evalcond[9]=((((-1.0000000008)*x1015))+x1020+(((1.0000000008)*x1016)));
8755if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
8756{
8757continue;
8758}
8759}
8760
8761{
8762std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8763vinfos[0].jointtype = 1;
8764vinfos[0].foffset = j0;
8765vinfos[0].indices[0] = _ij0[0];
8766vinfos[0].indices[1] = _ij0[1];
8767vinfos[0].maxsolutions = _nj0;
8768vinfos[1].jointtype = 1;
8769vinfos[1].foffset = j1;
8770vinfos[1].indices[0] = _ij1[0];
8771vinfos[1].indices[1] = _ij1[1];
8772vinfos[1].maxsolutions = _nj1;
8773vinfos[2].jointtype = 1;
8774vinfos[2].foffset = j2;
8775vinfos[2].indices[0] = _ij2[0];
8776vinfos[2].indices[1] = _ij2[1];
8777vinfos[2].maxsolutions = _nj2;
8778vinfos[3].jointtype = 1;
8779vinfos[3].foffset = j3;
8780vinfos[3].indices[0] = _ij3[0];
8781vinfos[3].indices[1] = _ij3[1];
8782vinfos[3].maxsolutions = _nj3;
8783vinfos[4].jointtype = 1;
8784vinfos[4].foffset = j4;
8785vinfos[4].indices[0] = _ij4[0];
8786vinfos[4].indices[1] = _ij4[1];
8787vinfos[4].maxsolutions = _nj4;
8788vinfos[5].jointtype = 1;
8789vinfos[5].foffset = j5;
8790vinfos[5].indices[0] = _ij5[0];
8791vinfos[5].indices[1] = _ij5[1];
8792vinfos[5].maxsolutions = _nj5;
8793std::vector<int> vfree(0);
8794solutions.AddSolution(vinfos,vfree);
8795}
8796}
8797}
8798
8799}
8800
8801}
8802
8803}
8804} while(0);
8805if( bgotonextstatement )
8806{
8807bool bgotonextstatement = true;
8808do
8809{
8810IkReal x1023=new_r00*new_r00;
8811CheckValue<IkReal> x1024=IKPowWithIntegerCheck(((((-1.0)*x1023))+(((-1.0000000016)*(new_r10*new_r10)))),-1);
8812if(!x1024.valid){
8813continue;
8814}
8815if((((-1.0)*x1023*(x1024.value))) < -0.00001)
8816continue;
8817IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1023*(x1024.value)))));
8818evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj3)))))+(IKabs((cj3+(((-1.0)*gconst13)))))), 6.28318530717959)));
8819if( IKabs(evalcond[0]) < 0.0000050000000000 )
8820{
8821bgotonextstatement=false;
8822{
8823IkReal j5eval[2];
8824IkReal x1025=new_r00*new_r00;
8825sj4=4.0e-5;
8826cj4=1.0;
8827j4=4.0e-5;
8828if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
8829continue;
8830sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
8831cj3=gconst13;
8832if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
8833 continue;
8834j3=IKacos(gconst13);
8835CheckValue<IkReal> x1026=IKPowWithIntegerCheck(((((-1.0)*x1025))+(((-1.0000000016)*(new_r10*new_r10)))),-1);
8836if(!x1026.valid){
8837continue;
8838}
8839if((((-1.0)*x1025*(x1026.value))) < -0.00001)
8840continue;
8841IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1025*(x1026.value)))));
8842IkReal x1027=(new_r00*new_r01);
8843IkReal x1028=(new_r10*new_r11);
8844j5eval[0]=(x1027+x1028);
8845j5eval[1]=IKsign(((((25000.0)*x1028))+(((25000.0)*x1027))));
8846if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
8847{
8848{
8849IkReal j5eval[2];
8850IkReal x1029=new_r00*new_r00;
8851sj4=4.0e-5;
8852cj4=1.0;
8853j4=4.0e-5;
8854if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
8855continue;
8856sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
8857cj3=gconst13;
8858if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
8859 continue;
8860j3=IKacos(gconst13);
8861CheckValue<IkReal> x1030=IKPowWithIntegerCheck(((((-1.0)*x1029))+(((-1.0000000016)*(new_r10*new_r10)))),-1);
8862if(!x1030.valid){
8863continue;
8864}
8865if((((-1.0)*x1029*(x1030.value))) < -0.00001)
8866continue;
8867IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1029*(x1030.value)))));
8868IkReal x1031=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
8869j5eval[0]=x1031;
8870j5eval[1]=IKsign(x1031);
8871if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
8872{
8873{
8874IkReal j5eval[1];
8875IkReal x1032=new_r00*new_r00;
8876sj4=4.0e-5;
8877cj4=1.0;
8878j4=4.0e-5;
8879if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
8880continue;
8881sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
8882cj3=gconst13;
8883if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
8884 continue;
8885j3=IKacos(gconst13);
8886CheckValue<IkReal> x1033=IKPowWithIntegerCheck(((((-1.0)*x1032))+(((-1.0000000016)*(new_r10*new_r10)))),-1);
8887if(!x1033.valid){
8888continue;
8889}
8890if((((-1.0)*x1032*(x1033.value))) < -0.00001)
8891continue;
8892IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1032*(x1033.value)))));
8893j5eval[0]=new_r01;
8894if( IKabs(j5eval[0]) < 0.0000010000000000 )
8895{
8896{
8897IkReal evalcond[1];
8898bool bgotonextstatement = true;
8899do
8900{
8901evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
8902if( IKabs(evalcond[0]) < 0.0000050000000000 )
8903{
8904bgotonextstatement=false;
8905{
8906IkReal j5eval[2];
8907IkReal x1034=new_r10*new_r10;
8908sj4=4.0e-5;
8909cj4=1.0;
8910j4=4.0e-5;
8911if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
8912continue;
8913sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
8914cj3=gconst13;
8915if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
8916 continue;
8917j3=IKacos(gconst13);
8918new_r11=0;
8919new_r01=0;
8920new_r22=0;
8921new_r20=0;
8922CheckValue<IkReal> x1035=IKPowWithIntegerCheck(((-1.0)+(((-1.6e-9)*x1034))),-1);
8923if(!x1035.valid){
8924continue;
8925}
8926if((((x1035.value)*(((-1.0)+(((1.0)*x1034)))))) < -0.00001)
8927continue;
8928IkReal gconst13=((-1.0)*(IKsqrt(((x1035.value)*(((-1.0)+(((1.0)*x1034))))))));
8929j5eval[0]=-1.0;
8930j5eval[1]=-1.0;
8931if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
8932{
8933{
8934IkReal j5array[1], cj5array[1], sj5array[1];
8935bool j5valid[1]={false};
8936_nj5 = 1;
8937IkReal x1036=gconst13*gconst13;
8938IkReal x1037=new_r00*new_r00;
8939IkReal x1038=(gconst13*new_r10);
8940IkReal x1039=((1.0)+(((-1.0)*x1036)));
8941IkReal x1040=((3.90625000625e+17)*x1036);
8942if((x1039) < -0.00001)
8943continue;
8944IkReal x1041=IKsqrt(x1039);
8945IkReal x1042=(new_r00*x1041);
8946CheckValue<IkReal> x1043=IKPowWithIntegerCheck(((((-1.0)*x1040*(new_r10*new_r10)))+(((3.90625e+17)*x1037*(pow(x1039,1.0))))),-1);
8947if(!x1043.valid){
8948continue;
8949}
8950CheckValue<IkReal> x1044=IKPowWithIntegerCheck(((((25000.0)*x1042))+(((-25000.00002)*x1038))),-1);
8951if(!x1044.valid){
8952continue;
8953}
8954if( IKabs(((x1043.value)*(((((3.906250009375e+17)*x1038*(gconst13*gconst13)))+((x1040*x1042))+(((-3.906250003125e+17)*x1037*x1038))+(((-3.90625e+17)*x1042*(new_r00*new_r00))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x1044.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst13*x1041)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1043.value)*(((((3.906250009375e+17)*x1038*(gconst13*gconst13)))+((x1040*x1042))+(((-3.906250003125e+17)*x1037*x1038))+(((-3.90625e+17)*x1042*(new_r00*new_r00)))))))+IKsqr(((x1044.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst13*x1041))))))-1) <= IKFAST_SINCOS_THRESH )
8955 continue;
8956j5array[0]=IKatan2(((x1043.value)*(((((3.906250009375e+17)*x1038*(gconst13*gconst13)))+((x1040*x1042))+(((-3.906250003125e+17)*x1037*x1038))+(((-3.90625e+17)*x1042*(new_r00*new_r00)))))), ((x1044.value)*(((((-25000.0)*new_r00*new_r10))+(((25000.00002)*gconst13*x1041))))));
8957sj5array[0]=IKsin(j5array[0]);
8958cj5array[0]=IKcos(j5array[0]);
8959if( j5array[0] > IKPI )
8960{
8961 j5array[0]-=IK2PI;
8962}
8963else if( j5array[0] < -IKPI )
8964{ j5array[0]+=IK2PI;
8965}
8966j5valid[0] = true;
8967for(int ij5 = 0; ij5 < 1; ++ij5)
8968{
8969if( !j5valid[ij5] )
8970{
8971 continue;
8972}
8973_ij5[0] = ij5; _ij5[1] = -1;
8974for(int iij5 = ij5+1; iij5 < 1; ++iij5)
8975{
8976if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
8977{
8978 j5valid[iij5]=false; _ij5[1] = iij5; break;
8979}
8980}
8981j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
8982{
8983IkReal evalcond[7];
8984IkReal x1045=IKcos(j5);
8985IkReal x1046=IKsin(j5);
8986IkReal x1047=((1.0000000008)*gconst13);
8987IkReal x1048=((1.0)*gconst13);
8988IkReal x1049=((1.0000000008)*x1046);
8989IkReal x1050=(new_r00*x1045);
8990if((((1.0)+(((-1.0)*gconst13*x1048)))) < -0.00001)
8991continue;
8992IkReal x1051=IKsqrt(((1.0)+(((-1.0)*gconst13*x1048))));
8993IkReal x1052=(x1045*x1051);
8994evalcond[0]=(x1050+(((-1.0)*new_r10*x1046))+(((-1.0)*x1047)));
8995evalcond[1]=(x1051+((new_r00*x1046))+((new_r10*x1045)));
8996evalcond[2]=((((-1.0)*new_r10*x1049))+(((-1.0)*x1048))+(((1.0000000008)*x1050)));
8997evalcond[3]=((((-1.0)*x1045*x1047))+new_r00+((x1046*x1051)));
8998evalcond[4]=(x1052+new_r10+((x1046*x1047)));
8999evalcond[5]=((((-1.0)*x1046*x1048))+(((-1.0000000008)*x1052)));
9000evalcond[6]=((((-1.0)*x1045*x1048))+((x1049*x1051)));
9001if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9002{
9003continue;
9004}
9005}
9006
9007{
9008std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9009vinfos[0].jointtype = 1;
9010vinfos[0].foffset = j0;
9011vinfos[0].indices[0] = _ij0[0];
9012vinfos[0].indices[1] = _ij0[1];
9013vinfos[0].maxsolutions = _nj0;
9014vinfos[1].jointtype = 1;
9015vinfos[1].foffset = j1;
9016vinfos[1].indices[0] = _ij1[0];
9017vinfos[1].indices[1] = _ij1[1];
9018vinfos[1].maxsolutions = _nj1;
9019vinfos[2].jointtype = 1;
9020vinfos[2].foffset = j2;
9021vinfos[2].indices[0] = _ij2[0];
9022vinfos[2].indices[1] = _ij2[1];
9023vinfos[2].maxsolutions = _nj2;
9024vinfos[3].jointtype = 1;
9025vinfos[3].foffset = j3;
9026vinfos[3].indices[0] = _ij3[0];
9027vinfos[3].indices[1] = _ij3[1];
9028vinfos[3].maxsolutions = _nj3;
9029vinfos[4].jointtype = 1;
9030vinfos[4].foffset = j4;
9031vinfos[4].indices[0] = _ij4[0];
9032vinfos[4].indices[1] = _ij4[1];
9033vinfos[4].maxsolutions = _nj4;
9034vinfos[5].jointtype = 1;
9035vinfos[5].foffset = j5;
9036vinfos[5].indices[0] = _ij5[0];
9037vinfos[5].indices[1] = _ij5[1];
9038vinfos[5].maxsolutions = _nj5;
9039std::vector<int> vfree(0);
9040solutions.AddSolution(vinfos,vfree);
9041}
9042}
9043}
9044
9045} else
9046{
9047{
9048IkReal j5array[1], cj5array[1], sj5array[1];
9049bool j5valid[1]={false};
9050_nj5 = 1;
9051if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9052continue;
9053IkReal x1053=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9054IkReal x1054=((25000.0)*x1053);
9055CheckValue<IkReal> x1055=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
9056if(!x1055.valid){
9057continue;
9058}
9059CheckValue<IkReal> x1056 = IKatan2WithCheck(IkReal(((((25000.00002)*gconst13*new_r10))+((new_r00*x1054)))),IkReal((((new_r10*x1054))+(((-25000.00002)*gconst13*new_r00)))),IKFAST_ATAN2_MAGTHRESH);
9060if(!x1056.valid){
9061continue;
9062}
9063j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1055.value)))+(x1056.value));
9064sj5array[0]=IKsin(j5array[0]);
9065cj5array[0]=IKcos(j5array[0]);
9066if( j5array[0] > IKPI )
9067{
9068 j5array[0]-=IK2PI;
9069}
9070else if( j5array[0] < -IKPI )
9071{ j5array[0]+=IK2PI;
9072}
9073j5valid[0] = true;
9074for(int ij5 = 0; ij5 < 1; ++ij5)
9075{
9076if( !j5valid[ij5] )
9077{
9078 continue;
9079}
9080_ij5[0] = ij5; _ij5[1] = -1;
9081for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9082{
9083if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9084{
9085 j5valid[iij5]=false; _ij5[1] = iij5; break;
9086}
9087}
9088j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9089{
9090IkReal evalcond[7];
9091IkReal x1057=IKcos(j5);
9092IkReal x1058=IKsin(j5);
9093IkReal x1059=((1.0000000008)*gconst13);
9094IkReal x1060=((1.0)*gconst13);
9095IkReal x1061=((1.0000000008)*x1058);
9096IkReal x1062=(new_r00*x1057);
9097IkReal x1063=x1053;
9098IkReal x1064=(x1057*x1063);
9099evalcond[0]=((((-1.0)*x1059))+x1062+(((-1.0)*new_r10*x1058)));
9100evalcond[1]=(x1063+((new_r00*x1058))+((new_r10*x1057)));
9101evalcond[2]=((((-1.0)*new_r10*x1061))+(((1.0000000008)*x1062))+(((-1.0)*x1060)));
9102evalcond[3]=((((-1.0)*x1057*x1059))+new_r00+((x1058*x1063)));
9103evalcond[4]=(x1064+new_r10+((x1058*x1059)));
9104evalcond[5]=((((-1.0000000008)*x1064))+(((-1.0)*x1058*x1060)));
9105evalcond[6]=(((x1061*x1063))+(((-1.0)*x1057*x1060)));
9106if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9107{
9108continue;
9109}
9110}
9111
9112{
9113std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9114vinfos[0].jointtype = 1;
9115vinfos[0].foffset = j0;
9116vinfos[0].indices[0] = _ij0[0];
9117vinfos[0].indices[1] = _ij0[1];
9118vinfos[0].maxsolutions = _nj0;
9119vinfos[1].jointtype = 1;
9120vinfos[1].foffset = j1;
9121vinfos[1].indices[0] = _ij1[0];
9122vinfos[1].indices[1] = _ij1[1];
9123vinfos[1].maxsolutions = _nj1;
9124vinfos[2].jointtype = 1;
9125vinfos[2].foffset = j2;
9126vinfos[2].indices[0] = _ij2[0];
9127vinfos[2].indices[1] = _ij2[1];
9128vinfos[2].maxsolutions = _nj2;
9129vinfos[3].jointtype = 1;
9130vinfos[3].foffset = j3;
9131vinfos[3].indices[0] = _ij3[0];
9132vinfos[3].indices[1] = _ij3[1];
9133vinfos[3].maxsolutions = _nj3;
9134vinfos[4].jointtype = 1;
9135vinfos[4].foffset = j4;
9136vinfos[4].indices[0] = _ij4[0];
9137vinfos[4].indices[1] = _ij4[1];
9138vinfos[4].maxsolutions = _nj4;
9139vinfos[5].jointtype = 1;
9140vinfos[5].foffset = j5;
9141vinfos[5].indices[0] = _ij5[0];
9142vinfos[5].indices[1] = _ij5[1];
9143vinfos[5].maxsolutions = _nj5;
9144std::vector<int> vfree(0);
9145solutions.AddSolution(vinfos,vfree);
9146}
9147}
9148}
9149
9150}
9151
9152}
9153
9154}
9155} while(0);
9156if( bgotonextstatement )
9157{
9158bool bgotonextstatement = true;
9159do
9160{
9161evalcond[0]=IKabs(new_r01);
9162if( IKabs(evalcond[0]) < 0.0000050000000000 )
9163{
9164bgotonextstatement=false;
9165{
9166IkReal j5eval[3];
9167IkReal x1065=new_r00*new_r00;
9168sj4=4.0e-5;
9169cj4=1.0;
9170j4=4.0e-5;
9171if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9172continue;
9173sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9174cj3=gconst13;
9175if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
9176 continue;
9177j3=IKacos(gconst13);
9178new_r01=0;
9179CheckValue<IkReal> x1066=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1065))),-1);
9180if(!x1066.valid){
9181continue;
9182}
9183if((((-1.0)*x1065*(x1066.value))) < -0.00001)
9184continue;
9185IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1065*(x1066.value)))));
9186IkReal x1067=new_r10*new_r10;
9187IkReal x1068=new_r00*new_r00;
9188IkReal x1069=((1.0)*x1068);
9189j5eval[0]=new_r11;
9190j5eval[1]=IKsign(new_r11);
9191CheckValue<IkReal> x1070=IKPowWithIntegerCheck(((((625000000.0)*x1068))+(((625000001.0)*x1067))),-1);
9192if(!x1070.valid){
9193continue;
9194}
9195CheckValue<IkReal> x1071=IKPowWithIntegerCheck(((((-1.0000000016)*x1067))+(((-1.0)*x1068))),-1);
9196if(!x1071.valid){
9197continue;
9198}
9199j5eval[2]=((((625000002.0)*(pow(x1067,1.0))*(pow(x1070.value,1.0))))+(((-1.0)*x1069*(x1071.value))));
9200if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
9201{
9202{
9203IkReal j5eval[2];
9204IkReal x1072=new_r00*new_r00;
9205sj4=4.0e-5;
9206cj4=1.0;
9207j4=4.0e-5;
9208if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9209continue;
9210sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9211cj3=gconst13;
9212if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
9213 continue;
9214j3=IKacos(gconst13);
9215new_r01=0;
9216CheckValue<IkReal> x1073=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1072))),-1);
9217if(!x1073.valid){
9218continue;
9219}
9220if((((-1.0)*x1072*(x1073.value))) < -0.00001)
9221continue;
9222IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1072*(x1073.value)))));
9223j5eval[0]=new_r10;
9224j5eval[1]=new_r11;
9225if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
9226{
9227{
9228IkReal j5eval[2];
9229IkReal x1074=new_r00*new_r00;
9230sj4=4.0e-5;
9231cj4=1.0;
9232j4=4.0e-5;
9233if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9234continue;
9235sj3=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9236cj3=gconst13;
9237if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
9238 continue;
9239j3=IKacos(gconst13);
9240new_r01=0;
9241CheckValue<IkReal> x1075=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1074))),-1);
9242if(!x1075.valid){
9243continue;
9244}
9245if((((-1.0)*x1074*(x1075.value))) < -0.00001)
9246continue;
9247IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1074*(x1075.value)))));
9248j5eval[0]=new_r00;
9249j5eval[1]=new_r11;
9250if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
9251{
9252continue; // 3 cases reached
9253
9254} else
9255{
9256{
9257IkReal j5array[1], cj5array[1], sj5array[1];
9258bool j5valid[1]={false};
9259_nj5 = 1;
9260CheckValue<IkReal> x1077=IKPowWithIntegerCheck(new_r11,-1);
9261if(!x1077.valid){
9262continue;
9263}
9264IkReal x1076=x1077.value;
9265CheckValue<IkReal> x1078=IKPowWithIntegerCheck(new_r00,-1);
9266if(!x1078.valid){
9267continue;
9268}
9269if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9270continue;
9271if( IKabs((x1076*(x1078.value)*(((((-1.0)*gconst13*new_r10))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*x1076)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1076*(x1078.value)*(((((-1.0)*gconst13*new_r10))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))))+IKsqr((gconst13*x1076))-1) <= IKFAST_SINCOS_THRESH )
9272 continue;
9273j5array[0]=IKatan2((x1076*(x1078.value)*(((((-1.0)*gconst13*new_r10))+(((-1.0)*new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))), (gconst13*x1076));
9274sj5array[0]=IKsin(j5array[0]);
9275cj5array[0]=IKcos(j5array[0]);
9276if( j5array[0] > IKPI )
9277{
9278 j5array[0]-=IK2PI;
9279}
9280else if( j5array[0] < -IKPI )
9281{ j5array[0]+=IK2PI;
9282}
9283j5valid[0] = true;
9284for(int ij5 = 0; ij5 < 1; ++ij5)
9285{
9286if( !j5valid[ij5] )
9287{
9288 continue;
9289}
9290_ij5[0] = ij5; _ij5[1] = -1;
9291for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9292{
9293if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9294{
9295 j5valid[iij5]=false; _ij5[1] = iij5; break;
9296}
9297}
9298j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9299{
9300IkReal evalcond[10];
9301IkReal x1079=IKcos(j5);
9302IkReal x1080=IKsin(j5);
9303IkReal x1081=((1.0)*gconst13);
9304IkReal x1082=((1.0000000008)*x1080);
9305IkReal x1083=((1.0)*x1080);
9306IkReal x1084=((1.0000000008)*x1079);
9307if((((1.0)+(((-1.0)*gconst13*x1081)))) < -0.00001)
9308continue;
9309IkReal x1085=IKsqrt(((1.0)+(((-1.0)*gconst13*x1081))));
9310evalcond[0]=(((new_r11*x1079))+(((-1.0)*x1081)));
9311evalcond[1]=((((-1.0)*new_r10*x1083))+(((-1.0000000008)*gconst13))+((new_r00*x1079)));
9312evalcond[2]=(x1085+((new_r00*x1080))+((new_r10*x1079)));
9313evalcond[3]=((((-1.0)*new_r11*x1083))+(((-1.0000000008)*x1085)));
9314evalcond[4]=((((-1.0)*new_r11*x1082))+(((-1.0)*x1085)));
9315evalcond[5]=((((-1.0)*new_r10*x1082))+((new_r00*x1084))+(((-1.0)*x1081)));
9316evalcond[6]=(((x1080*x1085))+new_r00+(((-1.0)*gconst13*x1084)));
9317evalcond[7]=(((x1079*x1085))+((gconst13*x1082))+new_r10);
9318evalcond[8]=((((-1.0)*x1080*x1081))+(((-1.0)*x1084*x1085)));
9319evalcond[9]=(((x1082*x1085))+(((-1.0)*x1079*x1081))+new_r11);
9320if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
9321{
9322continue;
9323}
9324}
9325
9326{
9327std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9328vinfos[0].jointtype = 1;
9329vinfos[0].foffset = j0;
9330vinfos[0].indices[0] = _ij0[0];
9331vinfos[0].indices[1] = _ij0[1];
9332vinfos[0].maxsolutions = _nj0;
9333vinfos[1].jointtype = 1;
9334vinfos[1].foffset = j1;
9335vinfos[1].indices[0] = _ij1[0];
9336vinfos[1].indices[1] = _ij1[1];
9337vinfos[1].maxsolutions = _nj1;
9338vinfos[2].jointtype = 1;
9339vinfos[2].foffset = j2;
9340vinfos[2].indices[0] = _ij2[0];
9341vinfos[2].indices[1] = _ij2[1];
9342vinfos[2].maxsolutions = _nj2;
9343vinfos[3].jointtype = 1;
9344vinfos[3].foffset = j3;
9345vinfos[3].indices[0] = _ij3[0];
9346vinfos[3].indices[1] = _ij3[1];
9347vinfos[3].maxsolutions = _nj3;
9348vinfos[4].jointtype = 1;
9349vinfos[4].foffset = j4;
9350vinfos[4].indices[0] = _ij4[0];
9351vinfos[4].indices[1] = _ij4[1];
9352vinfos[4].maxsolutions = _nj4;
9353vinfos[5].jointtype = 1;
9354vinfos[5].foffset = j5;
9355vinfos[5].indices[0] = _ij5[0];
9356vinfos[5].indices[1] = _ij5[1];
9357vinfos[5].maxsolutions = _nj5;
9358std::vector<int> vfree(0);
9359solutions.AddSolution(vinfos,vfree);
9360}
9361}
9362}
9363
9364}
9365
9366}
9367
9368} else
9369{
9370{
9371IkReal j5array[1], cj5array[1], sj5array[1];
9372bool j5valid[1]={false};
9373_nj5 = 1;
9374CheckValue<IkReal> x1087=IKPowWithIntegerCheck(new_r11,-1);
9375if(!x1087.valid){
9376continue;
9377}
9378IkReal x1086=x1087.value;
9379CheckValue<IkReal> x1088=IKPowWithIntegerCheck(new_r10,-1);
9380if(!x1088.valid){
9381continue;
9382}
9383if( IKabs(((4.0e-5)*x1086*(x1088.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*x1086)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((4.0e-5)*x1086*(x1088.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11))))))+IKsqr((gconst13*x1086))-1) <= IKFAST_SINCOS_THRESH )
9384 continue;
9385j5array[0]=IKatan2(((4.0e-5)*x1086*(x1088.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11))))), (gconst13*x1086));
9386sj5array[0]=IKsin(j5array[0]);
9387cj5array[0]=IKcos(j5array[0]);
9388if( j5array[0] > IKPI )
9389{
9390 j5array[0]-=IK2PI;
9391}
9392else if( j5array[0] < -IKPI )
9393{ j5array[0]+=IK2PI;
9394}
9395j5valid[0] = true;
9396for(int ij5 = 0; ij5 < 1; ++ij5)
9397{
9398if( !j5valid[ij5] )
9399{
9400 continue;
9401}
9402_ij5[0] = ij5; _ij5[1] = -1;
9403for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9404{
9405if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9406{
9407 j5valid[iij5]=false; _ij5[1] = iij5; break;
9408}
9409}
9410j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9411{
9412IkReal evalcond[10];
9413IkReal x1089=IKcos(j5);
9414IkReal x1090=IKsin(j5);
9415IkReal x1091=((1.0)*gconst13);
9416IkReal x1092=((1.0000000008)*x1090);
9417IkReal x1093=((1.0)*x1090);
9418IkReal x1094=((1.0000000008)*x1089);
9419if((((1.0)+(((-1.0)*gconst13*x1091)))) < -0.00001)
9420continue;
9421IkReal x1095=IKsqrt(((1.0)+(((-1.0)*gconst13*x1091))));
9422evalcond[0]=((((-1.0)*x1091))+((new_r11*x1089)));
9423evalcond[1]=(((new_r00*x1089))+(((-1.0000000008)*gconst13))+(((-1.0)*new_r10*x1093)));
9424evalcond[2]=(((new_r00*x1090))+x1095+((new_r10*x1089)));
9425evalcond[3]=((((-1.0000000008)*x1095))+(((-1.0)*new_r11*x1093)));
9426evalcond[4]=((((-1.0)*x1095))+(((-1.0)*new_r11*x1092)));
9427evalcond[5]=(((new_r00*x1094))+(((-1.0)*x1091))+(((-1.0)*new_r10*x1092)));
9428evalcond[6]=((((-1.0)*gconst13*x1094))+new_r00+((x1090*x1095)));
9429evalcond[7]=(((x1089*x1095))+new_r10+((gconst13*x1092)));
9430evalcond[8]=((((-1.0)*x1090*x1091))+(((-1.0)*x1094*x1095)));
9431evalcond[9]=((((-1.0)*x1089*x1091))+((x1092*x1095))+new_r11);
9432if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
9433{
9434continue;
9435}
9436}
9437
9438{
9439std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9440vinfos[0].jointtype = 1;
9441vinfos[0].foffset = j0;
9442vinfos[0].indices[0] = _ij0[0];
9443vinfos[0].indices[1] = _ij0[1];
9444vinfos[0].maxsolutions = _nj0;
9445vinfos[1].jointtype = 1;
9446vinfos[1].foffset = j1;
9447vinfos[1].indices[0] = _ij1[0];
9448vinfos[1].indices[1] = _ij1[1];
9449vinfos[1].maxsolutions = _nj1;
9450vinfos[2].jointtype = 1;
9451vinfos[2].foffset = j2;
9452vinfos[2].indices[0] = _ij2[0];
9453vinfos[2].indices[1] = _ij2[1];
9454vinfos[2].maxsolutions = _nj2;
9455vinfos[3].jointtype = 1;
9456vinfos[3].foffset = j3;
9457vinfos[3].indices[0] = _ij3[0];
9458vinfos[3].indices[1] = _ij3[1];
9459vinfos[3].maxsolutions = _nj3;
9460vinfos[4].jointtype = 1;
9461vinfos[4].foffset = j4;
9462vinfos[4].indices[0] = _ij4[0];
9463vinfos[4].indices[1] = _ij4[1];
9464vinfos[4].maxsolutions = _nj4;
9465vinfos[5].jointtype = 1;
9466vinfos[5].foffset = j5;
9467vinfos[5].indices[0] = _ij5[0];
9468vinfos[5].indices[1] = _ij5[1];
9469vinfos[5].maxsolutions = _nj5;
9470std::vector<int> vfree(0);
9471solutions.AddSolution(vinfos,vfree);
9472}
9473}
9474}
9475
9476}
9477
9478}
9479
9480} else
9481{
9482{
9483IkReal j5array[1], cj5array[1], sj5array[1];
9484bool j5valid[1]={false};
9485_nj5 = 1;
9486CheckValue<IkReal> x1096=IKPowWithIntegerCheck(IKsign(new_r11),-1);
9487if(!x1096.valid){
9488continue;
9489}
9490if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9491continue;
9492CheckValue<IkReal> x1097 = IKatan2WithCheck(IkReal(((-1.0000000008)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))),IkReal(gconst13),IKFAST_ATAN2_MAGTHRESH);
9493if(!x1097.valid){
9494continue;
9495}
9496j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1096.value)))+(x1097.value));
9497sj5array[0]=IKsin(j5array[0]);
9498cj5array[0]=IKcos(j5array[0]);
9499if( j5array[0] > IKPI )
9500{
9501 j5array[0]-=IK2PI;
9502}
9503else if( j5array[0] < -IKPI )
9504{ j5array[0]+=IK2PI;
9505}
9506j5valid[0] = true;
9507for(int ij5 = 0; ij5 < 1; ++ij5)
9508{
9509if( !j5valid[ij5] )
9510{
9511 continue;
9512}
9513_ij5[0] = ij5; _ij5[1] = -1;
9514for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9515{
9516if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9517{
9518 j5valid[iij5]=false; _ij5[1] = iij5; break;
9519}
9520}
9521j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9522{
9523IkReal evalcond[10];
9524IkReal x1098=IKcos(j5);
9525IkReal x1099=IKsin(j5);
9526IkReal x1100=((1.0)*gconst13);
9527IkReal x1101=((1.0000000008)*x1099);
9528IkReal x1102=((1.0)*x1099);
9529IkReal x1103=((1.0000000008)*x1098);
9530if((((1.0)+(((-1.0)*gconst13*x1100)))) < -0.00001)
9531continue;
9532IkReal x1104=IKsqrt(((1.0)+(((-1.0)*gconst13*x1100))));
9533evalcond[0]=(((new_r11*x1098))+(((-1.0)*x1100)));
9534evalcond[1]=(((new_r00*x1098))+(((-1.0000000008)*gconst13))+(((-1.0)*new_r10*x1102)));
9535evalcond[2]=(x1104+((new_r00*x1099))+((new_r10*x1098)));
9536evalcond[3]=((((-1.0000000008)*x1104))+(((-1.0)*new_r11*x1102)));
9537evalcond[4]=((((-1.0)*x1104))+(((-1.0)*new_r11*x1101)));
9538evalcond[5]=(((new_r00*x1103))+(((-1.0)*new_r10*x1101))+(((-1.0)*x1100)));
9539evalcond[6]=(((x1099*x1104))+new_r00+(((-1.0)*gconst13*x1103)));
9540evalcond[7]=(((x1098*x1104))+((gconst13*x1101))+new_r10);
9541evalcond[8]=((((-1.0)*x1103*x1104))+(((-1.0)*x1099*x1100)));
9542evalcond[9]=((((-1.0)*x1098*x1100))+((x1101*x1104))+new_r11);
9543if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
9544{
9545continue;
9546}
9547}
9548
9549{
9550std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9551vinfos[0].jointtype = 1;
9552vinfos[0].foffset = j0;
9553vinfos[0].indices[0] = _ij0[0];
9554vinfos[0].indices[1] = _ij0[1];
9555vinfos[0].maxsolutions = _nj0;
9556vinfos[1].jointtype = 1;
9557vinfos[1].foffset = j1;
9558vinfos[1].indices[0] = _ij1[0];
9559vinfos[1].indices[1] = _ij1[1];
9560vinfos[1].maxsolutions = _nj1;
9561vinfos[2].jointtype = 1;
9562vinfos[2].foffset = j2;
9563vinfos[2].indices[0] = _ij2[0];
9564vinfos[2].indices[1] = _ij2[1];
9565vinfos[2].maxsolutions = _nj2;
9566vinfos[3].jointtype = 1;
9567vinfos[3].foffset = j3;
9568vinfos[3].indices[0] = _ij3[0];
9569vinfos[3].indices[1] = _ij3[1];
9570vinfos[3].maxsolutions = _nj3;
9571vinfos[4].jointtype = 1;
9572vinfos[4].foffset = j4;
9573vinfos[4].indices[0] = _ij4[0];
9574vinfos[4].indices[1] = _ij4[1];
9575vinfos[4].maxsolutions = _nj4;
9576vinfos[5].jointtype = 1;
9577vinfos[5].foffset = j5;
9578vinfos[5].indices[0] = _ij5[0];
9579vinfos[5].indices[1] = _ij5[1];
9580vinfos[5].maxsolutions = _nj5;
9581std::vector<int> vfree(0);
9582solutions.AddSolution(vinfos,vfree);
9583}
9584}
9585}
9586
9587}
9588
9589}
9590
9591}
9592} while(0);
9593if( bgotonextstatement )
9594{
9595bool bgotonextstatement = true;
9596do
9597{
9598evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
9599if( IKabs(evalcond[0]) < 0.0000050000000000 )
9600{
9601bgotonextstatement=false;
9602{
9603IkReal j5array[2], cj5array[2], sj5array[2];
9604bool j5valid[2]={false};
9605_nj5 = 2;
9606cj5array[0]=((-1.0)*new_r10);
9607if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
9608{
9609 j5valid[0] = j5valid[1] = true;
9610 j5array[0] = IKacos(cj5array[0]);
9611 sj5array[0] = IKsin(j5array[0]);
9612 cj5array[1] = cj5array[0];
9613 j5array[1] = -j5array[0];
9614 sj5array[1] = -sj5array[0];
9615}
9616else if( isnan(cj5array[0]) )
9617{
9618 // probably any value will work
9619 j5valid[0] = true;
9620 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
9621}
9622for(int ij5 = 0; ij5 < 2; ++ij5)
9623{
9624if( !j5valid[ij5] )
9625{
9626 continue;
9627}
9628_ij5[0] = ij5; _ij5[1] = -1;
9629for(int iij5 = ij5+1; iij5 < 2; ++iij5)
9630{
9631if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9632{
9633 j5valid[iij5]=false; _ij5[1] = iij5; break;
9634}
9635}
9636j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9637{
9638IkReal evalcond[9];
9639IkReal x1105=IKsin(j5);
9640IkReal x1106=IKcos(j5);
9641IkReal x1107=(new_r10*x1105);
9642IkReal x1108=((1.0000000008)*x1106);
9643evalcond[0]=x1105;
9644evalcond[1]=(new_r01*x1105);
9645evalcond[2]=((-1.0)*x1107);
9646evalcond[3]=((1.0)+((new_r10*x1106)));
9647evalcond[4]=((1.0000000008)*x1105);
9648evalcond[5]=((-1.0000000008)*x1107);
9649evalcond[6]=(new_r01+(((-1.0)*x1108)));
9650evalcond[7]=((-1.0000000008)+((new_r01*x1106)));
9651evalcond[8]=((-1.0)+((new_r01*x1108)));
9652if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
9653{
9654continue;
9655}
9656}
9657
9658{
9659std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9660vinfos[0].jointtype = 1;
9661vinfos[0].foffset = j0;
9662vinfos[0].indices[0] = _ij0[0];
9663vinfos[0].indices[1] = _ij0[1];
9664vinfos[0].maxsolutions = _nj0;
9665vinfos[1].jointtype = 1;
9666vinfos[1].foffset = j1;
9667vinfos[1].indices[0] = _ij1[0];
9668vinfos[1].indices[1] = _ij1[1];
9669vinfos[1].maxsolutions = _nj1;
9670vinfos[2].jointtype = 1;
9671vinfos[2].foffset = j2;
9672vinfos[2].indices[0] = _ij2[0];
9673vinfos[2].indices[1] = _ij2[1];
9674vinfos[2].maxsolutions = _nj2;
9675vinfos[3].jointtype = 1;
9676vinfos[3].foffset = j3;
9677vinfos[3].indices[0] = _ij3[0];
9678vinfos[3].indices[1] = _ij3[1];
9679vinfos[3].maxsolutions = _nj3;
9680vinfos[4].jointtype = 1;
9681vinfos[4].foffset = j4;
9682vinfos[4].indices[0] = _ij4[0];
9683vinfos[4].indices[1] = _ij4[1];
9684vinfos[4].maxsolutions = _nj4;
9685vinfos[5].jointtype = 1;
9686vinfos[5].foffset = j5;
9687vinfos[5].indices[0] = _ij5[0];
9688vinfos[5].indices[1] = _ij5[1];
9689vinfos[5].maxsolutions = _nj5;
9690std::vector<int> vfree(0);
9691solutions.AddSolution(vinfos,vfree);
9692}
9693}
9694}
9695
9696}
9697} while(0);
9698if( bgotonextstatement )
9699{
9700bool bgotonextstatement = true;
9701do
9702{
9703evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
9704if( IKabs(evalcond[0]) < 0.0000050000000000 )
9705{
9706bgotonextstatement=false;
9707{
9708IkReal j5array[1], cj5array[1], sj5array[1];
9709bool j5valid[1]={false};
9710_nj5 = 1;
9711if( IKabs(((-0.9999999992)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11))+IKsqr(((0.9999999992)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
9712 continue;
9713j5array[0]=IKatan2(((-0.9999999992)*new_r11), ((0.9999999992)*new_r01));
9714sj5array[0]=IKsin(j5array[0]);
9715cj5array[0]=IKcos(j5array[0]);
9716if( j5array[0] > IKPI )
9717{
9718 j5array[0]-=IK2PI;
9719}
9720else if( j5array[0] < -IKPI )
9721{ j5array[0]+=IK2PI;
9722}
9723j5valid[0] = true;
9724for(int ij5 = 0; ij5 < 1; ++ij5)
9725{
9726if( !j5valid[ij5] )
9727{
9728 continue;
9729}
9730_ij5[0] = ij5; _ij5[1] = -1;
9731for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9732{
9733if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9734{
9735 j5valid[iij5]=false; _ij5[1] = iij5; break;
9736}
9737}
9738j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9739{
9740IkReal evalcond[7];
9741IkReal x1109=IKcos(j5);
9742IkReal x1110=IKsin(j5);
9743IkReal x1111=((1.0000000008)*x1110);
9744IkReal x1112=((1.0000000008)*x1109);
9745evalcond[0]=x1110;
9746evalcond[1]=x1109;
9747evalcond[2]=(new_r01+(((-1.0)*x1112)));
9748evalcond[3]=(x1111+new_r11);
9749evalcond[4]=(((new_r11*x1109))+((new_r01*x1110)));
9750evalcond[5]=((-1.0000000008)+((new_r01*x1109))+(((-1.0)*new_r11*x1110)));
9751evalcond[6]=((-1.0)+((new_r01*x1112))+(((-1.0)*new_r11*x1111)));
9752if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
9753{
9754continue;
9755}
9756}
9757
9758{
9759std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9760vinfos[0].jointtype = 1;
9761vinfos[0].foffset = j0;
9762vinfos[0].indices[0] = _ij0[0];
9763vinfos[0].indices[1] = _ij0[1];
9764vinfos[0].maxsolutions = _nj0;
9765vinfos[1].jointtype = 1;
9766vinfos[1].foffset = j1;
9767vinfos[1].indices[0] = _ij1[0];
9768vinfos[1].indices[1] = _ij1[1];
9769vinfos[1].maxsolutions = _nj1;
9770vinfos[2].jointtype = 1;
9771vinfos[2].foffset = j2;
9772vinfos[2].indices[0] = _ij2[0];
9773vinfos[2].indices[1] = _ij2[1];
9774vinfos[2].maxsolutions = _nj2;
9775vinfos[3].jointtype = 1;
9776vinfos[3].foffset = j3;
9777vinfos[3].indices[0] = _ij3[0];
9778vinfos[3].indices[1] = _ij3[1];
9779vinfos[3].maxsolutions = _nj3;
9780vinfos[4].jointtype = 1;
9781vinfos[4].foffset = j4;
9782vinfos[4].indices[0] = _ij4[0];
9783vinfos[4].indices[1] = _ij4[1];
9784vinfos[4].maxsolutions = _nj4;
9785vinfos[5].jointtype = 1;
9786vinfos[5].foffset = j5;
9787vinfos[5].indices[0] = _ij5[0];
9788vinfos[5].indices[1] = _ij5[1];
9789vinfos[5].maxsolutions = _nj5;
9790std::vector<int> vfree(0);
9791solutions.AddSolution(vinfos,vfree);
9792}
9793}
9794}
9795
9796}
9797} while(0);
9798if( bgotonextstatement )
9799{
9800bool bgotonextstatement = true;
9801do
9802{
9803if( 1 )
9804{
9805bgotonextstatement=false;
9806continue; // branch miss [j5]
9807
9808}
9809} while(0);
9810if( bgotonextstatement )
9811{
9812}
9813}
9814}
9815}
9816}
9817}
9818
9819} else
9820{
9821{
9822IkReal j5array[1], cj5array[1], sj5array[1];
9823bool j5valid[1]={false};
9824_nj5 = 1;
9825CheckValue<IkReal> x1120=IKPowWithIntegerCheck(new_r01,-1);
9826if(!x1120.valid){
9827continue;
9828}
9829IkReal x1113=x1120.value;
9830IkReal x1114=((25000.0)*new_r00);
9831IkReal x1115=(gconst13*x1113);
9832if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9833continue;
9834IkReal x1116=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9835IkReal x1117=((25000.0)*x1116);
9836CheckValue<IkReal> x1121=IKPowWithIntegerCheck(((((25000.00002)*gconst13*new_r01))+((new_r11*x1117))),-1);
9837if(!x1121.valid){
9838continue;
9839}
9840IkReal x1118=x1121.value;
9841IkReal x1119=(new_r11*x1118);
9842if( IKabs((x1115+(((-1.0)*x1114*x1119))+(((-1.0)*x1115*x1117*x1119)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1118*((((gconst13*x1117))+((new_r01*x1114)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1115+(((-1.0)*x1114*x1119))+(((-1.0)*x1115*x1117*x1119))))+IKsqr((x1118*((((gconst13*x1117))+((new_r01*x1114))))))-1) <= IKFAST_SINCOS_THRESH )
9843 continue;
9844j5array[0]=IKatan2((x1115+(((-1.0)*x1114*x1119))+(((-1.0)*x1115*x1117*x1119))), (x1118*((((gconst13*x1117))+((new_r01*x1114))))));
9845sj5array[0]=IKsin(j5array[0]);
9846cj5array[0]=IKcos(j5array[0]);
9847if( j5array[0] > IKPI )
9848{
9849 j5array[0]-=IK2PI;
9850}
9851else if( j5array[0] < -IKPI )
9852{ j5array[0]+=IK2PI;
9853}
9854j5valid[0] = true;
9855for(int ij5 = 0; ij5 < 1; ++ij5)
9856{
9857if( !j5valid[ij5] )
9858{
9859 continue;
9860}
9861_ij5[0] = ij5; _ij5[1] = -1;
9862for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9863{
9864if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9865{
9866 j5valid[iij5]=false; _ij5[1] = iij5; break;
9867}
9868}
9869j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9870{
9871IkReal evalcond[10];
9872IkReal x1122=IKcos(j5);
9873IkReal x1123=IKsin(j5);
9874IkReal x1124=((1.0)*gconst13);
9875IkReal x1125=((1.0000000008)*x1123);
9876IkReal x1126=((1.0)*x1123);
9877IkReal x1127=((1.0000000008)*x1122);
9878IkReal x1128=x1116;
9879evalcond[0]=(((new_r01*x1123))+(((-1.0)*x1124))+((new_r11*x1122)));
9880evalcond[1]=((((-1.0)*new_r10*x1126))+(((-1.0000000008)*gconst13))+((new_r00*x1122)));
9881evalcond[2]=(x1128+((new_r10*x1122))+((new_r00*x1123)));
9882evalcond[3]=((((-1.0)*new_r10*x1125))+(((-1.0)*x1124))+((new_r00*x1127)));
9883evalcond[4]=((((-1.0)*gconst13*x1127))+new_r00+((x1123*x1128)));
9884evalcond[5]=(((gconst13*x1125))+((x1122*x1128))+new_r10);
9885evalcond[6]=((((-1.0)*x1123*x1124))+(((-1.0)*x1127*x1128))+new_r01);
9886evalcond[7]=((((-1.0)*x1122*x1124))+((x1125*x1128))+new_r11);
9887evalcond[8]=((((-1.0)*new_r11*x1126))+((new_r01*x1122))+(((-1.0000000008)*x1128)));
9888evalcond[9]=((((-1.0)*new_r11*x1125))+((new_r01*x1127))+(((-1.0)*x1128)));
9889if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
9890{
9891continue;
9892}
9893}
9894
9895{
9896std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9897vinfos[0].jointtype = 1;
9898vinfos[0].foffset = j0;
9899vinfos[0].indices[0] = _ij0[0];
9900vinfos[0].indices[1] = _ij0[1];
9901vinfos[0].maxsolutions = _nj0;
9902vinfos[1].jointtype = 1;
9903vinfos[1].foffset = j1;
9904vinfos[1].indices[0] = _ij1[0];
9905vinfos[1].indices[1] = _ij1[1];
9906vinfos[1].maxsolutions = _nj1;
9907vinfos[2].jointtype = 1;
9908vinfos[2].foffset = j2;
9909vinfos[2].indices[0] = _ij2[0];
9910vinfos[2].indices[1] = _ij2[1];
9911vinfos[2].maxsolutions = _nj2;
9912vinfos[3].jointtype = 1;
9913vinfos[3].foffset = j3;
9914vinfos[3].indices[0] = _ij3[0];
9915vinfos[3].indices[1] = _ij3[1];
9916vinfos[3].maxsolutions = _nj3;
9917vinfos[4].jointtype = 1;
9918vinfos[4].foffset = j4;
9919vinfos[4].indices[0] = _ij4[0];
9920vinfos[4].indices[1] = _ij4[1];
9921vinfos[4].maxsolutions = _nj4;
9922vinfos[5].jointtype = 1;
9923vinfos[5].foffset = j5;
9924vinfos[5].indices[0] = _ij5[0];
9925vinfos[5].indices[1] = _ij5[1];
9926vinfos[5].maxsolutions = _nj5;
9927std::vector<int> vfree(0);
9928solutions.AddSolution(vinfos,vfree);
9929}
9930}
9931}
9932
9933}
9934
9935}
9936
9937} else
9938{
9939{
9940IkReal j5array[1], cj5array[1], sj5array[1];
9941bool j5valid[1]={false};
9942_nj5 = 1;
9943if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
9944continue;
9945IkReal x1129=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
9946CheckValue<IkReal> x1130 = IKatan2WithCheck(IkReal((((gconst13*new_r10))+((new_r11*x1129)))),IkReal(((((-1.0)*new_r01*x1129))+(((-1.0)*gconst13*new_r00)))),IKFAST_ATAN2_MAGTHRESH);
9947if(!x1130.valid){
9948continue;
9949}
9950CheckValue<IkReal> x1131=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
9951if(!x1131.valid){
9952continue;
9953}
9954j5array[0]=((-1.5707963267949)+(x1130.value)+(((1.5707963267949)*(x1131.value))));
9955sj5array[0]=IKsin(j5array[0]);
9956cj5array[0]=IKcos(j5array[0]);
9957if( j5array[0] > IKPI )
9958{
9959 j5array[0]-=IK2PI;
9960}
9961else if( j5array[0] < -IKPI )
9962{ j5array[0]+=IK2PI;
9963}
9964j5valid[0] = true;
9965for(int ij5 = 0; ij5 < 1; ++ij5)
9966{
9967if( !j5valid[ij5] )
9968{
9969 continue;
9970}
9971_ij5[0] = ij5; _ij5[1] = -1;
9972for(int iij5 = ij5+1; iij5 < 1; ++iij5)
9973{
9974if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
9975{
9976 j5valid[iij5]=false; _ij5[1] = iij5; break;
9977}
9978}
9979j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
9980{
9981IkReal evalcond[10];
9982IkReal x1132=IKcos(j5);
9983IkReal x1133=IKsin(j5);
9984IkReal x1134=((1.0)*gconst13);
9985IkReal x1135=((1.0000000008)*x1133);
9986IkReal x1136=((1.0)*x1133);
9987IkReal x1137=((1.0000000008)*x1132);
9988IkReal x1138=x1129;
9989evalcond[0]=((((-1.0)*x1134))+((new_r11*x1132))+((new_r01*x1133)));
9990evalcond[1]=((((-1.0)*new_r10*x1136))+(((-1.0000000008)*gconst13))+((new_r00*x1132)));
9991evalcond[2]=(x1138+((new_r00*x1133))+((new_r10*x1132)));
9992evalcond[3]=((((-1.0)*new_r10*x1135))+(((-1.0)*x1134))+((new_r00*x1137)));
9993evalcond[4]=((((-1.0)*gconst13*x1137))+new_r00+((x1133*x1138)));
9994evalcond[5]=(((gconst13*x1135))+new_r10+((x1132*x1138)));
9995evalcond[6]=(new_r01+(((-1.0)*x1137*x1138))+(((-1.0)*x1133*x1134)));
9996evalcond[7]=(((x1135*x1138))+(((-1.0)*x1132*x1134))+new_r11);
9997evalcond[8]=((((-1.0)*new_r11*x1136))+(((-1.0000000008)*x1138))+((new_r01*x1132)));
9998evalcond[9]=((((-1.0)*new_r11*x1135))+((new_r01*x1137))+(((-1.0)*x1138)));
9999if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10000{
10001continue;
10002}
10003}
10004
10005{
10006std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10007vinfos[0].jointtype = 1;
10008vinfos[0].foffset = j0;
10009vinfos[0].indices[0] = _ij0[0];
10010vinfos[0].indices[1] = _ij0[1];
10011vinfos[0].maxsolutions = _nj0;
10012vinfos[1].jointtype = 1;
10013vinfos[1].foffset = j1;
10014vinfos[1].indices[0] = _ij1[0];
10015vinfos[1].indices[1] = _ij1[1];
10016vinfos[1].maxsolutions = _nj1;
10017vinfos[2].jointtype = 1;
10018vinfos[2].foffset = j2;
10019vinfos[2].indices[0] = _ij2[0];
10020vinfos[2].indices[1] = _ij2[1];
10021vinfos[2].maxsolutions = _nj2;
10022vinfos[3].jointtype = 1;
10023vinfos[3].foffset = j3;
10024vinfos[3].indices[0] = _ij3[0];
10025vinfos[3].indices[1] = _ij3[1];
10026vinfos[3].maxsolutions = _nj3;
10027vinfos[4].jointtype = 1;
10028vinfos[4].foffset = j4;
10029vinfos[4].indices[0] = _ij4[0];
10030vinfos[4].indices[1] = _ij4[1];
10031vinfos[4].maxsolutions = _nj4;
10032vinfos[5].jointtype = 1;
10033vinfos[5].foffset = j5;
10034vinfos[5].indices[0] = _ij5[0];
10035vinfos[5].indices[1] = _ij5[1];
10036vinfos[5].maxsolutions = _nj5;
10037std::vector<int> vfree(0);
10038solutions.AddSolution(vinfos,vfree);
10039}
10040}
10041}
10042
10043}
10044
10045}
10046
10047} else
10048{
10049{
10050IkReal j5array[1], cj5array[1], sj5array[1];
10051bool j5valid[1]={false};
10052_nj5 = 1;
10053IkReal x1139=((25000.0)*gconst13);
10054IkReal x1140=((25000.00002)*gconst13);
10055CheckValue<IkReal> x1141=IKPowWithIntegerCheck(IKsign(((((25000.0)*new_r10*new_r11))+(((25000.0)*new_r00*new_r01)))),-1);
10056if(!x1141.valid){
10057continue;
10058}
10059CheckValue<IkReal> x1142 = IKatan2WithCheck(IkReal(((((-1.0)*new_r11*x1140))+((new_r00*x1139)))),IkReal((((new_r01*x1140))+((new_r10*x1139)))),IKFAST_ATAN2_MAGTHRESH);
10060if(!x1142.valid){
10061continue;
10062}
10063j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1141.value)))+(x1142.value));
10064sj5array[0]=IKsin(j5array[0]);
10065cj5array[0]=IKcos(j5array[0]);
10066if( j5array[0] > IKPI )
10067{
10068 j5array[0]-=IK2PI;
10069}
10070else if( j5array[0] < -IKPI )
10071{ j5array[0]+=IK2PI;
10072}
10073j5valid[0] = true;
10074for(int ij5 = 0; ij5 < 1; ++ij5)
10075{
10076if( !j5valid[ij5] )
10077{
10078 continue;
10079}
10080_ij5[0] = ij5; _ij5[1] = -1;
10081for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10082{
10083if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10084{
10085 j5valid[iij5]=false; _ij5[1] = iij5; break;
10086}
10087}
10088j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10089{
10090IkReal evalcond[10];
10091IkReal x1143=IKcos(j5);
10092IkReal x1144=IKsin(j5);
10093IkReal x1145=((1.0)*gconst13);
10094IkReal x1146=((1.0000000008)*x1144);
10095IkReal x1147=((1.0)*x1144);
10096IkReal x1148=((1.0000000008)*x1143);
10097if((((1.0)+(((-1.0)*gconst13*x1145)))) < -0.00001)
10098continue;
10099IkReal x1149=IKsqrt(((1.0)+(((-1.0)*gconst13*x1145))));
10100evalcond[0]=((((-1.0)*x1145))+((new_r01*x1144))+((new_r11*x1143)));
10101evalcond[1]=(((new_r00*x1143))+(((-1.0000000008)*gconst13))+(((-1.0)*new_r10*x1147)));
10102evalcond[2]=(x1149+((new_r00*x1144))+((new_r10*x1143)));
10103evalcond[3]=(((new_r00*x1148))+(((-1.0)*x1145))+(((-1.0)*new_r10*x1146)));
10104evalcond[4]=((((-1.0)*gconst13*x1148))+new_r00+((x1144*x1149)));
10105evalcond[5]=(((x1143*x1149))+((gconst13*x1146))+new_r10);
10106evalcond[6]=(new_r01+(((-1.0)*x1148*x1149))+(((-1.0)*x1144*x1145)));
10107evalcond[7]=((((-1.0)*x1143*x1145))+((x1146*x1149))+new_r11);
10108evalcond[8]=(((new_r01*x1143))+(((-1.0)*new_r11*x1147))+(((-1.0000000008)*x1149)));
10109evalcond[9]=(((new_r01*x1148))+(((-1.0)*x1149))+(((-1.0)*new_r11*x1146)));
10110if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10111{
10112continue;
10113}
10114}
10115
10116{
10117std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10118vinfos[0].jointtype = 1;
10119vinfos[0].foffset = j0;
10120vinfos[0].indices[0] = _ij0[0];
10121vinfos[0].indices[1] = _ij0[1];
10122vinfos[0].maxsolutions = _nj0;
10123vinfos[1].jointtype = 1;
10124vinfos[1].foffset = j1;
10125vinfos[1].indices[0] = _ij1[0];
10126vinfos[1].indices[1] = _ij1[1];
10127vinfos[1].maxsolutions = _nj1;
10128vinfos[2].jointtype = 1;
10129vinfos[2].foffset = j2;
10130vinfos[2].indices[0] = _ij2[0];
10131vinfos[2].indices[1] = _ij2[1];
10132vinfos[2].maxsolutions = _nj2;
10133vinfos[3].jointtype = 1;
10134vinfos[3].foffset = j3;
10135vinfos[3].indices[0] = _ij3[0];
10136vinfos[3].indices[1] = _ij3[1];
10137vinfos[3].maxsolutions = _nj3;
10138vinfos[4].jointtype = 1;
10139vinfos[4].foffset = j4;
10140vinfos[4].indices[0] = _ij4[0];
10141vinfos[4].indices[1] = _ij4[1];
10142vinfos[4].maxsolutions = _nj4;
10143vinfos[5].jointtype = 1;
10144vinfos[5].foffset = j5;
10145vinfos[5].indices[0] = _ij5[0];
10146vinfos[5].indices[1] = _ij5[1];
10147vinfos[5].maxsolutions = _nj5;
10148std::vector<int> vfree(0);
10149solutions.AddSolution(vinfos,vfree);
10150}
10151}
10152}
10153
10154}
10155
10156}
10157
10158}
10159} while(0);
10160if( bgotonextstatement )
10161{
10162bool bgotonextstatement = true;
10163do
10164{
10165IkReal x1150=new_r00*new_r00;
10166CheckValue<IkReal> x1151=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1150))),-1);
10167if(!x1151.valid){
10168continue;
10169}
10170if((((-1.0)*x1150*(x1151.value))) < -0.00001)
10171continue;
10172IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1150*(x1151.value)))));
10173evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((cj3+(((-1.0)*gconst13)))))+(IKabs(((1.0)+(IKsign(sj3)))))), 6.28318530717959)));
10174if( IKabs(evalcond[0]) < 0.0000050000000000 )
10175{
10176bgotonextstatement=false;
10177{
10178IkReal j5eval[2];
10179IkReal x1152=new_r00*new_r00;
10180sj4=4.0e-5;
10181cj4=1.0;
10182j4=4.0e-5;
10183if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10184continue;
10185sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10186cj3=gconst13;
10187if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10188 continue;
10189j3=((-1.0)*(IKacos(gconst13)));
10190CheckValue<IkReal> x1153=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1152))),-1);
10191if(!x1153.valid){
10192continue;
10193}
10194if((((-1.0)*x1152*(x1153.value))) < -0.00001)
10195continue;
10196IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1152*(x1153.value)))));
10197IkReal x1154=(new_r00*new_r01);
10198IkReal x1155=(new_r10*new_r11);
10199j5eval[0]=(x1155+x1154);
10200j5eval[1]=IKsign(((((25000.0)*x1155))+(((25000.0)*x1154))));
10201if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
10202{
10203{
10204IkReal j5eval[2];
10205IkReal x1156=new_r00*new_r00;
10206sj4=4.0e-5;
10207cj4=1.0;
10208j4=4.0e-5;
10209if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10210continue;
10211sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10212cj3=gconst13;
10213if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10214 continue;
10215j3=((-1.0)*(IKacos(gconst13)));
10216CheckValue<IkReal> x1157=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1156))),-1);
10217if(!x1157.valid){
10218continue;
10219}
10220if((((-1.0)*x1156*(x1157.value))) < -0.00001)
10221continue;
10222IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1156*(x1157.value)))));
10223IkReal x1158=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
10224j5eval[0]=x1158;
10225j5eval[1]=IKsign(x1158);
10226if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
10227{
10228{
10229IkReal j5eval[1];
10230IkReal x1159=new_r00*new_r00;
10231sj4=4.0e-5;
10232cj4=1.0;
10233j4=4.0e-5;
10234if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10235continue;
10236sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10237cj3=gconst13;
10238if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10239 continue;
10240j3=((-1.0)*(IKacos(gconst13)));
10241CheckValue<IkReal> x1160=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1159))),-1);
10242if(!x1160.valid){
10243continue;
10244}
10245if((((-1.0)*x1159*(x1160.value))) < -0.00001)
10246continue;
10247IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1159*(x1160.value)))));
10248j5eval[0]=new_r01;
10249if( IKabs(j5eval[0]) < 0.0000010000000000 )
10250{
10251{
10252IkReal evalcond[1];
10253bool bgotonextstatement = true;
10254do
10255{
10256evalcond[0]=IKabs(new_r01);
10257if( IKabs(evalcond[0]) < 0.0000050000000000 )
10258{
10259bgotonextstatement=false;
10260{
10261IkReal j5eval[1];
10262IkReal x1161=new_r00*new_r00;
10263sj4=4.0e-5;
10264cj4=1.0;
10265j4=4.0e-5;
10266if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10267continue;
10268sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10269cj3=gconst13;
10270if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10271 continue;
10272j3=((-1.0)*(IKacos(gconst13)));
10273new_r01=0;
10274CheckValue<IkReal> x1162=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1161))),-1);
10275if(!x1162.valid){
10276continue;
10277}
10278if((((-1.0)*x1161*(x1162.value))) < -0.00001)
10279continue;
10280IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1161*(x1162.value)))));
10281j5eval[0]=new_r11;
10282if( IKabs(j5eval[0]) < 0.0000010000000000 )
10283{
10284{
10285IkReal j5eval[2];
10286IkReal x1163=new_r00*new_r00;
10287sj4=4.0e-5;
10288cj4=1.0;
10289j4=4.0e-5;
10290if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10291continue;
10292sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10293cj3=gconst13;
10294if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10295 continue;
10296j3=((-1.0)*(IKacos(gconst13)));
10297new_r01=0;
10298CheckValue<IkReal> x1164=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1163))),-1);
10299if(!x1164.valid){
10300continue;
10301}
10302if((((-1.0)*x1163*(x1164.value))) < -0.00001)
10303continue;
10304IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1163*(x1164.value)))));
10305j5eval[0]=new_r10;
10306j5eval[1]=new_r11;
10307if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
10308{
10309{
10310IkReal j5eval[2];
10311IkReal x1165=new_r00*new_r00;
10312sj4=4.0e-5;
10313cj4=1.0;
10314j4=4.0e-5;
10315if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10316continue;
10317sj3=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))));
10318cj3=gconst13;
10319if( (gconst13) < -1-IKFAST_SINCOS_THRESH || (gconst13) > 1+IKFAST_SINCOS_THRESH )
10320 continue;
10321j3=((-1.0)*(IKacos(gconst13)));
10322new_r01=0;
10323CheckValue<IkReal> x1166=IKPowWithIntegerCheck(((((-1.0000000016)*(new_r10*new_r10)))+(((-1.0)*x1165))),-1);
10324if(!x1166.valid){
10325continue;
10326}
10327if((((-1.0)*x1165*(x1166.value))) < -0.00001)
10328continue;
10329IkReal gconst13=((-1.0)*(IKsqrt(((-1.0)*x1165*(x1166.value)))));
10330j5eval[0]=new_r00;
10331j5eval[1]=new_r11;
10332if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
10333{
10334continue; // 3 cases reached
10335
10336} else
10337{
10338{
10339IkReal j5array[1], cj5array[1], sj5array[1];
10340bool j5valid[1]={false};
10341_nj5 = 1;
10342CheckValue<IkReal> x1168=IKPowWithIntegerCheck(new_r11,-1);
10343if(!x1168.valid){
10344continue;
10345}
10346IkReal x1167=x1168.value;
10347CheckValue<IkReal> x1169=IKPowWithIntegerCheck(new_r00,-1);
10348if(!x1169.valid){
10349continue;
10350}
10351if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10352continue;
10353if( IKabs((x1167*(x1169.value)*(((((-1.0)*gconst13*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*x1167)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1167*(x1169.value)*(((((-1.0)*gconst13*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))))+IKsqr((gconst13*x1167))-1) <= IKFAST_SINCOS_THRESH )
10354 continue;
10355j5array[0]=IKatan2((x1167*(x1169.value)*(((((-1.0)*gconst13*new_r10))+((new_r11*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))))), (gconst13*x1167));
10356sj5array[0]=IKsin(j5array[0]);
10357cj5array[0]=IKcos(j5array[0]);
10358if( j5array[0] > IKPI )
10359{
10360 j5array[0]-=IK2PI;
10361}
10362else if( j5array[0] < -IKPI )
10363{ j5array[0]+=IK2PI;
10364}
10365j5valid[0] = true;
10366for(int ij5 = 0; ij5 < 1; ++ij5)
10367{
10368if( !j5valid[ij5] )
10369{
10370 continue;
10371}
10372_ij5[0] = ij5; _ij5[1] = -1;
10373for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10374{
10375if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10376{
10377 j5valid[iij5]=false; _ij5[1] = iij5; break;
10378}
10379}
10380j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10381{
10382IkReal evalcond[10];
10383IkReal x1170=IKcos(j5);
10384IkReal x1171=IKsin(j5);
10385IkReal x1172=((1.0)*gconst13);
10386IkReal x1173=((1.0000000008)*gconst13);
10387IkReal x1174=(new_r11*x1171);
10388IkReal x1175=(new_r00*x1170);
10389IkReal x1176=(new_r10*x1171);
10390if((((1.0)+(((-1.0)*gconst13*x1172)))) < -0.00001)
10391continue;
10392IkReal x1177=IKsqrt(((1.0)+(((-1.0)*gconst13*x1172))));
10393IkReal x1178=(x1171*x1177);
10394IkReal x1179=(x1170*x1177);
10395evalcond[0]=(((new_r11*x1170))+(((-1.0)*x1172)));
10396evalcond[1]=(x1175+(((-1.0)*x1173))+(((-1.0)*x1176)));
10397evalcond[2]=(x1177+(((-1.0000000008)*x1174)));
10398evalcond[3]=((((1.0000000008)*x1177))+(((-1.0)*x1174)));
10399evalcond[4]=(((new_r10*x1170))+((new_r00*x1171))+(((-1.0)*x1177)));
10400evalcond[5]=((((1.0000000008)*x1175))+(((-1.0000000008)*x1176))+(((-1.0)*x1172)));
10401evalcond[6]=((((1.0000000008)*x1179))+(((-1.0)*x1171*x1172)));
10402evalcond[7]=((((-1.0)*x1170*x1173))+new_r00+(((-1.0)*x1178)));
10403evalcond[8]=(new_r10+((x1171*x1173))+(((-1.0)*x1179)));
10404evalcond[9]=((((-1.0000000008)*x1178))+(((-1.0)*x1170*x1172))+new_r11);
10405if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10406{
10407continue;
10408}
10409}
10410
10411{
10412std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10413vinfos[0].jointtype = 1;
10414vinfos[0].foffset = j0;
10415vinfos[0].indices[0] = _ij0[0];
10416vinfos[0].indices[1] = _ij0[1];
10417vinfos[0].maxsolutions = _nj0;
10418vinfos[1].jointtype = 1;
10419vinfos[1].foffset = j1;
10420vinfos[1].indices[0] = _ij1[0];
10421vinfos[1].indices[1] = _ij1[1];
10422vinfos[1].maxsolutions = _nj1;
10423vinfos[2].jointtype = 1;
10424vinfos[2].foffset = j2;
10425vinfos[2].indices[0] = _ij2[0];
10426vinfos[2].indices[1] = _ij2[1];
10427vinfos[2].maxsolutions = _nj2;
10428vinfos[3].jointtype = 1;
10429vinfos[3].foffset = j3;
10430vinfos[3].indices[0] = _ij3[0];
10431vinfos[3].indices[1] = _ij3[1];
10432vinfos[3].maxsolutions = _nj3;
10433vinfos[4].jointtype = 1;
10434vinfos[4].foffset = j4;
10435vinfos[4].indices[0] = _ij4[0];
10436vinfos[4].indices[1] = _ij4[1];
10437vinfos[4].maxsolutions = _nj4;
10438vinfos[5].jointtype = 1;
10439vinfos[5].foffset = j5;
10440vinfos[5].indices[0] = _ij5[0];
10441vinfos[5].indices[1] = _ij5[1];
10442vinfos[5].maxsolutions = _nj5;
10443std::vector<int> vfree(0);
10444solutions.AddSolution(vinfos,vfree);
10445}
10446}
10447}
10448
10449}
10450
10451}
10452
10453} else
10454{
10455{
10456IkReal j5array[1], cj5array[1], sj5array[1];
10457bool j5valid[1]={false};
10458_nj5 = 1;
10459CheckValue<IkReal> x1181=IKPowWithIntegerCheck(new_r11,-1);
10460if(!x1181.valid){
10461continue;
10462}
10463IkReal x1180=x1181.value;
10464CheckValue<IkReal> x1182=IKPowWithIntegerCheck(new_r10,-1);
10465if(!x1182.valid){
10466continue;
10467}
10468if( IKabs(((4.0e-5)*x1180*(x1182.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*x1180)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((4.0e-5)*x1180*(x1182.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11))))))+IKsqr((gconst13*x1180))-1) <= IKFAST_SINCOS_THRESH )
10469 continue;
10470j5array[0]=IKatan2(((4.0e-5)*x1180*(x1182.value)*(((((25000.0)*gconst13*new_r00))+(((-25000.00002)*gconst13*new_r11))))), (gconst13*x1180));
10471sj5array[0]=IKsin(j5array[0]);
10472cj5array[0]=IKcos(j5array[0]);
10473if( j5array[0] > IKPI )
10474{
10475 j5array[0]-=IK2PI;
10476}
10477else if( j5array[0] < -IKPI )
10478{ j5array[0]+=IK2PI;
10479}
10480j5valid[0] = true;
10481for(int ij5 = 0; ij5 < 1; ++ij5)
10482{
10483if( !j5valid[ij5] )
10484{
10485 continue;
10486}
10487_ij5[0] = ij5; _ij5[1] = -1;
10488for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10489{
10490if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10491{
10492 j5valid[iij5]=false; _ij5[1] = iij5; break;
10493}
10494}
10495j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10496{
10497IkReal evalcond[10];
10498IkReal x1183=IKcos(j5);
10499IkReal x1184=IKsin(j5);
10500IkReal x1185=((1.0)*gconst13);
10501IkReal x1186=((1.0000000008)*gconst13);
10502IkReal x1187=(new_r11*x1184);
10503IkReal x1188=(new_r00*x1183);
10504IkReal x1189=(new_r10*x1184);
10505if((((1.0)+(((-1.0)*gconst13*x1185)))) < -0.00001)
10506continue;
10507IkReal x1190=IKsqrt(((1.0)+(((-1.0)*gconst13*x1185))));
10508IkReal x1191=(x1184*x1190);
10509IkReal x1192=(x1183*x1190);
10510evalcond[0]=((((-1.0)*x1185))+((new_r11*x1183)));
10511evalcond[1]=(x1188+(((-1.0)*x1186))+(((-1.0)*x1189)));
10512evalcond[2]=(x1190+(((-1.0000000008)*x1187)));
10513evalcond[3]=((((1.0000000008)*x1190))+(((-1.0)*x1187)));
10514evalcond[4]=(((new_r10*x1183))+((new_r00*x1184))+(((-1.0)*x1190)));
10515evalcond[5]=((((1.0000000008)*x1188))+(((-1.0)*x1185))+(((-1.0000000008)*x1189)));
10516evalcond[6]=((((1.0000000008)*x1192))+(((-1.0)*x1184*x1185)));
10517evalcond[7]=((((-1.0)*x1183*x1186))+new_r00+(((-1.0)*x1191)));
10518evalcond[8]=(((x1184*x1186))+new_r10+(((-1.0)*x1192)));
10519evalcond[9]=((((-1.0000000008)*x1191))+(((-1.0)*x1183*x1185))+new_r11);
10520if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10521{
10522continue;
10523}
10524}
10525
10526{
10527std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10528vinfos[0].jointtype = 1;
10529vinfos[0].foffset = j0;
10530vinfos[0].indices[0] = _ij0[0];
10531vinfos[0].indices[1] = _ij0[1];
10532vinfos[0].maxsolutions = _nj0;
10533vinfos[1].jointtype = 1;
10534vinfos[1].foffset = j1;
10535vinfos[1].indices[0] = _ij1[0];
10536vinfos[1].indices[1] = _ij1[1];
10537vinfos[1].maxsolutions = _nj1;
10538vinfos[2].jointtype = 1;
10539vinfos[2].foffset = j2;
10540vinfos[2].indices[0] = _ij2[0];
10541vinfos[2].indices[1] = _ij2[1];
10542vinfos[2].maxsolutions = _nj2;
10543vinfos[3].jointtype = 1;
10544vinfos[3].foffset = j3;
10545vinfos[3].indices[0] = _ij3[0];
10546vinfos[3].indices[1] = _ij3[1];
10547vinfos[3].maxsolutions = _nj3;
10548vinfos[4].jointtype = 1;
10549vinfos[4].foffset = j4;
10550vinfos[4].indices[0] = _ij4[0];
10551vinfos[4].indices[1] = _ij4[1];
10552vinfos[4].maxsolutions = _nj4;
10553vinfos[5].jointtype = 1;
10554vinfos[5].foffset = j5;
10555vinfos[5].indices[0] = _ij5[0];
10556vinfos[5].indices[1] = _ij5[1];
10557vinfos[5].maxsolutions = _nj5;
10558std::vector<int> vfree(0);
10559solutions.AddSolution(vinfos,vfree);
10560}
10561}
10562}
10563
10564}
10565
10566}
10567
10568} else
10569{
10570{
10571IkReal j5array[1], cj5array[1], sj5array[1];
10572bool j5valid[1]={false};
10573_nj5 = 1;
10574CheckValue<IkReal> x1194=IKPowWithIntegerCheck(new_r11,-1);
10575if(!x1194.valid){
10576continue;
10577}
10578IkReal x1193=x1194.value;
10579if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10580continue;
10581if( IKabs(((0.9999999992)*x1193*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst13*x1193)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*x1193*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))))+IKsqr((gconst13*x1193))-1) <= IKFAST_SINCOS_THRESH )
10582 continue;
10583j5array[0]=IKatan2(((0.9999999992)*x1193*(IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13))))))), (gconst13*x1193));
10584sj5array[0]=IKsin(j5array[0]);
10585cj5array[0]=IKcos(j5array[0]);
10586if( j5array[0] > IKPI )
10587{
10588 j5array[0]-=IK2PI;
10589}
10590else if( j5array[0] < -IKPI )
10591{ j5array[0]+=IK2PI;
10592}
10593j5valid[0] = true;
10594for(int ij5 = 0; ij5 < 1; ++ij5)
10595{
10596if( !j5valid[ij5] )
10597{
10598 continue;
10599}
10600_ij5[0] = ij5; _ij5[1] = -1;
10601for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10602{
10603if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10604{
10605 j5valid[iij5]=false; _ij5[1] = iij5; break;
10606}
10607}
10608j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10609{
10610IkReal evalcond[10];
10611IkReal x1195=IKcos(j5);
10612IkReal x1196=IKsin(j5);
10613IkReal x1197=((1.0)*gconst13);
10614IkReal x1198=((1.0000000008)*gconst13);
10615IkReal x1199=(new_r11*x1196);
10616IkReal x1200=(new_r00*x1195);
10617IkReal x1201=(new_r10*x1196);
10618if((((1.0)+(((-1.0)*gconst13*x1197)))) < -0.00001)
10619continue;
10620IkReal x1202=IKsqrt(((1.0)+(((-1.0)*gconst13*x1197))));
10621IkReal x1203=(x1196*x1202);
10622IkReal x1204=(x1195*x1202);
10623evalcond[0]=((((-1.0)*x1197))+((new_r11*x1195)));
10624evalcond[1]=(x1200+(((-1.0)*x1198))+(((-1.0)*x1201)));
10625evalcond[2]=(x1202+(((-1.0000000008)*x1199)));
10626evalcond[3]=((((1.0000000008)*x1202))+(((-1.0)*x1199)));
10627evalcond[4]=((((-1.0)*x1202))+((new_r00*x1196))+((new_r10*x1195)));
10628evalcond[5]=((((-1.0)*x1197))+(((1.0000000008)*x1200))+(((-1.0000000008)*x1201)));
10629evalcond[6]=((((1.0000000008)*x1204))+(((-1.0)*x1196*x1197)));
10630evalcond[7]=((((-1.0)*x1195*x1198))+(((-1.0)*x1203))+new_r00);
10631evalcond[8]=(((x1196*x1198))+(((-1.0)*x1204))+new_r10);
10632evalcond[9]=((((-1.0)*x1195*x1197))+(((-1.0000000008)*x1203))+new_r11);
10633if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10634{
10635continue;
10636}
10637}
10638
10639{
10640std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10641vinfos[0].jointtype = 1;
10642vinfos[0].foffset = j0;
10643vinfos[0].indices[0] = _ij0[0];
10644vinfos[0].indices[1] = _ij0[1];
10645vinfos[0].maxsolutions = _nj0;
10646vinfos[1].jointtype = 1;
10647vinfos[1].foffset = j1;
10648vinfos[1].indices[0] = _ij1[0];
10649vinfos[1].indices[1] = _ij1[1];
10650vinfos[1].maxsolutions = _nj1;
10651vinfos[2].jointtype = 1;
10652vinfos[2].foffset = j2;
10653vinfos[2].indices[0] = _ij2[0];
10654vinfos[2].indices[1] = _ij2[1];
10655vinfos[2].maxsolutions = _nj2;
10656vinfos[3].jointtype = 1;
10657vinfos[3].foffset = j3;
10658vinfos[3].indices[0] = _ij3[0];
10659vinfos[3].indices[1] = _ij3[1];
10660vinfos[3].maxsolutions = _nj3;
10661vinfos[4].jointtype = 1;
10662vinfos[4].foffset = j4;
10663vinfos[4].indices[0] = _ij4[0];
10664vinfos[4].indices[1] = _ij4[1];
10665vinfos[4].maxsolutions = _nj4;
10666vinfos[5].jointtype = 1;
10667vinfos[5].foffset = j5;
10668vinfos[5].indices[0] = _ij5[0];
10669vinfos[5].indices[1] = _ij5[1];
10670vinfos[5].maxsolutions = _nj5;
10671std::vector<int> vfree(0);
10672solutions.AddSolution(vinfos,vfree);
10673}
10674}
10675}
10676
10677}
10678
10679}
10680
10681}
10682} while(0);
10683if( bgotonextstatement )
10684{
10685bool bgotonextstatement = true;
10686do
10687{
10688evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
10689if( IKabs(evalcond[0]) < 0.0000050000000000 )
10690{
10691bgotonextstatement=false;
10692{
10693IkReal j5array[2], cj5array[2], sj5array[2];
10694bool j5valid[2]={false};
10695_nj5 = 2;
10696cj5array[0]=new_r10;
10697if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
10698{
10699 j5valid[0] = j5valid[1] = true;
10700 j5array[0] = IKacos(cj5array[0]);
10701 sj5array[0] = IKsin(j5array[0]);
10702 cj5array[1] = cj5array[0];
10703 j5array[1] = -j5array[0];
10704 sj5array[1] = -sj5array[0];
10705}
10706else if( isnan(cj5array[0]) )
10707{
10708 // probably any value will work
10709 j5valid[0] = true;
10710 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
10711}
10712for(int ij5 = 0; ij5 < 2; ++ij5)
10713{
10714if( !j5valid[ij5] )
10715{
10716 continue;
10717}
10718_ij5[0] = ij5; _ij5[1] = -1;
10719for(int iij5 = ij5+1; iij5 < 2; ++iij5)
10720{
10721if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10722{
10723 j5valid[iij5]=false; _ij5[1] = iij5; break;
10724}
10725}
10726j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10727{
10728IkReal evalcond[9];
10729IkReal x1205=IKsin(j5);
10730IkReal x1206=IKcos(j5);
10731IkReal x1207=((1.0000000008)*x1206);
10732IkReal x1208=((-1.0000000008)*x1205);
10733IkReal x1209=((-1.0)*x1205);
10734evalcond[0]=(new_r01*x1205);
10735evalcond[1]=x1209;
10736evalcond[2]=(new_r10*x1209);
10737evalcond[3]=((-1.0)+((new_r10*x1206)));
10738evalcond[4]=x1208;
10739evalcond[5]=(new_r10*x1208);
10740evalcond[6]=(x1207+new_r01);
10741evalcond[7]=((1.0000000008)+((new_r01*x1206)));
10742evalcond[8]=((1.0)+((new_r01*x1207)));
10743if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
10744{
10745continue;
10746}
10747}
10748
10749{
10750std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10751vinfos[0].jointtype = 1;
10752vinfos[0].foffset = j0;
10753vinfos[0].indices[0] = _ij0[0];
10754vinfos[0].indices[1] = _ij0[1];
10755vinfos[0].maxsolutions = _nj0;
10756vinfos[1].jointtype = 1;
10757vinfos[1].foffset = j1;
10758vinfos[1].indices[0] = _ij1[0];
10759vinfos[1].indices[1] = _ij1[1];
10760vinfos[1].maxsolutions = _nj1;
10761vinfos[2].jointtype = 1;
10762vinfos[2].foffset = j2;
10763vinfos[2].indices[0] = _ij2[0];
10764vinfos[2].indices[1] = _ij2[1];
10765vinfos[2].maxsolutions = _nj2;
10766vinfos[3].jointtype = 1;
10767vinfos[3].foffset = j3;
10768vinfos[3].indices[0] = _ij3[0];
10769vinfos[3].indices[1] = _ij3[1];
10770vinfos[3].maxsolutions = _nj3;
10771vinfos[4].jointtype = 1;
10772vinfos[4].foffset = j4;
10773vinfos[4].indices[0] = _ij4[0];
10774vinfos[4].indices[1] = _ij4[1];
10775vinfos[4].maxsolutions = _nj4;
10776vinfos[5].jointtype = 1;
10777vinfos[5].foffset = j5;
10778vinfos[5].indices[0] = _ij5[0];
10779vinfos[5].indices[1] = _ij5[1];
10780vinfos[5].maxsolutions = _nj5;
10781std::vector<int> vfree(0);
10782solutions.AddSolution(vinfos,vfree);
10783}
10784}
10785}
10786
10787}
10788} while(0);
10789if( bgotonextstatement )
10790{
10791bool bgotonextstatement = true;
10792do
10793{
10794evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
10795if( IKabs(evalcond[0]) < 0.0000050000000000 )
10796{
10797bgotonextstatement=false;
10798{
10799IkReal j5array[1], cj5array[1], sj5array[1];
10800bool j5valid[1]={false};
10801_nj5 = 1;
10802if( IKabs(((0.9999999992)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11))+IKsqr(((-0.9999999992)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
10803 continue;
10804j5array[0]=IKatan2(((0.9999999992)*new_r11), ((-0.9999999992)*new_r01));
10805sj5array[0]=IKsin(j5array[0]);
10806cj5array[0]=IKcos(j5array[0]);
10807if( j5array[0] > IKPI )
10808{
10809 j5array[0]-=IK2PI;
10810}
10811else if( j5array[0] < -IKPI )
10812{ j5array[0]+=IK2PI;
10813}
10814j5valid[0] = true;
10815for(int ij5 = 0; ij5 < 1; ++ij5)
10816{
10817if( !j5valid[ij5] )
10818{
10819 continue;
10820}
10821_ij5[0] = ij5; _ij5[1] = -1;
10822for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10823{
10824if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10825{
10826 j5valid[iij5]=false; _ij5[1] = iij5; break;
10827}
10828}
10829j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10830{
10831IkReal evalcond[7];
10832IkReal x1210=IKcos(j5);
10833IkReal x1211=IKsin(j5);
10834IkReal x1212=((1.0000000008)*x1211);
10835IkReal x1213=((1.0000000008)*x1210);
10836evalcond[0]=((-1.0)*x1211);
10837evalcond[1]=((-1.0)*x1210);
10838evalcond[2]=(x1213+new_r01);
10839evalcond[3]=(new_r11+(((-1.0)*x1212)));
10840evalcond[4]=(((new_r11*x1210))+((new_r01*x1211)));
10841evalcond[5]=((1.0000000008)+((new_r01*x1210))+(((-1.0)*new_r11*x1211)));
10842evalcond[6]=((1.0)+((new_r01*x1213))+(((-1.0)*new_r11*x1212)));
10843if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
10844{
10845continue;
10846}
10847}
10848
10849{
10850std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10851vinfos[0].jointtype = 1;
10852vinfos[0].foffset = j0;
10853vinfos[0].indices[0] = _ij0[0];
10854vinfos[0].indices[1] = _ij0[1];
10855vinfos[0].maxsolutions = _nj0;
10856vinfos[1].jointtype = 1;
10857vinfos[1].foffset = j1;
10858vinfos[1].indices[0] = _ij1[0];
10859vinfos[1].indices[1] = _ij1[1];
10860vinfos[1].maxsolutions = _nj1;
10861vinfos[2].jointtype = 1;
10862vinfos[2].foffset = j2;
10863vinfos[2].indices[0] = _ij2[0];
10864vinfos[2].indices[1] = _ij2[1];
10865vinfos[2].maxsolutions = _nj2;
10866vinfos[3].jointtype = 1;
10867vinfos[3].foffset = j3;
10868vinfos[3].indices[0] = _ij3[0];
10869vinfos[3].indices[1] = _ij3[1];
10870vinfos[3].maxsolutions = _nj3;
10871vinfos[4].jointtype = 1;
10872vinfos[4].foffset = j4;
10873vinfos[4].indices[0] = _ij4[0];
10874vinfos[4].indices[1] = _ij4[1];
10875vinfos[4].maxsolutions = _nj4;
10876vinfos[5].jointtype = 1;
10877vinfos[5].foffset = j5;
10878vinfos[5].indices[0] = _ij5[0];
10879vinfos[5].indices[1] = _ij5[1];
10880vinfos[5].maxsolutions = _nj5;
10881std::vector<int> vfree(0);
10882solutions.AddSolution(vinfos,vfree);
10883}
10884}
10885}
10886
10887}
10888} while(0);
10889if( bgotonextstatement )
10890{
10891bool bgotonextstatement = true;
10892do
10893{
10894if( 1 )
10895{
10896bgotonextstatement=false;
10897continue; // branch miss [j5]
10898
10899}
10900} while(0);
10901if( bgotonextstatement )
10902{
10903}
10904}
10905}
10906}
10907}
10908
10909} else
10910{
10911{
10912IkReal j5array[1], cj5array[1], sj5array[1];
10913bool j5valid[1]={false};
10914_nj5 = 1;
10915CheckValue<IkReal> x1221=IKPowWithIntegerCheck(new_r01,-1);
10916if(!x1221.valid){
10917continue;
10918}
10919IkReal x1214=x1221.value;
10920IkReal x1215=((25000.0)*new_r00);
10921IkReal x1216=(gconst13*x1214);
10922if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
10923continue;
10924IkReal x1217=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
10925IkReal x1218=((25000.0)*new_r11*x1217);
10926CheckValue<IkReal> x1222=IKPowWithIntegerCheck(((((25000.00002)*gconst13*new_r01))+(((-1.0)*x1218))),-1);
10927if(!x1222.valid){
10928continue;
10929}
10930IkReal x1219=x1222.value;
10931IkReal x1220=(new_r11*x1219);
10932CheckValue<IkReal> x1223=IKPowWithIntegerCheck(((((25000.00002)*gconst13*new_r01))+(((-25000.0)*new_r11*x1217))),-1);
10933if(!x1223.valid){
10934continue;
10935}
10936if( IKabs((x1216+(((-1.0)*x1215*x1220))+((x1216*x1218*(x1223.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1219*((((new_r01*x1215))+(((-25000.0)*gconst13*x1217)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1216+(((-1.0)*x1215*x1220))+((x1216*x1218*(x1223.value)))))+IKsqr((x1219*((((new_r01*x1215))+(((-25000.0)*gconst13*x1217))))))-1) <= IKFAST_SINCOS_THRESH )
10937 continue;
10938j5array[0]=IKatan2((x1216+(((-1.0)*x1215*x1220))+((x1216*x1218*(x1223.value)))), (x1219*((((new_r01*x1215))+(((-25000.0)*gconst13*x1217))))));
10939sj5array[0]=IKsin(j5array[0]);
10940cj5array[0]=IKcos(j5array[0]);
10941if( j5array[0] > IKPI )
10942{
10943 j5array[0]-=IK2PI;
10944}
10945else if( j5array[0] < -IKPI )
10946{ j5array[0]+=IK2PI;
10947}
10948j5valid[0] = true;
10949for(int ij5 = 0; ij5 < 1; ++ij5)
10950{
10951if( !j5valid[ij5] )
10952{
10953 continue;
10954}
10955_ij5[0] = ij5; _ij5[1] = -1;
10956for(int iij5 = ij5+1; iij5 < 1; ++iij5)
10957{
10958if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
10959{
10960 j5valid[iij5]=false; _ij5[1] = iij5; break;
10961}
10962}
10963j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
10964{
10965IkReal evalcond[10];
10966IkReal x1224=IKcos(j5);
10967IkReal x1225=IKsin(j5);
10968IkReal x1226=((1.0)*gconst13);
10969IkReal x1227=((1.0000000008)*gconst13);
10970IkReal x1228=(new_r11*x1225);
10971IkReal x1229=(new_r01*x1224);
10972IkReal x1230=(new_r00*x1224);
10973IkReal x1231=(new_r10*x1225);
10974IkReal x1232=x1217;
10975IkReal x1233=(x1225*x1232);
10976IkReal x1234=(x1224*x1232);
10977evalcond[0]=((((-1.0)*x1226))+((new_r11*x1224))+((new_r01*x1225)));
10978evalcond[1]=((((-1.0)*x1231))+x1230+(((-1.0)*x1227)));
10979evalcond[2]=((((-1.0)*x1232))+((new_r00*x1225))+((new_r10*x1224)));
10980evalcond[3]=((((-1.0)*x1226))+(((-1.0000000008)*x1231))+(((1.0000000008)*x1230)));
10981evalcond[4]=((((-1.0)*x1233))+(((-1.0)*x1224*x1227))+new_r00);
10982evalcond[5]=((((-1.0)*x1234))+((x1225*x1227))+new_r10);
10983evalcond[6]=((((-1.0)*x1225*x1226))+new_r01+(((1.0000000008)*x1234)));
10984evalcond[7]=((((-1.0)*x1224*x1226))+(((-1.0000000008)*x1233))+new_r11);
10985evalcond[8]=(x1229+(((-1.0)*x1228))+(((1.0000000008)*x1232)));
10986evalcond[9]=(x1232+(((-1.0000000008)*x1228))+(((1.0000000008)*x1229)));
10987if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
10988{
10989continue;
10990}
10991}
10992
10993{
10994std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10995vinfos[0].jointtype = 1;
10996vinfos[0].foffset = j0;
10997vinfos[0].indices[0] = _ij0[0];
10998vinfos[0].indices[1] = _ij0[1];
10999vinfos[0].maxsolutions = _nj0;
11000vinfos[1].jointtype = 1;
11001vinfos[1].foffset = j1;
11002vinfos[1].indices[0] = _ij1[0];
11003vinfos[1].indices[1] = _ij1[1];
11004vinfos[1].maxsolutions = _nj1;
11005vinfos[2].jointtype = 1;
11006vinfos[2].foffset = j2;
11007vinfos[2].indices[0] = _ij2[0];
11008vinfos[2].indices[1] = _ij2[1];
11009vinfos[2].maxsolutions = _nj2;
11010vinfos[3].jointtype = 1;
11011vinfos[3].foffset = j3;
11012vinfos[3].indices[0] = _ij3[0];
11013vinfos[3].indices[1] = _ij3[1];
11014vinfos[3].maxsolutions = _nj3;
11015vinfos[4].jointtype = 1;
11016vinfos[4].foffset = j4;
11017vinfos[4].indices[0] = _ij4[0];
11018vinfos[4].indices[1] = _ij4[1];
11019vinfos[4].maxsolutions = _nj4;
11020vinfos[5].jointtype = 1;
11021vinfos[5].foffset = j5;
11022vinfos[5].indices[0] = _ij5[0];
11023vinfos[5].indices[1] = _ij5[1];
11024vinfos[5].maxsolutions = _nj5;
11025std::vector<int> vfree(0);
11026solutions.AddSolution(vinfos,vfree);
11027}
11028}
11029}
11030
11031}
11032
11033}
11034
11035} else
11036{
11037{
11038IkReal j5array[1], cj5array[1], sj5array[1];
11039bool j5valid[1]={false};
11040_nj5 = 1;
11041IkReal x1235=((1.0)*new_r11);
11042if((((1.0)+(((-1.0)*(gconst13*gconst13))))) < -0.00001)
11043continue;
11044IkReal x1236=IKsqrt(((1.0)+(((-1.0)*(gconst13*gconst13)))));
11045CheckValue<IkReal> x1237 = IKatan2WithCheck(IkReal(((((-1.0)*x1235*x1236))+((gconst13*new_r10)))),IkReal(((((-1.0)*gconst13*new_r00))+((new_r01*x1236)))),IKFAST_ATAN2_MAGTHRESH);
11046if(!x1237.valid){
11047continue;
11048}
11049CheckValue<IkReal> x1238=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*x1235))+((new_r01*new_r10)))),-1);
11050if(!x1238.valid){
11051continue;
11052}
11053j5array[0]=((-1.5707963267949)+(x1237.value)+(((1.5707963267949)*(x1238.value))));
11054sj5array[0]=IKsin(j5array[0]);
11055cj5array[0]=IKcos(j5array[0]);
11056if( j5array[0] > IKPI )
11057{
11058 j5array[0]-=IK2PI;
11059}
11060else if( j5array[0] < -IKPI )
11061{ j5array[0]+=IK2PI;
11062}
11063j5valid[0] = true;
11064for(int ij5 = 0; ij5 < 1; ++ij5)
11065{
11066if( !j5valid[ij5] )
11067{
11068 continue;
11069}
11070_ij5[0] = ij5; _ij5[1] = -1;
11071for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11072{
11073if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11074{
11075 j5valid[iij5]=false; _ij5[1] = iij5; break;
11076}
11077}
11078j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11079{
11080IkReal evalcond[10];
11081IkReal x1239=IKcos(j5);
11082IkReal x1240=IKsin(j5);
11083IkReal x1241=((1.0)*gconst13);
11084IkReal x1242=((1.0000000008)*gconst13);
11085IkReal x1243=(new_r11*x1240);
11086IkReal x1244=(new_r01*x1239);
11087IkReal x1245=(new_r00*x1239);
11088IkReal x1246=(new_r10*x1240);
11089IkReal x1247=x1236;
11090IkReal x1248=(x1240*x1247);
11091IkReal x1249=(x1239*x1247);
11092evalcond[0]=((((-1.0)*x1241))+((new_r11*x1239))+((new_r01*x1240)));
11093evalcond[1]=(x1245+(((-1.0)*x1246))+(((-1.0)*x1242)));
11094evalcond[2]=((((-1.0)*x1247))+((new_r10*x1239))+((new_r00*x1240)));
11095evalcond[3]=((((1.0000000008)*x1245))+(((-1.0)*x1241))+(((-1.0000000008)*x1246)));
11096evalcond[4]=((((-1.0)*x1239*x1242))+(((-1.0)*x1248))+new_r00);
11097evalcond[5]=(((x1240*x1242))+(((-1.0)*x1249))+new_r10);
11098evalcond[6]=((((1.0000000008)*x1249))+(((-1.0)*x1240*x1241))+new_r01);
11099evalcond[7]=((((-1.0)*x1239*x1241))+new_r11+(((-1.0000000008)*x1248)));
11100evalcond[8]=(x1244+(((1.0000000008)*x1247))+(((-1.0)*x1243)));
11101evalcond[9]=(x1247+(((1.0000000008)*x1244))+(((-1.0000000008)*x1243)));
11102if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
11103{
11104continue;
11105}
11106}
11107
11108{
11109std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11110vinfos[0].jointtype = 1;
11111vinfos[0].foffset = j0;
11112vinfos[0].indices[0] = _ij0[0];
11113vinfos[0].indices[1] = _ij0[1];
11114vinfos[0].maxsolutions = _nj0;
11115vinfos[1].jointtype = 1;
11116vinfos[1].foffset = j1;
11117vinfos[1].indices[0] = _ij1[0];
11118vinfos[1].indices[1] = _ij1[1];
11119vinfos[1].maxsolutions = _nj1;
11120vinfos[2].jointtype = 1;
11121vinfos[2].foffset = j2;
11122vinfos[2].indices[0] = _ij2[0];
11123vinfos[2].indices[1] = _ij2[1];
11124vinfos[2].maxsolutions = _nj2;
11125vinfos[3].jointtype = 1;
11126vinfos[3].foffset = j3;
11127vinfos[3].indices[0] = _ij3[0];
11128vinfos[3].indices[1] = _ij3[1];
11129vinfos[3].maxsolutions = _nj3;
11130vinfos[4].jointtype = 1;
11131vinfos[4].foffset = j4;
11132vinfos[4].indices[0] = _ij4[0];
11133vinfos[4].indices[1] = _ij4[1];
11134vinfos[4].maxsolutions = _nj4;
11135vinfos[5].jointtype = 1;
11136vinfos[5].foffset = j5;
11137vinfos[5].indices[0] = _ij5[0];
11138vinfos[5].indices[1] = _ij5[1];
11139vinfos[5].maxsolutions = _nj5;
11140std::vector<int> vfree(0);
11141solutions.AddSolution(vinfos,vfree);
11142}
11143}
11144}
11145
11146}
11147
11148}
11149
11150} else
11151{
11152{
11153IkReal j5array[1], cj5array[1], sj5array[1];
11154bool j5valid[1]={false};
11155_nj5 = 1;
11156IkReal x1250=((25000.0)*gconst13);
11157IkReal x1251=((25000.00002)*gconst13);
11158CheckValue<IkReal> x1252=IKPowWithIntegerCheck(IKsign(((((25000.0)*new_r10*new_r11))+(((25000.0)*new_r00*new_r01)))),-1);
11159if(!x1252.valid){
11160continue;
11161}
11162CheckValue<IkReal> x1253 = IKatan2WithCheck(IkReal(((((-1.0)*new_r11*x1251))+((new_r00*x1250)))),IkReal((((new_r01*x1251))+((new_r10*x1250)))),IKFAST_ATAN2_MAGTHRESH);
11163if(!x1253.valid){
11164continue;
11165}
11166j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1252.value)))+(x1253.value));
11167sj5array[0]=IKsin(j5array[0]);
11168cj5array[0]=IKcos(j5array[0]);
11169if( j5array[0] > IKPI )
11170{
11171 j5array[0]-=IK2PI;
11172}
11173else if( j5array[0] < -IKPI )
11174{ j5array[0]+=IK2PI;
11175}
11176j5valid[0] = true;
11177for(int ij5 = 0; ij5 < 1; ++ij5)
11178{
11179if( !j5valid[ij5] )
11180{
11181 continue;
11182}
11183_ij5[0] = ij5; _ij5[1] = -1;
11184for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11185{
11186if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11187{
11188 j5valid[iij5]=false; _ij5[1] = iij5; break;
11189}
11190}
11191j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11192{
11193IkReal evalcond[10];
11194IkReal x1254=IKcos(j5);
11195IkReal x1255=IKsin(j5);
11196IkReal x1256=((1.0)*gconst13);
11197IkReal x1257=((1.0000000008)*gconst13);
11198IkReal x1258=(new_r11*x1255);
11199IkReal x1259=(new_r01*x1254);
11200IkReal x1260=(new_r00*x1254);
11201IkReal x1261=(new_r10*x1255);
11202if((((1.0)+(((-1.0)*gconst13*x1256)))) < -0.00001)
11203continue;
11204IkReal x1262=IKsqrt(((1.0)+(((-1.0)*gconst13*x1256))));
11205IkReal x1263=(x1255*x1262);
11206IkReal x1264=(x1254*x1262);
11207evalcond[0]=((((-1.0)*x1256))+((new_r01*x1255))+((new_r11*x1254)));
11208evalcond[1]=((((-1.0)*x1257))+x1260+(((-1.0)*x1261)));
11209evalcond[2]=(((new_r00*x1255))+(((-1.0)*x1262))+((new_r10*x1254)));
11210evalcond[3]=((((-1.0)*x1256))+(((1.0000000008)*x1260))+(((-1.0000000008)*x1261)));
11211evalcond[4]=((((-1.0)*x1254*x1257))+new_r00+(((-1.0)*x1263)));
11212evalcond[5]=(((x1255*x1257))+new_r10+(((-1.0)*x1264)));
11213evalcond[6]=((((-1.0)*x1255*x1256))+(((1.0000000008)*x1264))+new_r01);
11214evalcond[7]=((((-1.0000000008)*x1263))+(((-1.0)*x1254*x1256))+new_r11);
11215evalcond[8]=(x1259+(((1.0000000008)*x1262))+(((-1.0)*x1258)));
11216evalcond[9]=(x1262+(((1.0000000008)*x1259))+(((-1.0000000008)*x1258)));
11217if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
11218{
11219continue;
11220}
11221}
11222
11223{
11224std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11225vinfos[0].jointtype = 1;
11226vinfos[0].foffset = j0;
11227vinfos[0].indices[0] = _ij0[0];
11228vinfos[0].indices[1] = _ij0[1];
11229vinfos[0].maxsolutions = _nj0;
11230vinfos[1].jointtype = 1;
11231vinfos[1].foffset = j1;
11232vinfos[1].indices[0] = _ij1[0];
11233vinfos[1].indices[1] = _ij1[1];
11234vinfos[1].maxsolutions = _nj1;
11235vinfos[2].jointtype = 1;
11236vinfos[2].foffset = j2;
11237vinfos[2].indices[0] = _ij2[0];
11238vinfos[2].indices[1] = _ij2[1];
11239vinfos[2].maxsolutions = _nj2;
11240vinfos[3].jointtype = 1;
11241vinfos[3].foffset = j3;
11242vinfos[3].indices[0] = _ij3[0];
11243vinfos[3].indices[1] = _ij3[1];
11244vinfos[3].maxsolutions = _nj3;
11245vinfos[4].jointtype = 1;
11246vinfos[4].foffset = j4;
11247vinfos[4].indices[0] = _ij4[0];
11248vinfos[4].indices[1] = _ij4[1];
11249vinfos[4].maxsolutions = _nj4;
11250vinfos[5].jointtype = 1;
11251vinfos[5].foffset = j5;
11252vinfos[5].indices[0] = _ij5[0];
11253vinfos[5].indices[1] = _ij5[1];
11254vinfos[5].maxsolutions = _nj5;
11255std::vector<int> vfree(0);
11256solutions.AddSolution(vinfos,vfree);
11257}
11258}
11259}
11260
11261}
11262
11263}
11264
11265}
11266} while(0);
11267if( bgotonextstatement )
11268{
11269bool bgotonextstatement = true;
11270do
11271{
11272IkReal x1266 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
11273if(IKabs(x1266)==0){
11274continue;
11275}
11276IkReal x1265=pow(x1266,-0.5);
11277CheckValue<IkReal> x1267 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11278if(!x1267.valid){
11279continue;
11280}
11281IkReal gconst14=((-1.0)*(x1267.value));
11282IkReal gconst15=((1.0000000008)*new_r10*x1265);
11283IkReal gconst16=(new_r00*x1265);
11284CheckValue<IkReal> x1268 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11285if(!x1268.valid){
11286continue;
11287}
11288evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1268.value)+j3)))), 6.28318530717959)));
11289if( IKabs(evalcond[0]) < 0.0000050000000000 )
11290{
11291bgotonextstatement=false;
11292{
11293IkReal j5eval[3];
11294IkReal x1269=x1265;
11295sj4=4.0e-5;
11296cj4=1.0;
11297j4=4.0e-5;
11298sj3=gconst15;
11299cj3=gconst16;
11300CheckValue<IkReal> x1270 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11301if(!x1270.valid){
11302continue;
11303}
11304j3=((-1.0)*(x1270.value));
11305CheckValue<IkReal> x1271 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11306if(!x1271.valid){
11307continue;
11308}
11309IkReal gconst14=((-1.0)*(x1271.value));
11310IkReal gconst15=((1.0000000008)*new_r10*x1269);
11311IkReal gconst16=(new_r00*x1269);
11312IkReal x1272=new_r00*new_r00;
11313IkReal x1273=(new_r01*new_r10);
11314IkReal x1274=(x1273+(((-1.0)*new_r00*new_r11)));
11315IkReal x1277 = ((((625000001.0)*(new_r10*new_r10)))+(((625000000.0)*x1272)));
11316if(IKabs(x1277)==0){
11317continue;
11318}
11319IkReal x1275=pow(x1277,-0.5);
11320IkReal x1276=(new_r10*x1275);
11321j5eval[0]=x1274;
11322j5eval[1]=IKsign(x1274);
11323j5eval[2]=((IKabs(((((25000.0)*new_r00*x1276))+(((25000.00002)*new_r11*x1276)))))+(IKabs(((((25000.0)*x1272*x1275))+(((25000.00002)*x1273*x1275))))));
11324if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
11325{
11326{
11327IkReal j5eval[1];
11328IkReal x1278=x1265;
11329sj4=4.0e-5;
11330cj4=1.0;
11331j4=4.0e-5;
11332sj3=gconst15;
11333cj3=gconst16;
11334CheckValue<IkReal> x1279 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11335if(!x1279.valid){
11336continue;
11337}
11338j3=((-1.0)*(x1279.value));
11339CheckValue<IkReal> x1280 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11340if(!x1280.valid){
11341continue;
11342}
11343IkReal gconst14=((-1.0)*(x1280.value));
11344IkReal gconst15=((1.0000000008)*new_r10*x1278);
11345IkReal gconst16=(new_r00*x1278);
11346j5eval[0]=new_r00;
11347if( IKabs(j5eval[0]) < 0.0000010000000000 )
11348{
11349{
11350IkReal j5eval[2];
11351IkReal x1281=x1265;
11352sj4=4.0e-5;
11353cj4=1.0;
11354j4=4.0e-5;
11355sj3=gconst15;
11356cj3=gconst16;
11357CheckValue<IkReal> x1282 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11358if(!x1282.valid){
11359continue;
11360}
11361j3=((-1.0)*(x1282.value));
11362CheckValue<IkReal> x1283 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11363if(!x1283.valid){
11364continue;
11365}
11366IkReal gconst14=((-1.0)*(x1283.value));
11367IkReal gconst15=((1.0000000008)*new_r10*x1281);
11368IkReal gconst16=(new_r00*x1281);
11369j5eval[0]=new_r00;
11370IkReal x1284 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
11371if(IKabs(x1284)==0){
11372continue;
11373}
11374j5eval[1]=((-1.6e-9)*new_r00*new_r10*(pow(x1284,-0.5)));
11375if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
11376{
11377{
11378IkReal evalcond[1];
11379bool bgotonextstatement = true;
11380do
11381{
11382evalcond[0]=IKabs(new_r00);
11383if( IKabs(evalcond[0]) < 0.0000050000000000 )
11384{
11385bgotonextstatement=false;
11386{
11387IkReal j5eval[1];
11388sj4=4.0e-5;
11389cj4=1.0;
11390j4=4.0e-5;
11391sj3=gconst15;
11392cj3=gconst16;
11393CheckValue<IkReal> x1285 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
11394if(!x1285.valid){
11395continue;
11396}
11397j3=((-1.0)*(x1285.value));
11398new_r00=0;
11399CheckValue<IkReal> x1286 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
11400if(!x1286.valid){
11401continue;
11402}
11403IkReal gconst14=((-1.0)*(x1286.value));
11404IkReal x1287 = new_r10*new_r10;
11405if(IKabs(x1287)==0){
11406continue;
11407}
11408IkReal gconst15=(new_r10*(pow(x1287,-0.5)));
11409IkReal gconst16=0;
11410j5eval[0]=new_r10;
11411if( IKabs(j5eval[0]) < 0.0000010000000000 )
11412{
11413{
11414IkReal j5array[1], cj5array[1], sj5array[1];
11415bool j5valid[1]={false};
11416_nj5 = 1;
11417CheckValue<IkReal> x1289=IKPowWithIntegerCheck(gconst15,-1);
11418if(!x1289.valid){
11419continue;
11420}
11421IkReal x1288=x1289.value;
11422if( IKabs(((-0.9999999992)*new_r11*x1288)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x1288)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*x1288))+IKsqr(((-1.0)*new_r10*x1288))-1) <= IKFAST_SINCOS_THRESH )
11423 continue;
11424j5array[0]=IKatan2(((-0.9999999992)*new_r11*x1288), ((-1.0)*new_r10*x1288));
11425sj5array[0]=IKsin(j5array[0]);
11426cj5array[0]=IKcos(j5array[0]);
11427if( j5array[0] > IKPI )
11428{
11429 j5array[0]-=IK2PI;
11430}
11431else if( j5array[0] < -IKPI )
11432{ j5array[0]+=IK2PI;
11433}
11434j5valid[0] = true;
11435for(int ij5 = 0; ij5 < 1; ++ij5)
11436{
11437if( !j5valid[ij5] )
11438{
11439 continue;
11440}
11441_ij5[0] = ij5; _ij5[1] = -1;
11442for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11443{
11444if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11445{
11446 j5valid[iij5]=false; _ij5[1] = iij5; break;
11447}
11448}
11449j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11450{
11451IkReal evalcond[10];
11452IkReal x1290=IKsin(j5);
11453IkReal x1291=IKcos(j5);
11454IkReal x1292=(gconst15*x1290);
11455IkReal x1293=(new_r11*x1290);
11456IkReal x1294=(gconst15*x1291);
11457IkReal x1295=(new_r10*x1290);
11458IkReal x1296=(new_r01*x1291);
11459evalcond[0]=x1292;
11460evalcond[1]=((-1.0)*x1295);
11461evalcond[2]=(gconst15+((new_r10*x1291)));
11462evalcond[3]=(x1294+new_r10);
11463evalcond[4]=((-1.0000000008)*x1295);
11464evalcond[5]=(((new_r11*x1291))+((new_r01*x1290)));
11465evalcond[6]=((((-1.0000000008)*x1294))+new_r01);
11466evalcond[7]=((((1.0000000008)*x1292))+new_r11);
11467evalcond[8]=(x1296+(((-1.0000000008)*gconst15))+(((-1.0)*x1293)));
11468evalcond[9]=((((1.0000000008)*x1296))+(((-1.0000000008)*x1293))+(((-1.0)*gconst15)));
11469if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
11470{
11471continue;
11472}
11473}
11474
11475{
11476std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11477vinfos[0].jointtype = 1;
11478vinfos[0].foffset = j0;
11479vinfos[0].indices[0] = _ij0[0];
11480vinfos[0].indices[1] = _ij0[1];
11481vinfos[0].maxsolutions = _nj0;
11482vinfos[1].jointtype = 1;
11483vinfos[1].foffset = j1;
11484vinfos[1].indices[0] = _ij1[0];
11485vinfos[1].indices[1] = _ij1[1];
11486vinfos[1].maxsolutions = _nj1;
11487vinfos[2].jointtype = 1;
11488vinfos[2].foffset = j2;
11489vinfos[2].indices[0] = _ij2[0];
11490vinfos[2].indices[1] = _ij2[1];
11491vinfos[2].maxsolutions = _nj2;
11492vinfos[3].jointtype = 1;
11493vinfos[3].foffset = j3;
11494vinfos[3].indices[0] = _ij3[0];
11495vinfos[3].indices[1] = _ij3[1];
11496vinfos[3].maxsolutions = _nj3;
11497vinfos[4].jointtype = 1;
11498vinfos[4].foffset = j4;
11499vinfos[4].indices[0] = _ij4[0];
11500vinfos[4].indices[1] = _ij4[1];
11501vinfos[4].maxsolutions = _nj4;
11502vinfos[5].jointtype = 1;
11503vinfos[5].foffset = j5;
11504vinfos[5].indices[0] = _ij5[0];
11505vinfos[5].indices[1] = _ij5[1];
11506vinfos[5].maxsolutions = _nj5;
11507std::vector<int> vfree(0);
11508solutions.AddSolution(vinfos,vfree);
11509}
11510}
11511}
11512
11513} else
11514{
11515{
11516IkReal j5array[1], cj5array[1], sj5array[1];
11517bool j5valid[1]={false};
11518_nj5 = 1;
11519CheckValue<IkReal> x1297=IKPowWithIntegerCheck(gconst15,-1);
11520if(!x1297.valid){
11521continue;
11522}
11523CheckValue<IkReal> x1298=IKPowWithIntegerCheck(new_r10,-1);
11524if(!x1298.valid){
11525continue;
11526}
11527if( IKabs(((-0.9999999992)*new_r11*(x1297.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst15*(x1298.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*(x1297.value)))+IKsqr(((-1.0)*gconst15*(x1298.value)))-1) <= IKFAST_SINCOS_THRESH )
11528 continue;
11529j5array[0]=IKatan2(((-0.9999999992)*new_r11*(x1297.value)), ((-1.0)*gconst15*(x1298.value)));
11530sj5array[0]=IKsin(j5array[0]);
11531cj5array[0]=IKcos(j5array[0]);
11532if( j5array[0] > IKPI )
11533{
11534 j5array[0]-=IK2PI;
11535}
11536else if( j5array[0] < -IKPI )
11537{ j5array[0]+=IK2PI;
11538}
11539j5valid[0] = true;
11540for(int ij5 = 0; ij5 < 1; ++ij5)
11541{
11542if( !j5valid[ij5] )
11543{
11544 continue;
11545}
11546_ij5[0] = ij5; _ij5[1] = -1;
11547for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11548{
11549if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11550{
11551 j5valid[iij5]=false; _ij5[1] = iij5; break;
11552}
11553}
11554j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11555{
11556IkReal evalcond[10];
11557IkReal x1299=IKsin(j5);
11558IkReal x1300=IKcos(j5);
11559IkReal x1301=(gconst15*x1299);
11560IkReal x1302=(new_r11*x1299);
11561IkReal x1303=(gconst15*x1300);
11562IkReal x1304=(new_r10*x1299);
11563IkReal x1305=(new_r01*x1300);
11564evalcond[0]=x1301;
11565evalcond[1]=((-1.0)*x1304);
11566evalcond[2]=(gconst15+((new_r10*x1300)));
11567evalcond[3]=(x1303+new_r10);
11568evalcond[4]=((-1.0000000008)*x1304);
11569evalcond[5]=(((new_r11*x1300))+((new_r01*x1299)));
11570evalcond[6]=((((-1.0000000008)*x1303))+new_r01);
11571evalcond[7]=((((1.0000000008)*x1301))+new_r11);
11572evalcond[8]=(x1305+(((-1.0)*x1302))+(((-1.0000000008)*gconst15)));
11573evalcond[9]=((((-1.0000000008)*x1302))+(((1.0000000008)*x1305))+(((-1.0)*gconst15)));
11574if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
11575{
11576continue;
11577}
11578}
11579
11580{
11581std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11582vinfos[0].jointtype = 1;
11583vinfos[0].foffset = j0;
11584vinfos[0].indices[0] = _ij0[0];
11585vinfos[0].indices[1] = _ij0[1];
11586vinfos[0].maxsolutions = _nj0;
11587vinfos[1].jointtype = 1;
11588vinfos[1].foffset = j1;
11589vinfos[1].indices[0] = _ij1[0];
11590vinfos[1].indices[1] = _ij1[1];
11591vinfos[1].maxsolutions = _nj1;
11592vinfos[2].jointtype = 1;
11593vinfos[2].foffset = j2;
11594vinfos[2].indices[0] = _ij2[0];
11595vinfos[2].indices[1] = _ij2[1];
11596vinfos[2].maxsolutions = _nj2;
11597vinfos[3].jointtype = 1;
11598vinfos[3].foffset = j3;
11599vinfos[3].indices[0] = _ij3[0];
11600vinfos[3].indices[1] = _ij3[1];
11601vinfos[3].maxsolutions = _nj3;
11602vinfos[4].jointtype = 1;
11603vinfos[4].foffset = j4;
11604vinfos[4].indices[0] = _ij4[0];
11605vinfos[4].indices[1] = _ij4[1];
11606vinfos[4].maxsolutions = _nj4;
11607vinfos[5].jointtype = 1;
11608vinfos[5].foffset = j5;
11609vinfos[5].indices[0] = _ij5[0];
11610vinfos[5].indices[1] = _ij5[1];
11611vinfos[5].maxsolutions = _nj5;
11612std::vector<int> vfree(0);
11613solutions.AddSolution(vinfos,vfree);
11614}
11615}
11616}
11617
11618}
11619
11620}
11621
11622}
11623} while(0);
11624if( bgotonextstatement )
11625{
11626bool bgotonextstatement = true;
11627do
11628{
11629evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
11630if( IKabs(evalcond[0]) < 0.0000050000000000 )
11631{
11632bgotonextstatement=false;
11633{
11634IkReal j5eval[5];
11635IkReal x1307 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
11636if(IKabs(x1307)==0){
11637continue;
11638}
11639IkReal x1306=pow(x1307,-0.5);
11640sj4=4.0e-5;
11641cj4=1.0;
11642j4=4.0e-5;
11643sj3=gconst15;
11644cj3=gconst16;
11645CheckValue<IkReal> x1308 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11646if(!x1308.valid){
11647continue;
11648}
11649j3=((-1.0)*(x1308.value));
11650new_r11=0;
11651new_r01=0;
11652new_r22=0;
11653new_r20=0;
11654CheckValue<IkReal> x1309 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11655if(!x1309.valid){
11656continue;
11657}
11658IkReal gconst14=((-1.0)*(x1309.value));
11659IkReal gconst15=((1.0000000008)*new_r10*x1306);
11660IkReal gconst16=(new_r00*x1306);
11661j5eval[0]=-1.0;
11662j5eval[1]=3.90625000625e+17;
11663j5eval[2]=((1.0)+(((1.6e-9)*(new_r10*new_r10))));
11664j5eval[3]=1.0;
11665j5eval[4]=-1.0;
11666if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 || IKabs(j5eval[3]) < 0.0000010000000000 || IKabs(j5eval[4]) < 0.0000010000000000 )
11667{
11668{
11669IkReal j5eval[1];
11670IkReal x1311 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
11671if(IKabs(x1311)==0){
11672continue;
11673}
11674IkReal x1310=pow(x1311,-0.5);
11675sj4=4.0e-5;
11676cj4=1.0;
11677j4=4.0e-5;
11678sj3=gconst15;
11679cj3=gconst16;
11680CheckValue<IkReal> x1312 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11681if(!x1312.valid){
11682continue;
11683}
11684j3=((-1.0)*(x1312.value));
11685new_r11=0;
11686new_r01=0;
11687new_r22=0;
11688new_r20=0;
11689CheckValue<IkReal> x1313 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11690if(!x1313.valid){
11691continue;
11692}
11693IkReal gconst14=((-1.0)*(x1313.value));
11694IkReal gconst15=((1.0000000008)*new_r10*x1310);
11695IkReal gconst16=(new_r00*x1310);
11696IkReal x1314=new_r10*new_r10;
11697CheckValue<IkReal> x1316=IKPowWithIntegerCheck(((1.0)+(((1.6e-9)*x1314))),-1);
11698if(!x1316.valid){
11699continue;
11700}
11701IkReal x1315=x1316.value;
11702IkReal x1317=((1.0)+(((-1.0)*x1314)));
11703j5eval[0]=IKsign(((((625000002.0)*x1315*(x1314*x1314)))+(((-625000000.0)*x1315*(x1317*x1317)))));
11704if( IKabs(j5eval[0]) < 0.0000010000000000 )
11705{
11706{
11707IkReal j5eval[2];
11708IkReal x1319 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
11709if(IKabs(x1319)==0){
11710continue;
11711}
11712IkReal x1318=pow(x1319,-0.5);
11713sj4=4.0e-5;
11714cj4=1.0;
11715j4=4.0e-5;
11716sj3=gconst15;
11717cj3=gconst16;
11718CheckValue<IkReal> x1320 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11719if(!x1320.valid){
11720continue;
11721}
11722j3=((-1.0)*(x1320.value));
11723new_r11=0;
11724new_r01=0;
11725new_r22=0;
11726new_r20=0;
11727CheckValue<IkReal> x1321 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
11728if(!x1321.valid){
11729continue;
11730}
11731IkReal gconst14=((-1.0)*(x1321.value));
11732IkReal gconst15=((1.0000000008)*new_r10*x1318);
11733IkReal gconst16=(new_r00*x1318);
11734IkReal x1322=new_r10*new_r10;
11735IkReal x1323=((1.0)+(((1.6e-9)*x1322)));
11736CheckValue<IkReal> x1324=IKPowWithIntegerCheck(x1323,-1);
11737if(!x1324.valid){
11738continue;
11739}
11740j5eval[0]=((-3.20000000256e-9)*x1322*(x1324.value)*(((1.0)+(((-1.0)*x1322)))));
11741IkReal x1325 = x1323;
11742if(IKabs(x1325)==0){
11743continue;
11744}
11745j5eval[1]=((-1.6e-9)*new_r00*new_r10*(pow(x1325,-0.5)));
11746if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
11747{
11748continue; // 3 cases reached
11749
11750} else
11751{
11752{
11753IkReal j5array[1], cj5array[1], sj5array[1];
11754bool j5valid[1]={false};
11755_nj5 = 1;
11756IkReal x1326=gconst15*gconst15;
11757IkReal x1327=(gconst16*new_r10);
11758CheckValue<IkReal> x1328=IKPowWithIntegerCheck(((((625000000.0)*(x1327*x1327)))+(((-625000001.0)*x1326*(new_r00*new_r00)))),-1);
11759if(!x1328.valid){
11760continue;
11761}
11762CheckValue<IkReal> x1329=IKPowWithIntegerCheck(((((25000.0)*x1327))+(((-25000.00002)*gconst15*new_r00))),-1);
11763if(!x1329.valid){
11764continue;
11765}
11766if( IKabs(((x1328.value)*(((((625000000.5)*x1326*x1327))+(((625000001.0)*new_r00*(gconst15*gconst15*gconst15))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-25000.0)*gconst15*gconst16*(x1329.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1328.value)*(((((625000000.5)*x1326*x1327))+(((625000001.0)*new_r00*(gconst15*gconst15*gconst15)))))))+IKsqr(((-25000.0)*gconst15*gconst16*(x1329.value)))-1) <= IKFAST_SINCOS_THRESH )
11767 continue;
11768j5array[0]=IKatan2(((x1328.value)*(((((625000000.5)*x1326*x1327))+(((625000001.0)*new_r00*(gconst15*gconst15*gconst15)))))), ((-25000.0)*gconst15*gconst16*(x1329.value)));
11769sj5array[0]=IKsin(j5array[0]);
11770cj5array[0]=IKcos(j5array[0]);
11771if( j5array[0] > IKPI )
11772{
11773 j5array[0]-=IK2PI;
11774}
11775else if( j5array[0] < -IKPI )
11776{ j5array[0]+=IK2PI;
11777}
11778j5valid[0] = true;
11779for(int ij5 = 0; ij5 < 1; ++ij5)
11780{
11781if( !j5valid[ij5] )
11782{
11783 continue;
11784}
11785_ij5[0] = ij5; _ij5[1] = -1;
11786for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11787{
11788if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11789{
11790 j5valid[iij5]=false; _ij5[1] = iij5; break;
11791}
11792}
11793j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11794{
11795IkReal evalcond[7];
11796IkReal x1330=IKsin(j5);
11797IkReal x1331=IKcos(j5);
11798IkReal x1332=((1.0000000008)*gconst16);
11799IkReal x1333=((1.0)*gconst16);
11800IkReal x1334=((1.0000000008)*x1330);
11801IkReal x1335=((1.0)*x1330);
11802IkReal x1336=(gconst15*x1331);
11803IkReal x1337=(new_r00*x1331);
11804evalcond[0]=(((new_r10*x1331))+gconst15+((new_r00*x1330)));
11805evalcond[1]=(((gconst15*x1330))+(((-1.0)*x1331*x1332))+new_r00);
11806evalcond[2]=(x1336+((x1330*x1332))+new_r10);
11807evalcond[3]=((((-1.0)*x1330*x1333))+(((-1.0000000008)*x1336)));
11808evalcond[4]=(((gconst15*x1334))+(((-1.0)*x1331*x1333)));
11809evalcond[5]=(x1337+(((-1.0)*new_r10*x1335))+(((-1.0)*x1332)));
11810evalcond[6]=((((-1.0)*new_r10*x1334))+(((-1.0)*x1333))+(((1.0000000008)*x1337)));
11811if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
11812{
11813continue;
11814}
11815}
11816
11817{
11818std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11819vinfos[0].jointtype = 1;
11820vinfos[0].foffset = j0;
11821vinfos[0].indices[0] = _ij0[0];
11822vinfos[0].indices[1] = _ij0[1];
11823vinfos[0].maxsolutions = _nj0;
11824vinfos[1].jointtype = 1;
11825vinfos[1].foffset = j1;
11826vinfos[1].indices[0] = _ij1[0];
11827vinfos[1].indices[1] = _ij1[1];
11828vinfos[1].maxsolutions = _nj1;
11829vinfos[2].jointtype = 1;
11830vinfos[2].foffset = j2;
11831vinfos[2].indices[0] = _ij2[0];
11832vinfos[2].indices[1] = _ij2[1];
11833vinfos[2].maxsolutions = _nj2;
11834vinfos[3].jointtype = 1;
11835vinfos[3].foffset = j3;
11836vinfos[3].indices[0] = _ij3[0];
11837vinfos[3].indices[1] = _ij3[1];
11838vinfos[3].maxsolutions = _nj3;
11839vinfos[4].jointtype = 1;
11840vinfos[4].foffset = j4;
11841vinfos[4].indices[0] = _ij4[0];
11842vinfos[4].indices[1] = _ij4[1];
11843vinfos[4].maxsolutions = _nj4;
11844vinfos[5].jointtype = 1;
11845vinfos[5].foffset = j5;
11846vinfos[5].indices[0] = _ij5[0];
11847vinfos[5].indices[1] = _ij5[1];
11848vinfos[5].maxsolutions = _nj5;
11849std::vector<int> vfree(0);
11850solutions.AddSolution(vinfos,vfree);
11851}
11852}
11853}
11854
11855}
11856
11857}
11858
11859} else
11860{
11861{
11862IkReal j5array[1], cj5array[1], sj5array[1];
11863bool j5valid[1]={false};
11864_nj5 = 1;
11865IkReal x1338=gconst16*gconst16;
11866IkReal x1339=gconst15*gconst15;
11867IkReal x1340=((625000000.0)*x1338);
11868IkReal x1341=((625000000.5)*gconst16*x1339);
11869CheckValue<IkReal> x1342=IKPowWithIntegerCheck(IKsign(((((-1.0)*x1340*(new_r00*new_r00)))+(((625000001.0)*x1339*(new_r10*new_r10))))),-1);
11870if(!x1342.valid){
11871continue;
11872}
11873CheckValue<IkReal> x1343 = IKatan2WithCheck(IkReal((((gconst15*new_r00*x1340))+(((-1.0)*new_r10*x1341)))),IkReal(((((-625000001.0)*new_r10*(gconst15*gconst15*gconst15)))+((new_r00*x1341)))),IKFAST_ATAN2_MAGTHRESH);
11874if(!x1343.valid){
11875continue;
11876}
11877j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1342.value)))+(x1343.value));
11878sj5array[0]=IKsin(j5array[0]);
11879cj5array[0]=IKcos(j5array[0]);
11880if( j5array[0] > IKPI )
11881{
11882 j5array[0]-=IK2PI;
11883}
11884else if( j5array[0] < -IKPI )
11885{ j5array[0]+=IK2PI;
11886}
11887j5valid[0] = true;
11888for(int ij5 = 0; ij5 < 1; ++ij5)
11889{
11890if( !j5valid[ij5] )
11891{
11892 continue;
11893}
11894_ij5[0] = ij5; _ij5[1] = -1;
11895for(int iij5 = ij5+1; iij5 < 1; ++iij5)
11896{
11897if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
11898{
11899 j5valid[iij5]=false; _ij5[1] = iij5; break;
11900}
11901}
11902j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
11903{
11904IkReal evalcond[7];
11905IkReal x1344=IKsin(j5);
11906IkReal x1345=IKcos(j5);
11907IkReal x1346=((1.0000000008)*gconst16);
11908IkReal x1347=((1.0)*gconst16);
11909IkReal x1348=((1.0000000008)*x1344);
11910IkReal x1349=((1.0)*x1344);
11911IkReal x1350=(gconst15*x1345);
11912IkReal x1351=(new_r00*x1345);
11913evalcond[0]=(gconst15+((new_r00*x1344))+((new_r10*x1345)));
11914evalcond[1]=(new_r00+((gconst15*x1344))+(((-1.0)*x1345*x1346)));
11915evalcond[2]=(x1350+((x1344*x1346))+new_r10);
11916evalcond[3]=((((-1.0000000008)*x1350))+(((-1.0)*x1344*x1347)));
11917evalcond[4]=(((gconst15*x1348))+(((-1.0)*x1345*x1347)));
11918evalcond[5]=(x1351+(((-1.0)*x1346))+(((-1.0)*new_r10*x1349)));
11919evalcond[6]=((((-1.0)*x1347))+(((-1.0)*new_r10*x1348))+(((1.0000000008)*x1351)));
11920if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
11921{
11922continue;
11923}
11924}
11925
11926{
11927std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11928vinfos[0].jointtype = 1;
11929vinfos[0].foffset = j0;
11930vinfos[0].indices[0] = _ij0[0];
11931vinfos[0].indices[1] = _ij0[1];
11932vinfos[0].maxsolutions = _nj0;
11933vinfos[1].jointtype = 1;
11934vinfos[1].foffset = j1;
11935vinfos[1].indices[0] = _ij1[0];
11936vinfos[1].indices[1] = _ij1[1];
11937vinfos[1].maxsolutions = _nj1;
11938vinfos[2].jointtype = 1;
11939vinfos[2].foffset = j2;
11940vinfos[2].indices[0] = _ij2[0];
11941vinfos[2].indices[1] = _ij2[1];
11942vinfos[2].maxsolutions = _nj2;
11943vinfos[3].jointtype = 1;
11944vinfos[3].foffset = j3;
11945vinfos[3].indices[0] = _ij3[0];
11946vinfos[3].indices[1] = _ij3[1];
11947vinfos[3].maxsolutions = _nj3;
11948vinfos[4].jointtype = 1;
11949vinfos[4].foffset = j4;
11950vinfos[4].indices[0] = _ij4[0];
11951vinfos[4].indices[1] = _ij4[1];
11952vinfos[4].maxsolutions = _nj4;
11953vinfos[5].jointtype = 1;
11954vinfos[5].foffset = j5;
11955vinfos[5].indices[0] = _ij5[0];
11956vinfos[5].indices[1] = _ij5[1];
11957vinfos[5].maxsolutions = _nj5;
11958std::vector<int> vfree(0);
11959solutions.AddSolution(vinfos,vfree);
11960}
11961}
11962}
11963
11964}
11965
11966}
11967
11968} else
11969{
11970{
11971IkReal j5array[1], cj5array[1], sj5array[1];
11972bool j5valid[1]={false};
11973_nj5 = 1;
11974IkReal x1352=((25000.0)*gconst15);
11975IkReal x1353=((25000.00002)*gconst16);
11976CheckValue<IkReal> x1354=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
11977if(!x1354.valid){
11978continue;
11979}
11980CheckValue<IkReal> x1355 = IKatan2WithCheck(IkReal((((new_r10*x1353))+((new_r00*x1352)))),IkReal((((new_r10*x1352))+(((-1.0)*new_r00*x1353)))),IKFAST_ATAN2_MAGTHRESH);
11981if(!x1355.valid){
11982continue;
11983}
11984j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1354.value)))+(x1355.value));
11985sj5array[0]=IKsin(j5array[0]);
11986cj5array[0]=IKcos(j5array[0]);
11987if( j5array[0] > IKPI )
11988{
11989 j5array[0]-=IK2PI;
11990}
11991else if( j5array[0] < -IKPI )
11992{ j5array[0]+=IK2PI;
11993}
11994j5valid[0] = true;
11995for(int ij5 = 0; ij5 < 1; ++ij5)
11996{
11997if( !j5valid[ij5] )
11998{
11999 continue;
12000}
12001_ij5[0] = ij5; _ij5[1] = -1;
12002for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12003{
12004if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12005{
12006 j5valid[iij5]=false; _ij5[1] = iij5; break;
12007}
12008}
12009j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12010{
12011IkReal evalcond[7];
12012IkReal x1356=IKsin(j5);
12013IkReal x1357=IKcos(j5);
12014IkReal x1358=((1.0000000008)*gconst16);
12015IkReal x1359=((1.0)*gconst16);
12016IkReal x1360=((1.0000000008)*x1356);
12017IkReal x1361=((1.0)*x1356);
12018IkReal x1362=(gconst15*x1357);
12019IkReal x1363=(new_r00*x1357);
12020evalcond[0]=(((new_r10*x1357))+gconst15+((new_r00*x1356)));
12021evalcond[1]=(((gconst15*x1356))+new_r00+(((-1.0)*x1357*x1358)));
12022evalcond[2]=(x1362+new_r10+((x1356*x1358)));
12023evalcond[3]=((((-1.0000000008)*x1362))+(((-1.0)*x1356*x1359)));
12024evalcond[4]=(((gconst15*x1360))+(((-1.0)*x1357*x1359)));
12025evalcond[5]=(x1363+(((-1.0)*x1358))+(((-1.0)*new_r10*x1361)));
12026evalcond[6]=((((-1.0)*x1359))+(((1.0000000008)*x1363))+(((-1.0)*new_r10*x1360)));
12027if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
12028{
12029continue;
12030}
12031}
12032
12033{
12034std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12035vinfos[0].jointtype = 1;
12036vinfos[0].foffset = j0;
12037vinfos[0].indices[0] = _ij0[0];
12038vinfos[0].indices[1] = _ij0[1];
12039vinfos[0].maxsolutions = _nj0;
12040vinfos[1].jointtype = 1;
12041vinfos[1].foffset = j1;
12042vinfos[1].indices[0] = _ij1[0];
12043vinfos[1].indices[1] = _ij1[1];
12044vinfos[1].maxsolutions = _nj1;
12045vinfos[2].jointtype = 1;
12046vinfos[2].foffset = j2;
12047vinfos[2].indices[0] = _ij2[0];
12048vinfos[2].indices[1] = _ij2[1];
12049vinfos[2].maxsolutions = _nj2;
12050vinfos[3].jointtype = 1;
12051vinfos[3].foffset = j3;
12052vinfos[3].indices[0] = _ij3[0];
12053vinfos[3].indices[1] = _ij3[1];
12054vinfos[3].maxsolutions = _nj3;
12055vinfos[4].jointtype = 1;
12056vinfos[4].foffset = j4;
12057vinfos[4].indices[0] = _ij4[0];
12058vinfos[4].indices[1] = _ij4[1];
12059vinfos[4].maxsolutions = _nj4;
12060vinfos[5].jointtype = 1;
12061vinfos[5].foffset = j5;
12062vinfos[5].indices[0] = _ij5[0];
12063vinfos[5].indices[1] = _ij5[1];
12064vinfos[5].maxsolutions = _nj5;
12065std::vector<int> vfree(0);
12066solutions.AddSolution(vinfos,vfree);
12067}
12068}
12069}
12070
12071}
12072
12073}
12074
12075}
12076} while(0);
12077if( bgotonextstatement )
12078{
12079bool bgotonextstatement = true;
12080do
12081{
12082evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
12083if( IKabs(evalcond[0]) < 0.0000050000000000 )
12084{
12085bgotonextstatement=false;
12086{
12087IkReal j5array[1], cj5array[1], sj5array[1];
12088bool j5valid[1]={false};
12089_nj5 = 1;
12090CheckValue<IkReal> x1365=IKPowWithIntegerCheck(gconst16,-1);
12091if(!x1365.valid){
12092continue;
12093}
12094IkReal x1364=x1365.value;
12095if( IKabs((new_r01*x1364)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r00*x1364)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x1364))+IKsqr(((0.9999999992)*new_r00*x1364))-1) <= IKFAST_SINCOS_THRESH )
12096 continue;
12097j5array[0]=IKatan2((new_r01*x1364), ((0.9999999992)*new_r00*x1364));
12098sj5array[0]=IKsin(j5array[0]);
12099cj5array[0]=IKcos(j5array[0]);
12100if( j5array[0] > IKPI )
12101{
12102 j5array[0]-=IK2PI;
12103}
12104else if( j5array[0] < -IKPI )
12105{ j5array[0]+=IK2PI;
12106}
12107j5valid[0] = true;
12108for(int ij5 = 0; ij5 < 1; ++ij5)
12109{
12110if( !j5valid[ij5] )
12111{
12112 continue;
12113}
12114_ij5[0] = ij5; _ij5[1] = -1;
12115for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12116{
12117if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12118{
12119 j5valid[iij5]=false; _ij5[1] = iij5; break;
12120}
12121}
12122j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12123{
12124IkReal evalcond[10];
12125IkReal x1366=IKcos(j5);
12126IkReal x1367=IKsin(j5);
12127IkReal x1368=((1.0)*gconst16);
12128IkReal x1369=((1.0000000008)*gconst16);
12129IkReal x1370=(new_r00*x1366);
12130IkReal x1371=(new_r01*x1366);
12131evalcond[0]=(new_r00*x1367);
12132evalcond[1]=x1371;
12133evalcond[2]=((-1.0)*gconst16*x1366);
12134evalcond[3]=(new_r01+(((-1.0)*x1367*x1368)));
12135evalcond[4]=(((new_r01*x1367))+(((-1.0)*x1368)));
12136evalcond[5]=(x1367*x1369);
12137evalcond[6]=((1.0000000008)*x1371);
12138evalcond[7]=((((-1.0)*x1366*x1369))+new_r00);
12139evalcond[8]=(x1370+(((-1.0)*x1369)));
12140evalcond[9]=((((1.0000000008)*x1370))+(((-1.0)*x1368)));
12141if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12142{
12143continue;
12144}
12145}
12146
12147{
12148std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12149vinfos[0].jointtype = 1;
12150vinfos[0].foffset = j0;
12151vinfos[0].indices[0] = _ij0[0];
12152vinfos[0].indices[1] = _ij0[1];
12153vinfos[0].maxsolutions = _nj0;
12154vinfos[1].jointtype = 1;
12155vinfos[1].foffset = j1;
12156vinfos[1].indices[0] = _ij1[0];
12157vinfos[1].indices[1] = _ij1[1];
12158vinfos[1].maxsolutions = _nj1;
12159vinfos[2].jointtype = 1;
12160vinfos[2].foffset = j2;
12161vinfos[2].indices[0] = _ij2[0];
12162vinfos[2].indices[1] = _ij2[1];
12163vinfos[2].maxsolutions = _nj2;
12164vinfos[3].jointtype = 1;
12165vinfos[3].foffset = j3;
12166vinfos[3].indices[0] = _ij3[0];
12167vinfos[3].indices[1] = _ij3[1];
12168vinfos[3].maxsolutions = _nj3;
12169vinfos[4].jointtype = 1;
12170vinfos[4].foffset = j4;
12171vinfos[4].indices[0] = _ij4[0];
12172vinfos[4].indices[1] = _ij4[1];
12173vinfos[4].maxsolutions = _nj4;
12174vinfos[5].jointtype = 1;
12175vinfos[5].foffset = j5;
12176vinfos[5].indices[0] = _ij5[0];
12177vinfos[5].indices[1] = _ij5[1];
12178vinfos[5].maxsolutions = _nj5;
12179std::vector<int> vfree(0);
12180solutions.AddSolution(vinfos,vfree);
12181}
12182}
12183}
12184
12185}
12186} while(0);
12187if( bgotonextstatement )
12188{
12189bool bgotonextstatement = true;
12190do
12191{
12192if( 1 )
12193{
12194bgotonextstatement=false;
12195continue; // branch miss [j5]
12196
12197}
12198} while(0);
12199if( bgotonextstatement )
12200{
12201}
12202}
12203}
12204}
12205}
12206
12207} else
12208{
12209{
12210IkReal j5array[1], cj5array[1], sj5array[1];
12211bool j5valid[1]={false};
12212_nj5 = 1;
12213CheckValue<IkReal> x1378=IKPowWithIntegerCheck(new_r00,-1);
12214if(!x1378.valid){
12215continue;
12216}
12217IkReal x1372=x1378.value;
12218IkReal x1373=((25000.0)*gconst16);
12219IkReal x1374=((25000.0)*new_r01);
12220IkReal x1375=(gconst15*x1372);
12221CheckValue<IkReal> x1379=IKPowWithIntegerCheck(((((-25000.00002)*gconst15*new_r00))+((new_r10*x1373))),-1);
12222if(!x1379.valid){
12223continue;
12224}
12225IkReal x1376=x1379.value;
12226IkReal x1377=(new_r10*x1376);
12227CheckValue<IkReal> x1380=IKPowWithIntegerCheck(((((25000.0)*gconst16*new_r10))+(((-25000.00002)*gconst15*new_r00))),-1);
12228if(!x1380.valid){
12229continue;
12230}
12231if( IKabs(((((-1.0)*x1375))+((new_r10*x1373*x1375*(x1380.value)))+((x1374*x1377)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1376*(((((-1.0)*new_r00*x1374))+(((-1.0)*gconst15*x1373)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x1375))+((new_r10*x1373*x1375*(x1380.value)))+((x1374*x1377))))+IKsqr((x1376*(((((-1.0)*new_r00*x1374))+(((-1.0)*gconst15*x1373))))))-1) <= IKFAST_SINCOS_THRESH )
12232 continue;
12233j5array[0]=IKatan2(((((-1.0)*x1375))+((new_r10*x1373*x1375*(x1380.value)))+((x1374*x1377))), (x1376*(((((-1.0)*new_r00*x1374))+(((-1.0)*gconst15*x1373))))));
12234sj5array[0]=IKsin(j5array[0]);
12235cj5array[0]=IKcos(j5array[0]);
12236if( j5array[0] > IKPI )
12237{
12238 j5array[0]-=IK2PI;
12239}
12240else if( j5array[0] < -IKPI )
12241{ j5array[0]+=IK2PI;
12242}
12243j5valid[0] = true;
12244for(int ij5 = 0; ij5 < 1; ++ij5)
12245{
12246if( !j5valid[ij5] )
12247{
12248 continue;
12249}
12250_ij5[0] = ij5; _ij5[1] = -1;
12251for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12252{
12253if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12254{
12255 j5valid[iij5]=false; _ij5[1] = iij5; break;
12256}
12257}
12258j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12259{
12260IkReal evalcond[10];
12261IkReal x1381=IKcos(j5);
12262IkReal x1382=IKsin(j5);
12263IkReal x1383=((1.0)*gconst16);
12264IkReal x1384=((1.0000000008)*gconst15);
12265IkReal x1385=((1.0000000008)*gconst16);
12266IkReal x1386=(gconst15*x1381);
12267IkReal x1387=(new_r00*x1381);
12268IkReal x1388=((1.0000000008)*x1382);
12269IkReal x1389=(new_r01*x1381);
12270IkReal x1390=((1.0)*x1382);
12271evalcond[0]=(((new_r10*x1381))+gconst15+((new_r00*x1382)));
12272evalcond[1]=((((-1.0)*x1383))+((new_r11*x1381))+((new_r01*x1382)));
12273evalcond[2]=(((gconst15*x1382))+(((-1.0)*x1381*x1385))+new_r00);
12274evalcond[3]=(x1386+new_r10+((x1382*x1385)));
12275evalcond[4]=((((-1.0)*x1382*x1383))+(((-1.0)*x1381*x1384))+new_r01);
12276evalcond[5]=((((-1.0)*x1381*x1383))+new_r11+((x1382*x1384)));
12277evalcond[6]=((((-1.0)*x1385))+x1387+(((-1.0)*new_r10*x1390)));
12278evalcond[7]=((((-1.0)*x1384))+x1389+(((-1.0)*new_r11*x1390)));
12279evalcond[8]=((((-1.0)*x1383))+(((1.0000000008)*x1387))+(((-1.0)*new_r10*x1388)));
12280evalcond[9]=((((1.0000000008)*x1389))+(((-1.0)*new_r11*x1388))+(((-1.0)*gconst15)));
12281if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12282{
12283continue;
12284}
12285}
12286
12287{
12288std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12289vinfos[0].jointtype = 1;
12290vinfos[0].foffset = j0;
12291vinfos[0].indices[0] = _ij0[0];
12292vinfos[0].indices[1] = _ij0[1];
12293vinfos[0].maxsolutions = _nj0;
12294vinfos[1].jointtype = 1;
12295vinfos[1].foffset = j1;
12296vinfos[1].indices[0] = _ij1[0];
12297vinfos[1].indices[1] = _ij1[1];
12298vinfos[1].maxsolutions = _nj1;
12299vinfos[2].jointtype = 1;
12300vinfos[2].foffset = j2;
12301vinfos[2].indices[0] = _ij2[0];
12302vinfos[2].indices[1] = _ij2[1];
12303vinfos[2].maxsolutions = _nj2;
12304vinfos[3].jointtype = 1;
12305vinfos[3].foffset = j3;
12306vinfos[3].indices[0] = _ij3[0];
12307vinfos[3].indices[1] = _ij3[1];
12308vinfos[3].maxsolutions = _nj3;
12309vinfos[4].jointtype = 1;
12310vinfos[4].foffset = j4;
12311vinfos[4].indices[0] = _ij4[0];
12312vinfos[4].indices[1] = _ij4[1];
12313vinfos[4].maxsolutions = _nj4;
12314vinfos[5].jointtype = 1;
12315vinfos[5].foffset = j5;
12316vinfos[5].indices[0] = _ij5[0];
12317vinfos[5].indices[1] = _ij5[1];
12318vinfos[5].maxsolutions = _nj5;
12319std::vector<int> vfree(0);
12320solutions.AddSolution(vinfos,vfree);
12321}
12322}
12323}
12324
12325}
12326
12327}
12328
12329} else
12330{
12331{
12332IkReal j5array[1], cj5array[1], sj5array[1];
12333bool j5valid[1]={false};
12334_nj5 = 1;
12335CheckValue<IkReal> x1395=IKPowWithIntegerCheck(new_r00,-1);
12336if(!x1395.valid){
12337continue;
12338}
12339IkReal x1391=x1395.value;
12340IkReal x1392=gconst15*gconst15;
12341IkReal x1393=((25000.0)*new_r10);
12342CheckValue<IkReal> x1396=IKPowWithIntegerCheck(((((25000.00002)*gconst16*new_r00))+((gconst15*x1393))),-1);
12343if(!x1396.valid){
12344continue;
12345}
12346IkReal x1394=x1396.value;
12347CheckValue<IkReal> x1397=IKPowWithIntegerCheck(x1391,-2);
12348if(!x1397.valid){
12349continue;
12350}
12351if( IKabs(((((-1.0)*gconst15*x1391))+(((-1.0)*new_r00*x1393*x1394))+((x1391*x1392*x1393*x1394)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1394*(((((-25000.0)*x1392))+(((25000.0)*(x1397.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*gconst15*x1391))+(((-1.0)*new_r00*x1393*x1394))+((x1391*x1392*x1393*x1394))))+IKsqr((x1394*(((((-25000.0)*x1392))+(((25000.0)*(x1397.value)))))))-1) <= IKFAST_SINCOS_THRESH )
12352 continue;
12353j5array[0]=IKatan2(((((-1.0)*gconst15*x1391))+(((-1.0)*new_r00*x1393*x1394))+((x1391*x1392*x1393*x1394))), (x1394*(((((-25000.0)*x1392))+(((25000.0)*(x1397.value)))))));
12354sj5array[0]=IKsin(j5array[0]);
12355cj5array[0]=IKcos(j5array[0]);
12356if( j5array[0] > IKPI )
12357{
12358 j5array[0]-=IK2PI;
12359}
12360else if( j5array[0] < -IKPI )
12361{ j5array[0]+=IK2PI;
12362}
12363j5valid[0] = true;
12364for(int ij5 = 0; ij5 < 1; ++ij5)
12365{
12366if( !j5valid[ij5] )
12367{
12368 continue;
12369}
12370_ij5[0] = ij5; _ij5[1] = -1;
12371for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12372{
12373if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12374{
12375 j5valid[iij5]=false; _ij5[1] = iij5; break;
12376}
12377}
12378j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12379{
12380IkReal evalcond[10];
12381IkReal x1398=IKcos(j5);
12382IkReal x1399=IKsin(j5);
12383IkReal x1400=((1.0)*gconst16);
12384IkReal x1401=((1.0000000008)*gconst15);
12385IkReal x1402=((1.0000000008)*gconst16);
12386IkReal x1403=(gconst15*x1398);
12387IkReal x1404=(new_r00*x1398);
12388IkReal x1405=((1.0000000008)*x1399);
12389IkReal x1406=(new_r01*x1398);
12390IkReal x1407=((1.0)*x1399);
12391evalcond[0]=(((new_r10*x1398))+gconst15+((new_r00*x1399)));
12392evalcond[1]=(((new_r11*x1398))+(((-1.0)*x1400))+((new_r01*x1399)));
12393evalcond[2]=(((gconst15*x1399))+(((-1.0)*x1398*x1402))+new_r00);
12394evalcond[3]=(((x1399*x1402))+x1403+new_r10);
12395evalcond[4]=((((-1.0)*x1399*x1400))+(((-1.0)*x1398*x1401))+new_r01);
12396evalcond[5]=((((-1.0)*x1398*x1400))+((x1399*x1401))+new_r11);
12397evalcond[6]=((((-1.0)*x1402))+x1404+(((-1.0)*new_r10*x1407)));
12398evalcond[7]=((((-1.0)*x1401))+x1406+(((-1.0)*new_r11*x1407)));
12399evalcond[8]=((((1.0000000008)*x1404))+(((-1.0)*x1400))+(((-1.0)*new_r10*x1405)));
12400evalcond[9]=((((1.0000000008)*x1406))+(((-1.0)*gconst15))+(((-1.0)*new_r11*x1405)));
12401if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12402{
12403continue;
12404}
12405}
12406
12407{
12408std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12409vinfos[0].jointtype = 1;
12410vinfos[0].foffset = j0;
12411vinfos[0].indices[0] = _ij0[0];
12412vinfos[0].indices[1] = _ij0[1];
12413vinfos[0].maxsolutions = _nj0;
12414vinfos[1].jointtype = 1;
12415vinfos[1].foffset = j1;
12416vinfos[1].indices[0] = _ij1[0];
12417vinfos[1].indices[1] = _ij1[1];
12418vinfos[1].maxsolutions = _nj1;
12419vinfos[2].jointtype = 1;
12420vinfos[2].foffset = j2;
12421vinfos[2].indices[0] = _ij2[0];
12422vinfos[2].indices[1] = _ij2[1];
12423vinfos[2].maxsolutions = _nj2;
12424vinfos[3].jointtype = 1;
12425vinfos[3].foffset = j3;
12426vinfos[3].indices[0] = _ij3[0];
12427vinfos[3].indices[1] = _ij3[1];
12428vinfos[3].maxsolutions = _nj3;
12429vinfos[4].jointtype = 1;
12430vinfos[4].foffset = j4;
12431vinfos[4].indices[0] = _ij4[0];
12432vinfos[4].indices[1] = _ij4[1];
12433vinfos[4].maxsolutions = _nj4;
12434vinfos[5].jointtype = 1;
12435vinfos[5].foffset = j5;
12436vinfos[5].indices[0] = _ij5[0];
12437vinfos[5].indices[1] = _ij5[1];
12438vinfos[5].maxsolutions = _nj5;
12439std::vector<int> vfree(0);
12440solutions.AddSolution(vinfos,vfree);
12441}
12442}
12443}
12444
12445}
12446
12447}
12448
12449} else
12450{
12451{
12452IkReal j5array[1], cj5array[1], sj5array[1];
12453bool j5valid[1]={false};
12454_nj5 = 1;
12455IkReal x1408=((1.0)*new_r00);
12456CheckValue<IkReal> x1409=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x1408)))),-1);
12457if(!x1409.valid){
12458continue;
12459}
12460CheckValue<IkReal> x1410 = IKatan2WithCheck(IkReal((((gconst16*new_r10))+((gconst15*new_r11)))),IkReal(((((-1.0)*gconst16*x1408))+(((-1.0)*gconst15*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
12461if(!x1410.valid){
12462continue;
12463}
12464j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1409.value)))+(x1410.value));
12465sj5array[0]=IKsin(j5array[0]);
12466cj5array[0]=IKcos(j5array[0]);
12467if( j5array[0] > IKPI )
12468{
12469 j5array[0]-=IK2PI;
12470}
12471else if( j5array[0] < -IKPI )
12472{ j5array[0]+=IK2PI;
12473}
12474j5valid[0] = true;
12475for(int ij5 = 0; ij5 < 1; ++ij5)
12476{
12477if( !j5valid[ij5] )
12478{
12479 continue;
12480}
12481_ij5[0] = ij5; _ij5[1] = -1;
12482for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12483{
12484if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12485{
12486 j5valid[iij5]=false; _ij5[1] = iij5; break;
12487}
12488}
12489j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12490{
12491IkReal evalcond[10];
12492IkReal x1411=IKcos(j5);
12493IkReal x1412=IKsin(j5);
12494IkReal x1413=((1.0)*gconst16);
12495IkReal x1414=((1.0000000008)*gconst15);
12496IkReal x1415=((1.0000000008)*gconst16);
12497IkReal x1416=(gconst15*x1411);
12498IkReal x1417=(new_r00*x1411);
12499IkReal x1418=((1.0000000008)*x1412);
12500IkReal x1419=(new_r01*x1411);
12501IkReal x1420=((1.0)*x1412);
12502evalcond[0]=(((new_r00*x1412))+gconst15+((new_r10*x1411)));
12503evalcond[1]=(((new_r01*x1412))+(((-1.0)*x1413))+((new_r11*x1411)));
12504evalcond[2]=((((-1.0)*x1411*x1415))+((gconst15*x1412))+new_r00);
12505evalcond[3]=(((x1412*x1415))+x1416+new_r10);
12506evalcond[4]=((((-1.0)*x1412*x1413))+(((-1.0)*x1411*x1414))+new_r01);
12507evalcond[5]=(((x1412*x1414))+(((-1.0)*x1411*x1413))+new_r11);
12508evalcond[6]=((((-1.0)*x1415))+(((-1.0)*new_r10*x1420))+x1417);
12509evalcond[7]=((((-1.0)*x1414))+(((-1.0)*new_r11*x1420))+x1419);
12510evalcond[8]=((((-1.0)*new_r10*x1418))+(((-1.0)*x1413))+(((1.0000000008)*x1417)));
12511evalcond[9]=((((-1.0)*new_r11*x1418))+(((1.0000000008)*x1419))+(((-1.0)*gconst15)));
12512if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12513{
12514continue;
12515}
12516}
12517
12518{
12519std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12520vinfos[0].jointtype = 1;
12521vinfos[0].foffset = j0;
12522vinfos[0].indices[0] = _ij0[0];
12523vinfos[0].indices[1] = _ij0[1];
12524vinfos[0].maxsolutions = _nj0;
12525vinfos[1].jointtype = 1;
12526vinfos[1].foffset = j1;
12527vinfos[1].indices[0] = _ij1[0];
12528vinfos[1].indices[1] = _ij1[1];
12529vinfos[1].maxsolutions = _nj1;
12530vinfos[2].jointtype = 1;
12531vinfos[2].foffset = j2;
12532vinfos[2].indices[0] = _ij2[0];
12533vinfos[2].indices[1] = _ij2[1];
12534vinfos[2].maxsolutions = _nj2;
12535vinfos[3].jointtype = 1;
12536vinfos[3].foffset = j3;
12537vinfos[3].indices[0] = _ij3[0];
12538vinfos[3].indices[1] = _ij3[1];
12539vinfos[3].maxsolutions = _nj3;
12540vinfos[4].jointtype = 1;
12541vinfos[4].foffset = j4;
12542vinfos[4].indices[0] = _ij4[0];
12543vinfos[4].indices[1] = _ij4[1];
12544vinfos[4].maxsolutions = _nj4;
12545vinfos[5].jointtype = 1;
12546vinfos[5].foffset = j5;
12547vinfos[5].indices[0] = _ij5[0];
12548vinfos[5].indices[1] = _ij5[1];
12549vinfos[5].maxsolutions = _nj5;
12550std::vector<int> vfree(0);
12551solutions.AddSolution(vinfos,vfree);
12552}
12553}
12554}
12555
12556}
12557
12558}
12559
12560}
12561} while(0);
12562if( bgotonextstatement )
12563{
12564bool bgotonextstatement = true;
12565do
12566{
12567IkReal x1422 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
12568if(IKabs(x1422)==0){
12569continue;
12570}
12571IkReal x1421=pow(x1422,-0.5);
12572CheckValue<IkReal> x1423 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12573if(!x1423.valid){
12574continue;
12575}
12576IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1423.value))));
12577IkReal gconst18=((-1.0000000008)*new_r10*x1421);
12578IkReal gconst19=((-1.0)*new_r00*x1421);
12579CheckValue<IkReal> x1424 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12580if(!x1424.valid){
12581continue;
12582}
12583evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1424.value)+j3)))), 6.28318530717959)));
12584if( IKabs(evalcond[0]) < 0.0000050000000000 )
12585{
12586bgotonextstatement=false;
12587{
12588IkReal j5eval[2];
12589IkReal x1425=x1421;
12590sj4=4.0e-5;
12591cj4=1.0;
12592j4=4.0e-5;
12593sj3=gconst18;
12594cj3=gconst19;
12595CheckValue<IkReal> x1426 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12596if(!x1426.valid){
12597continue;
12598}
12599j3=((3.14159265)+(((-1.0)*(x1426.value))));
12600CheckValue<IkReal> x1427 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12601if(!x1427.valid){
12602continue;
12603}
12604IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1427.value))));
12605IkReal gconst18=((-1.0000000008)*new_r10*x1425);
12606IkReal gconst19=((-1.0)*new_r00*x1425);
12607IkReal x1428=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
12608j5eval[0]=x1428;
12609j5eval[1]=IKsign(x1428);
12610if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
12611{
12612{
12613IkReal j5eval[1];
12614IkReal x1429=x1421;
12615sj4=4.0e-5;
12616cj4=1.0;
12617j4=4.0e-5;
12618sj3=gconst18;
12619cj3=gconst19;
12620CheckValue<IkReal> x1430 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12621if(!x1430.valid){
12622continue;
12623}
12624j3=((3.14159265)+(((-1.0)*(x1430.value))));
12625CheckValue<IkReal> x1431 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12626if(!x1431.valid){
12627continue;
12628}
12629IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1431.value))));
12630IkReal gconst18=((-1.0000000008)*new_r10*x1429);
12631IkReal gconst19=((-1.0)*new_r00*x1429);
12632j5eval[0]=new_r00;
12633if( IKabs(j5eval[0]) < 0.0000010000000000 )
12634{
12635{
12636IkReal j5eval[2];
12637IkReal x1432=x1421;
12638sj4=4.0e-5;
12639cj4=1.0;
12640j4=4.0e-5;
12641sj3=gconst18;
12642cj3=gconst19;
12643CheckValue<IkReal> x1433 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12644if(!x1433.valid){
12645continue;
12646}
12647j3=((3.14159265)+(((-1.0)*(x1433.value))));
12648CheckValue<IkReal> x1434 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12649if(!x1434.valid){
12650continue;
12651}
12652IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1434.value))));
12653IkReal gconst18=((-1.0000000008)*new_r10*x1432);
12654IkReal gconst19=((-1.0)*new_r00*x1432);
12655j5eval[0]=new_r00;
12656IkReal x1435 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
12657if(IKabs(x1435)==0){
12658continue;
12659}
12660j5eval[1]=((1.60000013238459e-9)*new_r00*new_r10*(pow(x1435,-0.5)));
12661if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
12662{
12663{
12664IkReal evalcond[1];
12665bool bgotonextstatement = true;
12666do
12667{
12668evalcond[0]=IKabs(new_r00);
12669if( IKabs(evalcond[0]) < 0.0000050000000000 )
12670{
12671bgotonextstatement=false;
12672{
12673IkReal j5eval[1];
12674sj4=4.0e-5;
12675cj4=1.0;
12676j4=4.0e-5;
12677sj3=gconst18;
12678cj3=gconst19;
12679CheckValue<IkReal> x1436 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
12680if(!x1436.valid){
12681continue;
12682}
12683j3=((3.14159265)+(((-1.0)*(x1436.value))));
12684new_r00=0;
12685CheckValue<IkReal> x1437 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
12686if(!x1437.valid){
12687continue;
12688}
12689IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1437.value))));
12690IkReal x1438 = new_r10*new_r10;
12691if(IKabs(x1438)==0){
12692continue;
12693}
12694IkReal gconst18=((-1.0)*new_r10*(pow(x1438,-0.5)));
12695IkReal gconst19=0;
12696j5eval[0]=new_r10;
12697if( IKabs(j5eval[0]) < 0.0000010000000000 )
12698{
12699{
12700IkReal j5array[1], cj5array[1], sj5array[1];
12701bool j5valid[1]={false};
12702_nj5 = 1;
12703CheckValue<IkReal> x1440=IKPowWithIntegerCheck(gconst18,-1);
12704if(!x1440.valid){
12705continue;
12706}
12707IkReal x1439=x1440.value;
12708if( IKabs(((-0.9999999992)*new_r11*x1439)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x1439)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*x1439))+IKsqr(((-1.0)*new_r10*x1439))-1) <= IKFAST_SINCOS_THRESH )
12709 continue;
12710j5array[0]=IKatan2(((-0.9999999992)*new_r11*x1439), ((-1.0)*new_r10*x1439));
12711sj5array[0]=IKsin(j5array[0]);
12712cj5array[0]=IKcos(j5array[0]);
12713if( j5array[0] > IKPI )
12714{
12715 j5array[0]-=IK2PI;
12716}
12717else if( j5array[0] < -IKPI )
12718{ j5array[0]+=IK2PI;
12719}
12720j5valid[0] = true;
12721for(int ij5 = 0; ij5 < 1; ++ij5)
12722{
12723if( !j5valid[ij5] )
12724{
12725 continue;
12726}
12727_ij5[0] = ij5; _ij5[1] = -1;
12728for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12729{
12730if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12731{
12732 j5valid[iij5]=false; _ij5[1] = iij5; break;
12733}
12734}
12735j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12736{
12737IkReal evalcond[10];
12738IkReal x1441=IKsin(j5);
12739IkReal x1442=IKcos(j5);
12740IkReal x1443=((1.0000000008)*gconst18);
12741IkReal x1444=(gconst18*x1441);
12742IkReal x1445=(new_r01*x1442);
12743IkReal x1446=(new_r11*x1441);
12744IkReal x1447=(new_r10*x1441);
12745evalcond[0]=x1444;
12746evalcond[1]=((-1.0)*x1447);
12747evalcond[2]=(((new_r10*x1442))+gconst18);
12748evalcond[3]=(new_r10+((gconst18*x1442)));
12749evalcond[4]=((-1.0000000008)*x1447);
12750evalcond[5]=(((new_r11*x1442))+((new_r01*x1441)));
12751evalcond[6]=(new_r01+(((-1.0)*x1442*x1443)));
12752evalcond[7]=(((x1441*x1443))+new_r11);
12753evalcond[8]=((((-1.0)*x1446))+x1445+(((-1.0)*x1443)));
12754evalcond[9]=((((1.0000000008)*x1445))+(((-1.0)*gconst18))+(((-1.0000000008)*x1446)));
12755if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12756{
12757continue;
12758}
12759}
12760
12761{
12762std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12763vinfos[0].jointtype = 1;
12764vinfos[0].foffset = j0;
12765vinfos[0].indices[0] = _ij0[0];
12766vinfos[0].indices[1] = _ij0[1];
12767vinfos[0].maxsolutions = _nj0;
12768vinfos[1].jointtype = 1;
12769vinfos[1].foffset = j1;
12770vinfos[1].indices[0] = _ij1[0];
12771vinfos[1].indices[1] = _ij1[1];
12772vinfos[1].maxsolutions = _nj1;
12773vinfos[2].jointtype = 1;
12774vinfos[2].foffset = j2;
12775vinfos[2].indices[0] = _ij2[0];
12776vinfos[2].indices[1] = _ij2[1];
12777vinfos[2].maxsolutions = _nj2;
12778vinfos[3].jointtype = 1;
12779vinfos[3].foffset = j3;
12780vinfos[3].indices[0] = _ij3[0];
12781vinfos[3].indices[1] = _ij3[1];
12782vinfos[3].maxsolutions = _nj3;
12783vinfos[4].jointtype = 1;
12784vinfos[4].foffset = j4;
12785vinfos[4].indices[0] = _ij4[0];
12786vinfos[4].indices[1] = _ij4[1];
12787vinfos[4].maxsolutions = _nj4;
12788vinfos[5].jointtype = 1;
12789vinfos[5].foffset = j5;
12790vinfos[5].indices[0] = _ij5[0];
12791vinfos[5].indices[1] = _ij5[1];
12792vinfos[5].maxsolutions = _nj5;
12793std::vector<int> vfree(0);
12794solutions.AddSolution(vinfos,vfree);
12795}
12796}
12797}
12798
12799} else
12800{
12801{
12802IkReal j5array[1], cj5array[1], sj5array[1];
12803bool j5valid[1]={false};
12804_nj5 = 1;
12805CheckValue<IkReal> x1448=IKPowWithIntegerCheck(gconst18,-1);
12806if(!x1448.valid){
12807continue;
12808}
12809CheckValue<IkReal> x1449=IKPowWithIntegerCheck(new_r10,-1);
12810if(!x1449.valid){
12811continue;
12812}
12813if( IKabs(((-0.9999999992)*new_r11*(x1448.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst18*(x1449.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.9999999992)*new_r11*(x1448.value)))+IKsqr(((-1.0)*gconst18*(x1449.value)))-1) <= IKFAST_SINCOS_THRESH )
12814 continue;
12815j5array[0]=IKatan2(((-0.9999999992)*new_r11*(x1448.value)), ((-1.0)*gconst18*(x1449.value)));
12816sj5array[0]=IKsin(j5array[0]);
12817cj5array[0]=IKcos(j5array[0]);
12818if( j5array[0] > IKPI )
12819{
12820 j5array[0]-=IK2PI;
12821}
12822else if( j5array[0] < -IKPI )
12823{ j5array[0]+=IK2PI;
12824}
12825j5valid[0] = true;
12826for(int ij5 = 0; ij5 < 1; ++ij5)
12827{
12828if( !j5valid[ij5] )
12829{
12830 continue;
12831}
12832_ij5[0] = ij5; _ij5[1] = -1;
12833for(int iij5 = ij5+1; iij5 < 1; ++iij5)
12834{
12835if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
12836{
12837 j5valid[iij5]=false; _ij5[1] = iij5; break;
12838}
12839}
12840j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
12841{
12842IkReal evalcond[10];
12843IkReal x1450=IKsin(j5);
12844IkReal x1451=IKcos(j5);
12845IkReal x1452=((1.0000000008)*gconst18);
12846IkReal x1453=(gconst18*x1450);
12847IkReal x1454=(new_r01*x1451);
12848IkReal x1455=(new_r11*x1450);
12849IkReal x1456=(new_r10*x1450);
12850evalcond[0]=x1453;
12851evalcond[1]=((-1.0)*x1456);
12852evalcond[2]=(gconst18+((new_r10*x1451)));
12853evalcond[3]=(((gconst18*x1451))+new_r10);
12854evalcond[4]=((-1.0000000008)*x1456);
12855evalcond[5]=(((new_r01*x1450))+((new_r11*x1451)));
12856evalcond[6]=(new_r01+(((-1.0)*x1451*x1452)));
12857evalcond[7]=(((x1450*x1452))+new_r11);
12858evalcond[8]=((((-1.0)*x1452))+(((-1.0)*x1455))+x1454);
12859evalcond[9]=((((1.0000000008)*x1454))+(((-1.0)*gconst18))+(((-1.0000000008)*x1455)));
12860if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
12861{
12862continue;
12863}
12864}
12865
12866{
12867std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12868vinfos[0].jointtype = 1;
12869vinfos[0].foffset = j0;
12870vinfos[0].indices[0] = _ij0[0];
12871vinfos[0].indices[1] = _ij0[1];
12872vinfos[0].maxsolutions = _nj0;
12873vinfos[1].jointtype = 1;
12874vinfos[1].foffset = j1;
12875vinfos[1].indices[0] = _ij1[0];
12876vinfos[1].indices[1] = _ij1[1];
12877vinfos[1].maxsolutions = _nj1;
12878vinfos[2].jointtype = 1;
12879vinfos[2].foffset = j2;
12880vinfos[2].indices[0] = _ij2[0];
12881vinfos[2].indices[1] = _ij2[1];
12882vinfos[2].maxsolutions = _nj2;
12883vinfos[3].jointtype = 1;
12884vinfos[3].foffset = j3;
12885vinfos[3].indices[0] = _ij3[0];
12886vinfos[3].indices[1] = _ij3[1];
12887vinfos[3].maxsolutions = _nj3;
12888vinfos[4].jointtype = 1;
12889vinfos[4].foffset = j4;
12890vinfos[4].indices[0] = _ij4[0];
12891vinfos[4].indices[1] = _ij4[1];
12892vinfos[4].maxsolutions = _nj4;
12893vinfos[5].jointtype = 1;
12894vinfos[5].foffset = j5;
12895vinfos[5].indices[0] = _ij5[0];
12896vinfos[5].indices[1] = _ij5[1];
12897vinfos[5].maxsolutions = _nj5;
12898std::vector<int> vfree(0);
12899solutions.AddSolution(vinfos,vfree);
12900}
12901}
12902}
12903
12904}
12905
12906}
12907
12908}
12909} while(0);
12910if( bgotonextstatement )
12911{
12912bool bgotonextstatement = true;
12913do
12914{
12915evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
12916if( IKabs(evalcond[0]) < 0.0000050000000000 )
12917{
12918bgotonextstatement=false;
12919{
12920IkReal j5eval[3];
12921IkReal x1458 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
12922if(IKabs(x1458)==0){
12923continue;
12924}
12925IkReal x1457=pow(x1458,-0.5);
12926sj4=4.0e-5;
12927cj4=1.0;
12928j4=4.0e-5;
12929sj3=gconst18;
12930cj3=gconst19;
12931CheckValue<IkReal> x1459 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12932if(!x1459.valid){
12933continue;
12934}
12935j3=((3.14159265)+(((-1.0)*(x1459.value))));
12936new_r11=0;
12937new_r01=0;
12938new_r22=0;
12939new_r20=0;
12940CheckValue<IkReal> x1460 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12941if(!x1460.valid){
12942continue;
12943}
12944IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1460.value))));
12945IkReal gconst18=((-1.0000000008)*new_r10*x1457);
12946IkReal gconst19=((-1.0)*new_r00*x1457);
12947IkReal x1461=new_r10*new_r10;
12948CheckValue<IkReal> x1465=IKPowWithIntegerCheck(((625000000.0)+(((1.0)*x1461))),-1);
12949if(!x1465.valid){
12950continue;
12951}
12952IkReal x1462=x1465.value;
12953if((((625000000.0)+x1461)) < -0.00001)
12954continue;
12955IkReal x1463=IKsqrt(((625000000.0)+x1461));
12956IkReal x1464=(x1462*x1463);
12957j5eval[0]=-1.0;
12958j5eval[1]=-1.0;
12959IkReal x1466 = ((1.0)+(((1.6e-9)*x1461)));
12960if(IKabs(x1466)==0){
12961continue;
12962}
12963j5eval[2]=((IKabs(((50000.00004)*new_r00*new_r10*(pow(x1466,-0.5)))))+(IKabs(((((625000000.5)*x1464))+(((-1250000001.0)*x1461*x1464))))));
12964if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
12965{
12966{
12967IkReal j5eval[1];
12968IkReal x1468 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
12969if(IKabs(x1468)==0){
12970continue;
12971}
12972IkReal x1467=pow(x1468,-0.5);
12973sj4=4.0e-5;
12974cj4=1.0;
12975j4=4.0e-5;
12976sj3=gconst18;
12977cj3=gconst19;
12978CheckValue<IkReal> x1469 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12979if(!x1469.valid){
12980continue;
12981}
12982j3=((3.14159265)+(((-1.0)*(x1469.value))));
12983new_r11=0;
12984new_r01=0;
12985new_r22=0;
12986new_r20=0;
12987CheckValue<IkReal> x1470 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
12988if(!x1470.valid){
12989continue;
12990}
12991IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1470.value))));
12992IkReal gconst18=((-1.0000000008)*new_r10*x1467);
12993IkReal gconst19=((-1.0)*new_r00*x1467);
12994IkReal x1471=new_r10*new_r10;
12995CheckValue<IkReal> x1473=IKPowWithIntegerCheck(((1.0)+(((1.6e-9)*x1471))),-1);
12996if(!x1473.valid){
12997continue;
12998}
12999IkReal x1472=x1473.value;
13000IkReal x1474=((1.0)+(((-1.0)*x1471)));
13001j5eval[0]=IKsign(((((625000002.0)*x1472*(x1471*x1471)))+(((-625000000.0)*x1472*(x1474*x1474)))));
13002if( IKabs(j5eval[0]) < 0.0000010000000000 )
13003{
13004{
13005IkReal j5eval[2];
13006IkReal x1476 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
13007if(IKabs(x1476)==0){
13008continue;
13009}
13010IkReal x1475=pow(x1476,-0.5);
13011sj4=4.0e-5;
13012cj4=1.0;
13013j4=4.0e-5;
13014sj3=gconst18;
13015cj3=gconst19;
13016CheckValue<IkReal> x1477 = IKatan2WithCheck(IkReal(((-1.0)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
13017if(!x1477.valid){
13018continue;
13019}
13020j3=((3.14159265)+(((-1.0)*(x1477.value))));
13021new_r11=0;
13022new_r01=0;
13023new_r22=0;
13024new_r20=0;
13025CheckValue<IkReal> x1478 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
13026if(!x1478.valid){
13027continue;
13028}
13029IkReal gconst17=((3.14159265358979)+(((-1.0)*(x1478.value))));
13030IkReal gconst18=((-1.0000000008)*new_r10*x1475);
13031IkReal gconst19=((-1.0)*new_r00*x1475);
13032IkReal x1479=new_r10*new_r10;
13033IkReal x1480=((1.0)+(((1.6e-9)*x1479)));
13034CheckValue<IkReal> x1481=IKPowWithIntegerCheck(x1480,-1);
13035if(!x1481.valid){
13036continue;
13037}
13038j5eval[0]=((-3.20000004272458e-9)*x1479*(x1481.value)*(((1.0)+(((-1.0)*x1479)))));
13039IkReal x1482 = x1480;
13040if(IKabs(x1482)==0){
13041continue;
13042}
13043j5eval[1]=((1.60000013238459e-9)*new_r00*new_r10*(pow(x1482,-0.5)));
13044if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
13045{
13046continue; // 3 cases reached
13047
13048} else
13049{
13050{
13051IkReal j5array[1], cj5array[1], sj5array[1];
13052bool j5valid[1]={false};
13053_nj5 = 1;
13054IkReal x1483=gconst18*gconst18;
13055IkReal x1484=(gconst19*new_r10);
13056CheckValue<IkReal> x1485=IKPowWithIntegerCheck(((((-625000001.0)*x1483*(new_r00*new_r00)))+(((625000000.0)*(x1484*x1484)))),-1);
13057if(!x1485.valid){
13058continue;
13059}
13060CheckValue<IkReal> x1486=IKPowWithIntegerCheck(((((-25000.00002)*gconst18*new_r00))+(((25000.0)*x1484))),-1);
13061if(!x1486.valid){
13062continue;
13063}
13064if( IKabs(((x1485.value)*(((((625000000.5)*x1483*x1484))+(((625000001.0)*new_r00*(gconst18*gconst18*gconst18))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-25000.0)*gconst18*gconst19*(x1486.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1485.value)*(((((625000000.5)*x1483*x1484))+(((625000001.0)*new_r00*(gconst18*gconst18*gconst18)))))))+IKsqr(((-25000.0)*gconst18*gconst19*(x1486.value)))-1) <= IKFAST_SINCOS_THRESH )
13065 continue;
13066j5array[0]=IKatan2(((x1485.value)*(((((625000000.5)*x1483*x1484))+(((625000001.0)*new_r00*(gconst18*gconst18*gconst18)))))), ((-25000.0)*gconst18*gconst19*(x1486.value)));
13067sj5array[0]=IKsin(j5array[0]);
13068cj5array[0]=IKcos(j5array[0]);
13069if( j5array[0] > IKPI )
13070{
13071 j5array[0]-=IK2PI;
13072}
13073else if( j5array[0] < -IKPI )
13074{ j5array[0]+=IK2PI;
13075}
13076j5valid[0] = true;
13077for(int ij5 = 0; ij5 < 1; ++ij5)
13078{
13079if( !j5valid[ij5] )
13080{
13081 continue;
13082}
13083_ij5[0] = ij5; _ij5[1] = -1;
13084for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13085{
13086if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13087{
13088 j5valid[iij5]=false; _ij5[1] = iij5; break;
13089}
13090}
13091j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13092{
13093IkReal evalcond[7];
13094IkReal x1487=IKsin(j5);
13095IkReal x1488=IKcos(j5);
13096IkReal x1489=((1.0000000008)*gconst19);
13097IkReal x1490=((1.0)*gconst19);
13098IkReal x1491=(gconst18*x1487);
13099IkReal x1492=(new_r00*x1488);
13100IkReal x1493=(gconst18*x1488);
13101IkReal x1494=(new_r10*x1487);
13102evalcond[0]=(gconst18+((new_r00*x1487))+((new_r10*x1488)));
13103evalcond[1]=(x1491+(((-1.0)*x1488*x1489))+new_r00);
13104evalcond[2]=(((x1487*x1489))+x1493+new_r10);
13105evalcond[3]=((((-1.0000000008)*x1493))+(((-1.0)*x1487*x1490)));
13106evalcond[4]=((((1.0000000008)*x1491))+(((-1.0)*x1488*x1490)));
13107evalcond[5]=((((-1.0)*x1489))+(((-1.0)*x1494))+x1492);
13108evalcond[6]=((((-1.0000000008)*x1494))+(((-1.0)*x1490))+(((1.0000000008)*x1492)));
13109if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
13110{
13111continue;
13112}
13113}
13114
13115{
13116std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13117vinfos[0].jointtype = 1;
13118vinfos[0].foffset = j0;
13119vinfos[0].indices[0] = _ij0[0];
13120vinfos[0].indices[1] = _ij0[1];
13121vinfos[0].maxsolutions = _nj0;
13122vinfos[1].jointtype = 1;
13123vinfos[1].foffset = j1;
13124vinfos[1].indices[0] = _ij1[0];
13125vinfos[1].indices[1] = _ij1[1];
13126vinfos[1].maxsolutions = _nj1;
13127vinfos[2].jointtype = 1;
13128vinfos[2].foffset = j2;
13129vinfos[2].indices[0] = _ij2[0];
13130vinfos[2].indices[1] = _ij2[1];
13131vinfos[2].maxsolutions = _nj2;
13132vinfos[3].jointtype = 1;
13133vinfos[3].foffset = j3;
13134vinfos[3].indices[0] = _ij3[0];
13135vinfos[3].indices[1] = _ij3[1];
13136vinfos[3].maxsolutions = _nj3;
13137vinfos[4].jointtype = 1;
13138vinfos[4].foffset = j4;
13139vinfos[4].indices[0] = _ij4[0];
13140vinfos[4].indices[1] = _ij4[1];
13141vinfos[4].maxsolutions = _nj4;
13142vinfos[5].jointtype = 1;
13143vinfos[5].foffset = j5;
13144vinfos[5].indices[0] = _ij5[0];
13145vinfos[5].indices[1] = _ij5[1];
13146vinfos[5].maxsolutions = _nj5;
13147std::vector<int> vfree(0);
13148solutions.AddSolution(vinfos,vfree);
13149}
13150}
13151}
13152
13153}
13154
13155}
13156
13157} else
13158{
13159{
13160IkReal j5array[1], cj5array[1], sj5array[1];
13161bool j5valid[1]={false};
13162_nj5 = 1;
13163IkReal x1495=gconst18*gconst18;
13164IkReal x1496=gconst19*gconst19;
13165IkReal x1497=((625000000.0)*x1496);
13166IkReal x1498=((625000000.5)*gconst19*x1495);
13167CheckValue<IkReal> x1499=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x1495*(new_r10*new_r10)))+(((-1.0)*x1497*(new_r00*new_r00))))),-1);
13168if(!x1499.valid){
13169continue;
13170}
13171CheckValue<IkReal> x1500 = IKatan2WithCheck(IkReal(((((-1.0)*new_r10*x1498))+((gconst18*new_r00*x1497)))),IkReal(((((-625000001.0)*new_r10*(gconst18*gconst18*gconst18)))+((new_r00*x1498)))),IKFAST_ATAN2_MAGTHRESH);
13172if(!x1500.valid){
13173continue;
13174}
13175j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1499.value)))+(x1500.value));
13176sj5array[0]=IKsin(j5array[0]);
13177cj5array[0]=IKcos(j5array[0]);
13178if( j5array[0] > IKPI )
13179{
13180 j5array[0]-=IK2PI;
13181}
13182else if( j5array[0] < -IKPI )
13183{ j5array[0]+=IK2PI;
13184}
13185j5valid[0] = true;
13186for(int ij5 = 0; ij5 < 1; ++ij5)
13187{
13188if( !j5valid[ij5] )
13189{
13190 continue;
13191}
13192_ij5[0] = ij5; _ij5[1] = -1;
13193for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13194{
13195if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13196{
13197 j5valid[iij5]=false; _ij5[1] = iij5; break;
13198}
13199}
13200j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13201{
13202IkReal evalcond[7];
13203IkReal x1501=IKsin(j5);
13204IkReal x1502=IKcos(j5);
13205IkReal x1503=((1.0000000008)*gconst19);
13206IkReal x1504=((1.0)*gconst19);
13207IkReal x1505=(gconst18*x1501);
13208IkReal x1506=(new_r00*x1502);
13209IkReal x1507=(gconst18*x1502);
13210IkReal x1508=(new_r10*x1501);
13211evalcond[0]=(((new_r10*x1502))+gconst18+((new_r00*x1501)));
13212evalcond[1]=(x1505+new_r00+(((-1.0)*x1502*x1503)));
13213evalcond[2]=(((x1501*x1503))+x1507+new_r10);
13214evalcond[3]=((((-1.0)*x1501*x1504))+(((-1.0000000008)*x1507)));
13215evalcond[4]=((((-1.0)*x1502*x1504))+(((1.0000000008)*x1505)));
13216evalcond[5]=((((-1.0)*x1503))+(((-1.0)*x1508))+x1506);
13217evalcond[6]=((((-1.0)*x1504))+(((-1.0000000008)*x1508))+(((1.0000000008)*x1506)));
13218if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
13219{
13220continue;
13221}
13222}
13223
13224{
13225std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13226vinfos[0].jointtype = 1;
13227vinfos[0].foffset = j0;
13228vinfos[0].indices[0] = _ij0[0];
13229vinfos[0].indices[1] = _ij0[1];
13230vinfos[0].maxsolutions = _nj0;
13231vinfos[1].jointtype = 1;
13232vinfos[1].foffset = j1;
13233vinfos[1].indices[0] = _ij1[0];
13234vinfos[1].indices[1] = _ij1[1];
13235vinfos[1].maxsolutions = _nj1;
13236vinfos[2].jointtype = 1;
13237vinfos[2].foffset = j2;
13238vinfos[2].indices[0] = _ij2[0];
13239vinfos[2].indices[1] = _ij2[1];
13240vinfos[2].maxsolutions = _nj2;
13241vinfos[3].jointtype = 1;
13242vinfos[3].foffset = j3;
13243vinfos[3].indices[0] = _ij3[0];
13244vinfos[3].indices[1] = _ij3[1];
13245vinfos[3].maxsolutions = _nj3;
13246vinfos[4].jointtype = 1;
13247vinfos[4].foffset = j4;
13248vinfos[4].indices[0] = _ij4[0];
13249vinfos[4].indices[1] = _ij4[1];
13250vinfos[4].maxsolutions = _nj4;
13251vinfos[5].jointtype = 1;
13252vinfos[5].foffset = j5;
13253vinfos[5].indices[0] = _ij5[0];
13254vinfos[5].indices[1] = _ij5[1];
13255vinfos[5].maxsolutions = _nj5;
13256std::vector<int> vfree(0);
13257solutions.AddSolution(vinfos,vfree);
13258}
13259}
13260}
13261
13262}
13263
13264}
13265
13266} else
13267{
13268{
13269IkReal j5array[1], cj5array[1], sj5array[1];
13270bool j5valid[1]={false};
13271_nj5 = 1;
13272IkReal x1509=((25000.0)*gconst18);
13273IkReal x1510=((25000.00002)*gconst19);
13274CheckValue<IkReal> x1511=IKPowWithIntegerCheck(IKsign(((((-25000.0)*(new_r10*new_r10)))+(((-25000.0)*(new_r00*new_r00))))),-1);
13275if(!x1511.valid){
13276continue;
13277}
13278CheckValue<IkReal> x1512 = IKatan2WithCheck(IkReal((((new_r10*x1510))+((new_r00*x1509)))),IkReal((((new_r10*x1509))+(((-1.0)*new_r00*x1510)))),IKFAST_ATAN2_MAGTHRESH);
13279if(!x1512.valid){
13280continue;
13281}
13282j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1511.value)))+(x1512.value));
13283sj5array[0]=IKsin(j5array[0]);
13284cj5array[0]=IKcos(j5array[0]);
13285if( j5array[0] > IKPI )
13286{
13287 j5array[0]-=IK2PI;
13288}
13289else if( j5array[0] < -IKPI )
13290{ j5array[0]+=IK2PI;
13291}
13292j5valid[0] = true;
13293for(int ij5 = 0; ij5 < 1; ++ij5)
13294{
13295if( !j5valid[ij5] )
13296{
13297 continue;
13298}
13299_ij5[0] = ij5; _ij5[1] = -1;
13300for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13301{
13302if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13303{
13304 j5valid[iij5]=false; _ij5[1] = iij5; break;
13305}
13306}
13307j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13308{
13309IkReal evalcond[7];
13310IkReal x1513=IKsin(j5);
13311IkReal x1514=IKcos(j5);
13312IkReal x1515=((1.0000000008)*gconst19);
13313IkReal x1516=((1.0)*gconst19);
13314IkReal x1517=(gconst18*x1513);
13315IkReal x1518=(new_r00*x1514);
13316IkReal x1519=(gconst18*x1514);
13317IkReal x1520=(new_r10*x1513);
13318evalcond[0]=(((new_r10*x1514))+gconst18+((new_r00*x1513)));
13319evalcond[1]=(x1517+(((-1.0)*x1514*x1515))+new_r00);
13320evalcond[2]=(((x1513*x1515))+x1519+new_r10);
13321evalcond[3]=((((-1.0)*x1513*x1516))+(((-1.0000000008)*x1519)));
13322evalcond[4]=((((-1.0)*x1514*x1516))+(((1.0000000008)*x1517)));
13323evalcond[5]=((((-1.0)*x1515))+x1518+(((-1.0)*x1520)));
13324evalcond[6]=((((-1.0)*x1516))+(((-1.0000000008)*x1520))+(((1.0000000008)*x1518)));
13325if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
13326{
13327continue;
13328}
13329}
13330
13331{
13332std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13333vinfos[0].jointtype = 1;
13334vinfos[0].foffset = j0;
13335vinfos[0].indices[0] = _ij0[0];
13336vinfos[0].indices[1] = _ij0[1];
13337vinfos[0].maxsolutions = _nj0;
13338vinfos[1].jointtype = 1;
13339vinfos[1].foffset = j1;
13340vinfos[1].indices[0] = _ij1[0];
13341vinfos[1].indices[1] = _ij1[1];
13342vinfos[1].maxsolutions = _nj1;
13343vinfos[2].jointtype = 1;
13344vinfos[2].foffset = j2;
13345vinfos[2].indices[0] = _ij2[0];
13346vinfos[2].indices[1] = _ij2[1];
13347vinfos[2].maxsolutions = _nj2;
13348vinfos[3].jointtype = 1;
13349vinfos[3].foffset = j3;
13350vinfos[3].indices[0] = _ij3[0];
13351vinfos[3].indices[1] = _ij3[1];
13352vinfos[3].maxsolutions = _nj3;
13353vinfos[4].jointtype = 1;
13354vinfos[4].foffset = j4;
13355vinfos[4].indices[0] = _ij4[0];
13356vinfos[4].indices[1] = _ij4[1];
13357vinfos[4].maxsolutions = _nj4;
13358vinfos[5].jointtype = 1;
13359vinfos[5].foffset = j5;
13360vinfos[5].indices[0] = _ij5[0];
13361vinfos[5].indices[1] = _ij5[1];
13362vinfos[5].maxsolutions = _nj5;
13363std::vector<int> vfree(0);
13364solutions.AddSolution(vinfos,vfree);
13365}
13366}
13367}
13368
13369}
13370
13371}
13372
13373}
13374} while(0);
13375if( bgotonextstatement )
13376{
13377bool bgotonextstatement = true;
13378do
13379{
13380evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
13381if( IKabs(evalcond[0]) < 0.0000050000000000 )
13382{
13383bgotonextstatement=false;
13384{
13385IkReal j5array[1], cj5array[1], sj5array[1];
13386bool j5valid[1]={false};
13387_nj5 = 1;
13388CheckValue<IkReal> x1522=IKPowWithIntegerCheck(gconst19,-1);
13389if(!x1522.valid){
13390continue;
13391}
13392IkReal x1521=x1522.value;
13393if( IKabs((new_r01*x1521)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((0.9999999992)*new_r00*x1521)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x1521))+IKsqr(((0.9999999992)*new_r00*x1521))-1) <= IKFAST_SINCOS_THRESH )
13394 continue;
13395j5array[0]=IKatan2((new_r01*x1521), ((0.9999999992)*new_r00*x1521));
13396sj5array[0]=IKsin(j5array[0]);
13397cj5array[0]=IKcos(j5array[0]);
13398if( j5array[0] > IKPI )
13399{
13400 j5array[0]-=IK2PI;
13401}
13402else if( j5array[0] < -IKPI )
13403{ j5array[0]+=IK2PI;
13404}
13405j5valid[0] = true;
13406for(int ij5 = 0; ij5 < 1; ++ij5)
13407{
13408if( !j5valid[ij5] )
13409{
13410 continue;
13411}
13412_ij5[0] = ij5; _ij5[1] = -1;
13413for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13414{
13415if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13416{
13417 j5valid[iij5]=false; _ij5[1] = iij5; break;
13418}
13419}
13420j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13421{
13422IkReal evalcond[10];
13423IkReal x1523=IKcos(j5);
13424IkReal x1524=IKsin(j5);
13425IkReal x1525=((1.0)*gconst19);
13426IkReal x1526=((1.0000000008)*gconst19);
13427IkReal x1527=(new_r00*x1523);
13428IkReal x1528=(new_r01*x1523);
13429evalcond[0]=(new_r00*x1524);
13430evalcond[1]=x1528;
13431evalcond[2]=((-1.0)*gconst19*x1523);
13432evalcond[3]=((((-1.0)*x1524*x1525))+new_r01);
13433evalcond[4]=((((-1.0)*x1525))+((new_r01*x1524)));
13434evalcond[5]=(x1524*x1526);
13435evalcond[6]=((1.0000000008)*x1528);
13436evalcond[7]=((((-1.0)*x1523*x1526))+new_r00);
13437evalcond[8]=((((-1.0)*x1526))+x1527);
13438evalcond[9]=((((-1.0)*x1525))+(((1.0000000008)*x1527)));
13439if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
13440{
13441continue;
13442}
13443}
13444
13445{
13446std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13447vinfos[0].jointtype = 1;
13448vinfos[0].foffset = j0;
13449vinfos[0].indices[0] = _ij0[0];
13450vinfos[0].indices[1] = _ij0[1];
13451vinfos[0].maxsolutions = _nj0;
13452vinfos[1].jointtype = 1;
13453vinfos[1].foffset = j1;
13454vinfos[1].indices[0] = _ij1[0];
13455vinfos[1].indices[1] = _ij1[1];
13456vinfos[1].maxsolutions = _nj1;
13457vinfos[2].jointtype = 1;
13458vinfos[2].foffset = j2;
13459vinfos[2].indices[0] = _ij2[0];
13460vinfos[2].indices[1] = _ij2[1];
13461vinfos[2].maxsolutions = _nj2;
13462vinfos[3].jointtype = 1;
13463vinfos[3].foffset = j3;
13464vinfos[3].indices[0] = _ij3[0];
13465vinfos[3].indices[1] = _ij3[1];
13466vinfos[3].maxsolutions = _nj3;
13467vinfos[4].jointtype = 1;
13468vinfos[4].foffset = j4;
13469vinfos[4].indices[0] = _ij4[0];
13470vinfos[4].indices[1] = _ij4[1];
13471vinfos[4].maxsolutions = _nj4;
13472vinfos[5].jointtype = 1;
13473vinfos[5].foffset = j5;
13474vinfos[5].indices[0] = _ij5[0];
13475vinfos[5].indices[1] = _ij5[1];
13476vinfos[5].maxsolutions = _nj5;
13477std::vector<int> vfree(0);
13478solutions.AddSolution(vinfos,vfree);
13479}
13480}
13481}
13482
13483}
13484} while(0);
13485if( bgotonextstatement )
13486{
13487bool bgotonextstatement = true;
13488do
13489{
13490if( 1 )
13491{
13492bgotonextstatement=false;
13493continue; // branch miss [j5]
13494
13495}
13496} while(0);
13497if( bgotonextstatement )
13498{
13499}
13500}
13501}
13502}
13503}
13504
13505} else
13506{
13507{
13508IkReal j5array[1], cj5array[1], sj5array[1];
13509bool j5valid[1]={false};
13510_nj5 = 1;
13511CheckValue<IkReal> x1534=IKPowWithIntegerCheck(new_r00,-1);
13512if(!x1534.valid){
13513continue;
13514}
13515IkReal x1529=x1534.value;
13516IkReal x1530=((25000.0)*new_r10);
13517IkReal x1531=((25000.0)*gconst18*gconst19);
13518CheckValue<IkReal> x1535=IKPowWithIntegerCheck(((((-25000.00002)*gconst18*new_r00))+((gconst19*x1530))),-1);
13519if(!x1535.valid){
13520continue;
13521}
13522IkReal x1532=x1535.value;
13523IkReal x1533=(new_r10*x1532);
13524CheckValue<IkReal> x1536=IKPowWithIntegerCheck(((((-25000.00002)*gconst18*new_r00))+(((25000.0)*gconst19*new_r10))),-1);
13525if(!x1536.valid){
13526continue;
13527}
13528CheckValue<IkReal> x1537=IKPowWithIntegerCheck(((((-25000.00002)*gconst18*new_r00))+(((25000.0)*gconst19*new_r10))),-1);
13529if(!x1537.valid){
13530continue;
13531}
13532if( IKabs((((gconst18*gconst19*x1529*x1530*(x1536.value)))+(((-1.0)*gconst18*x1529))+((new_r01*x1530*(x1537.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1532*(((((-25000.0)*new_r00*new_r01))+(((-1.0)*x1531)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((gconst18*gconst19*x1529*x1530*(x1536.value)))+(((-1.0)*gconst18*x1529))+((new_r01*x1530*(x1537.value)))))+IKsqr((x1532*(((((-25000.0)*new_r00*new_r01))+(((-1.0)*x1531))))))-1) <= IKFAST_SINCOS_THRESH )
13533 continue;
13534j5array[0]=IKatan2((((gconst18*gconst19*x1529*x1530*(x1536.value)))+(((-1.0)*gconst18*x1529))+((new_r01*x1530*(x1537.value)))), (x1532*(((((-25000.0)*new_r00*new_r01))+(((-1.0)*x1531))))));
13535sj5array[0]=IKsin(j5array[0]);
13536cj5array[0]=IKcos(j5array[0]);
13537if( j5array[0] > IKPI )
13538{
13539 j5array[0]-=IK2PI;
13540}
13541else if( j5array[0] < -IKPI )
13542{ j5array[0]+=IK2PI;
13543}
13544j5valid[0] = true;
13545for(int ij5 = 0; ij5 < 1; ++ij5)
13546{
13547if( !j5valid[ij5] )
13548{
13549 continue;
13550}
13551_ij5[0] = ij5; _ij5[1] = -1;
13552for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13553{
13554if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13555{
13556 j5valid[iij5]=false; _ij5[1] = iij5; break;
13557}
13558}
13559j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13560{
13561IkReal evalcond[10];
13562IkReal x1538=IKcos(j5);
13563IkReal x1539=IKsin(j5);
13564IkReal x1540=((1.0)*gconst19);
13565IkReal x1541=((1.0000000008)*gconst19);
13566IkReal x1542=(new_r11*x1539);
13567IkReal x1543=(gconst18*x1538);
13568IkReal x1544=(new_r01*x1538);
13569IkReal x1545=(new_r00*x1538);
13570IkReal x1546=(gconst18*x1539);
13571IkReal x1547=(new_r10*x1539);
13572evalcond[0]=(gconst18+((new_r00*x1539))+((new_r10*x1538)));
13573evalcond[1]=(((new_r01*x1539))+((new_r11*x1538))+(((-1.0)*x1540)));
13574evalcond[2]=(x1546+new_r00+(((-1.0)*x1538*x1541)));
13575evalcond[3]=(((x1539*x1541))+x1543+new_r10);
13576evalcond[4]=((((-1.0)*x1539*x1540))+new_r01+(((-1.0000000008)*x1543)));
13577evalcond[5]=((((1.0000000008)*x1546))+new_r11+(((-1.0)*x1538*x1540)));
13578evalcond[6]=((((-1.0)*x1547))+x1545+(((-1.0)*x1541)));
13579evalcond[7]=((((-1.0)*x1542))+(((-1.0000000008)*gconst18))+x1544);
13580evalcond[8]=((((1.0000000008)*x1545))+(((-1.0)*x1540))+(((-1.0000000008)*x1547)));
13581evalcond[9]=((((1.0000000008)*x1544))+(((-1.0)*gconst18))+(((-1.0000000008)*x1542)));
13582if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
13583{
13584continue;
13585}
13586}
13587
13588{
13589std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13590vinfos[0].jointtype = 1;
13591vinfos[0].foffset = j0;
13592vinfos[0].indices[0] = _ij0[0];
13593vinfos[0].indices[1] = _ij0[1];
13594vinfos[0].maxsolutions = _nj0;
13595vinfos[1].jointtype = 1;
13596vinfos[1].foffset = j1;
13597vinfos[1].indices[0] = _ij1[0];
13598vinfos[1].indices[1] = _ij1[1];
13599vinfos[1].maxsolutions = _nj1;
13600vinfos[2].jointtype = 1;
13601vinfos[2].foffset = j2;
13602vinfos[2].indices[0] = _ij2[0];
13603vinfos[2].indices[1] = _ij2[1];
13604vinfos[2].maxsolutions = _nj2;
13605vinfos[3].jointtype = 1;
13606vinfos[3].foffset = j3;
13607vinfos[3].indices[0] = _ij3[0];
13608vinfos[3].indices[1] = _ij3[1];
13609vinfos[3].maxsolutions = _nj3;
13610vinfos[4].jointtype = 1;
13611vinfos[4].foffset = j4;
13612vinfos[4].indices[0] = _ij4[0];
13613vinfos[4].indices[1] = _ij4[1];
13614vinfos[4].maxsolutions = _nj4;
13615vinfos[5].jointtype = 1;
13616vinfos[5].foffset = j5;
13617vinfos[5].indices[0] = _ij5[0];
13618vinfos[5].indices[1] = _ij5[1];
13619vinfos[5].maxsolutions = _nj5;
13620std::vector<int> vfree(0);
13621solutions.AddSolution(vinfos,vfree);
13622}
13623}
13624}
13625
13626}
13627
13628}
13629
13630} else
13631{
13632{
13633IkReal j5array[1], cj5array[1], sj5array[1];
13634bool j5valid[1]={false};
13635_nj5 = 1;
13636CheckValue<IkReal> x1552=IKPowWithIntegerCheck(new_r00,-1);
13637if(!x1552.valid){
13638continue;
13639}
13640IkReal x1548=x1552.value;
13641IkReal x1549=gconst18*gconst18;
13642CheckValue<IkReal> x1553=IKPowWithIntegerCheck(((((25000.00002)*gconst19*new_r00))+(((25000.0)*gconst18*new_r10))),-1);
13643if(!x1553.valid){
13644continue;
13645}
13646IkReal x1550=x1553.value;
13647IkReal x1551=((25000.0)*new_r10*x1550);
13648CheckValue<IkReal> x1554=IKPowWithIntegerCheck(x1548,-2);
13649if(!x1554.valid){
13650continue;
13651}
13652if( IKabs((((x1548*x1549*x1551))+(((-1.0)*gconst18*x1548))+(((-1.0)*new_r00*x1551)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1550*(((((25000.0)*(x1554.value)))+(((-25000.0)*x1549)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((x1548*x1549*x1551))+(((-1.0)*gconst18*x1548))+(((-1.0)*new_r00*x1551))))+IKsqr((x1550*(((((25000.0)*(x1554.value)))+(((-25000.0)*x1549))))))-1) <= IKFAST_SINCOS_THRESH )
13653 continue;
13654j5array[0]=IKatan2((((x1548*x1549*x1551))+(((-1.0)*gconst18*x1548))+(((-1.0)*new_r00*x1551))), (x1550*(((((25000.0)*(x1554.value)))+(((-25000.0)*x1549))))));
13655sj5array[0]=IKsin(j5array[0]);
13656cj5array[0]=IKcos(j5array[0]);
13657if( j5array[0] > IKPI )
13658{
13659 j5array[0]-=IK2PI;
13660}
13661else if( j5array[0] < -IKPI )
13662{ j5array[0]+=IK2PI;
13663}
13664j5valid[0] = true;
13665for(int ij5 = 0; ij5 < 1; ++ij5)
13666{
13667if( !j5valid[ij5] )
13668{
13669 continue;
13670}
13671_ij5[0] = ij5; _ij5[1] = -1;
13672for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13673{
13674if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13675{
13676 j5valid[iij5]=false; _ij5[1] = iij5; break;
13677}
13678}
13679j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13680{
13681IkReal evalcond[10];
13682IkReal x1555=IKcos(j5);
13683IkReal x1556=IKsin(j5);
13684IkReal x1557=((1.0)*gconst19);
13685IkReal x1558=((1.0000000008)*gconst19);
13686IkReal x1559=(new_r11*x1556);
13687IkReal x1560=(gconst18*x1555);
13688IkReal x1561=(new_r01*x1555);
13689IkReal x1562=(new_r00*x1555);
13690IkReal x1563=(gconst18*x1556);
13691IkReal x1564=(new_r10*x1556);
13692evalcond[0]=(((new_r00*x1556))+gconst18+((new_r10*x1555)));
13693evalcond[1]=(((new_r01*x1556))+((new_r11*x1555))+(((-1.0)*x1557)));
13694evalcond[2]=((((-1.0)*x1555*x1558))+x1563+new_r00);
13695evalcond[3]=(((x1556*x1558))+x1560+new_r10);
13696evalcond[4]=((((-1.0)*x1556*x1557))+new_r01+(((-1.0000000008)*x1560)));
13697evalcond[5]=((((1.0000000008)*x1563))+(((-1.0)*x1555*x1557))+new_r11);
13698evalcond[6]=(x1562+(((-1.0)*x1558))+(((-1.0)*x1564)));
13699evalcond[7]=((((-1.0)*x1559))+(((-1.0000000008)*gconst18))+x1561);
13700evalcond[8]=((((1.0000000008)*x1562))+(((-1.0)*x1557))+(((-1.0000000008)*x1564)));
13701evalcond[9]=((((1.0000000008)*x1561))+(((-1.0)*gconst18))+(((-1.0000000008)*x1559)));
13702if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
13703{
13704continue;
13705}
13706}
13707
13708{
13709std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13710vinfos[0].jointtype = 1;
13711vinfos[0].foffset = j0;
13712vinfos[0].indices[0] = _ij0[0];
13713vinfos[0].indices[1] = _ij0[1];
13714vinfos[0].maxsolutions = _nj0;
13715vinfos[1].jointtype = 1;
13716vinfos[1].foffset = j1;
13717vinfos[1].indices[0] = _ij1[0];
13718vinfos[1].indices[1] = _ij1[1];
13719vinfos[1].maxsolutions = _nj1;
13720vinfos[2].jointtype = 1;
13721vinfos[2].foffset = j2;
13722vinfos[2].indices[0] = _ij2[0];
13723vinfos[2].indices[1] = _ij2[1];
13724vinfos[2].maxsolutions = _nj2;
13725vinfos[3].jointtype = 1;
13726vinfos[3].foffset = j3;
13727vinfos[3].indices[0] = _ij3[0];
13728vinfos[3].indices[1] = _ij3[1];
13729vinfos[3].maxsolutions = _nj3;
13730vinfos[4].jointtype = 1;
13731vinfos[4].foffset = j4;
13732vinfos[4].indices[0] = _ij4[0];
13733vinfos[4].indices[1] = _ij4[1];
13734vinfos[4].maxsolutions = _nj4;
13735vinfos[5].jointtype = 1;
13736vinfos[5].foffset = j5;
13737vinfos[5].indices[0] = _ij5[0];
13738vinfos[5].indices[1] = _ij5[1];
13739vinfos[5].maxsolutions = _nj5;
13740std::vector<int> vfree(0);
13741solutions.AddSolution(vinfos,vfree);
13742}
13743}
13744}
13745
13746}
13747
13748}
13749
13750} else
13751{
13752{
13753IkReal j5array[1], cj5array[1], sj5array[1];
13754bool j5valid[1]={false};
13755_nj5 = 1;
13756IkReal x1565=((1.0)*new_r00);
13757CheckValue<IkReal> x1566 = IKatan2WithCheck(IkReal((((gconst18*new_r11))+((gconst19*new_r10)))),IkReal(((((-1.0)*gconst19*x1565))+(((-1.0)*gconst18*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
13758if(!x1566.valid){
13759continue;
13760}
13761CheckValue<IkReal> x1567=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x1565))+((new_r01*new_r10)))),-1);
13762if(!x1567.valid){
13763continue;
13764}
13765j5array[0]=((-1.5707963267949)+(x1566.value)+(((1.5707963267949)*(x1567.value))));
13766sj5array[0]=IKsin(j5array[0]);
13767cj5array[0]=IKcos(j5array[0]);
13768if( j5array[0] > IKPI )
13769{
13770 j5array[0]-=IK2PI;
13771}
13772else if( j5array[0] < -IKPI )
13773{ j5array[0]+=IK2PI;
13774}
13775j5valid[0] = true;
13776for(int ij5 = 0; ij5 < 1; ++ij5)
13777{
13778if( !j5valid[ij5] )
13779{
13780 continue;
13781}
13782_ij5[0] = ij5; _ij5[1] = -1;
13783for(int iij5 = ij5+1; iij5 < 1; ++iij5)
13784{
13785if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13786{
13787 j5valid[iij5]=false; _ij5[1] = iij5; break;
13788}
13789}
13790j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13791{
13792IkReal evalcond[10];
13793IkReal x1568=IKcos(j5);
13794IkReal x1569=IKsin(j5);
13795IkReal x1570=((1.0)*gconst19);
13796IkReal x1571=((1.0000000008)*gconst19);
13797IkReal x1572=(new_r11*x1569);
13798IkReal x1573=(gconst18*x1568);
13799IkReal x1574=(new_r01*x1568);
13800IkReal x1575=(new_r00*x1568);
13801IkReal x1576=(gconst18*x1569);
13802IkReal x1577=(new_r10*x1569);
13803evalcond[0]=(((new_r00*x1569))+((new_r10*x1568))+gconst18);
13804evalcond[1]=(((new_r01*x1569))+((new_r11*x1568))+(((-1.0)*x1570)));
13805evalcond[2]=((((-1.0)*x1568*x1571))+x1576+new_r00);
13806evalcond[3]=(((x1569*x1571))+x1573+new_r10);
13807evalcond[4]=((((-1.0)*x1569*x1570))+new_r01+(((-1.0000000008)*x1573)));
13808evalcond[5]=((((1.0000000008)*x1576))+(((-1.0)*x1568*x1570))+new_r11);
13809evalcond[6]=(x1575+(((-1.0)*x1571))+(((-1.0)*x1577)));
13810evalcond[7]=((((-1.0000000008)*gconst18))+x1574+(((-1.0)*x1572)));
13811evalcond[8]=((((1.0000000008)*x1575))+(((-1.0)*x1570))+(((-1.0000000008)*x1577)));
13812evalcond[9]=((((1.0000000008)*x1574))+(((-1.0)*gconst18))+(((-1.0000000008)*x1572)));
13813if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
13814{
13815continue;
13816}
13817}
13818
13819{
13820std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13821vinfos[0].jointtype = 1;
13822vinfos[0].foffset = j0;
13823vinfos[0].indices[0] = _ij0[0];
13824vinfos[0].indices[1] = _ij0[1];
13825vinfos[0].maxsolutions = _nj0;
13826vinfos[1].jointtype = 1;
13827vinfos[1].foffset = j1;
13828vinfos[1].indices[0] = _ij1[0];
13829vinfos[1].indices[1] = _ij1[1];
13830vinfos[1].maxsolutions = _nj1;
13831vinfos[2].jointtype = 1;
13832vinfos[2].foffset = j2;
13833vinfos[2].indices[0] = _ij2[0];
13834vinfos[2].indices[1] = _ij2[1];
13835vinfos[2].maxsolutions = _nj2;
13836vinfos[3].jointtype = 1;
13837vinfos[3].foffset = j3;
13838vinfos[3].indices[0] = _ij3[0];
13839vinfos[3].indices[1] = _ij3[1];
13840vinfos[3].maxsolutions = _nj3;
13841vinfos[4].jointtype = 1;
13842vinfos[4].foffset = j4;
13843vinfos[4].indices[0] = _ij4[0];
13844vinfos[4].indices[1] = _ij4[1];
13845vinfos[4].maxsolutions = _nj4;
13846vinfos[5].jointtype = 1;
13847vinfos[5].foffset = j5;
13848vinfos[5].indices[0] = _ij5[0];
13849vinfos[5].indices[1] = _ij5[1];
13850vinfos[5].maxsolutions = _nj5;
13851std::vector<int> vfree(0);
13852solutions.AddSolution(vinfos,vfree);
13853}
13854}
13855}
13856
13857}
13858
13859}
13860
13861}
13862} while(0);
13863if( bgotonextstatement )
13864{
13865bool bgotonextstatement = true;
13866do
13867{
13868evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
13869if( IKabs(evalcond[0]) < 0.0000050000000000 )
13870{
13871bgotonextstatement=false;
13872{
13873IkReal j5eval[1];
13874sj4=4.0e-5;
13875cj4=1.0;
13876j4=4.0e-5;
13877new_r11=0;
13878new_r01=0;
13879new_r22=0;
13880new_r20=0;
13881j5eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
13882if( IKabs(j5eval[0]) < 0.0000010000000000 )
13883{
13884{
13885IkReal j5eval[1];
13886sj4=4.0e-5;
13887cj4=1.0;
13888j4=4.0e-5;
13889new_r11=0;
13890new_r01=0;
13891new_r22=0;
13892new_r20=0;
13893j5eval[0]=1.0;
13894if( IKabs(j5eval[0]) < 0.0000010000000000 )
13895{
13896continue; // no branches [j5]
13897
13898} else
13899{
13900{
13901IkReal j5array[2], cj5array[2], sj5array[2];
13902bool j5valid[2]={false};
13903_nj5 = 2;
13904CheckValue<IkReal> x1579 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r00)),IkReal(((-1.0000000008)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
13905if(!x1579.valid){
13906continue;
13907}
13908IkReal x1578=x1579.value;
13909j5array[0]=((-1.0)*x1578);
13910sj5array[0]=IKsin(j5array[0]);
13911cj5array[0]=IKcos(j5array[0]);
13912j5array[1]=((3.14159265358979)+(((-1.0)*x1578)));
13913sj5array[1]=IKsin(j5array[1]);
13914cj5array[1]=IKcos(j5array[1]);
13915if( j5array[0] > IKPI )
13916{
13917 j5array[0]-=IK2PI;
13918}
13919else if( j5array[0] < -IKPI )
13920{ j5array[0]+=IK2PI;
13921}
13922j5valid[0] = true;
13923if( j5array[1] > IKPI )
13924{
13925 j5array[1]-=IK2PI;
13926}
13927else if( j5array[1] < -IKPI )
13928{ j5array[1]+=IK2PI;
13929}
13930j5valid[1] = true;
13931for(int ij5 = 0; ij5 < 2; ++ij5)
13932{
13933if( !j5valid[ij5] )
13934{
13935 continue;
13936}
13937_ij5[0] = ij5; _ij5[1] = -1;
13938for(int iij5 = ij5+1; iij5 < 2; ++iij5)
13939{
13940if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
13941{
13942 j5valid[iij5]=false; _ij5[1] = iij5; break;
13943}
13944}
13945j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
13946{
13947IkReal evalcond[2];
13948IkReal x1580=IKcos(j5);
13949IkReal x1581=IKsin(j5);
13950evalcond[0]=(((new_r10*x1580))+((new_r00*x1581)));
13951evalcond[1]=((((-1.0)*new_r10*x1581))+((new_r00*x1580)));
13952if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
13953{
13954continue;
13955}
13956}
13957
13958{
13959std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13960vinfos[0].jointtype = 1;
13961vinfos[0].foffset = j0;
13962vinfos[0].indices[0] = _ij0[0];
13963vinfos[0].indices[1] = _ij0[1];
13964vinfos[0].maxsolutions = _nj0;
13965vinfos[1].jointtype = 1;
13966vinfos[1].foffset = j1;
13967vinfos[1].indices[0] = _ij1[0];
13968vinfos[1].indices[1] = _ij1[1];
13969vinfos[1].maxsolutions = _nj1;
13970vinfos[2].jointtype = 1;
13971vinfos[2].foffset = j2;
13972vinfos[2].indices[0] = _ij2[0];
13973vinfos[2].indices[1] = _ij2[1];
13974vinfos[2].maxsolutions = _nj2;
13975vinfos[3].jointtype = 1;
13976vinfos[3].foffset = j3;
13977vinfos[3].indices[0] = _ij3[0];
13978vinfos[3].indices[1] = _ij3[1];
13979vinfos[3].maxsolutions = _nj3;
13980vinfos[4].jointtype = 1;
13981vinfos[4].foffset = j4;
13982vinfos[4].indices[0] = _ij4[0];
13983vinfos[4].indices[1] = _ij4[1];
13984vinfos[4].maxsolutions = _nj4;
13985vinfos[5].jointtype = 1;
13986vinfos[5].foffset = j5;
13987vinfos[5].indices[0] = _ij5[0];
13988vinfos[5].indices[1] = _ij5[1];
13989vinfos[5].maxsolutions = _nj5;
13990std::vector<int> vfree(0);
13991solutions.AddSolution(vinfos,vfree);
13992}
13993}
13994}
13995
13996}
13997
13998}
13999
14000} else
14001{
14002{
14003IkReal j5array[2], cj5array[2], sj5array[2];
14004bool j5valid[2]={false};
14005_nj5 = 2;
14006CheckValue<IkReal> x1583 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
14007if(!x1583.valid){
14008continue;
14009}
14010IkReal x1582=x1583.value;
14011j5array[0]=((-1.0)*x1582);
14012sj5array[0]=IKsin(j5array[0]);
14013cj5array[0]=IKcos(j5array[0]);
14014j5array[1]=((3.14159265358979)+(((-1.0)*x1582)));
14015sj5array[1]=IKsin(j5array[1]);
14016cj5array[1]=IKcos(j5array[1]);
14017if( j5array[0] > IKPI )
14018{
14019 j5array[0]-=IK2PI;
14020}
14021else if( j5array[0] < -IKPI )
14022{ j5array[0]+=IK2PI;
14023}
14024j5valid[0] = true;
14025if( j5array[1] > IKPI )
14026{
14027 j5array[1]-=IK2PI;
14028}
14029else if( j5array[1] < -IKPI )
14030{ j5array[1]+=IK2PI;
14031}
14032j5valid[1] = true;
14033for(int ij5 = 0; ij5 < 2; ++ij5)
14034{
14035if( !j5valid[ij5] )
14036{
14037 continue;
14038}
14039_ij5[0] = ij5; _ij5[1] = -1;
14040for(int iij5 = ij5+1; iij5 < 2; ++iij5)
14041{
14042if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14043{
14044 j5valid[iij5]=false; _ij5[1] = iij5; break;
14045}
14046}
14047j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14048{
14049IkReal evalcond[2];
14050IkReal x1584=IKcos(j5);
14051IkReal x1585=IKsin(j5);
14052IkReal x1586=(new_r00*x1584);
14053IkReal x1587=(new_r10*x1585);
14054evalcond[0]=(x1586+(((-1.0)*x1587)));
14055evalcond[1]=((((-1.0000000008)*x1587))+(((1.0000000008)*x1586)));
14056if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
14057{
14058continue;
14059}
14060}
14061
14062{
14063std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14064vinfos[0].jointtype = 1;
14065vinfos[0].foffset = j0;
14066vinfos[0].indices[0] = _ij0[0];
14067vinfos[0].indices[1] = _ij0[1];
14068vinfos[0].maxsolutions = _nj0;
14069vinfos[1].jointtype = 1;
14070vinfos[1].foffset = j1;
14071vinfos[1].indices[0] = _ij1[0];
14072vinfos[1].indices[1] = _ij1[1];
14073vinfos[1].maxsolutions = _nj1;
14074vinfos[2].jointtype = 1;
14075vinfos[2].foffset = j2;
14076vinfos[2].indices[0] = _ij2[0];
14077vinfos[2].indices[1] = _ij2[1];
14078vinfos[2].maxsolutions = _nj2;
14079vinfos[3].jointtype = 1;
14080vinfos[3].foffset = j3;
14081vinfos[3].indices[0] = _ij3[0];
14082vinfos[3].indices[1] = _ij3[1];
14083vinfos[3].maxsolutions = _nj3;
14084vinfos[4].jointtype = 1;
14085vinfos[4].foffset = j4;
14086vinfos[4].indices[0] = _ij4[0];
14087vinfos[4].indices[1] = _ij4[1];
14088vinfos[4].maxsolutions = _nj4;
14089vinfos[5].jointtype = 1;
14090vinfos[5].foffset = j5;
14091vinfos[5].indices[0] = _ij5[0];
14092vinfos[5].indices[1] = _ij5[1];
14093vinfos[5].maxsolutions = _nj5;
14094std::vector<int> vfree(0);
14095solutions.AddSolution(vinfos,vfree);
14096}
14097}
14098}
14099
14100}
14101
14102}
14103
14104}
14105} while(0);
14106if( bgotonextstatement )
14107{
14108bool bgotonextstatement = true;
14109do
14110{
14111evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
14112if( IKabs(evalcond[0]) < 0.0000050000000000 )
14113{
14114bgotonextstatement=false;
14115{
14116IkReal j5eval[1];
14117sj4=4.0e-5;
14118cj4=1.0;
14119j4=4.0e-5;
14120new_r11=0;
14121new_r10=0;
14122new_r22=0;
14123new_r02=0;
14124j5eval[0]=new_r00;
14125if( IKabs(j5eval[0]) < 0.0000010000000000 )
14126{
14127{
14128IkReal j5eval[2];
14129sj4=4.0e-5;
14130cj4=1.0;
14131j4=4.0e-5;
14132new_r11=0;
14133new_r10=0;
14134new_r22=0;
14135new_r02=0;
14136j5eval[0]=new_r00;
14137j5eval[1]=new_r01;
14138if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
14139{
14140continue; // no branches [j5]
14141
14142} else
14143{
14144{
14145IkReal j5array[1], cj5array[1], sj5array[1];
14146bool j5valid[1]={false};
14147_nj5 = 1;
14148CheckValue<IkReal> x1588=IKPowWithIntegerCheck(new_r00,-1);
14149if(!x1588.valid){
14150continue;
14151}
14152CheckValue<IkReal> x1589=IKPowWithIntegerCheck(new_r01,-1);
14153if(!x1589.valid){
14154continue;
14155}
14156if( IKabs(((-1.0)*sj3*(x1588.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((1.0000000008)*sj3*(x1589.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj3*(x1588.value)))+IKsqr(((1.0000000008)*sj3*(x1589.value)))-1) <= IKFAST_SINCOS_THRESH )
14157 continue;
14158j5array[0]=IKatan2(((-1.0)*sj3*(x1588.value)), ((1.0000000008)*sj3*(x1589.value)));
14159sj5array[0]=IKsin(j5array[0]);
14160cj5array[0]=IKcos(j5array[0]);
14161if( j5array[0] > IKPI )
14162{
14163 j5array[0]-=IK2PI;
14164}
14165else if( j5array[0] < -IKPI )
14166{ j5array[0]+=IK2PI;
14167}
14168j5valid[0] = true;
14169for(int ij5 = 0; ij5 < 1; ++ij5)
14170{
14171if( !j5valid[ij5] )
14172{
14173 continue;
14174}
14175_ij5[0] = ij5; _ij5[1] = -1;
14176for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14177{
14178if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14179{
14180 j5valid[iij5]=false; _ij5[1] = iij5; break;
14181}
14182}
14183j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14184{
14185IkReal evalcond[10];
14186IkReal x1590=IKsin(j5);
14187IkReal x1591=IKcos(j5);
14188IkReal x1592=((1.0)*cj3);
14189IkReal x1593=((1.0000000008)*cj3);
14190IkReal x1594=((1.0000000008)*sj3);
14191IkReal x1595=(new_r00*x1591);
14192IkReal x1596=(sj3*x1591);
14193IkReal x1597=(new_r01*x1591);
14194evalcond[0]=(sj3+((new_r00*x1590)));
14195evalcond[1]=((((-1.0)*x1592))+((new_r01*x1590)));
14196evalcond[2]=((((-1.0)*x1593))+x1595);
14197evalcond[3]=((((-1.0)*x1594))+x1597);
14198evalcond[4]=((((-1.0)*x1592))+(((1.0000000008)*x1595)));
14199evalcond[5]=((((-1.0)*sj3))+(((1.0000000008)*x1597)));
14200evalcond[6]=(((x1590*x1593))+x1596);
14201evalcond[7]=((((-1.0)*x1591*x1593))+new_r00+((sj3*x1590)));
14202evalcond[8]=(((x1590*x1594))+(((-1.0)*x1591*x1592)));
14203evalcond[9]=((((-1.0)*x1591*x1594))+(((-1.0)*x1590*x1592))+new_r01);
14204if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
14205{
14206continue;
14207}
14208}
14209
14210{
14211std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14212vinfos[0].jointtype = 1;
14213vinfos[0].foffset = j0;
14214vinfos[0].indices[0] = _ij0[0];
14215vinfos[0].indices[1] = _ij0[1];
14216vinfos[0].maxsolutions = _nj0;
14217vinfos[1].jointtype = 1;
14218vinfos[1].foffset = j1;
14219vinfos[1].indices[0] = _ij1[0];
14220vinfos[1].indices[1] = _ij1[1];
14221vinfos[1].maxsolutions = _nj1;
14222vinfos[2].jointtype = 1;
14223vinfos[2].foffset = j2;
14224vinfos[2].indices[0] = _ij2[0];
14225vinfos[2].indices[1] = _ij2[1];
14226vinfos[2].maxsolutions = _nj2;
14227vinfos[3].jointtype = 1;
14228vinfos[3].foffset = j3;
14229vinfos[3].indices[0] = _ij3[0];
14230vinfos[3].indices[1] = _ij3[1];
14231vinfos[3].maxsolutions = _nj3;
14232vinfos[4].jointtype = 1;
14233vinfos[4].foffset = j4;
14234vinfos[4].indices[0] = _ij4[0];
14235vinfos[4].indices[1] = _ij4[1];
14236vinfos[4].maxsolutions = _nj4;
14237vinfos[5].jointtype = 1;
14238vinfos[5].foffset = j5;
14239vinfos[5].indices[0] = _ij5[0];
14240vinfos[5].indices[1] = _ij5[1];
14241vinfos[5].maxsolutions = _nj5;
14242std::vector<int> vfree(0);
14243solutions.AddSolution(vinfos,vfree);
14244}
14245}
14246}
14247
14248}
14249
14250}
14251
14252} else
14253{
14254{
14255IkReal j5array[1], cj5array[1], sj5array[1];
14256bool j5valid[1]={false};
14257_nj5 = 1;
14258CheckValue<IkReal> x1599=IKPowWithIntegerCheck(new_r00,-1);
14259if(!x1599.valid){
14260continue;
14261}
14262IkReal x1598=x1599.value;
14263if( IKabs(((-1.0)*sj3*x1598)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((1.0000000008)*cj3*x1598)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj3*x1598))+IKsqr(((1.0000000008)*cj3*x1598))-1) <= IKFAST_SINCOS_THRESH )
14264 continue;
14265j5array[0]=IKatan2(((-1.0)*sj3*x1598), ((1.0000000008)*cj3*x1598));
14266sj5array[0]=IKsin(j5array[0]);
14267cj5array[0]=IKcos(j5array[0]);
14268if( j5array[0] > IKPI )
14269{
14270 j5array[0]-=IK2PI;
14271}
14272else if( j5array[0] < -IKPI )
14273{ j5array[0]+=IK2PI;
14274}
14275j5valid[0] = true;
14276for(int ij5 = 0; ij5 < 1; ++ij5)
14277{
14278if( !j5valid[ij5] )
14279{
14280 continue;
14281}
14282_ij5[0] = ij5; _ij5[1] = -1;
14283for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14284{
14285if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14286{
14287 j5valid[iij5]=false; _ij5[1] = iij5; break;
14288}
14289}
14290j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14291{
14292IkReal evalcond[10];
14293IkReal x1600=IKsin(j5);
14294IkReal x1601=IKcos(j5);
14295IkReal x1602=((1.0)*cj3);
14296IkReal x1603=((1.0000000008)*cj3);
14297IkReal x1604=((1.0000000008)*sj3);
14298IkReal x1605=(new_r00*x1601);
14299IkReal x1606=(sj3*x1601);
14300IkReal x1607=(new_r01*x1601);
14301evalcond[0]=(sj3+((new_r00*x1600)));
14302evalcond[1]=((((-1.0)*x1602))+((new_r01*x1600)));
14303evalcond[2]=((((-1.0)*x1603))+x1605);
14304evalcond[3]=((((-1.0)*x1604))+x1607);
14305evalcond[4]=((((-1.0)*x1602))+(((1.0000000008)*x1605)));
14306evalcond[5]=((((-1.0)*sj3))+(((1.0000000008)*x1607)));
14307evalcond[6]=(x1606+((x1600*x1603)));
14308evalcond[7]=(((sj3*x1600))+(((-1.0)*x1601*x1603))+new_r00);
14309evalcond[8]=(((x1600*x1604))+(((-1.0)*x1601*x1602)));
14310evalcond[9]=((((-1.0)*x1601*x1604))+(((-1.0)*x1600*x1602))+new_r01);
14311if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
14312{
14313continue;
14314}
14315}
14316
14317{
14318std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14319vinfos[0].jointtype = 1;
14320vinfos[0].foffset = j0;
14321vinfos[0].indices[0] = _ij0[0];
14322vinfos[0].indices[1] = _ij0[1];
14323vinfos[0].maxsolutions = _nj0;
14324vinfos[1].jointtype = 1;
14325vinfos[1].foffset = j1;
14326vinfos[1].indices[0] = _ij1[0];
14327vinfos[1].indices[1] = _ij1[1];
14328vinfos[1].maxsolutions = _nj1;
14329vinfos[2].jointtype = 1;
14330vinfos[2].foffset = j2;
14331vinfos[2].indices[0] = _ij2[0];
14332vinfos[2].indices[1] = _ij2[1];
14333vinfos[2].maxsolutions = _nj2;
14334vinfos[3].jointtype = 1;
14335vinfos[3].foffset = j3;
14336vinfos[3].indices[0] = _ij3[0];
14337vinfos[3].indices[1] = _ij3[1];
14338vinfos[3].maxsolutions = _nj3;
14339vinfos[4].jointtype = 1;
14340vinfos[4].foffset = j4;
14341vinfos[4].indices[0] = _ij4[0];
14342vinfos[4].indices[1] = _ij4[1];
14343vinfos[4].maxsolutions = _nj4;
14344vinfos[5].jointtype = 1;
14345vinfos[5].foffset = j5;
14346vinfos[5].indices[0] = _ij5[0];
14347vinfos[5].indices[1] = _ij5[1];
14348vinfos[5].maxsolutions = _nj5;
14349std::vector<int> vfree(0);
14350solutions.AddSolution(vinfos,vfree);
14351}
14352}
14353}
14354
14355}
14356
14357}
14358
14359}
14360} while(0);
14361if( bgotonextstatement )
14362{
14363bool bgotonextstatement = true;
14364do
14365{
14366evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
14367if( IKabs(evalcond[0]) < 0.0000050000000000 )
14368{
14369bgotonextstatement=false;
14370{
14371IkReal j5eval[1];
14372sj4=4.0e-5;
14373cj4=1.0;
14374j4=4.0e-5;
14375new_r00=0;
14376new_r01=0;
14377new_r12=0;
14378new_r22=0;
14379j5eval[0]=new_r10;
14380if( IKabs(j5eval[0]) < 0.0000010000000000 )
14381{
14382{
14383IkReal j5eval[2];
14384sj4=4.0e-5;
14385cj4=1.0;
14386j4=4.0e-5;
14387new_r00=0;
14388new_r01=0;
14389new_r12=0;
14390new_r22=0;
14391j5eval[0]=new_r11;
14392j5eval[1]=new_r10;
14393if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
14394{
14395continue; // no branches [j5]
14396
14397} else
14398{
14399{
14400IkReal j5array[1], cj5array[1], sj5array[1];
14401bool j5valid[1]={false};
14402_nj5 = 1;
14403CheckValue<IkReal> x1608=IKPowWithIntegerCheck(new_r11,-1);
14404if(!x1608.valid){
14405continue;
14406}
14407CheckValue<IkReal> x1609=IKPowWithIntegerCheck(new_r10,-1);
14408if(!x1609.valid){
14409continue;
14410}
14411if( IKabs(((-1.0000000008)*sj3*(x1608.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj3*(x1609.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0000000008)*sj3*(x1608.value)))+IKsqr(((-1.0)*sj3*(x1609.value)))-1) <= IKFAST_SINCOS_THRESH )
14412 continue;
14413j5array[0]=IKatan2(((-1.0000000008)*sj3*(x1608.value)), ((-1.0)*sj3*(x1609.value)));
14414sj5array[0]=IKsin(j5array[0]);
14415cj5array[0]=IKcos(j5array[0]);
14416if( j5array[0] > IKPI )
14417{
14418 j5array[0]-=IK2PI;
14419}
14420else if( j5array[0] < -IKPI )
14421{ j5array[0]+=IK2PI;
14422}
14423j5valid[0] = true;
14424for(int ij5 = 0; ij5 < 1; ++ij5)
14425{
14426if( !j5valid[ij5] )
14427{
14428 continue;
14429}
14430_ij5[0] = ij5; _ij5[1] = -1;
14431for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14432{
14433if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14434{
14435 j5valid[iij5]=false; _ij5[1] = iij5; break;
14436}
14437}
14438j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14439{
14440IkReal evalcond[10];
14441IkReal x1610=IKcos(j5);
14442IkReal x1611=IKsin(j5);
14443IkReal x1612=((1.0)*cj3);
14444IkReal x1613=((1.0000000008)*cj3);
14445IkReal x1614=((1.0000000008)*sj3);
14446IkReal x1615=(sj3*x1610);
14447IkReal x1616=(new_r10*x1611);
14448IkReal x1617=(new_r11*x1611);
14449evalcond[0]=(sj3+((new_r10*x1610)));
14450evalcond[1]=(((new_r11*x1610))+(((-1.0)*x1612)));
14451evalcond[2]=((((-1.0)*x1616))+(((-1.0)*x1613)));
14452evalcond[3]=((((-1.0)*x1617))+(((-1.0)*x1614)));
14453evalcond[4]=((((-1.0)*x1612))+(((-1.0000000008)*x1616)));
14454evalcond[5]=((((-1.0)*sj3))+(((-1.0000000008)*x1617)));
14455evalcond[6]=(((sj3*x1611))+(((-1.0)*x1610*x1613)));
14456evalcond[7]=(x1615+new_r10+((x1611*x1613)));
14457evalcond[8]=((((-1.0)*x1611*x1612))+(((-1.0)*x1610*x1614)));
14458evalcond[9]=((((-1.0)*x1610*x1612))+new_r11+((x1611*x1614)));
14459if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
14460{
14461continue;
14462}
14463}
14464
14465{
14466std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14467vinfos[0].jointtype = 1;
14468vinfos[0].foffset = j0;
14469vinfos[0].indices[0] = _ij0[0];
14470vinfos[0].indices[1] = _ij0[1];
14471vinfos[0].maxsolutions = _nj0;
14472vinfos[1].jointtype = 1;
14473vinfos[1].foffset = j1;
14474vinfos[1].indices[0] = _ij1[0];
14475vinfos[1].indices[1] = _ij1[1];
14476vinfos[1].maxsolutions = _nj1;
14477vinfos[2].jointtype = 1;
14478vinfos[2].foffset = j2;
14479vinfos[2].indices[0] = _ij2[0];
14480vinfos[2].indices[1] = _ij2[1];
14481vinfos[2].maxsolutions = _nj2;
14482vinfos[3].jointtype = 1;
14483vinfos[3].foffset = j3;
14484vinfos[3].indices[0] = _ij3[0];
14485vinfos[3].indices[1] = _ij3[1];
14486vinfos[3].maxsolutions = _nj3;
14487vinfos[4].jointtype = 1;
14488vinfos[4].foffset = j4;
14489vinfos[4].indices[0] = _ij4[0];
14490vinfos[4].indices[1] = _ij4[1];
14491vinfos[4].maxsolutions = _nj4;
14492vinfos[5].jointtype = 1;
14493vinfos[5].foffset = j5;
14494vinfos[5].indices[0] = _ij5[0];
14495vinfos[5].indices[1] = _ij5[1];
14496vinfos[5].maxsolutions = _nj5;
14497std::vector<int> vfree(0);
14498solutions.AddSolution(vinfos,vfree);
14499}
14500}
14501}
14502
14503}
14504
14505}
14506
14507} else
14508{
14509{
14510IkReal j5array[1], cj5array[1], sj5array[1];
14511bool j5valid[1]={false};
14512_nj5 = 1;
14513CheckValue<IkReal> x1619=IKPowWithIntegerCheck(new_r10,-1);
14514if(!x1619.valid){
14515continue;
14516}
14517IkReal x1618=x1619.value;
14518if( IKabs(((-1.0000000008)*cj3*x1618)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj3*x1618)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0000000008)*cj3*x1618))+IKsqr(((-1.0)*sj3*x1618))-1) <= IKFAST_SINCOS_THRESH )
14519 continue;
14520j5array[0]=IKatan2(((-1.0000000008)*cj3*x1618), ((-1.0)*sj3*x1618));
14521sj5array[0]=IKsin(j5array[0]);
14522cj5array[0]=IKcos(j5array[0]);
14523if( j5array[0] > IKPI )
14524{
14525 j5array[0]-=IK2PI;
14526}
14527else if( j5array[0] < -IKPI )
14528{ j5array[0]+=IK2PI;
14529}
14530j5valid[0] = true;
14531for(int ij5 = 0; ij5 < 1; ++ij5)
14532{
14533if( !j5valid[ij5] )
14534{
14535 continue;
14536}
14537_ij5[0] = ij5; _ij5[1] = -1;
14538for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14539{
14540if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14541{
14542 j5valid[iij5]=false; _ij5[1] = iij5; break;
14543}
14544}
14545j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14546{
14547IkReal evalcond[10];
14548IkReal x1620=IKcos(j5);
14549IkReal x1621=IKsin(j5);
14550IkReal x1622=((1.0)*cj3);
14551IkReal x1623=((1.0000000008)*cj3);
14552IkReal x1624=((1.0000000008)*sj3);
14553IkReal x1625=(sj3*x1620);
14554IkReal x1626=(new_r10*x1621);
14555IkReal x1627=(new_r11*x1621);
14556evalcond[0]=(sj3+((new_r10*x1620)));
14557evalcond[1]=(((new_r11*x1620))+(((-1.0)*x1622)));
14558evalcond[2]=((((-1.0)*x1626))+(((-1.0)*x1623)));
14559evalcond[3]=((((-1.0)*x1627))+(((-1.0)*x1624)));
14560evalcond[4]=((((-1.0)*x1622))+(((-1.0000000008)*x1626)));
14561evalcond[5]=((((-1.0)*sj3))+(((-1.0000000008)*x1627)));
14562evalcond[6]=(((sj3*x1621))+(((-1.0)*x1620*x1623)));
14563evalcond[7]=(x1625+new_r10+((x1621*x1623)));
14564evalcond[8]=((((-1.0)*x1621*x1622))+(((-1.0)*x1620*x1624)));
14565evalcond[9]=((((-1.0)*x1620*x1622))+new_r11+((x1621*x1624)));
14566if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
14567{
14568continue;
14569}
14570}
14571
14572{
14573std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14574vinfos[0].jointtype = 1;
14575vinfos[0].foffset = j0;
14576vinfos[0].indices[0] = _ij0[0];
14577vinfos[0].indices[1] = _ij0[1];
14578vinfos[0].maxsolutions = _nj0;
14579vinfos[1].jointtype = 1;
14580vinfos[1].foffset = j1;
14581vinfos[1].indices[0] = _ij1[0];
14582vinfos[1].indices[1] = _ij1[1];
14583vinfos[1].maxsolutions = _nj1;
14584vinfos[2].jointtype = 1;
14585vinfos[2].foffset = j2;
14586vinfos[2].indices[0] = _ij2[0];
14587vinfos[2].indices[1] = _ij2[1];
14588vinfos[2].maxsolutions = _nj2;
14589vinfos[3].jointtype = 1;
14590vinfos[3].foffset = j3;
14591vinfos[3].indices[0] = _ij3[0];
14592vinfos[3].indices[1] = _ij3[1];
14593vinfos[3].maxsolutions = _nj3;
14594vinfos[4].jointtype = 1;
14595vinfos[4].foffset = j4;
14596vinfos[4].indices[0] = _ij4[0];
14597vinfos[4].indices[1] = _ij4[1];
14598vinfos[4].maxsolutions = _nj4;
14599vinfos[5].jointtype = 1;
14600vinfos[5].foffset = j5;
14601vinfos[5].indices[0] = _ij5[0];
14602vinfos[5].indices[1] = _ij5[1];
14603vinfos[5].maxsolutions = _nj5;
14604std::vector<int> vfree(0);
14605solutions.AddSolution(vinfos,vfree);
14606}
14607}
14608}
14609
14610}
14611
14612}
14613
14614}
14615} while(0);
14616if( bgotonextstatement )
14617{
14618bool bgotonextstatement = true;
14619do
14620{
14621evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
14622if( IKabs(evalcond[0]) < 0.0000050000000000 )
14623{
14624bgotonextstatement=false;
14625{
14626IkReal j5eval[1];
14627sj4=4.0e-5;
14628cj4=1.0;
14629j4=4.0e-5;
14630new_r00=0;
14631new_r10=0;
14632new_r21=0;
14633new_r22=0;
14634j5eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
14635if( IKabs(j5eval[0]) < 0.0000010000000000 )
14636{
14637{
14638IkReal j5eval[1];
14639sj4=4.0e-5;
14640cj4=1.0;
14641j4=4.0e-5;
14642new_r00=0;
14643new_r10=0;
14644new_r21=0;
14645new_r22=0;
14646j5eval[0]=1.0;
14647if( IKabs(j5eval[0]) < 0.0000010000000000 )
14648{
14649continue; // no branches [j5]
14650
14651} else
14652{
14653{
14654IkReal j5array[2], cj5array[2], sj5array[2];
14655bool j5valid[2]={false};
14656_nj5 = 2;
14657CheckValue<IkReal> x1629 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r01)),IkReal(((-1.0000000008)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
14658if(!x1629.valid){
14659continue;
14660}
14661IkReal x1628=x1629.value;
14662j5array[0]=((-1.0)*x1628);
14663sj5array[0]=IKsin(j5array[0]);
14664cj5array[0]=IKcos(j5array[0]);
14665j5array[1]=((3.14159265358979)+(((-1.0)*x1628)));
14666sj5array[1]=IKsin(j5array[1]);
14667cj5array[1]=IKcos(j5array[1]);
14668if( j5array[0] > IKPI )
14669{
14670 j5array[0]-=IK2PI;
14671}
14672else if( j5array[0] < -IKPI )
14673{ j5array[0]+=IK2PI;
14674}
14675j5valid[0] = true;
14676if( j5array[1] > IKPI )
14677{
14678 j5array[1]-=IK2PI;
14679}
14680else if( j5array[1] < -IKPI )
14681{ j5array[1]+=IK2PI;
14682}
14683j5valid[1] = true;
14684for(int ij5 = 0; ij5 < 2; ++ij5)
14685{
14686if( !j5valid[ij5] )
14687{
14688 continue;
14689}
14690_ij5[0] = ij5; _ij5[1] = -1;
14691for(int iij5 = ij5+1; iij5 < 2; ++iij5)
14692{
14693if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14694{
14695 j5valid[iij5]=false; _ij5[1] = iij5; break;
14696}
14697}
14698j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14699{
14700IkReal evalcond[2];
14701IkReal x1630=IKcos(j5);
14702IkReal x1631=IKsin(j5);
14703evalcond[0]=(((new_r11*x1630))+((new_r01*x1631)));
14704evalcond[1]=(((new_r01*x1630))+(((-1.0)*new_r11*x1631)));
14705if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
14706{
14707continue;
14708}
14709}
14710
14711{
14712std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14713vinfos[0].jointtype = 1;
14714vinfos[0].foffset = j0;
14715vinfos[0].indices[0] = _ij0[0];
14716vinfos[0].indices[1] = _ij0[1];
14717vinfos[0].maxsolutions = _nj0;
14718vinfos[1].jointtype = 1;
14719vinfos[1].foffset = j1;
14720vinfos[1].indices[0] = _ij1[0];
14721vinfos[1].indices[1] = _ij1[1];
14722vinfos[1].maxsolutions = _nj1;
14723vinfos[2].jointtype = 1;
14724vinfos[2].foffset = j2;
14725vinfos[2].indices[0] = _ij2[0];
14726vinfos[2].indices[1] = _ij2[1];
14727vinfos[2].maxsolutions = _nj2;
14728vinfos[3].jointtype = 1;
14729vinfos[3].foffset = j3;
14730vinfos[3].indices[0] = _ij3[0];
14731vinfos[3].indices[1] = _ij3[1];
14732vinfos[3].maxsolutions = _nj3;
14733vinfos[4].jointtype = 1;
14734vinfos[4].foffset = j4;
14735vinfos[4].indices[0] = _ij4[0];
14736vinfos[4].indices[1] = _ij4[1];
14737vinfos[4].maxsolutions = _nj4;
14738vinfos[5].jointtype = 1;
14739vinfos[5].foffset = j5;
14740vinfos[5].indices[0] = _ij5[0];
14741vinfos[5].indices[1] = _ij5[1];
14742vinfos[5].maxsolutions = _nj5;
14743std::vector<int> vfree(0);
14744solutions.AddSolution(vinfos,vfree);
14745}
14746}
14747}
14748
14749}
14750
14751}
14752
14753} else
14754{
14755{
14756IkReal j5array[2], cj5array[2], sj5array[2];
14757bool j5valid[2]={false};
14758_nj5 = 2;
14759CheckValue<IkReal> x1633 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
14760if(!x1633.valid){
14761continue;
14762}
14763IkReal x1632=x1633.value;
14764j5array[0]=((-1.0)*x1632);
14765sj5array[0]=IKsin(j5array[0]);
14766cj5array[0]=IKcos(j5array[0]);
14767j5array[1]=((3.14159265358979)+(((-1.0)*x1632)));
14768sj5array[1]=IKsin(j5array[1]);
14769cj5array[1]=IKcos(j5array[1]);
14770if( j5array[0] > IKPI )
14771{
14772 j5array[0]-=IK2PI;
14773}
14774else if( j5array[0] < -IKPI )
14775{ j5array[0]+=IK2PI;
14776}
14777j5valid[0] = true;
14778if( j5array[1] > IKPI )
14779{
14780 j5array[1]-=IK2PI;
14781}
14782else if( j5array[1] < -IKPI )
14783{ j5array[1]+=IK2PI;
14784}
14785j5valid[1] = true;
14786for(int ij5 = 0; ij5 < 2; ++ij5)
14787{
14788if( !j5valid[ij5] )
14789{
14790 continue;
14791}
14792_ij5[0] = ij5; _ij5[1] = -1;
14793for(int iij5 = ij5+1; iij5 < 2; ++iij5)
14794{
14795if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14796{
14797 j5valid[iij5]=false; _ij5[1] = iij5; break;
14798}
14799}
14800j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14801{
14802IkReal evalcond[2];
14803IkReal x1634=IKcos(j5);
14804IkReal x1635=IKsin(j5);
14805IkReal x1636=(new_r11*x1635);
14806IkReal x1637=(new_r01*x1634);
14807evalcond[0]=(x1637+(((-1.0)*x1636)));
14808evalcond[1]=((((-1.0000000008)*x1636))+(((1.0000000008)*x1637)));
14809if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
14810{
14811continue;
14812}
14813}
14814
14815{
14816std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14817vinfos[0].jointtype = 1;
14818vinfos[0].foffset = j0;
14819vinfos[0].indices[0] = _ij0[0];
14820vinfos[0].indices[1] = _ij0[1];
14821vinfos[0].maxsolutions = _nj0;
14822vinfos[1].jointtype = 1;
14823vinfos[1].foffset = j1;
14824vinfos[1].indices[0] = _ij1[0];
14825vinfos[1].indices[1] = _ij1[1];
14826vinfos[1].maxsolutions = _nj1;
14827vinfos[2].jointtype = 1;
14828vinfos[2].foffset = j2;
14829vinfos[2].indices[0] = _ij2[0];
14830vinfos[2].indices[1] = _ij2[1];
14831vinfos[2].maxsolutions = _nj2;
14832vinfos[3].jointtype = 1;
14833vinfos[3].foffset = j3;
14834vinfos[3].indices[0] = _ij3[0];
14835vinfos[3].indices[1] = _ij3[1];
14836vinfos[3].maxsolutions = _nj3;
14837vinfos[4].jointtype = 1;
14838vinfos[4].foffset = j4;
14839vinfos[4].indices[0] = _ij4[0];
14840vinfos[4].indices[1] = _ij4[1];
14841vinfos[4].maxsolutions = _nj4;
14842vinfos[5].jointtype = 1;
14843vinfos[5].foffset = j5;
14844vinfos[5].indices[0] = _ij5[0];
14845vinfos[5].indices[1] = _ij5[1];
14846vinfos[5].maxsolutions = _nj5;
14847std::vector<int> vfree(0);
14848solutions.AddSolution(vinfos,vfree);
14849}
14850}
14851}
14852
14853}
14854
14855}
14856
14857}
14858} while(0);
14859if( bgotonextstatement )
14860{
14861bool bgotonextstatement = true;
14862do
14863{
14864if( 1 )
14865{
14866bgotonextstatement=false;
14867continue; // branch miss [j5]
14868
14869}
14870} while(0);
14871if( bgotonextstatement )
14872{
14873}
14874}
14875}
14876}
14877}
14878}
14879}
14880}
14881}
14882}
14883}
14884}
14885}
14886}
14887
14888} else
14889{
14890{
14891IkReal j5array[1], cj5array[1], sj5array[1];
14892bool j5valid[1]={false};
14893_nj5 = 1;
14894CheckValue<IkReal> x1643=IKPowWithIntegerCheck(new_r00,-1);
14895if(!x1643.valid){
14896continue;
14897}
14898IkReal x1638=x1643.value;
14899IkReal x1639=((25000.0)*new_r01);
14900IkReal x1640=((25000.0)*cj3*sj3);
14901CheckValue<IkReal> x1644=IKPowWithIntegerCheck(((((25000.0)*cj3*new_r10))+(((-25000.00002)*new_r00*sj3))),-1);
14902if(!x1644.valid){
14903continue;
14904}
14905IkReal x1641=x1644.value;
14906IkReal x1642=(new_r10*x1641);
14907if( IKabs(((((-1.0)*sj3*x1638))+((x1639*x1642))+((x1638*x1640*x1642)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1641*(((((-1.0)*new_r00*x1639))+(((-1.0)*x1640)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*sj3*x1638))+((x1639*x1642))+((x1638*x1640*x1642))))+IKsqr((x1641*(((((-1.0)*new_r00*x1639))+(((-1.0)*x1640))))))-1) <= IKFAST_SINCOS_THRESH )
14908 continue;
14909j5array[0]=IKatan2(((((-1.0)*sj3*x1638))+((x1639*x1642))+((x1638*x1640*x1642))), (x1641*(((((-1.0)*new_r00*x1639))+(((-1.0)*x1640))))));
14910sj5array[0]=IKsin(j5array[0]);
14911cj5array[0]=IKcos(j5array[0]);
14912if( j5array[0] > IKPI )
14913{
14914 j5array[0]-=IK2PI;
14915}
14916else if( j5array[0] < -IKPI )
14917{ j5array[0]+=IK2PI;
14918}
14919j5valid[0] = true;
14920for(int ij5 = 0; ij5 < 1; ++ij5)
14921{
14922if( !j5valid[ij5] )
14923{
14924 continue;
14925}
14926_ij5[0] = ij5; _ij5[1] = -1;
14927for(int iij5 = ij5+1; iij5 < 1; ++iij5)
14928{
14929if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
14930{
14931 j5valid[iij5]=false; _ij5[1] = iij5; break;
14932}
14933}
14934j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
14935{
14936IkReal evalcond[10];
14937IkReal x1645=IKcos(j5);
14938IkReal x1646=IKsin(j5);
14939IkReal x1647=((1.0)*cj3);
14940IkReal x1648=((1.0000000008)*cj3);
14941IkReal x1649=(cj3*x1645);
14942IkReal x1650=(new_r11*x1646);
14943IkReal x1651=(sj3*x1646);
14944IkReal x1652=(new_r01*x1645);
14945IkReal x1653=(new_r00*x1645);
14946IkReal x1654=(sj3*x1645);
14947IkReal x1655=(new_r10*x1646);
14948evalcond[0]=(((new_r10*x1645))+sj3+((new_r00*x1646)));
14949evalcond[1]=(((new_r11*x1645))+(((-1.0)*x1647))+((new_r01*x1646)));
14950evalcond[2]=(x1651+(((-1.0)*x1645*x1648))+new_r00);
14951evalcond[3]=(x1654+((x1646*x1648))+new_r10);
14952evalcond[4]=((((-1.0)*x1646*x1647))+(((-1.0000000008)*x1654))+new_r01);
14953evalcond[5]=((((-1.0)*x1645*x1647))+(((1.0000000008)*x1651))+new_r11);
14954evalcond[6]=(x1653+(((-1.0)*x1655))+(((-1.0)*x1648)));
14955evalcond[7]=(x1652+(((-1.0)*x1650))+(((-1.0000000008)*sj3)));
14956evalcond[8]=((((-1.0000000008)*x1655))+(((-1.0)*x1647))+(((1.0000000008)*x1653)));
14957evalcond[9]=((((-1.0)*sj3))+(((-1.0000000008)*x1650))+(((1.0000000008)*x1652)));
14958if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
14959{
14960continue;
14961}
14962}
14963
14964{
14965std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14966vinfos[0].jointtype = 1;
14967vinfos[0].foffset = j0;
14968vinfos[0].indices[0] = _ij0[0];
14969vinfos[0].indices[1] = _ij0[1];
14970vinfos[0].maxsolutions = _nj0;
14971vinfos[1].jointtype = 1;
14972vinfos[1].foffset = j1;
14973vinfos[1].indices[0] = _ij1[0];
14974vinfos[1].indices[1] = _ij1[1];
14975vinfos[1].maxsolutions = _nj1;
14976vinfos[2].jointtype = 1;
14977vinfos[2].foffset = j2;
14978vinfos[2].indices[0] = _ij2[0];
14979vinfos[2].indices[1] = _ij2[1];
14980vinfos[2].maxsolutions = _nj2;
14981vinfos[3].jointtype = 1;
14982vinfos[3].foffset = j3;
14983vinfos[3].indices[0] = _ij3[0];
14984vinfos[3].indices[1] = _ij3[1];
14985vinfos[3].maxsolutions = _nj3;
14986vinfos[4].jointtype = 1;
14987vinfos[4].foffset = j4;
14988vinfos[4].indices[0] = _ij4[0];
14989vinfos[4].indices[1] = _ij4[1];
14990vinfos[4].maxsolutions = _nj4;
14991vinfos[5].jointtype = 1;
14992vinfos[5].foffset = j5;
14993vinfos[5].indices[0] = _ij5[0];
14994vinfos[5].indices[1] = _ij5[1];
14995vinfos[5].maxsolutions = _nj5;
14996std::vector<int> vfree(0);
14997solutions.AddSolution(vinfos,vfree);
14998}
14999}
15000}
15001
15002}
15003
15004}
15005
15006} else
15007{
15008{
15009IkReal j5array[1], cj5array[1], sj5array[1];
15010bool j5valid[1]={false};
15011_nj5 = 1;
15012IkReal x1656=new_r00*new_r00;
15013IkReal x1657=cj3*cj3;
15014IkReal x1658=new_r10*new_r10;
15015IkReal x1659=((625000000.0)*new_r00);
15016IkReal x1660=((25000.00002)*cj3);
15017IkReal x1661=((625000000.5)*cj3);
15018IkReal x1662=((25000.0)*new_r00);
15019IkReal x1663=((625000000.0)*x1656);
15020CheckValue<IkReal> x1664=IKPowWithIntegerCheck(((((-625000001.0)*x1657*x1658))+x1663+(((-1.0)*x1657*x1663))),-1);
15021if(!x1664.valid){
15022continue;
15023}
15024CheckValue<IkReal> x1665=IKPowWithIntegerCheck((((sj3*x1662))+(((-1.0)*new_r10*x1660))),-1);
15025if(!x1665.valid){
15026continue;
15027}
15028if( IKabs(((x1664.value)*(((((-1.0)*x1659*(sj3*sj3*sj3)))+((x1661*(new_r10*new_r10*new_r10)))+((new_r10*x1661*(cj3*cj3)))+(((-1.0)*new_r10*x1661))+((sj3*x1658*x1659)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x1665.value)*((((sj3*x1660))+(((-1.0)*new_r10*x1662)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1664.value)*(((((-1.0)*x1659*(sj3*sj3*sj3)))+((x1661*(new_r10*new_r10*new_r10)))+((new_r10*x1661*(cj3*cj3)))+(((-1.0)*new_r10*x1661))+((sj3*x1658*x1659))))))+IKsqr(((x1665.value)*((((sj3*x1660))+(((-1.0)*new_r10*x1662))))))-1) <= IKFAST_SINCOS_THRESH )
15029 continue;
15030j5array[0]=IKatan2(((x1664.value)*(((((-1.0)*x1659*(sj3*sj3*sj3)))+((x1661*(new_r10*new_r10*new_r10)))+((new_r10*x1661*(cj3*cj3)))+(((-1.0)*new_r10*x1661))+((sj3*x1658*x1659))))), ((x1665.value)*((((sj3*x1660))+(((-1.0)*new_r10*x1662))))));
15031sj5array[0]=IKsin(j5array[0]);
15032cj5array[0]=IKcos(j5array[0]);
15033if( j5array[0] > IKPI )
15034{
15035 j5array[0]-=IK2PI;
15036}
15037else if( j5array[0] < -IKPI )
15038{ j5array[0]+=IK2PI;
15039}
15040j5valid[0] = true;
15041for(int ij5 = 0; ij5 < 1; ++ij5)
15042{
15043if( !j5valid[ij5] )
15044{
15045 continue;
15046}
15047_ij5[0] = ij5; _ij5[1] = -1;
15048for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15049{
15050if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15051{
15052 j5valid[iij5]=false; _ij5[1] = iij5; break;
15053}
15054}
15055j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15056{
15057IkReal evalcond[10];
15058IkReal x1666=IKcos(j5);
15059IkReal x1667=IKsin(j5);
15060IkReal x1668=((1.0)*cj3);
15061IkReal x1669=((1.0000000008)*cj3);
15062IkReal x1670=(cj3*x1666);
15063IkReal x1671=(new_r11*x1667);
15064IkReal x1672=(sj3*x1667);
15065IkReal x1673=(new_r01*x1666);
15066IkReal x1674=(new_r00*x1666);
15067IkReal x1675=(sj3*x1666);
15068IkReal x1676=(new_r10*x1667);
15069evalcond[0]=(sj3+((new_r00*x1667))+((new_r10*x1666)));
15070evalcond[1]=(((new_r11*x1666))+((new_r01*x1667))+(((-1.0)*x1668)));
15071evalcond[2]=(x1672+new_r00+(((-1.0)*x1666*x1669)));
15072evalcond[3]=(x1675+((x1667*x1669))+new_r10);
15073evalcond[4]=((((-1.0)*x1667*x1668))+new_r01+(((-1.0000000008)*x1675)));
15074evalcond[5]=((((1.0000000008)*x1672))+new_r11+(((-1.0)*x1666*x1668)));
15075evalcond[6]=(x1674+(((-1.0)*x1676))+(((-1.0)*x1669)));
15076evalcond[7]=(x1673+(((-1.0)*x1671))+(((-1.0000000008)*sj3)));
15077evalcond[8]=((((1.0000000008)*x1674))+(((-1.0)*x1668))+(((-1.0000000008)*x1676)));
15078evalcond[9]=((((-1.0)*sj3))+(((1.0000000008)*x1673))+(((-1.0000000008)*x1671)));
15079if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
15080{
15081continue;
15082}
15083}
15084
15085{
15086std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15087vinfos[0].jointtype = 1;
15088vinfos[0].foffset = j0;
15089vinfos[0].indices[0] = _ij0[0];
15090vinfos[0].indices[1] = _ij0[1];
15091vinfos[0].maxsolutions = _nj0;
15092vinfos[1].jointtype = 1;
15093vinfos[1].foffset = j1;
15094vinfos[1].indices[0] = _ij1[0];
15095vinfos[1].indices[1] = _ij1[1];
15096vinfos[1].maxsolutions = _nj1;
15097vinfos[2].jointtype = 1;
15098vinfos[2].foffset = j2;
15099vinfos[2].indices[0] = _ij2[0];
15100vinfos[2].indices[1] = _ij2[1];
15101vinfos[2].maxsolutions = _nj2;
15102vinfos[3].jointtype = 1;
15103vinfos[3].foffset = j3;
15104vinfos[3].indices[0] = _ij3[0];
15105vinfos[3].indices[1] = _ij3[1];
15106vinfos[3].maxsolutions = _nj3;
15107vinfos[4].jointtype = 1;
15108vinfos[4].foffset = j4;
15109vinfos[4].indices[0] = _ij4[0];
15110vinfos[4].indices[1] = _ij4[1];
15111vinfos[4].maxsolutions = _nj4;
15112vinfos[5].jointtype = 1;
15113vinfos[5].foffset = j5;
15114vinfos[5].indices[0] = _ij5[0];
15115vinfos[5].indices[1] = _ij5[1];
15116vinfos[5].maxsolutions = _nj5;
15117std::vector<int> vfree(0);
15118solutions.AddSolution(vinfos,vfree);
15119}
15120}
15121}
15122
15123}
15124
15125}
15126
15127} else
15128{
15129{
15130IkReal j5array[1], cj5array[1], sj5array[1];
15131bool j5valid[1]={false};
15132_nj5 = 1;
15133IkReal x1677=((1.0)*new_r00);
15134CheckValue<IkReal> x1678 = IKatan2WithCheck(IkReal((((new_r11*sj3))+((cj3*new_r10)))),IkReal(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x1677)))),IKFAST_ATAN2_MAGTHRESH);
15135if(!x1678.valid){
15136continue;
15137}
15138CheckValue<IkReal> x1679=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x1677)))),-1);
15139if(!x1679.valid){
15140continue;
15141}
15142j5array[0]=((-1.5707963267949)+(x1678.value)+(((1.5707963267949)*(x1679.value))));
15143sj5array[0]=IKsin(j5array[0]);
15144cj5array[0]=IKcos(j5array[0]);
15145if( j5array[0] > IKPI )
15146{
15147 j5array[0]-=IK2PI;
15148}
15149else if( j5array[0] < -IKPI )
15150{ j5array[0]+=IK2PI;
15151}
15152j5valid[0] = true;
15153for(int ij5 = 0; ij5 < 1; ++ij5)
15154{
15155if( !j5valid[ij5] )
15156{
15157 continue;
15158}
15159_ij5[0] = ij5; _ij5[1] = -1;
15160for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15161{
15162if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15163{
15164 j5valid[iij5]=false; _ij5[1] = iij5; break;
15165}
15166}
15167j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15168{
15169IkReal evalcond[10];
15170IkReal x1680=IKcos(j5);
15171IkReal x1681=IKsin(j5);
15172IkReal x1682=((1.0)*cj3);
15173IkReal x1683=((1.0000000008)*cj3);
15174IkReal x1684=(cj3*x1680);
15175IkReal x1685=(new_r11*x1681);
15176IkReal x1686=(sj3*x1681);
15177IkReal x1687=(new_r01*x1680);
15178IkReal x1688=(new_r00*x1680);
15179IkReal x1689=(sj3*x1680);
15180IkReal x1690=(new_r10*x1681);
15181evalcond[0]=(((new_r00*x1681))+sj3+((new_r10*x1680)));
15182evalcond[1]=((((-1.0)*x1682))+((new_r11*x1680))+((new_r01*x1681)));
15183evalcond[2]=(x1686+(((-1.0)*x1680*x1683))+new_r00);
15184evalcond[3]=(((x1681*x1683))+x1689+new_r10);
15185evalcond[4]=((((-1.0)*x1681*x1682))+(((-1.0000000008)*x1689))+new_r01);
15186evalcond[5]=((((-1.0)*x1680*x1682))+new_r11+(((1.0000000008)*x1686)));
15187evalcond[6]=((((-1.0)*x1683))+x1688+(((-1.0)*x1690)));
15188evalcond[7]=(x1687+(((-1.0)*x1685))+(((-1.0000000008)*sj3)));
15189evalcond[8]=((((-1.0)*x1682))+(((1.0000000008)*x1688))+(((-1.0000000008)*x1690)));
15190evalcond[9]=((((-1.0)*sj3))+(((-1.0000000008)*x1685))+(((1.0000000008)*x1687)));
15191if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
15192{
15193continue;
15194}
15195}
15196
15197{
15198std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15199vinfos[0].jointtype = 1;
15200vinfos[0].foffset = j0;
15201vinfos[0].indices[0] = _ij0[0];
15202vinfos[0].indices[1] = _ij0[1];
15203vinfos[0].maxsolutions = _nj0;
15204vinfos[1].jointtype = 1;
15205vinfos[1].foffset = j1;
15206vinfos[1].indices[0] = _ij1[0];
15207vinfos[1].indices[1] = _ij1[1];
15208vinfos[1].maxsolutions = _nj1;
15209vinfos[2].jointtype = 1;
15210vinfos[2].foffset = j2;
15211vinfos[2].indices[0] = _ij2[0];
15212vinfos[2].indices[1] = _ij2[1];
15213vinfos[2].maxsolutions = _nj2;
15214vinfos[3].jointtype = 1;
15215vinfos[3].foffset = j3;
15216vinfos[3].indices[0] = _ij3[0];
15217vinfos[3].indices[1] = _ij3[1];
15218vinfos[3].maxsolutions = _nj3;
15219vinfos[4].jointtype = 1;
15220vinfos[4].foffset = j4;
15221vinfos[4].indices[0] = _ij4[0];
15222vinfos[4].indices[1] = _ij4[1];
15223vinfos[4].maxsolutions = _nj4;
15224vinfos[5].jointtype = 1;
15225vinfos[5].foffset = j5;
15226vinfos[5].indices[0] = _ij5[0];
15227vinfos[5].indices[1] = _ij5[1];
15228vinfos[5].maxsolutions = _nj5;
15229std::vector<int> vfree(0);
15230solutions.AddSolution(vinfos,vfree);
15231}
15232}
15233}
15234
15235}
15236
15237}
15238
15239}
15240} while(0);
15241if( bgotonextstatement )
15242{
15243bool bgotonextstatement = true;
15244do
15245{
15246evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14163265358977)+j4)))), 6.28318530717959)));
15247evalcond[1]=new_r02;
15248evalcond[2]=new_r12;
15249evalcond[3]=new_r20;
15250evalcond[4]=new_r21;
15251if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
15252{
15253bgotonextstatement=false;
15254{
15255IkReal j5eval[3];
15256sj4=-4.0e-5;
15257cj4=-1.0;
15258j4=3.14163265;
15259IkReal x1691=((1.0)*new_r00);
15260IkReal x1692=((((-1.0)*new_r11*x1691))+((new_r01*new_r10)));
15261j5eval[0]=x1692;
15262j5eval[1]=IKsign(x1692);
15263j5eval[2]=((IKabs((((new_r11*sj3))+((cj3*new_r10)))))+(IKabs(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x1691))))));
15264if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
15265{
15266{
15267IkReal j5eval[2];
15268sj4=-4.0e-5;
15269cj4=-1.0;
15270j4=3.14163265;
15271j5eval[0]=((((1.0000000008)*new_r00*sj3))+((cj3*new_r10)));
15272j5eval[1]=new_r00;
15273if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
15274{
15275{
15276IkReal j5eval[2];
15277sj4=-4.0e-5;
15278cj4=-1.0;
15279j4=3.14163265;
15280j5eval[0]=new_r00;
15281j5eval[1]=(((new_r00*sj3))+(((1.0000000008)*cj3*new_r10)));
15282if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
15283{
15284{
15285IkReal evalcond[1];
15286bool bgotonextstatement = true;
15287do
15288{
15289IkReal x1694 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
15290if(IKabs(x1694)==0){
15291continue;
15292}
15293IkReal x1693=pow(x1694,-0.5);
15294CheckValue<IkReal> x1695 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15295if(!x1695.valid){
15296continue;
15297}
15298IkReal gconst20=((-1.0)*(x1695.value));
15299IkReal gconst21=((-1.0000000008)*new_r10*x1693);
15300IkReal gconst22=(new_r00*x1693);
15301CheckValue<IkReal> x1696 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15302if(!x1696.valid){
15303continue;
15304}
15305evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1696.value)+j3)))), 6.28318530717959)));
15306if( IKabs(evalcond[0]) < 0.0000050000000000 )
15307{
15308bgotonextstatement=false;
15309{
15310IkReal j5eval[3];
15311IkReal x1697=x1693;
15312sj4=-4.0e-5;
15313cj4=-1.0;
15314j4=3.14163265;
15315sj3=gconst21;
15316cj3=gconst22;
15317CheckValue<IkReal> x1698 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15318if(!x1698.valid){
15319continue;
15320}
15321j3=((-1.0)*(x1698.value));
15322CheckValue<IkReal> x1699 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15323if(!x1699.valid){
15324continue;
15325}
15326IkReal gconst20=((-1.0)*(x1699.value));
15327IkReal gconst21=((-1.0000000008)*new_r10*x1697);
15328IkReal gconst22=(new_r00*x1697);
15329IkReal x1700=new_r00*new_r00;
15330IkReal x1701=(new_r01*new_r10);
15331IkReal x1702=(x1701+(((-1.0)*new_r00*new_r11)));
15332IkReal x1705 = ((((625000000.0)*x1700))+(((625000001.0)*(new_r10*new_r10))));
15333if(IKabs(x1705)==0){
15334continue;
15335}
15336IkReal x1703=pow(x1705,-0.5);
15337IkReal x1704=(new_r10*x1703);
15338j5eval[0]=x1702;
15339j5eval[1]=IKsign(x1702);
15340j5eval[2]=((IKabs(((((25000.0)*new_r00*x1704))+(((-25000.00002)*new_r11*x1704)))))+(IKabs(((((-25000.0)*x1700*x1703))+(((25000.00002)*x1701*x1703))))));
15341if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
15342{
15343{
15344IkReal j5eval[2];
15345IkReal x1706=x1693;
15346sj4=-4.0e-5;
15347cj4=-1.0;
15348j4=3.14163265;
15349sj3=gconst21;
15350cj3=gconst22;
15351CheckValue<IkReal> x1707 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15352if(!x1707.valid){
15353continue;
15354}
15355j3=((-1.0)*(x1707.value));
15356CheckValue<IkReal> x1708 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15357if(!x1708.valid){
15358continue;
15359}
15360IkReal gconst20=((-1.0)*(x1708.value));
15361IkReal gconst21=((-1.0000000008)*new_r10*x1706);
15362IkReal gconst22=(new_r00*x1706);
15363j5eval[0]=new_r00;
15364IkReal x1709 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
15365if(IKabs(x1709)==0){
15366continue;
15367}
15368j5eval[1]=((-1.6e-9)*new_r00*new_r10*(pow(x1709,-0.5)));
15369if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
15370{
15371{
15372IkReal j5eval[1];
15373IkReal x1710=x1693;
15374sj4=-4.0e-5;
15375cj4=-1.0;
15376j4=3.14163265;
15377sj3=gconst21;
15378cj3=gconst22;
15379CheckValue<IkReal> x1711 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15380if(!x1711.valid){
15381continue;
15382}
15383j3=((-1.0)*(x1711.value));
15384CheckValue<IkReal> x1712 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15385if(!x1712.valid){
15386continue;
15387}
15388IkReal gconst20=((-1.0)*(x1712.value));
15389IkReal gconst21=((-1.0000000008)*new_r10*x1710);
15390IkReal gconst22=(new_r00*x1710);
15391j5eval[0]=new_r00;
15392if( IKabs(j5eval[0]) < 0.0000010000000000 )
15393{
15394{
15395IkReal evalcond[1];
15396bool bgotonextstatement = true;
15397do
15398{
15399evalcond[0]=IKabs(new_r00);
15400if( IKabs(evalcond[0]) < 0.0000050000000000 )
15401{
15402bgotonextstatement=false;
15403{
15404IkReal j5eval[1];
15405sj4=-4.0e-5;
15406cj4=-1.0;
15407j4=3.14163265;
15408sj3=gconst21;
15409cj3=gconst22;
15410CheckValue<IkReal> x1713 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15411if(!x1713.valid){
15412continue;
15413}
15414j3=((-1.0)*(x1713.value));
15415new_r00=0;
15416CheckValue<IkReal> x1714 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15417if(!x1714.valid){
15418continue;
15419}
15420IkReal gconst20=((-1.0)*(x1714.value));
15421IkReal x1715 = new_r10*new_r10;
15422if(IKabs(x1715)==0){
15423continue;
15424}
15425IkReal gconst21=((-1.0)*new_r10*(pow(x1715,-0.5)));
15426IkReal gconst22=0;
15427j5eval[0]=new_r10;
15428if( IKabs(j5eval[0]) < 0.0000010000000000 )
15429{
15430{
15431IkReal j5array[1], cj5array[1], sj5array[1];
15432bool j5valid[1]={false};
15433_nj5 = 1;
15434CheckValue<IkReal> x1717=IKPowWithIntegerCheck(gconst21,-1);
15435if(!x1717.valid){
15436continue;
15437}
15438IkReal x1716=x1717.value;
15439if( IKabs(((0.9999999992)*new_r11*x1716)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x1716)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*x1716))+IKsqr(((-1.0)*new_r10*x1716))-1) <= IKFAST_SINCOS_THRESH )
15440 continue;
15441j5array[0]=IKatan2(((0.9999999992)*new_r11*x1716), ((-1.0)*new_r10*x1716));
15442sj5array[0]=IKsin(j5array[0]);
15443cj5array[0]=IKcos(j5array[0]);
15444if( j5array[0] > IKPI )
15445{
15446 j5array[0]-=IK2PI;
15447}
15448else if( j5array[0] < -IKPI )
15449{ j5array[0]+=IK2PI;
15450}
15451j5valid[0] = true;
15452for(int ij5 = 0; ij5 < 1; ++ij5)
15453{
15454if( !j5valid[ij5] )
15455{
15456 continue;
15457}
15458_ij5[0] = ij5; _ij5[1] = -1;
15459for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15460{
15461if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15462{
15463 j5valid[iij5]=false; _ij5[1] = iij5; break;
15464}
15465}
15466j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15467{
15468IkReal evalcond[10];
15469IkReal x1718=IKsin(j5);
15470IkReal x1719=IKcos(j5);
15471IkReal x1720=(new_r10*x1718);
15472IkReal x1721=((1.0000000008)*x1719);
15473IkReal x1722=(new_r11*x1718);
15474IkReal x1723=(gconst21*x1718);
15475evalcond[0]=x1723;
15476evalcond[1]=((-1.0)*x1720);
15477evalcond[2]=(((new_r10*x1719))+gconst21);
15478evalcond[3]=(((gconst21*x1719))+new_r10);
15479evalcond[4]=((1.0000000008)*x1720);
15480evalcond[5]=(((new_r11*x1719))+((new_r01*x1718)));
15481evalcond[6]=(((gconst21*x1721))+new_r01);
15482evalcond[7]=((((-1.0000000008)*x1723))+new_r11);
15483evalcond[8]=(((new_r01*x1719))+(((1.0000000008)*gconst21))+(((-1.0)*x1722)));
15484evalcond[9]=((((-1.0)*new_r01*x1721))+(((1.0000000008)*x1722))+(((-1.0)*gconst21)));
15485if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
15486{
15487continue;
15488}
15489}
15490
15491{
15492std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15493vinfos[0].jointtype = 1;
15494vinfos[0].foffset = j0;
15495vinfos[0].indices[0] = _ij0[0];
15496vinfos[0].indices[1] = _ij0[1];
15497vinfos[0].maxsolutions = _nj0;
15498vinfos[1].jointtype = 1;
15499vinfos[1].foffset = j1;
15500vinfos[1].indices[0] = _ij1[0];
15501vinfos[1].indices[1] = _ij1[1];
15502vinfos[1].maxsolutions = _nj1;
15503vinfos[2].jointtype = 1;
15504vinfos[2].foffset = j2;
15505vinfos[2].indices[0] = _ij2[0];
15506vinfos[2].indices[1] = _ij2[1];
15507vinfos[2].maxsolutions = _nj2;
15508vinfos[3].jointtype = 1;
15509vinfos[3].foffset = j3;
15510vinfos[3].indices[0] = _ij3[0];
15511vinfos[3].indices[1] = _ij3[1];
15512vinfos[3].maxsolutions = _nj3;
15513vinfos[4].jointtype = 1;
15514vinfos[4].foffset = j4;
15515vinfos[4].indices[0] = _ij4[0];
15516vinfos[4].indices[1] = _ij4[1];
15517vinfos[4].maxsolutions = _nj4;
15518vinfos[5].jointtype = 1;
15519vinfos[5].foffset = j5;
15520vinfos[5].indices[0] = _ij5[0];
15521vinfos[5].indices[1] = _ij5[1];
15522vinfos[5].maxsolutions = _nj5;
15523std::vector<int> vfree(0);
15524solutions.AddSolution(vinfos,vfree);
15525}
15526}
15527}
15528
15529} else
15530{
15531{
15532IkReal j5array[1], cj5array[1], sj5array[1];
15533bool j5valid[1]={false};
15534_nj5 = 1;
15535CheckValue<IkReal> x1724=IKPowWithIntegerCheck(gconst21,-1);
15536if(!x1724.valid){
15537continue;
15538}
15539CheckValue<IkReal> x1725=IKPowWithIntegerCheck(new_r10,-1);
15540if(!x1725.valid){
15541continue;
15542}
15543if( IKabs(((0.9999999992)*new_r11*(x1724.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst21*(x1725.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*(x1724.value)))+IKsqr(((-1.0)*gconst21*(x1725.value)))-1) <= IKFAST_SINCOS_THRESH )
15544 continue;
15545j5array[0]=IKatan2(((0.9999999992)*new_r11*(x1724.value)), ((-1.0)*gconst21*(x1725.value)));
15546sj5array[0]=IKsin(j5array[0]);
15547cj5array[0]=IKcos(j5array[0]);
15548if( j5array[0] > IKPI )
15549{
15550 j5array[0]-=IK2PI;
15551}
15552else if( j5array[0] < -IKPI )
15553{ j5array[0]+=IK2PI;
15554}
15555j5valid[0] = true;
15556for(int ij5 = 0; ij5 < 1; ++ij5)
15557{
15558if( !j5valid[ij5] )
15559{
15560 continue;
15561}
15562_ij5[0] = ij5; _ij5[1] = -1;
15563for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15564{
15565if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15566{
15567 j5valid[iij5]=false; _ij5[1] = iij5; break;
15568}
15569}
15570j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15571{
15572IkReal evalcond[10];
15573IkReal x1726=IKsin(j5);
15574IkReal x1727=IKcos(j5);
15575IkReal x1728=(new_r10*x1726);
15576IkReal x1729=((1.0000000008)*x1727);
15577IkReal x1730=(new_r11*x1726);
15578IkReal x1731=(gconst21*x1726);
15579evalcond[0]=x1731;
15580evalcond[1]=((-1.0)*x1728);
15581evalcond[2]=(gconst21+((new_r10*x1727)));
15582evalcond[3]=(((gconst21*x1727))+new_r10);
15583evalcond[4]=((1.0000000008)*x1728);
15584evalcond[5]=(((new_r11*x1727))+((new_r01*x1726)));
15585evalcond[6]=(((gconst21*x1729))+new_r01);
15586evalcond[7]=((((-1.0000000008)*x1731))+new_r11);
15587evalcond[8]=((((1.0000000008)*gconst21))+(((-1.0)*x1730))+((new_r01*x1727)));
15588evalcond[9]=((((-1.0)*new_r01*x1729))+(((1.0000000008)*x1730))+(((-1.0)*gconst21)));
15589if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
15590{
15591continue;
15592}
15593}
15594
15595{
15596std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15597vinfos[0].jointtype = 1;
15598vinfos[0].foffset = j0;
15599vinfos[0].indices[0] = _ij0[0];
15600vinfos[0].indices[1] = _ij0[1];
15601vinfos[0].maxsolutions = _nj0;
15602vinfos[1].jointtype = 1;
15603vinfos[1].foffset = j1;
15604vinfos[1].indices[0] = _ij1[0];
15605vinfos[1].indices[1] = _ij1[1];
15606vinfos[1].maxsolutions = _nj1;
15607vinfos[2].jointtype = 1;
15608vinfos[2].foffset = j2;
15609vinfos[2].indices[0] = _ij2[0];
15610vinfos[2].indices[1] = _ij2[1];
15611vinfos[2].maxsolutions = _nj2;
15612vinfos[3].jointtype = 1;
15613vinfos[3].foffset = j3;
15614vinfos[3].indices[0] = _ij3[0];
15615vinfos[3].indices[1] = _ij3[1];
15616vinfos[3].maxsolutions = _nj3;
15617vinfos[4].jointtype = 1;
15618vinfos[4].foffset = j4;
15619vinfos[4].indices[0] = _ij4[0];
15620vinfos[4].indices[1] = _ij4[1];
15621vinfos[4].maxsolutions = _nj4;
15622vinfos[5].jointtype = 1;
15623vinfos[5].foffset = j5;
15624vinfos[5].indices[0] = _ij5[0];
15625vinfos[5].indices[1] = _ij5[1];
15626vinfos[5].maxsolutions = _nj5;
15627std::vector<int> vfree(0);
15628solutions.AddSolution(vinfos,vfree);
15629}
15630}
15631}
15632
15633}
15634
15635}
15636
15637}
15638} while(0);
15639if( bgotonextstatement )
15640{
15641bool bgotonextstatement = true;
15642do
15643{
15644evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
15645if( IKabs(evalcond[0]) < 0.0000050000000000 )
15646{
15647bgotonextstatement=false;
15648{
15649IkReal j5eval[5];
15650IkReal x1733 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
15651if(IKabs(x1733)==0){
15652continue;
15653}
15654IkReal x1732=pow(x1733,-0.5);
15655sj4=-4.0e-5;
15656cj4=-1.0;
15657j4=3.14163265;
15658sj3=gconst21;
15659cj3=gconst22;
15660CheckValue<IkReal> x1734 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15661if(!x1734.valid){
15662continue;
15663}
15664j3=((-1.0)*(x1734.value));
15665new_r11=0;
15666new_r01=0;
15667new_r22=0;
15668new_r20=0;
15669CheckValue<IkReal> x1735 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15670if(!x1735.valid){
15671continue;
15672}
15673IkReal gconst20=((-1.0)*(x1735.value));
15674IkReal gconst21=((-1.0000000008)*new_r10*x1732);
15675IkReal gconst22=(new_r00*x1732);
15676j5eval[0]=1.0;
15677j5eval[1]=1.0;
15678j5eval[2]=3.90625000625e+17;
15679j5eval[3]=((1.0)+(((1.6e-9)*(new_r10*new_r10))));
15680j5eval[4]=1.0;
15681if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 || IKabs(j5eval[3]) < 0.0000010000000000 || IKabs(j5eval[4]) < 0.0000010000000000 )
15682{
15683{
15684IkReal j5eval[1];
15685IkReal x1737 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
15686if(IKabs(x1737)==0){
15687continue;
15688}
15689IkReal x1736=pow(x1737,-0.5);
15690sj4=-4.0e-5;
15691cj4=-1.0;
15692j4=3.14163265;
15693sj3=gconst21;
15694cj3=gconst22;
15695CheckValue<IkReal> x1738 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15696if(!x1738.valid){
15697continue;
15698}
15699j3=((-1.0)*(x1738.value));
15700new_r11=0;
15701new_r01=0;
15702new_r22=0;
15703new_r20=0;
15704CheckValue<IkReal> x1739 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15705if(!x1739.valid){
15706continue;
15707}
15708IkReal gconst20=((-1.0)*(x1739.value));
15709IkReal gconst21=((-1.0000000008)*new_r10*x1736);
15710IkReal gconst22=(new_r00*x1736);
15711IkReal x1740=new_r10*new_r10;
15712CheckValue<IkReal> x1742=IKPowWithIntegerCheck(((1.0)+(((1.6e-9)*x1740))),-1);
15713if(!x1742.valid){
15714continue;
15715}
15716IkReal x1741=x1742.value;
15717IkReal x1743=((1.0)+(((-1.0)*x1740)));
15718j5eval[0]=IKsign(((((625000002.0)*x1741*(x1740*x1740)))+(((-625000000.0)*x1741*(x1743*x1743)))));
15719if( IKabs(j5eval[0]) < 0.0000010000000000 )
15720{
15721{
15722IkReal j5eval[2];
15723IkReal x1745 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
15724if(IKabs(x1745)==0){
15725continue;
15726}
15727IkReal x1744=pow(x1745,-0.5);
15728sj4=-4.0e-5;
15729cj4=-1.0;
15730j4=3.14163265;
15731sj3=gconst21;
15732cj3=gconst22;
15733CheckValue<IkReal> x1746 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15734if(!x1746.valid){
15735continue;
15736}
15737j3=((-1.0)*(x1746.value));
15738new_r11=0;
15739new_r01=0;
15740new_r22=0;
15741new_r20=0;
15742CheckValue<IkReal> x1747 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
15743if(!x1747.valid){
15744continue;
15745}
15746IkReal gconst20=((-1.0)*(x1747.value));
15747IkReal gconst21=((-1.0000000008)*new_r10*x1744);
15748IkReal gconst22=(new_r00*x1744);
15749IkReal x1748=new_r10*new_r10;
15750IkReal x1749=((1.0)+(((1.6e-9)*x1748)));
15751CheckValue<IkReal> x1750=IKPowWithIntegerCheck(x1749,-1);
15752if(!x1750.valid){
15753continue;
15754}
15755j5eval[0]=((-3.20000000256e-9)*x1748*(x1750.value)*(((1.0)+(((-1.0)*x1748)))));
15756IkReal x1751 = x1749;
15757if(IKabs(x1751)==0){
15758continue;
15759}
15760j5eval[1]=((-1.6e-9)*new_r00*new_r10*(pow(x1751,-0.5)));
15761if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
15762{
15763continue; // 3 cases reached
15764
15765} else
15766{
15767{
15768IkReal j5array[1], cj5array[1], sj5array[1];
15769bool j5valid[1]={false};
15770_nj5 = 1;
15771IkReal x1752=gconst21*gconst21;
15772IkReal x1753=(gconst22*new_r10);
15773CheckValue<IkReal> x1754=IKPowWithIntegerCheck(((((-625000001.0)*x1752*(new_r00*new_r00)))+(((625000000.0)*(x1753*x1753)))),-1);
15774if(!x1754.valid){
15775continue;
15776}
15777CheckValue<IkReal> x1755=IKPowWithIntegerCheck(((((25000.00002)*gconst21*new_r00))+(((25000.0)*x1753))),-1);
15778if(!x1755.valid){
15779continue;
15780}
15781if( IKabs(((x1754.value)*(((((-625000000.5)*x1752*x1753))+(((625000001.0)*new_r00*(gconst21*gconst21*gconst21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-25000.0)*gconst21*gconst22*(x1755.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1754.value)*(((((-625000000.5)*x1752*x1753))+(((625000001.0)*new_r00*(gconst21*gconst21*gconst21)))))))+IKsqr(((-25000.0)*gconst21*gconst22*(x1755.value)))-1) <= IKFAST_SINCOS_THRESH )
15782 continue;
15783j5array[0]=IKatan2(((x1754.value)*(((((-625000000.5)*x1752*x1753))+(((625000001.0)*new_r00*(gconst21*gconst21*gconst21)))))), ((-25000.0)*gconst21*gconst22*(x1755.value)));
15784sj5array[0]=IKsin(j5array[0]);
15785cj5array[0]=IKcos(j5array[0]);
15786if( j5array[0] > IKPI )
15787{
15788 j5array[0]-=IK2PI;
15789}
15790else if( j5array[0] < -IKPI )
15791{ j5array[0]+=IK2PI;
15792}
15793j5valid[0] = true;
15794for(int ij5 = 0; ij5 < 1; ++ij5)
15795{
15796if( !j5valid[ij5] )
15797{
15798 continue;
15799}
15800_ij5[0] = ij5; _ij5[1] = -1;
15801for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15802{
15803if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15804{
15805 j5valid[iij5]=false; _ij5[1] = iij5; break;
15806}
15807}
15808j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15809{
15810IkReal evalcond[7];
15811IkReal x1756=IKcos(j5);
15812IkReal x1757=IKsin(j5);
15813IkReal x1758=((1.0)*gconst22);
15814IkReal x1759=((1.0000000008)*gconst22);
15815IkReal x1760=((1.0000000008)*x1757);
15816IkReal x1761=(gconst21*x1756);
15817IkReal x1762=(new_r00*x1756);
15818evalcond[0]=(gconst21+((new_r00*x1757))+((new_r10*x1756)));
15819evalcond[1]=(((gconst21*x1757))+new_r00+((x1756*x1759)));
15820evalcond[2]=((((-1.0)*x1757*x1759))+x1761+new_r10);
15821evalcond[3]=((((-1.0)*x1757*x1758))+(((1.0000000008)*x1761)));
15822evalcond[4]=((((-1.0)*gconst21*x1760))+(((-1.0)*x1756*x1758)));
15823evalcond[5]=(x1762+x1759+(((-1.0)*new_r10*x1757)));
15824evalcond[6]=((((-1.0000000008)*x1762))+((new_r10*x1760))+(((-1.0)*x1758)));
15825if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
15826{
15827continue;
15828}
15829}
15830
15831{
15832std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15833vinfos[0].jointtype = 1;
15834vinfos[0].foffset = j0;
15835vinfos[0].indices[0] = _ij0[0];
15836vinfos[0].indices[1] = _ij0[1];
15837vinfos[0].maxsolutions = _nj0;
15838vinfos[1].jointtype = 1;
15839vinfos[1].foffset = j1;
15840vinfos[1].indices[0] = _ij1[0];
15841vinfos[1].indices[1] = _ij1[1];
15842vinfos[1].maxsolutions = _nj1;
15843vinfos[2].jointtype = 1;
15844vinfos[2].foffset = j2;
15845vinfos[2].indices[0] = _ij2[0];
15846vinfos[2].indices[1] = _ij2[1];
15847vinfos[2].maxsolutions = _nj2;
15848vinfos[3].jointtype = 1;
15849vinfos[3].foffset = j3;
15850vinfos[3].indices[0] = _ij3[0];
15851vinfos[3].indices[1] = _ij3[1];
15852vinfos[3].maxsolutions = _nj3;
15853vinfos[4].jointtype = 1;
15854vinfos[4].foffset = j4;
15855vinfos[4].indices[0] = _ij4[0];
15856vinfos[4].indices[1] = _ij4[1];
15857vinfos[4].maxsolutions = _nj4;
15858vinfos[5].jointtype = 1;
15859vinfos[5].foffset = j5;
15860vinfos[5].indices[0] = _ij5[0];
15861vinfos[5].indices[1] = _ij5[1];
15862vinfos[5].maxsolutions = _nj5;
15863std::vector<int> vfree(0);
15864solutions.AddSolution(vinfos,vfree);
15865}
15866}
15867}
15868
15869}
15870
15871}
15872
15873} else
15874{
15875{
15876IkReal j5array[1], cj5array[1], sj5array[1];
15877bool j5valid[1]={false};
15878_nj5 = 1;
15879IkReal x1763=gconst22*gconst22;
15880IkReal x1764=gconst21*gconst21;
15881IkReal x1765=((625000000.0)*x1763);
15882IkReal x1766=((625000000.5)*gconst22*x1764);
15883CheckValue<IkReal> x1767 = IKatan2WithCheck(IkReal((((gconst21*new_r00*x1765))+((new_r10*x1766)))),IkReal(((((-625000001.0)*new_r10*(gconst21*gconst21*gconst21)))+(((-1.0)*new_r00*x1766)))),IKFAST_ATAN2_MAGTHRESH);
15884if(!x1767.valid){
15885continue;
15886}
15887CheckValue<IkReal> x1768=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x1764*(new_r10*new_r10)))+(((-1.0)*x1765*(new_r00*new_r00))))),-1);
15888if(!x1768.valid){
15889continue;
15890}
15891j5array[0]=((-1.5707963267949)+(x1767.value)+(((1.5707963267949)*(x1768.value))));
15892sj5array[0]=IKsin(j5array[0]);
15893cj5array[0]=IKcos(j5array[0]);
15894if( j5array[0] > IKPI )
15895{
15896 j5array[0]-=IK2PI;
15897}
15898else if( j5array[0] < -IKPI )
15899{ j5array[0]+=IK2PI;
15900}
15901j5valid[0] = true;
15902for(int ij5 = 0; ij5 < 1; ++ij5)
15903{
15904if( !j5valid[ij5] )
15905{
15906 continue;
15907}
15908_ij5[0] = ij5; _ij5[1] = -1;
15909for(int iij5 = ij5+1; iij5 < 1; ++iij5)
15910{
15911if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
15912{
15913 j5valid[iij5]=false; _ij5[1] = iij5; break;
15914}
15915}
15916j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
15917{
15918IkReal evalcond[7];
15919IkReal x1769=IKcos(j5);
15920IkReal x1770=IKsin(j5);
15921IkReal x1771=((1.0)*gconst22);
15922IkReal x1772=((1.0000000008)*gconst22);
15923IkReal x1773=((1.0000000008)*x1770);
15924IkReal x1774=(gconst21*x1769);
15925IkReal x1775=(new_r00*x1769);
15926evalcond[0]=(((new_r00*x1770))+((new_r10*x1769))+gconst21);
15927evalcond[1]=(new_r00+((gconst21*x1770))+((x1769*x1772)));
15928evalcond[2]=(x1774+(((-1.0)*x1770*x1772))+new_r10);
15929evalcond[3]=((((-1.0)*x1770*x1771))+(((1.0000000008)*x1774)));
15930evalcond[4]=((((-1.0)*gconst21*x1773))+(((-1.0)*x1769*x1771)));
15931evalcond[5]=(x1775+x1772+(((-1.0)*new_r10*x1770)));
15932evalcond[6]=((((-1.0000000008)*x1775))+(((-1.0)*x1771))+((new_r10*x1773)));
15933if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
15934{
15935continue;
15936}
15937}
15938
15939{
15940std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15941vinfos[0].jointtype = 1;
15942vinfos[0].foffset = j0;
15943vinfos[0].indices[0] = _ij0[0];
15944vinfos[0].indices[1] = _ij0[1];
15945vinfos[0].maxsolutions = _nj0;
15946vinfos[1].jointtype = 1;
15947vinfos[1].foffset = j1;
15948vinfos[1].indices[0] = _ij1[0];
15949vinfos[1].indices[1] = _ij1[1];
15950vinfos[1].maxsolutions = _nj1;
15951vinfos[2].jointtype = 1;
15952vinfos[2].foffset = j2;
15953vinfos[2].indices[0] = _ij2[0];
15954vinfos[2].indices[1] = _ij2[1];
15955vinfos[2].maxsolutions = _nj2;
15956vinfos[3].jointtype = 1;
15957vinfos[3].foffset = j3;
15958vinfos[3].indices[0] = _ij3[0];
15959vinfos[3].indices[1] = _ij3[1];
15960vinfos[3].maxsolutions = _nj3;
15961vinfos[4].jointtype = 1;
15962vinfos[4].foffset = j4;
15963vinfos[4].indices[0] = _ij4[0];
15964vinfos[4].indices[1] = _ij4[1];
15965vinfos[4].maxsolutions = _nj4;
15966vinfos[5].jointtype = 1;
15967vinfos[5].foffset = j5;
15968vinfos[5].indices[0] = _ij5[0];
15969vinfos[5].indices[1] = _ij5[1];
15970vinfos[5].maxsolutions = _nj5;
15971std::vector<int> vfree(0);
15972solutions.AddSolution(vinfos,vfree);
15973}
15974}
15975}
15976
15977}
15978
15979}
15980
15981} else
15982{
15983{
15984IkReal j5array[1], cj5array[1], sj5array[1];
15985bool j5valid[1]={false};
15986_nj5 = 1;
15987IkReal x1776=((25000.00002)*gconst22);
15988IkReal x1777=((25000.0)*gconst21);
15989CheckValue<IkReal> x1778=IKPowWithIntegerCheck(IKsign(((((25000.0)*(new_r10*new_r10)))+(((25000.0)*(new_r00*new_r00))))),-1);
15990if(!x1778.valid){
15991continue;
15992}
15993CheckValue<IkReal> x1779 = IKatan2WithCheck(IkReal((((new_r10*x1776))+(((-1.0)*new_r00*x1777)))),IkReal(((((-1.0)*new_r10*x1777))+(((-1.0)*new_r00*x1776)))),IKFAST_ATAN2_MAGTHRESH);
15994if(!x1779.valid){
15995continue;
15996}
15997j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1778.value)))+(x1779.value));
15998sj5array[0]=IKsin(j5array[0]);
15999cj5array[0]=IKcos(j5array[0]);
16000if( j5array[0] > IKPI )
16001{
16002 j5array[0]-=IK2PI;
16003}
16004else if( j5array[0] < -IKPI )
16005{ j5array[0]+=IK2PI;
16006}
16007j5valid[0] = true;
16008for(int ij5 = 0; ij5 < 1; ++ij5)
16009{
16010if( !j5valid[ij5] )
16011{
16012 continue;
16013}
16014_ij5[0] = ij5; _ij5[1] = -1;
16015for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16016{
16017if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16018{
16019 j5valid[iij5]=false; _ij5[1] = iij5; break;
16020}
16021}
16022j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16023{
16024IkReal evalcond[7];
16025IkReal x1780=IKcos(j5);
16026IkReal x1781=IKsin(j5);
16027IkReal x1782=((1.0)*gconst22);
16028IkReal x1783=((1.0000000008)*gconst22);
16029IkReal x1784=((1.0000000008)*x1781);
16030IkReal x1785=(gconst21*x1780);
16031IkReal x1786=(new_r00*x1780);
16032evalcond[0]=(gconst21+((new_r10*x1780))+((new_r00*x1781)));
16033evalcond[1]=(((gconst21*x1781))+new_r00+((x1780*x1783)));
16034evalcond[2]=(x1785+new_r10+(((-1.0)*x1781*x1783)));
16035evalcond[3]=((((1.0000000008)*x1785))+(((-1.0)*x1781*x1782)));
16036evalcond[4]=((((-1.0)*gconst21*x1784))+(((-1.0)*x1780*x1782)));
16037evalcond[5]=(x1783+x1786+(((-1.0)*new_r10*x1781)));
16038evalcond[6]=((((-1.0)*x1782))+((new_r10*x1784))+(((-1.0000000008)*x1786)));
16039if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
16040{
16041continue;
16042}
16043}
16044
16045{
16046std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16047vinfos[0].jointtype = 1;
16048vinfos[0].foffset = j0;
16049vinfos[0].indices[0] = _ij0[0];
16050vinfos[0].indices[1] = _ij0[1];
16051vinfos[0].maxsolutions = _nj0;
16052vinfos[1].jointtype = 1;
16053vinfos[1].foffset = j1;
16054vinfos[1].indices[0] = _ij1[0];
16055vinfos[1].indices[1] = _ij1[1];
16056vinfos[1].maxsolutions = _nj1;
16057vinfos[2].jointtype = 1;
16058vinfos[2].foffset = j2;
16059vinfos[2].indices[0] = _ij2[0];
16060vinfos[2].indices[1] = _ij2[1];
16061vinfos[2].maxsolutions = _nj2;
16062vinfos[3].jointtype = 1;
16063vinfos[3].foffset = j3;
16064vinfos[3].indices[0] = _ij3[0];
16065vinfos[3].indices[1] = _ij3[1];
16066vinfos[3].maxsolutions = _nj3;
16067vinfos[4].jointtype = 1;
16068vinfos[4].foffset = j4;
16069vinfos[4].indices[0] = _ij4[0];
16070vinfos[4].indices[1] = _ij4[1];
16071vinfos[4].maxsolutions = _nj4;
16072vinfos[5].jointtype = 1;
16073vinfos[5].foffset = j5;
16074vinfos[5].indices[0] = _ij5[0];
16075vinfos[5].indices[1] = _ij5[1];
16076vinfos[5].maxsolutions = _nj5;
16077std::vector<int> vfree(0);
16078solutions.AddSolution(vinfos,vfree);
16079}
16080}
16081}
16082
16083}
16084
16085}
16086
16087}
16088} while(0);
16089if( bgotonextstatement )
16090{
16091bool bgotonextstatement = true;
16092do
16093{
16094evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
16095if( IKabs(evalcond[0]) < 0.0000050000000000 )
16096{
16097bgotonextstatement=false;
16098{
16099IkReal j5array[1], cj5array[1], sj5array[1];
16100bool j5valid[1]={false};
16101_nj5 = 1;
16102CheckValue<IkReal> x1788=IKPowWithIntegerCheck(gconst22,-1);
16103if(!x1788.valid){
16104continue;
16105}
16106IkReal x1787=x1788.value;
16107if( IKabs((new_r01*x1787)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r00*x1787)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x1787))+IKsqr(((-0.9999999992)*new_r00*x1787))-1) <= IKFAST_SINCOS_THRESH )
16108 continue;
16109j5array[0]=IKatan2((new_r01*x1787), ((-0.9999999992)*new_r00*x1787));
16110sj5array[0]=IKsin(j5array[0]);
16111cj5array[0]=IKcos(j5array[0]);
16112if( j5array[0] > IKPI )
16113{
16114 j5array[0]-=IK2PI;
16115}
16116else if( j5array[0] < -IKPI )
16117{ j5array[0]+=IK2PI;
16118}
16119j5valid[0] = true;
16120for(int ij5 = 0; ij5 < 1; ++ij5)
16121{
16122if( !j5valid[ij5] )
16123{
16124 continue;
16125}
16126_ij5[0] = ij5; _ij5[1] = -1;
16127for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16128{
16129if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16130{
16131 j5valid[iij5]=false; _ij5[1] = iij5; break;
16132}
16133}
16134j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16135{
16136IkReal evalcond[10];
16137IkReal x1789=IKcos(j5);
16138IkReal x1790=IKsin(j5);
16139IkReal x1791=((1.0)*gconst22);
16140IkReal x1792=(gconst22*x1790);
16141IkReal x1793=(gconst22*x1789);
16142IkReal x1794=(new_r00*x1789);
16143IkReal x1795=(new_r01*x1789);
16144evalcond[0]=(new_r00*x1790);
16145evalcond[1]=x1795;
16146evalcond[2]=((-1.0)*x1793);
16147evalcond[3]=((((-1.0)*x1790*x1791))+new_r01);
16148evalcond[4]=((((-1.0)*x1791))+((new_r01*x1790)));
16149evalcond[5]=((-1.0000000008)*x1792);
16150evalcond[6]=((-1.0000000008)*x1795);
16151evalcond[7]=((((1.0000000008)*x1793))+new_r00);
16152evalcond[8]=(x1794+(((1.0000000008)*gconst22)));
16153evalcond[9]=((((-1.0)*x1791))+(((-1.0000000008)*x1794)));
16154if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16155{
16156continue;
16157}
16158}
16159
16160{
16161std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16162vinfos[0].jointtype = 1;
16163vinfos[0].foffset = j0;
16164vinfos[0].indices[0] = _ij0[0];
16165vinfos[0].indices[1] = _ij0[1];
16166vinfos[0].maxsolutions = _nj0;
16167vinfos[1].jointtype = 1;
16168vinfos[1].foffset = j1;
16169vinfos[1].indices[0] = _ij1[0];
16170vinfos[1].indices[1] = _ij1[1];
16171vinfos[1].maxsolutions = _nj1;
16172vinfos[2].jointtype = 1;
16173vinfos[2].foffset = j2;
16174vinfos[2].indices[0] = _ij2[0];
16175vinfos[2].indices[1] = _ij2[1];
16176vinfos[2].maxsolutions = _nj2;
16177vinfos[3].jointtype = 1;
16178vinfos[3].foffset = j3;
16179vinfos[3].indices[0] = _ij3[0];
16180vinfos[3].indices[1] = _ij3[1];
16181vinfos[3].maxsolutions = _nj3;
16182vinfos[4].jointtype = 1;
16183vinfos[4].foffset = j4;
16184vinfos[4].indices[0] = _ij4[0];
16185vinfos[4].indices[1] = _ij4[1];
16186vinfos[4].maxsolutions = _nj4;
16187vinfos[5].jointtype = 1;
16188vinfos[5].foffset = j5;
16189vinfos[5].indices[0] = _ij5[0];
16190vinfos[5].indices[1] = _ij5[1];
16191vinfos[5].maxsolutions = _nj5;
16192std::vector<int> vfree(0);
16193solutions.AddSolution(vinfos,vfree);
16194}
16195}
16196}
16197
16198}
16199} while(0);
16200if( bgotonextstatement )
16201{
16202bool bgotonextstatement = true;
16203do
16204{
16205if( 1 )
16206{
16207bgotonextstatement=false;
16208continue; // branch miss [j5]
16209
16210}
16211} while(0);
16212if( bgotonextstatement )
16213{
16214}
16215}
16216}
16217}
16218}
16219
16220} else
16221{
16222{
16223IkReal j5array[1], cj5array[1], sj5array[1];
16224bool j5valid[1]={false};
16225_nj5 = 1;
16226CheckValue<IkReal> x1802=IKPowWithIntegerCheck(new_r00,-1);
16227if(!x1802.valid){
16228continue;
16229}
16230IkReal x1796=x1802.value;
16231IkReal x1797=gconst21*gconst21;
16232IkReal x1798=((25000.0)*new_r10);
16233IkReal x1799=((25000.0)*x1797);
16234CheckValue<IkReal> x1803=IKPowWithIntegerCheck(((((-1.0)*gconst21*x1798))+(((25000.00002)*gconst22*new_r00))),-1);
16235if(!x1803.valid){
16236continue;
16237}
16238IkReal x1800=x1803.value;
16239CheckValue<IkReal> x1804=IKPowWithIntegerCheck(((((-25000.0)*gconst21*new_r10))+(((25000.00002)*gconst22*new_r00))),-1);
16240if(!x1804.valid){
16241continue;
16242}
16243IkReal x1801=(x1798*(x1804.value));
16244CheckValue<IkReal> x1805=IKPowWithIntegerCheck(x1796,-2);
16245if(!x1805.valid){
16246continue;
16247}
16248if( IKabs((((new_r00*x1801))+(((-1.0)*gconst21*x1796))+(((-1.0)*x1796*x1797*x1801)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1800*((x1799+(((-25000.0)*(x1805.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r00*x1801))+(((-1.0)*gconst21*x1796))+(((-1.0)*x1796*x1797*x1801))))+IKsqr((x1800*((x1799+(((-25000.0)*(x1805.value)))))))-1) <= IKFAST_SINCOS_THRESH )
16249 continue;
16250j5array[0]=IKatan2((((new_r00*x1801))+(((-1.0)*gconst21*x1796))+(((-1.0)*x1796*x1797*x1801))), (x1800*((x1799+(((-25000.0)*(x1805.value)))))));
16251sj5array[0]=IKsin(j5array[0]);
16252cj5array[0]=IKcos(j5array[0]);
16253if( j5array[0] > IKPI )
16254{
16255 j5array[0]-=IK2PI;
16256}
16257else if( j5array[0] < -IKPI )
16258{ j5array[0]+=IK2PI;
16259}
16260j5valid[0] = true;
16261for(int ij5 = 0; ij5 < 1; ++ij5)
16262{
16263if( !j5valid[ij5] )
16264{
16265 continue;
16266}
16267_ij5[0] = ij5; _ij5[1] = -1;
16268for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16269{
16270if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16271{
16272 j5valid[iij5]=false; _ij5[1] = iij5; break;
16273}
16274}
16275j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16276{
16277IkReal evalcond[10];
16278IkReal x1806=IKcos(j5);
16279IkReal x1807=IKsin(j5);
16280IkReal x1808=((1.0)*gconst22);
16281IkReal x1809=((1.0000000008)*gconst21);
16282IkReal x1810=((1.0000000008)*gconst22);
16283IkReal x1811=(gconst22*x1807);
16284IkReal x1812=(new_r11*x1807);
16285IkReal x1813=(gconst21*x1807);
16286IkReal x1814=(new_r01*x1806);
16287IkReal x1815=(new_r00*x1806);
16288IkReal x1816=(new_r10*x1807);
16289evalcond[0]=(((new_r00*x1807))+gconst21+((new_r10*x1806)));
16290evalcond[1]=((((-1.0)*x1808))+((new_r11*x1806))+((new_r01*x1807)));
16291evalcond[2]=(x1813+new_r00+((x1806*x1810)));
16292evalcond[3]=((((-1.0)*x1807*x1810))+((gconst21*x1806))+new_r10);
16293evalcond[4]=(((x1806*x1809))+new_r01+(((-1.0)*x1807*x1808)));
16294evalcond[5]=((((-1.0)*x1806*x1808))+new_r11+(((-1.0)*x1807*x1809)));
16295evalcond[6]=(x1815+x1810+(((-1.0)*x1816)));
16296evalcond[7]=(x1814+x1809+(((-1.0)*x1812)));
16297evalcond[8]=((((-1.0)*x1808))+(((1.0000000008)*x1816))+(((-1.0000000008)*x1815)));
16298evalcond[9]=((((-1.0)*gconst21))+(((1.0000000008)*x1812))+(((-1.0000000008)*x1814)));
16299if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16300{
16301continue;
16302}
16303}
16304
16305{
16306std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16307vinfos[0].jointtype = 1;
16308vinfos[0].foffset = j0;
16309vinfos[0].indices[0] = _ij0[0];
16310vinfos[0].indices[1] = _ij0[1];
16311vinfos[0].maxsolutions = _nj0;
16312vinfos[1].jointtype = 1;
16313vinfos[1].foffset = j1;
16314vinfos[1].indices[0] = _ij1[0];
16315vinfos[1].indices[1] = _ij1[1];
16316vinfos[1].maxsolutions = _nj1;
16317vinfos[2].jointtype = 1;
16318vinfos[2].foffset = j2;
16319vinfos[2].indices[0] = _ij2[0];
16320vinfos[2].indices[1] = _ij2[1];
16321vinfos[2].maxsolutions = _nj2;
16322vinfos[3].jointtype = 1;
16323vinfos[3].foffset = j3;
16324vinfos[3].indices[0] = _ij3[0];
16325vinfos[3].indices[1] = _ij3[1];
16326vinfos[3].maxsolutions = _nj3;
16327vinfos[4].jointtype = 1;
16328vinfos[4].foffset = j4;
16329vinfos[4].indices[0] = _ij4[0];
16330vinfos[4].indices[1] = _ij4[1];
16331vinfos[4].maxsolutions = _nj4;
16332vinfos[5].jointtype = 1;
16333vinfos[5].foffset = j5;
16334vinfos[5].indices[0] = _ij5[0];
16335vinfos[5].indices[1] = _ij5[1];
16336vinfos[5].maxsolutions = _nj5;
16337std::vector<int> vfree(0);
16338solutions.AddSolution(vinfos,vfree);
16339}
16340}
16341}
16342
16343}
16344
16345}
16346
16347} else
16348{
16349{
16350IkReal j5array[1], cj5array[1], sj5array[1];
16351bool j5valid[1]={false};
16352_nj5 = 1;
16353CheckValue<IkReal> x1822=IKPowWithIntegerCheck(new_r00,-1);
16354if(!x1822.valid){
16355continue;
16356}
16357IkReal x1817=x1822.value;
16358IkReal x1818=(gconst21*x1817);
16359IkReal x1819=((25000.0)*new_r01);
16360IkReal x1820=((25000.0)*gconst22*new_r10);
16361CheckValue<IkReal> x1823=IKPowWithIntegerCheck((x1820+(((25000.00002)*gconst21*new_r00))),-1);
16362if(!x1823.valid){
16363continue;
16364}
16365IkReal x1821=x1823.value;
16366if( IKabs((((new_r10*x1819*x1821))+((x1818*x1820*x1821))+(((-1.0)*x1818)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1821*(((((-25000.0)*gconst21*gconst22))+(((-1.0)*new_r00*x1819)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r10*x1819*x1821))+((x1818*x1820*x1821))+(((-1.0)*x1818))))+IKsqr((x1821*(((((-25000.0)*gconst21*gconst22))+(((-1.0)*new_r00*x1819))))))-1) <= IKFAST_SINCOS_THRESH )
16367 continue;
16368j5array[0]=IKatan2((((new_r10*x1819*x1821))+((x1818*x1820*x1821))+(((-1.0)*x1818))), (x1821*(((((-25000.0)*gconst21*gconst22))+(((-1.0)*new_r00*x1819))))));
16369sj5array[0]=IKsin(j5array[0]);
16370cj5array[0]=IKcos(j5array[0]);
16371if( j5array[0] > IKPI )
16372{
16373 j5array[0]-=IK2PI;
16374}
16375else if( j5array[0] < -IKPI )
16376{ j5array[0]+=IK2PI;
16377}
16378j5valid[0] = true;
16379for(int ij5 = 0; ij5 < 1; ++ij5)
16380{
16381if( !j5valid[ij5] )
16382{
16383 continue;
16384}
16385_ij5[0] = ij5; _ij5[1] = -1;
16386for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16387{
16388if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16389{
16390 j5valid[iij5]=false; _ij5[1] = iij5; break;
16391}
16392}
16393j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16394{
16395IkReal evalcond[10];
16396IkReal x1824=IKcos(j5);
16397IkReal x1825=IKsin(j5);
16398IkReal x1826=((1.0)*gconst22);
16399IkReal x1827=((1.0000000008)*gconst21);
16400IkReal x1828=((1.0000000008)*gconst22);
16401IkReal x1829=(gconst22*x1825);
16402IkReal x1830=(new_r11*x1825);
16403IkReal x1831=(gconst21*x1825);
16404IkReal x1832=(new_r01*x1824);
16405IkReal x1833=(new_r00*x1824);
16406IkReal x1834=(new_r10*x1825);
16407evalcond[0]=(((new_r10*x1824))+((new_r00*x1825))+gconst21);
16408evalcond[1]=((((-1.0)*x1826))+((new_r01*x1825))+((new_r11*x1824)));
16409evalcond[2]=(((x1824*x1828))+x1831+new_r00);
16410evalcond[3]=((((-1.0)*x1825*x1828))+((gconst21*x1824))+new_r10);
16411evalcond[4]=(((x1824*x1827))+(((-1.0)*x1825*x1826))+new_r01);
16412evalcond[5]=((((-1.0)*x1825*x1827))+(((-1.0)*x1824*x1826))+new_r11);
16413evalcond[6]=((((-1.0)*x1834))+x1828+x1833);
16414evalcond[7]=((((-1.0)*x1830))+x1827+x1832);
16415evalcond[8]=((((-1.0)*x1826))+(((1.0000000008)*x1834))+(((-1.0000000008)*x1833)));
16416evalcond[9]=((((1.0000000008)*x1830))+(((-1.0000000008)*x1832))+(((-1.0)*gconst21)));
16417if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16418{
16419continue;
16420}
16421}
16422
16423{
16424std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16425vinfos[0].jointtype = 1;
16426vinfos[0].foffset = j0;
16427vinfos[0].indices[0] = _ij0[0];
16428vinfos[0].indices[1] = _ij0[1];
16429vinfos[0].maxsolutions = _nj0;
16430vinfos[1].jointtype = 1;
16431vinfos[1].foffset = j1;
16432vinfos[1].indices[0] = _ij1[0];
16433vinfos[1].indices[1] = _ij1[1];
16434vinfos[1].maxsolutions = _nj1;
16435vinfos[2].jointtype = 1;
16436vinfos[2].foffset = j2;
16437vinfos[2].indices[0] = _ij2[0];
16438vinfos[2].indices[1] = _ij2[1];
16439vinfos[2].maxsolutions = _nj2;
16440vinfos[3].jointtype = 1;
16441vinfos[3].foffset = j3;
16442vinfos[3].indices[0] = _ij3[0];
16443vinfos[3].indices[1] = _ij3[1];
16444vinfos[3].maxsolutions = _nj3;
16445vinfos[4].jointtype = 1;
16446vinfos[4].foffset = j4;
16447vinfos[4].indices[0] = _ij4[0];
16448vinfos[4].indices[1] = _ij4[1];
16449vinfos[4].maxsolutions = _nj4;
16450vinfos[5].jointtype = 1;
16451vinfos[5].foffset = j5;
16452vinfos[5].indices[0] = _ij5[0];
16453vinfos[5].indices[1] = _ij5[1];
16454vinfos[5].maxsolutions = _nj5;
16455std::vector<int> vfree(0);
16456solutions.AddSolution(vinfos,vfree);
16457}
16458}
16459}
16460
16461}
16462
16463}
16464
16465} else
16466{
16467{
16468IkReal j5array[1], cj5array[1], sj5array[1];
16469bool j5valid[1]={false};
16470_nj5 = 1;
16471IkReal x1835=((1.0)*new_r00);
16472CheckValue<IkReal> x1836=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x1835))+((new_r01*new_r10)))),-1);
16473if(!x1836.valid){
16474continue;
16475}
16476CheckValue<IkReal> x1837 = IKatan2WithCheck(IkReal((((gconst21*new_r11))+((gconst22*new_r10)))),IkReal(((((-1.0)*gconst21*new_r01))+(((-1.0)*gconst22*x1835)))),IKFAST_ATAN2_MAGTHRESH);
16477if(!x1837.valid){
16478continue;
16479}
16480j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1836.value)))+(x1837.value));
16481sj5array[0]=IKsin(j5array[0]);
16482cj5array[0]=IKcos(j5array[0]);
16483if( j5array[0] > IKPI )
16484{
16485 j5array[0]-=IK2PI;
16486}
16487else if( j5array[0] < -IKPI )
16488{ j5array[0]+=IK2PI;
16489}
16490j5valid[0] = true;
16491for(int ij5 = 0; ij5 < 1; ++ij5)
16492{
16493if( !j5valid[ij5] )
16494{
16495 continue;
16496}
16497_ij5[0] = ij5; _ij5[1] = -1;
16498for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16499{
16500if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16501{
16502 j5valid[iij5]=false; _ij5[1] = iij5; break;
16503}
16504}
16505j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16506{
16507IkReal evalcond[10];
16508IkReal x1838=IKcos(j5);
16509IkReal x1839=IKsin(j5);
16510IkReal x1840=((1.0)*gconst22);
16511IkReal x1841=((1.0000000008)*gconst21);
16512IkReal x1842=((1.0000000008)*gconst22);
16513IkReal x1843=(gconst22*x1839);
16514IkReal x1844=(new_r11*x1839);
16515IkReal x1845=(gconst21*x1839);
16516IkReal x1846=(new_r01*x1838);
16517IkReal x1847=(new_r00*x1838);
16518IkReal x1848=(new_r10*x1839);
16519evalcond[0]=(((new_r00*x1839))+gconst21+((new_r10*x1838)));
16520evalcond[1]=(((new_r01*x1839))+(((-1.0)*x1840))+((new_r11*x1838)));
16521evalcond[2]=(((x1838*x1842))+x1845+new_r00);
16522evalcond[3]=((((-1.0)*x1839*x1842))+new_r10+((gconst21*x1838)));
16523evalcond[4]=(((x1838*x1841))+(((-1.0)*x1839*x1840))+new_r01);
16524evalcond[5]=((((-1.0)*x1839*x1841))+new_r11+(((-1.0)*x1838*x1840)));
16525evalcond[6]=(x1842+x1847+(((-1.0)*x1848)));
16526evalcond[7]=(x1841+x1846+(((-1.0)*x1844)));
16527evalcond[8]=((((-1.0000000008)*x1847))+(((-1.0)*x1840))+(((1.0000000008)*x1848)));
16528evalcond[9]=((((-1.0000000008)*x1846))+(((1.0000000008)*x1844))+(((-1.0)*gconst21)));
16529if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16530{
16531continue;
16532}
16533}
16534
16535{
16536std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16537vinfos[0].jointtype = 1;
16538vinfos[0].foffset = j0;
16539vinfos[0].indices[0] = _ij0[0];
16540vinfos[0].indices[1] = _ij0[1];
16541vinfos[0].maxsolutions = _nj0;
16542vinfos[1].jointtype = 1;
16543vinfos[1].foffset = j1;
16544vinfos[1].indices[0] = _ij1[0];
16545vinfos[1].indices[1] = _ij1[1];
16546vinfos[1].maxsolutions = _nj1;
16547vinfos[2].jointtype = 1;
16548vinfos[2].foffset = j2;
16549vinfos[2].indices[0] = _ij2[0];
16550vinfos[2].indices[1] = _ij2[1];
16551vinfos[2].maxsolutions = _nj2;
16552vinfos[3].jointtype = 1;
16553vinfos[3].foffset = j3;
16554vinfos[3].indices[0] = _ij3[0];
16555vinfos[3].indices[1] = _ij3[1];
16556vinfos[3].maxsolutions = _nj3;
16557vinfos[4].jointtype = 1;
16558vinfos[4].foffset = j4;
16559vinfos[4].indices[0] = _ij4[0];
16560vinfos[4].indices[1] = _ij4[1];
16561vinfos[4].maxsolutions = _nj4;
16562vinfos[5].jointtype = 1;
16563vinfos[5].foffset = j5;
16564vinfos[5].indices[0] = _ij5[0];
16565vinfos[5].indices[1] = _ij5[1];
16566vinfos[5].maxsolutions = _nj5;
16567std::vector<int> vfree(0);
16568solutions.AddSolution(vinfos,vfree);
16569}
16570}
16571}
16572
16573}
16574
16575}
16576
16577}
16578} while(0);
16579if( bgotonextstatement )
16580{
16581bool bgotonextstatement = true;
16582do
16583{
16584IkReal x1850 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
16585if(IKabs(x1850)==0){
16586continue;
16587}
16588IkReal x1849=pow(x1850,-0.5);
16589CheckValue<IkReal> x1851 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16590if(!x1851.valid){
16591continue;
16592}
16593IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1851.value))));
16594IkReal gconst24=((1.0000000008)*new_r10*x1849);
16595IkReal gconst25=((-1.0)*new_r00*x1849);
16596CheckValue<IkReal> x1852 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16597if(!x1852.valid){
16598continue;
16599}
16600evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1852.value)+j3)))), 6.28318530717959)));
16601if( IKabs(evalcond[0]) < 0.0000050000000000 )
16602{
16603bgotonextstatement=false;
16604{
16605IkReal j5eval[2];
16606IkReal x1853=x1849;
16607sj4=-4.0e-5;
16608cj4=-1.0;
16609j4=3.14163265;
16610sj3=gconst24;
16611cj3=gconst25;
16612CheckValue<IkReal> x1854 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16613if(!x1854.valid){
16614continue;
16615}
16616j3=((3.14159265)+(((-1.0)*(x1854.value))));
16617CheckValue<IkReal> x1855 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16618if(!x1855.valid){
16619continue;
16620}
16621IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1855.value))));
16622IkReal gconst24=((1.0000000008)*new_r10*x1853);
16623IkReal gconst25=((-1.0)*new_r00*x1853);
16624IkReal x1856=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
16625j5eval[0]=x1856;
16626j5eval[1]=IKsign(x1856);
16627if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
16628{
16629{
16630IkReal j5eval[2];
16631IkReal x1857=x1849;
16632sj4=-4.0e-5;
16633cj4=-1.0;
16634j4=3.14163265;
16635sj3=gconst24;
16636cj3=gconst25;
16637CheckValue<IkReal> x1858 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16638if(!x1858.valid){
16639continue;
16640}
16641j3=((3.14159265)+(((-1.0)*(x1858.value))));
16642CheckValue<IkReal> x1859 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16643if(!x1859.valid){
16644continue;
16645}
16646IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1859.value))));
16647IkReal gconst24=((1.0000000008)*new_r10*x1857);
16648IkReal gconst25=((-1.0)*new_r00*x1857);
16649j5eval[0]=new_r00;
16650IkReal x1860 = ((((1.0000000016)*(new_r10*new_r10)))+(new_r00*new_r00));
16651if(IKabs(x1860)==0){
16652continue;
16653}
16654j5eval[1]=((1.60000013238459e-9)*new_r00*new_r10*(pow(x1860,-0.5)));
16655if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
16656{
16657{
16658IkReal j5eval[1];
16659IkReal x1861=x1849;
16660sj4=-4.0e-5;
16661cj4=-1.0;
16662j4=3.14163265;
16663sj3=gconst24;
16664cj3=gconst25;
16665CheckValue<IkReal> x1862 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16666if(!x1862.valid){
16667continue;
16668}
16669j3=((3.14159265)+(((-1.0)*(x1862.value))));
16670CheckValue<IkReal> x1863 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16671if(!x1863.valid){
16672continue;
16673}
16674IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1863.value))));
16675IkReal gconst24=((1.0000000008)*new_r10*x1861);
16676IkReal gconst25=((-1.0)*new_r00*x1861);
16677j5eval[0]=new_r00;
16678if( IKabs(j5eval[0]) < 0.0000010000000000 )
16679{
16680{
16681IkReal evalcond[1];
16682bool bgotonextstatement = true;
16683do
16684{
16685evalcond[0]=IKabs(new_r00);
16686if( IKabs(evalcond[0]) < 0.0000050000000000 )
16687{
16688bgotonextstatement=false;
16689{
16690IkReal j5eval[1];
16691sj4=-4.0e-5;
16692cj4=-1.0;
16693j4=3.14163265;
16694sj3=gconst24;
16695cj3=gconst25;
16696CheckValue<IkReal> x1864 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
16697if(!x1864.valid){
16698continue;
16699}
16700j3=((3.14159265)+(((-1.0)*(x1864.value))));
16701new_r00=0;
16702CheckValue<IkReal> x1865 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
16703if(!x1865.valid){
16704continue;
16705}
16706IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1865.value))));
16707IkReal x1866 = new_r10*new_r10;
16708if(IKabs(x1866)==0){
16709continue;
16710}
16711IkReal gconst24=((1.0)*new_r10*(pow(x1866,-0.5)));
16712IkReal gconst25=0;
16713j5eval[0]=new_r10;
16714if( IKabs(j5eval[0]) < 0.0000010000000000 )
16715{
16716{
16717IkReal j5array[1], cj5array[1], sj5array[1];
16718bool j5valid[1]={false};
16719_nj5 = 1;
16720CheckValue<IkReal> x1868=IKPowWithIntegerCheck(gconst24,-1);
16721if(!x1868.valid){
16722continue;
16723}
16724IkReal x1867=x1868.value;
16725if( IKabs(((0.9999999992)*new_r11*x1867)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x1867)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*x1867))+IKsqr(((-1.0)*new_r10*x1867))-1) <= IKFAST_SINCOS_THRESH )
16726 continue;
16727j5array[0]=IKatan2(((0.9999999992)*new_r11*x1867), ((-1.0)*new_r10*x1867));
16728sj5array[0]=IKsin(j5array[0]);
16729cj5array[0]=IKcos(j5array[0]);
16730if( j5array[0] > IKPI )
16731{
16732 j5array[0]-=IK2PI;
16733}
16734else if( j5array[0] < -IKPI )
16735{ j5array[0]+=IK2PI;
16736}
16737j5valid[0] = true;
16738for(int ij5 = 0; ij5 < 1; ++ij5)
16739{
16740if( !j5valid[ij5] )
16741{
16742 continue;
16743}
16744_ij5[0] = ij5; _ij5[1] = -1;
16745for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16746{
16747if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16748{
16749 j5valid[iij5]=false; _ij5[1] = iij5; break;
16750}
16751}
16752j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16753{
16754IkReal evalcond[10];
16755IkReal x1869=IKsin(j5);
16756IkReal x1870=IKcos(j5);
16757IkReal x1871=((1.0000000008)*x1869);
16758IkReal x1872=((1.0000000008)*x1870);
16759evalcond[0]=(gconst24*x1869);
16760evalcond[1]=((-1.0)*new_r10*x1869);
16761evalcond[2]=(((new_r10*x1870))+gconst24);
16762evalcond[3]=(((gconst24*x1870))+new_r10);
16763evalcond[4]=(new_r10*x1871);
16764evalcond[5]=(((new_r01*x1869))+((new_r11*x1870)));
16765evalcond[6]=(((gconst24*x1872))+new_r01);
16766evalcond[7]=((((-1.0)*gconst24*x1871))+new_r11);
16767evalcond[8]=((((1.0000000008)*gconst24))+((new_r01*x1870))+(((-1.0)*new_r11*x1869)));
16768evalcond[9]=((((-1.0)*gconst24))+((new_r11*x1871))+(((-1.0)*new_r01*x1872)));
16769if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16770{
16771continue;
16772}
16773}
16774
16775{
16776std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16777vinfos[0].jointtype = 1;
16778vinfos[0].foffset = j0;
16779vinfos[0].indices[0] = _ij0[0];
16780vinfos[0].indices[1] = _ij0[1];
16781vinfos[0].maxsolutions = _nj0;
16782vinfos[1].jointtype = 1;
16783vinfos[1].foffset = j1;
16784vinfos[1].indices[0] = _ij1[0];
16785vinfos[1].indices[1] = _ij1[1];
16786vinfos[1].maxsolutions = _nj1;
16787vinfos[2].jointtype = 1;
16788vinfos[2].foffset = j2;
16789vinfos[2].indices[0] = _ij2[0];
16790vinfos[2].indices[1] = _ij2[1];
16791vinfos[2].maxsolutions = _nj2;
16792vinfos[3].jointtype = 1;
16793vinfos[3].foffset = j3;
16794vinfos[3].indices[0] = _ij3[0];
16795vinfos[3].indices[1] = _ij3[1];
16796vinfos[3].maxsolutions = _nj3;
16797vinfos[4].jointtype = 1;
16798vinfos[4].foffset = j4;
16799vinfos[4].indices[0] = _ij4[0];
16800vinfos[4].indices[1] = _ij4[1];
16801vinfos[4].maxsolutions = _nj4;
16802vinfos[5].jointtype = 1;
16803vinfos[5].foffset = j5;
16804vinfos[5].indices[0] = _ij5[0];
16805vinfos[5].indices[1] = _ij5[1];
16806vinfos[5].maxsolutions = _nj5;
16807std::vector<int> vfree(0);
16808solutions.AddSolution(vinfos,vfree);
16809}
16810}
16811}
16812
16813} else
16814{
16815{
16816IkReal j5array[1], cj5array[1], sj5array[1];
16817bool j5valid[1]={false};
16818_nj5 = 1;
16819CheckValue<IkReal> x1873=IKPowWithIntegerCheck(gconst24,-1);
16820if(!x1873.valid){
16821continue;
16822}
16823CheckValue<IkReal> x1874=IKPowWithIntegerCheck(new_r10,-1);
16824if(!x1874.valid){
16825continue;
16826}
16827if( IKabs(((0.9999999992)*new_r11*(x1873.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst24*(x1874.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*(x1873.value)))+IKsqr(((-1.0)*gconst24*(x1874.value)))-1) <= IKFAST_SINCOS_THRESH )
16828 continue;
16829j5array[0]=IKatan2(((0.9999999992)*new_r11*(x1873.value)), ((-1.0)*gconst24*(x1874.value)));
16830sj5array[0]=IKsin(j5array[0]);
16831cj5array[0]=IKcos(j5array[0]);
16832if( j5array[0] > IKPI )
16833{
16834 j5array[0]-=IK2PI;
16835}
16836else if( j5array[0] < -IKPI )
16837{ j5array[0]+=IK2PI;
16838}
16839j5valid[0] = true;
16840for(int ij5 = 0; ij5 < 1; ++ij5)
16841{
16842if( !j5valid[ij5] )
16843{
16844 continue;
16845}
16846_ij5[0] = ij5; _ij5[1] = -1;
16847for(int iij5 = ij5+1; iij5 < 1; ++iij5)
16848{
16849if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
16850{
16851 j5valid[iij5]=false; _ij5[1] = iij5; break;
16852}
16853}
16854j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
16855{
16856IkReal evalcond[10];
16857IkReal x1875=IKsin(j5);
16858IkReal x1876=IKcos(j5);
16859IkReal x1877=((1.0000000008)*x1875);
16860IkReal x1878=((1.0000000008)*x1876);
16861evalcond[0]=(gconst24*x1875);
16862evalcond[1]=((-1.0)*new_r10*x1875);
16863evalcond[2]=(((new_r10*x1876))+gconst24);
16864evalcond[3]=(((gconst24*x1876))+new_r10);
16865evalcond[4]=(new_r10*x1877);
16866evalcond[5]=(((new_r01*x1875))+((new_r11*x1876)));
16867evalcond[6]=(((gconst24*x1878))+new_r01);
16868evalcond[7]=((((-1.0)*gconst24*x1877))+new_r11);
16869evalcond[8]=((((1.0000000008)*gconst24))+(((-1.0)*new_r11*x1875))+((new_r01*x1876)));
16870evalcond[9]=((((-1.0)*gconst24))+((new_r11*x1877))+(((-1.0)*new_r01*x1878)));
16871if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
16872{
16873continue;
16874}
16875}
16876
16877{
16878std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16879vinfos[0].jointtype = 1;
16880vinfos[0].foffset = j0;
16881vinfos[0].indices[0] = _ij0[0];
16882vinfos[0].indices[1] = _ij0[1];
16883vinfos[0].maxsolutions = _nj0;
16884vinfos[1].jointtype = 1;
16885vinfos[1].foffset = j1;
16886vinfos[1].indices[0] = _ij1[0];
16887vinfos[1].indices[1] = _ij1[1];
16888vinfos[1].maxsolutions = _nj1;
16889vinfos[2].jointtype = 1;
16890vinfos[2].foffset = j2;
16891vinfos[2].indices[0] = _ij2[0];
16892vinfos[2].indices[1] = _ij2[1];
16893vinfos[2].maxsolutions = _nj2;
16894vinfos[3].jointtype = 1;
16895vinfos[3].foffset = j3;
16896vinfos[3].indices[0] = _ij3[0];
16897vinfos[3].indices[1] = _ij3[1];
16898vinfos[3].maxsolutions = _nj3;
16899vinfos[4].jointtype = 1;
16900vinfos[4].foffset = j4;
16901vinfos[4].indices[0] = _ij4[0];
16902vinfos[4].indices[1] = _ij4[1];
16903vinfos[4].maxsolutions = _nj4;
16904vinfos[5].jointtype = 1;
16905vinfos[5].foffset = j5;
16906vinfos[5].indices[0] = _ij5[0];
16907vinfos[5].indices[1] = _ij5[1];
16908vinfos[5].maxsolutions = _nj5;
16909std::vector<int> vfree(0);
16910solutions.AddSolution(vinfos,vfree);
16911}
16912}
16913}
16914
16915}
16916
16917}
16918
16919}
16920} while(0);
16921if( bgotonextstatement )
16922{
16923bool bgotonextstatement = true;
16924do
16925{
16926evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
16927if( IKabs(evalcond[0]) < 0.0000050000000000 )
16928{
16929bgotonextstatement=false;
16930{
16931IkReal j5eval[3];
16932IkReal x1880 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
16933if(IKabs(x1880)==0){
16934continue;
16935}
16936IkReal x1879=pow(x1880,-0.5);
16937sj4=-4.0e-5;
16938cj4=-1.0;
16939j4=3.14163265;
16940sj3=gconst24;
16941cj3=gconst25;
16942CheckValue<IkReal> x1881 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16943if(!x1881.valid){
16944continue;
16945}
16946j3=((3.14159265)+(((-1.0)*(x1881.value))));
16947new_r11=0;
16948new_r01=0;
16949new_r22=0;
16950new_r20=0;
16951CheckValue<IkReal> x1882 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16952if(!x1882.valid){
16953continue;
16954}
16955IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1882.value))));
16956IkReal gconst24=((1.0000000008)*new_r10*x1879);
16957IkReal gconst25=((-1.0)*new_r00*x1879);
16958IkReal x1883=new_r10*new_r10;
16959CheckValue<IkReal> x1887=IKPowWithIntegerCheck(((625000000.0)+(((1.0)*x1883))),-1);
16960if(!x1887.valid){
16961continue;
16962}
16963IkReal x1884=x1887.value;
16964if((((625000000.0)+x1883)) < -0.00001)
16965continue;
16966IkReal x1885=IKsqrt(((625000000.0)+x1883));
16967IkReal x1886=(x1884*x1885);
16968j5eval[0]=1.0;
16969j5eval[1]=1.0;
16970IkReal x1888 = ((1.0)+(((1.6e-9)*x1883)));
16971if(IKabs(x1888)==0){
16972continue;
16973}
16974j5eval[2]=((IKabs(((((-1250000001.0)*x1883*x1886))+(((625000000.5)*x1886)))))+(IKabs(((50000.00004)*new_r00*new_r10*(pow(x1888,-0.5))))));
16975if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
16976{
16977{
16978IkReal j5eval[1];
16979IkReal x1890 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
16980if(IKabs(x1890)==0){
16981continue;
16982}
16983IkReal x1889=pow(x1890,-0.5);
16984sj4=-4.0e-5;
16985cj4=-1.0;
16986j4=3.14163265;
16987sj3=gconst24;
16988cj3=gconst25;
16989CheckValue<IkReal> x1891 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16990if(!x1891.valid){
16991continue;
16992}
16993j3=((3.14159265)+(((-1.0)*(x1891.value))));
16994new_r11=0;
16995new_r01=0;
16996new_r22=0;
16997new_r20=0;
16998CheckValue<IkReal> x1892 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
16999if(!x1892.valid){
17000continue;
17001}
17002IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1892.value))));
17003IkReal gconst24=((1.0000000008)*new_r10*x1889);
17004IkReal gconst25=((-1.0)*new_r00*x1889);
17005IkReal x1893=new_r10*new_r10;
17006CheckValue<IkReal> x1895=IKPowWithIntegerCheck(((1.0)+(((1.6e-9)*x1893))),-1);
17007if(!x1895.valid){
17008continue;
17009}
17010IkReal x1894=x1895.value;
17011IkReal x1896=((1.0)+(((-1.0)*x1893)));
17012j5eval[0]=IKsign(((((-625000000.0)*x1894*(x1896*x1896)))+(((625000002.0)*x1894*(x1893*x1893)))));
17013if( IKabs(j5eval[0]) < 0.0000010000000000 )
17014{
17015{
17016IkReal j5eval[2];
17017IkReal x1898 = ((1.0)+(((1.6e-9)*(new_r10*new_r10))));
17018if(IKabs(x1898)==0){
17019continue;
17020}
17021IkReal x1897=pow(x1898,-0.5);
17022sj4=-4.0e-5;
17023cj4=-1.0;
17024j4=3.14163265;
17025sj3=gconst24;
17026cj3=gconst25;
17027CheckValue<IkReal> x1899 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
17028if(!x1899.valid){
17029continue;
17030}
17031j3=((3.14159265)+(((-1.0)*(x1899.value))));
17032new_r11=0;
17033new_r01=0;
17034new_r22=0;
17035new_r20=0;
17036CheckValue<IkReal> x1900 = IKatan2WithCheck(IkReal(((1.0000000008)*new_r10)),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
17037if(!x1900.valid){
17038continue;
17039}
17040IkReal gconst23=((3.14159265358979)+(((-1.0)*(x1900.value))));
17041IkReal gconst24=((1.0000000008)*new_r10*x1897);
17042IkReal gconst25=((-1.0)*new_r00*x1897);
17043IkReal x1901=new_r10*new_r10;
17044IkReal x1902=((1.0)+(((1.6e-9)*x1901)));
17045CheckValue<IkReal> x1903=IKPowWithIntegerCheck(x1902,-1);
17046if(!x1903.valid){
17047continue;
17048}
17049j5eval[0]=((-3.20000004272458e-9)*x1901*(x1903.value)*(((1.0)+(((-1.0)*x1901)))));
17050IkReal x1904 = x1902;
17051if(IKabs(x1904)==0){
17052continue;
17053}
17054j5eval[1]=((1.60000013238459e-9)*new_r00*new_r10*(pow(x1904,-0.5)));
17055if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
17056{
17057continue; // 3 cases reached
17058
17059} else
17060{
17061{
17062IkReal j5array[1], cj5array[1], sj5array[1];
17063bool j5valid[1]={false};
17064_nj5 = 1;
17065IkReal x1905=gconst24*gconst24;
17066IkReal x1906=(gconst25*new_r10);
17067CheckValue<IkReal> x1907=IKPowWithIntegerCheck(((((625000000.0)*(x1906*x1906)))+(((-625000001.0)*x1905*(new_r00*new_r00)))),-1);
17068if(!x1907.valid){
17069continue;
17070}
17071CheckValue<IkReal> x1908=IKPowWithIntegerCheck(((((25000.0)*x1906))+(((25000.00002)*gconst24*new_r00))),-1);
17072if(!x1908.valid){
17073continue;
17074}
17075if( IKabs(((x1907.value)*(((((-625000000.5)*x1905*x1906))+(((625000001.0)*new_r00*(gconst24*gconst24*gconst24))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-25000.0)*gconst24*gconst25*(x1908.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x1907.value)*(((((-625000000.5)*x1905*x1906))+(((625000001.0)*new_r00*(gconst24*gconst24*gconst24)))))))+IKsqr(((-25000.0)*gconst24*gconst25*(x1908.value)))-1) <= IKFAST_SINCOS_THRESH )
17076 continue;
17077j5array[0]=IKatan2(((x1907.value)*(((((-625000000.5)*x1905*x1906))+(((625000001.0)*new_r00*(gconst24*gconst24*gconst24)))))), ((-25000.0)*gconst24*gconst25*(x1908.value)));
17078sj5array[0]=IKsin(j5array[0]);
17079cj5array[0]=IKcos(j5array[0]);
17080if( j5array[0] > IKPI )
17081{
17082 j5array[0]-=IK2PI;
17083}
17084else if( j5array[0] < -IKPI )
17085{ j5array[0]+=IK2PI;
17086}
17087j5valid[0] = true;
17088for(int ij5 = 0; ij5 < 1; ++ij5)
17089{
17090if( !j5valid[ij5] )
17091{
17092 continue;
17093}
17094_ij5[0] = ij5; _ij5[1] = -1;
17095for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17096{
17097if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17098{
17099 j5valid[iij5]=false; _ij5[1] = iij5; break;
17100}
17101}
17102j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17103{
17104IkReal evalcond[7];
17105IkReal x1909=IKsin(j5);
17106IkReal x1910=IKcos(j5);
17107IkReal x1911=((1.0)*gconst25);
17108IkReal x1912=((1.0000000008)*x1909);
17109IkReal x1913=((1.0000000008)*x1910);
17110evalcond[0]=(gconst24+((new_r10*x1910))+((new_r00*x1909)));
17111evalcond[1]=(((gconst24*x1909))+((gconst25*x1913))+new_r00);
17112evalcond[2]=((((-1.0)*gconst25*x1912))+((gconst24*x1910))+new_r10);
17113evalcond[3]=(((gconst24*x1913))+(((-1.0)*x1909*x1911)));
17114evalcond[4]=((((-1.0)*x1910*x1911))+(((-1.0)*gconst24*x1912)));
17115evalcond[5]=((((1.0000000008)*gconst25))+(((-1.0)*new_r10*x1909))+((new_r00*x1910)));
17116evalcond[6]=((((-1.0)*new_r00*x1913))+((new_r10*x1912))+(((-1.0)*x1911)));
17117if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
17118{
17119continue;
17120}
17121}
17122
17123{
17124std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17125vinfos[0].jointtype = 1;
17126vinfos[0].foffset = j0;
17127vinfos[0].indices[0] = _ij0[0];
17128vinfos[0].indices[1] = _ij0[1];
17129vinfos[0].maxsolutions = _nj0;
17130vinfos[1].jointtype = 1;
17131vinfos[1].foffset = j1;
17132vinfos[1].indices[0] = _ij1[0];
17133vinfos[1].indices[1] = _ij1[1];
17134vinfos[1].maxsolutions = _nj1;
17135vinfos[2].jointtype = 1;
17136vinfos[2].foffset = j2;
17137vinfos[2].indices[0] = _ij2[0];
17138vinfos[2].indices[1] = _ij2[1];
17139vinfos[2].maxsolutions = _nj2;
17140vinfos[3].jointtype = 1;
17141vinfos[3].foffset = j3;
17142vinfos[3].indices[0] = _ij3[0];
17143vinfos[3].indices[1] = _ij3[1];
17144vinfos[3].maxsolutions = _nj3;
17145vinfos[4].jointtype = 1;
17146vinfos[4].foffset = j4;
17147vinfos[4].indices[0] = _ij4[0];
17148vinfos[4].indices[1] = _ij4[1];
17149vinfos[4].maxsolutions = _nj4;
17150vinfos[5].jointtype = 1;
17151vinfos[5].foffset = j5;
17152vinfos[5].indices[0] = _ij5[0];
17153vinfos[5].indices[1] = _ij5[1];
17154vinfos[5].maxsolutions = _nj5;
17155std::vector<int> vfree(0);
17156solutions.AddSolution(vinfos,vfree);
17157}
17158}
17159}
17160
17161}
17162
17163}
17164
17165} else
17166{
17167{
17168IkReal j5array[1], cj5array[1], sj5array[1];
17169bool j5valid[1]={false};
17170_nj5 = 1;
17171IkReal x1914=gconst25*gconst25;
17172IkReal x1915=gconst24*gconst24;
17173IkReal x1916=((625000000.0)*x1914);
17174IkReal x1917=((625000000.5)*gconst25*x1915);
17175CheckValue<IkReal> x1918 = IKatan2WithCheck(IkReal((((new_r10*x1917))+((gconst24*new_r00*x1916)))),IkReal(((((-625000001.0)*new_r10*(gconst24*gconst24*gconst24)))+(((-1.0)*new_r00*x1917)))),IKFAST_ATAN2_MAGTHRESH);
17176if(!x1918.valid){
17177continue;
17178}
17179CheckValue<IkReal> x1919=IKPowWithIntegerCheck(IKsign(((((-1.0)*x1916*(new_r00*new_r00)))+(((625000001.0)*x1915*(new_r10*new_r10))))),-1);
17180if(!x1919.valid){
17181continue;
17182}
17183j5array[0]=((-1.5707963267949)+(x1918.value)+(((1.5707963267949)*(x1919.value))));
17184sj5array[0]=IKsin(j5array[0]);
17185cj5array[0]=IKcos(j5array[0]);
17186if( j5array[0] > IKPI )
17187{
17188 j5array[0]-=IK2PI;
17189}
17190else if( j5array[0] < -IKPI )
17191{ j5array[0]+=IK2PI;
17192}
17193j5valid[0] = true;
17194for(int ij5 = 0; ij5 < 1; ++ij5)
17195{
17196if( !j5valid[ij5] )
17197{
17198 continue;
17199}
17200_ij5[0] = ij5; _ij5[1] = -1;
17201for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17202{
17203if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17204{
17205 j5valid[iij5]=false; _ij5[1] = iij5; break;
17206}
17207}
17208j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17209{
17210IkReal evalcond[7];
17211IkReal x1920=IKsin(j5);
17212IkReal x1921=IKcos(j5);
17213IkReal x1922=((1.0)*gconst25);
17214IkReal x1923=((1.0000000008)*x1920);
17215IkReal x1924=((1.0000000008)*x1921);
17216evalcond[0]=(gconst24+((new_r00*x1920))+((new_r10*x1921)));
17217evalcond[1]=(((gconst25*x1924))+((gconst24*x1920))+new_r00);
17218evalcond[2]=((((-1.0)*gconst25*x1923))+((gconst24*x1921))+new_r10);
17219evalcond[3]=(((gconst24*x1924))+(((-1.0)*x1920*x1922)));
17220evalcond[4]=((((-1.0)*gconst24*x1923))+(((-1.0)*x1921*x1922)));
17221evalcond[5]=((((1.0000000008)*gconst25))+((new_r00*x1921))+(((-1.0)*new_r10*x1920)));
17222evalcond[6]=((((-1.0)*x1922))+((new_r10*x1923))+(((-1.0)*new_r00*x1924)));
17223if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
17224{
17225continue;
17226}
17227}
17228
17229{
17230std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17231vinfos[0].jointtype = 1;
17232vinfos[0].foffset = j0;
17233vinfos[0].indices[0] = _ij0[0];
17234vinfos[0].indices[1] = _ij0[1];
17235vinfos[0].maxsolutions = _nj0;
17236vinfos[1].jointtype = 1;
17237vinfos[1].foffset = j1;
17238vinfos[1].indices[0] = _ij1[0];
17239vinfos[1].indices[1] = _ij1[1];
17240vinfos[1].maxsolutions = _nj1;
17241vinfos[2].jointtype = 1;
17242vinfos[2].foffset = j2;
17243vinfos[2].indices[0] = _ij2[0];
17244vinfos[2].indices[1] = _ij2[1];
17245vinfos[2].maxsolutions = _nj2;
17246vinfos[3].jointtype = 1;
17247vinfos[3].foffset = j3;
17248vinfos[3].indices[0] = _ij3[0];
17249vinfos[3].indices[1] = _ij3[1];
17250vinfos[3].maxsolutions = _nj3;
17251vinfos[4].jointtype = 1;
17252vinfos[4].foffset = j4;
17253vinfos[4].indices[0] = _ij4[0];
17254vinfos[4].indices[1] = _ij4[1];
17255vinfos[4].maxsolutions = _nj4;
17256vinfos[5].jointtype = 1;
17257vinfos[5].foffset = j5;
17258vinfos[5].indices[0] = _ij5[0];
17259vinfos[5].indices[1] = _ij5[1];
17260vinfos[5].maxsolutions = _nj5;
17261std::vector<int> vfree(0);
17262solutions.AddSolution(vinfos,vfree);
17263}
17264}
17265}
17266
17267}
17268
17269}
17270
17271} else
17272{
17273{
17274IkReal j5array[1], cj5array[1], sj5array[1];
17275bool j5valid[1]={false};
17276_nj5 = 1;
17277IkReal x1925=((25000.00002)*gconst25);
17278IkReal x1926=((25000.0)*gconst24);
17279CheckValue<IkReal> x1927 = IKatan2WithCheck(IkReal((((new_r10*x1925))+(((-1.0)*new_r00*x1926)))),IkReal(((((-1.0)*new_r10*x1926))+(((-1.0)*new_r00*x1925)))),IKFAST_ATAN2_MAGTHRESH);
17280if(!x1927.valid){
17281continue;
17282}
17283CheckValue<IkReal> x1928=IKPowWithIntegerCheck(IKsign(((((25000.0)*(new_r10*new_r10)))+(((25000.0)*(new_r00*new_r00))))),-1);
17284if(!x1928.valid){
17285continue;
17286}
17287j5array[0]=((-1.5707963267949)+(x1927.value)+(((1.5707963267949)*(x1928.value))));
17288sj5array[0]=IKsin(j5array[0]);
17289cj5array[0]=IKcos(j5array[0]);
17290if( j5array[0] > IKPI )
17291{
17292 j5array[0]-=IK2PI;
17293}
17294else if( j5array[0] < -IKPI )
17295{ j5array[0]+=IK2PI;
17296}
17297j5valid[0] = true;
17298for(int ij5 = 0; ij5 < 1; ++ij5)
17299{
17300if( !j5valid[ij5] )
17301{
17302 continue;
17303}
17304_ij5[0] = ij5; _ij5[1] = -1;
17305for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17306{
17307if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17308{
17309 j5valid[iij5]=false; _ij5[1] = iij5; break;
17310}
17311}
17312j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17313{
17314IkReal evalcond[7];
17315IkReal x1929=IKsin(j5);
17316IkReal x1930=IKcos(j5);
17317IkReal x1931=((1.0)*gconst25);
17318IkReal x1932=((1.0000000008)*x1929);
17319IkReal x1933=((1.0000000008)*x1930);
17320evalcond[0]=(gconst24+((new_r10*x1930))+((new_r00*x1929)));
17321evalcond[1]=(((gconst24*x1929))+((gconst25*x1933))+new_r00);
17322evalcond[2]=((((-1.0)*gconst25*x1932))+((gconst24*x1930))+new_r10);
17323evalcond[3]=(((gconst24*x1933))+(((-1.0)*x1929*x1931)));
17324evalcond[4]=((((-1.0)*x1930*x1931))+(((-1.0)*gconst24*x1932)));
17325evalcond[5]=((((1.0000000008)*gconst25))+((new_r00*x1930))+(((-1.0)*new_r10*x1929)));
17326evalcond[6]=((((-1.0)*new_r00*x1933))+((new_r10*x1932))+(((-1.0)*x1931)));
17327if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
17328{
17329continue;
17330}
17331}
17332
17333{
17334std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17335vinfos[0].jointtype = 1;
17336vinfos[0].foffset = j0;
17337vinfos[0].indices[0] = _ij0[0];
17338vinfos[0].indices[1] = _ij0[1];
17339vinfos[0].maxsolutions = _nj0;
17340vinfos[1].jointtype = 1;
17341vinfos[1].foffset = j1;
17342vinfos[1].indices[0] = _ij1[0];
17343vinfos[1].indices[1] = _ij1[1];
17344vinfos[1].maxsolutions = _nj1;
17345vinfos[2].jointtype = 1;
17346vinfos[2].foffset = j2;
17347vinfos[2].indices[0] = _ij2[0];
17348vinfos[2].indices[1] = _ij2[1];
17349vinfos[2].maxsolutions = _nj2;
17350vinfos[3].jointtype = 1;
17351vinfos[3].foffset = j3;
17352vinfos[3].indices[0] = _ij3[0];
17353vinfos[3].indices[1] = _ij3[1];
17354vinfos[3].maxsolutions = _nj3;
17355vinfos[4].jointtype = 1;
17356vinfos[4].foffset = j4;
17357vinfos[4].indices[0] = _ij4[0];
17358vinfos[4].indices[1] = _ij4[1];
17359vinfos[4].maxsolutions = _nj4;
17360vinfos[5].jointtype = 1;
17361vinfos[5].foffset = j5;
17362vinfos[5].indices[0] = _ij5[0];
17363vinfos[5].indices[1] = _ij5[1];
17364vinfos[5].maxsolutions = _nj5;
17365std::vector<int> vfree(0);
17366solutions.AddSolution(vinfos,vfree);
17367}
17368}
17369}
17370
17371}
17372
17373}
17374
17375}
17376} while(0);
17377if( bgotonextstatement )
17378{
17379bool bgotonextstatement = true;
17380do
17381{
17382evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
17383if( IKabs(evalcond[0]) < 0.0000050000000000 )
17384{
17385bgotonextstatement=false;
17386{
17387IkReal j5array[1], cj5array[1], sj5array[1];
17388bool j5valid[1]={false};
17389_nj5 = 1;
17390CheckValue<IkReal> x1935=IKPowWithIntegerCheck(gconst25,-1);
17391if(!x1935.valid){
17392continue;
17393}
17394IkReal x1934=x1935.value;
17395if( IKabs((new_r01*x1934)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r00*x1934)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x1934))+IKsqr(((-0.9999999992)*new_r00*x1934))-1) <= IKFAST_SINCOS_THRESH )
17396 continue;
17397j5array[0]=IKatan2((new_r01*x1934), ((-0.9999999992)*new_r00*x1934));
17398sj5array[0]=IKsin(j5array[0]);
17399cj5array[0]=IKcos(j5array[0]);
17400if( j5array[0] > IKPI )
17401{
17402 j5array[0]-=IK2PI;
17403}
17404else if( j5array[0] < -IKPI )
17405{ j5array[0]+=IK2PI;
17406}
17407j5valid[0] = true;
17408for(int ij5 = 0; ij5 < 1; ++ij5)
17409{
17410if( !j5valid[ij5] )
17411{
17412 continue;
17413}
17414_ij5[0] = ij5; _ij5[1] = -1;
17415for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17416{
17417if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17418{
17419 j5valid[iij5]=false; _ij5[1] = iij5; break;
17420}
17421}
17422j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17423{
17424IkReal evalcond[10];
17425IkReal x1936=IKcos(j5);
17426IkReal x1937=IKsin(j5);
17427IkReal x1938=((1.0)*gconst25);
17428IkReal x1939=(gconst25*x1936);
17429IkReal x1940=(new_r00*x1936);
17430IkReal x1941=(new_r01*x1936);
17431evalcond[0]=(new_r00*x1937);
17432evalcond[1]=x1941;
17433evalcond[2]=((-1.0)*x1939);
17434evalcond[3]=((((-1.0)*x1937*x1938))+new_r01);
17435evalcond[4]=(((new_r01*x1937))+(((-1.0)*x1938)));
17436evalcond[5]=((-1.0000000008)*gconst25*x1937);
17437evalcond[6]=((-1.0000000008)*x1941);
17438evalcond[7]=((((1.0000000008)*x1939))+new_r00);
17439evalcond[8]=((((1.0000000008)*gconst25))+x1940);
17440evalcond[9]=((((-1.0000000008)*x1940))+(((-1.0)*x1938)));
17441if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
17442{
17443continue;
17444}
17445}
17446
17447{
17448std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17449vinfos[0].jointtype = 1;
17450vinfos[0].foffset = j0;
17451vinfos[0].indices[0] = _ij0[0];
17452vinfos[0].indices[1] = _ij0[1];
17453vinfos[0].maxsolutions = _nj0;
17454vinfos[1].jointtype = 1;
17455vinfos[1].foffset = j1;
17456vinfos[1].indices[0] = _ij1[0];
17457vinfos[1].indices[1] = _ij1[1];
17458vinfos[1].maxsolutions = _nj1;
17459vinfos[2].jointtype = 1;
17460vinfos[2].foffset = j2;
17461vinfos[2].indices[0] = _ij2[0];
17462vinfos[2].indices[1] = _ij2[1];
17463vinfos[2].maxsolutions = _nj2;
17464vinfos[3].jointtype = 1;
17465vinfos[3].foffset = j3;
17466vinfos[3].indices[0] = _ij3[0];
17467vinfos[3].indices[1] = _ij3[1];
17468vinfos[3].maxsolutions = _nj3;
17469vinfos[4].jointtype = 1;
17470vinfos[4].foffset = j4;
17471vinfos[4].indices[0] = _ij4[0];
17472vinfos[4].indices[1] = _ij4[1];
17473vinfos[4].maxsolutions = _nj4;
17474vinfos[5].jointtype = 1;
17475vinfos[5].foffset = j5;
17476vinfos[5].indices[0] = _ij5[0];
17477vinfos[5].indices[1] = _ij5[1];
17478vinfos[5].maxsolutions = _nj5;
17479std::vector<int> vfree(0);
17480solutions.AddSolution(vinfos,vfree);
17481}
17482}
17483}
17484
17485}
17486} while(0);
17487if( bgotonextstatement )
17488{
17489bool bgotonextstatement = true;
17490do
17491{
17492if( 1 )
17493{
17494bgotonextstatement=false;
17495continue; // branch miss [j5]
17496
17497}
17498} while(0);
17499if( bgotonextstatement )
17500{
17501}
17502}
17503}
17504}
17505}
17506
17507} else
17508{
17509{
17510IkReal j5array[1], cj5array[1], sj5array[1];
17511bool j5valid[1]={false};
17512_nj5 = 1;
17513CheckValue<IkReal> x1946=IKPowWithIntegerCheck(new_r00,-1);
17514if(!x1946.valid){
17515continue;
17516}
17517IkReal x1942=x1946.value;
17518IkReal x1943=gconst24*gconst24;
17519IkReal x1944=((25000.0)*new_r10);
17520CheckValue<IkReal> x1947=IKPowWithIntegerCheck(((((-1.0)*gconst24*x1944))+(((25000.00002)*gconst25*new_r00))),-1);
17521if(!x1947.valid){
17522continue;
17523}
17524IkReal x1945=x1947.value;
17525CheckValue<IkReal> x1948=IKPowWithIntegerCheck(((((-25000.0)*gconst24*new_r10))+(((25000.00002)*gconst25*new_r00))),-1);
17526if(!x1948.valid){
17527continue;
17528}
17529CheckValue<IkReal> x1949=IKPowWithIntegerCheck(((((-25000.0)*gconst24*new_r10))+(((25000.00002)*gconst25*new_r00))),-1);
17530if(!x1949.valid){
17531continue;
17532}
17533CheckValue<IkReal> x1950=IKPowWithIntegerCheck(x1942,-2);
17534if(!x1950.valid){
17535continue;
17536}
17537if( IKabs(((((-1.0)*gconst24*x1942))+((new_r00*x1944*(x1948.value)))+(((-1.0)*x1942*x1943*x1944*(x1949.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1945*(((((25000.0)*x1943))+(((-25000.0)*(x1950.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*gconst24*x1942))+((new_r00*x1944*(x1948.value)))+(((-1.0)*x1942*x1943*x1944*(x1949.value)))))+IKsqr((x1945*(((((25000.0)*x1943))+(((-25000.0)*(x1950.value)))))))-1) <= IKFAST_SINCOS_THRESH )
17538 continue;
17539j5array[0]=IKatan2(((((-1.0)*gconst24*x1942))+((new_r00*x1944*(x1948.value)))+(((-1.0)*x1942*x1943*x1944*(x1949.value)))), (x1945*(((((25000.0)*x1943))+(((-25000.0)*(x1950.value)))))));
17540sj5array[0]=IKsin(j5array[0]);
17541cj5array[0]=IKcos(j5array[0]);
17542if( j5array[0] > IKPI )
17543{
17544 j5array[0]-=IK2PI;
17545}
17546else if( j5array[0] < -IKPI )
17547{ j5array[0]+=IK2PI;
17548}
17549j5valid[0] = true;
17550for(int ij5 = 0; ij5 < 1; ++ij5)
17551{
17552if( !j5valid[ij5] )
17553{
17554 continue;
17555}
17556_ij5[0] = ij5; _ij5[1] = -1;
17557for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17558{
17559if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17560{
17561 j5valid[iij5]=false; _ij5[1] = iij5; break;
17562}
17563}
17564j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17565{
17566IkReal evalcond[10];
17567IkReal x1951=IKcos(j5);
17568IkReal x1952=IKsin(j5);
17569IkReal x1953=((1.0)*gconst25);
17570IkReal x1954=((1.0000000008)*gconst25);
17571IkReal x1955=((1.0000000008)*gconst24);
17572IkReal x1956=(new_r11*x1952);
17573IkReal x1957=(new_r01*x1951);
17574IkReal x1958=(new_r00*x1951);
17575IkReal x1959=(new_r10*x1952);
17576evalcond[0]=(((new_r10*x1951))+((new_r00*x1952))+gconst24);
17577evalcond[1]=(((new_r11*x1951))+(((-1.0)*x1953))+((new_r01*x1952)));
17578evalcond[2]=(((gconst24*x1952))+((x1951*x1954))+new_r00);
17579evalcond[3]=((((-1.0)*x1952*x1954))+((gconst24*x1951))+new_r10);
17580evalcond[4]=((((-1.0)*x1952*x1953))+((x1951*x1955))+new_r01);
17581evalcond[5]=((((-1.0)*x1952*x1955))+(((-1.0)*x1951*x1953))+new_r11);
17582evalcond[6]=(x1954+x1958+(((-1.0)*x1959)));
17583evalcond[7]=(x1955+x1957+(((-1.0)*x1956)));
17584evalcond[8]=((((1.0000000008)*x1959))+(((-1.0)*x1953))+(((-1.0000000008)*x1958)));
17585evalcond[9]=((((1.0000000008)*x1956))+(((-1.0000000008)*x1957))+(((-1.0)*gconst24)));
17586if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
17587{
17588continue;
17589}
17590}
17591
17592{
17593std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17594vinfos[0].jointtype = 1;
17595vinfos[0].foffset = j0;
17596vinfos[0].indices[0] = _ij0[0];
17597vinfos[0].indices[1] = _ij0[1];
17598vinfos[0].maxsolutions = _nj0;
17599vinfos[1].jointtype = 1;
17600vinfos[1].foffset = j1;
17601vinfos[1].indices[0] = _ij1[0];
17602vinfos[1].indices[1] = _ij1[1];
17603vinfos[1].maxsolutions = _nj1;
17604vinfos[2].jointtype = 1;
17605vinfos[2].foffset = j2;
17606vinfos[2].indices[0] = _ij2[0];
17607vinfos[2].indices[1] = _ij2[1];
17608vinfos[2].maxsolutions = _nj2;
17609vinfos[3].jointtype = 1;
17610vinfos[3].foffset = j3;
17611vinfos[3].indices[0] = _ij3[0];
17612vinfos[3].indices[1] = _ij3[1];
17613vinfos[3].maxsolutions = _nj3;
17614vinfos[4].jointtype = 1;
17615vinfos[4].foffset = j4;
17616vinfos[4].indices[0] = _ij4[0];
17617vinfos[4].indices[1] = _ij4[1];
17618vinfos[4].maxsolutions = _nj4;
17619vinfos[5].jointtype = 1;
17620vinfos[5].foffset = j5;
17621vinfos[5].indices[0] = _ij5[0];
17622vinfos[5].indices[1] = _ij5[1];
17623vinfos[5].maxsolutions = _nj5;
17624std::vector<int> vfree(0);
17625solutions.AddSolution(vinfos,vfree);
17626}
17627}
17628}
17629
17630}
17631
17632}
17633
17634} else
17635{
17636{
17637IkReal j5array[1], cj5array[1], sj5array[1];
17638bool j5valid[1]={false};
17639_nj5 = 1;
17640CheckValue<IkReal> x1964=IKPowWithIntegerCheck(new_r00,-1);
17641if(!x1964.valid){
17642continue;
17643}
17644IkReal x1960=x1964.value;
17645IkReal x1961=((25000.0)*new_r10);
17646IkReal x1962=(gconst24*x1960);
17647CheckValue<IkReal> x1965=IKPowWithIntegerCheck((((gconst25*x1961))+(((25000.00002)*gconst24*new_r00))),-1);
17648if(!x1965.valid){
17649continue;
17650}
17651IkReal x1963=x1965.value;
17652if( IKabs(((((-1.0)*x1962))+((new_r01*x1961*x1963))+((gconst25*x1961*x1962*x1963)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1963*(((((-25000.0)*new_r00*new_r01))+(((-25000.0)*gconst24*gconst25)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x1962))+((new_r01*x1961*x1963))+((gconst25*x1961*x1962*x1963))))+IKsqr((x1963*(((((-25000.0)*new_r00*new_r01))+(((-25000.0)*gconst24*gconst25))))))-1) <= IKFAST_SINCOS_THRESH )
17653 continue;
17654j5array[0]=IKatan2(((((-1.0)*x1962))+((new_r01*x1961*x1963))+((gconst25*x1961*x1962*x1963))), (x1963*(((((-25000.0)*new_r00*new_r01))+(((-25000.0)*gconst24*gconst25))))));
17655sj5array[0]=IKsin(j5array[0]);
17656cj5array[0]=IKcos(j5array[0]);
17657if( j5array[0] > IKPI )
17658{
17659 j5array[0]-=IK2PI;
17660}
17661else if( j5array[0] < -IKPI )
17662{ j5array[0]+=IK2PI;
17663}
17664j5valid[0] = true;
17665for(int ij5 = 0; ij5 < 1; ++ij5)
17666{
17667if( !j5valid[ij5] )
17668{
17669 continue;
17670}
17671_ij5[0] = ij5; _ij5[1] = -1;
17672for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17673{
17674if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17675{
17676 j5valid[iij5]=false; _ij5[1] = iij5; break;
17677}
17678}
17679j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17680{
17681IkReal evalcond[10];
17682IkReal x1966=IKcos(j5);
17683IkReal x1967=IKsin(j5);
17684IkReal x1968=((1.0)*gconst25);
17685IkReal x1969=((1.0000000008)*gconst25);
17686IkReal x1970=((1.0000000008)*gconst24);
17687IkReal x1971=(new_r11*x1967);
17688IkReal x1972=(new_r01*x1966);
17689IkReal x1973=(new_r00*x1966);
17690IkReal x1974=(new_r10*x1967);
17691evalcond[0]=(((new_r00*x1967))+gconst24+((new_r10*x1966)));
17692evalcond[1]=(((new_r11*x1966))+((new_r01*x1967))+(((-1.0)*x1968)));
17693evalcond[2]=(((gconst24*x1967))+((x1966*x1969))+new_r00);
17694evalcond[3]=(((gconst24*x1966))+new_r10+(((-1.0)*x1967*x1969)));
17695evalcond[4]=(((x1966*x1970))+new_r01+(((-1.0)*x1967*x1968)));
17696evalcond[5]=((((-1.0)*x1966*x1968))+new_r11+(((-1.0)*x1967*x1970)));
17697evalcond[6]=((((-1.0)*x1974))+x1969+x1973);
17698evalcond[7]=((((-1.0)*x1971))+x1972+x1970);
17699evalcond[8]=((((-1.0)*x1968))+(((-1.0000000008)*x1973))+(((1.0000000008)*x1974)));
17700evalcond[9]=((((-1.0)*gconst24))+(((-1.0000000008)*x1972))+(((1.0000000008)*x1971)));
17701if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
17702{
17703continue;
17704}
17705}
17706
17707{
17708std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17709vinfos[0].jointtype = 1;
17710vinfos[0].foffset = j0;
17711vinfos[0].indices[0] = _ij0[0];
17712vinfos[0].indices[1] = _ij0[1];
17713vinfos[0].maxsolutions = _nj0;
17714vinfos[1].jointtype = 1;
17715vinfos[1].foffset = j1;
17716vinfos[1].indices[0] = _ij1[0];
17717vinfos[1].indices[1] = _ij1[1];
17718vinfos[1].maxsolutions = _nj1;
17719vinfos[2].jointtype = 1;
17720vinfos[2].foffset = j2;
17721vinfos[2].indices[0] = _ij2[0];
17722vinfos[2].indices[1] = _ij2[1];
17723vinfos[2].maxsolutions = _nj2;
17724vinfos[3].jointtype = 1;
17725vinfos[3].foffset = j3;
17726vinfos[3].indices[0] = _ij3[0];
17727vinfos[3].indices[1] = _ij3[1];
17728vinfos[3].maxsolutions = _nj3;
17729vinfos[4].jointtype = 1;
17730vinfos[4].foffset = j4;
17731vinfos[4].indices[0] = _ij4[0];
17732vinfos[4].indices[1] = _ij4[1];
17733vinfos[4].maxsolutions = _nj4;
17734vinfos[5].jointtype = 1;
17735vinfos[5].foffset = j5;
17736vinfos[5].indices[0] = _ij5[0];
17737vinfos[5].indices[1] = _ij5[1];
17738vinfos[5].maxsolutions = _nj5;
17739std::vector<int> vfree(0);
17740solutions.AddSolution(vinfos,vfree);
17741}
17742}
17743}
17744
17745}
17746
17747}
17748
17749} else
17750{
17751{
17752IkReal j5array[1], cj5array[1], sj5array[1];
17753bool j5valid[1]={false};
17754_nj5 = 1;
17755IkReal x1975=((1.0)*new_r00);
17756CheckValue<IkReal> x1976 = IKatan2WithCheck(IkReal((((gconst25*new_r10))+((gconst24*new_r11)))),IkReal(((((-1.0)*gconst24*new_r01))+(((-1.0)*gconst25*x1975)))),IKFAST_ATAN2_MAGTHRESH);
17757if(!x1976.valid){
17758continue;
17759}
17760CheckValue<IkReal> x1977=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x1975))+((new_r01*new_r10)))),-1);
17761if(!x1977.valid){
17762continue;
17763}
17764j5array[0]=((-1.5707963267949)+(x1976.value)+(((1.5707963267949)*(x1977.value))));
17765sj5array[0]=IKsin(j5array[0]);
17766cj5array[0]=IKcos(j5array[0]);
17767if( j5array[0] > IKPI )
17768{
17769 j5array[0]-=IK2PI;
17770}
17771else if( j5array[0] < -IKPI )
17772{ j5array[0]+=IK2PI;
17773}
17774j5valid[0] = true;
17775for(int ij5 = 0; ij5 < 1; ++ij5)
17776{
17777if( !j5valid[ij5] )
17778{
17779 continue;
17780}
17781_ij5[0] = ij5; _ij5[1] = -1;
17782for(int iij5 = ij5+1; iij5 < 1; ++iij5)
17783{
17784if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
17785{
17786 j5valid[iij5]=false; _ij5[1] = iij5; break;
17787}
17788}
17789j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
17790{
17791IkReal evalcond[10];
17792IkReal x1978=IKcos(j5);
17793IkReal x1979=IKsin(j5);
17794IkReal x1980=((1.0)*gconst25);
17795IkReal x1981=((1.0000000008)*gconst25);
17796IkReal x1982=((1.0000000008)*gconst24);
17797IkReal x1983=(new_r11*x1979);
17798IkReal x1984=(new_r01*x1978);
17799IkReal x1985=(new_r00*x1978);
17800IkReal x1986=(new_r10*x1979);
17801evalcond[0]=(((new_r10*x1978))+((new_r00*x1979))+gconst24);
17802evalcond[1]=(((new_r01*x1979))+((new_r11*x1978))+(((-1.0)*x1980)));
17803evalcond[2]=(((gconst24*x1979))+((x1978*x1981))+new_r00);
17804evalcond[3]=(((gconst24*x1978))+(((-1.0)*x1979*x1981))+new_r10);
17805evalcond[4]=((((-1.0)*x1979*x1980))+((x1978*x1982))+new_r01);
17806evalcond[5]=((((-1.0)*x1979*x1982))+new_r11+(((-1.0)*x1978*x1980)));
17807evalcond[6]=(x1985+x1981+(((-1.0)*x1986)));
17808evalcond[7]=(x1984+x1982+(((-1.0)*x1983)));
17809evalcond[8]=((((1.0000000008)*x1986))+(((-1.0)*x1980))+(((-1.0000000008)*x1985)));
17810evalcond[9]=((((1.0000000008)*x1983))+(((-1.0000000008)*x1984))+(((-1.0)*gconst24)));
17811if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
17812{
17813continue;
17814}
17815}
17816
17817{
17818std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17819vinfos[0].jointtype = 1;
17820vinfos[0].foffset = j0;
17821vinfos[0].indices[0] = _ij0[0];
17822vinfos[0].indices[1] = _ij0[1];
17823vinfos[0].maxsolutions = _nj0;
17824vinfos[1].jointtype = 1;
17825vinfos[1].foffset = j1;
17826vinfos[1].indices[0] = _ij1[0];
17827vinfos[1].indices[1] = _ij1[1];
17828vinfos[1].maxsolutions = _nj1;
17829vinfos[2].jointtype = 1;
17830vinfos[2].foffset = j2;
17831vinfos[2].indices[0] = _ij2[0];
17832vinfos[2].indices[1] = _ij2[1];
17833vinfos[2].maxsolutions = _nj2;
17834vinfos[3].jointtype = 1;
17835vinfos[3].foffset = j3;
17836vinfos[3].indices[0] = _ij3[0];
17837vinfos[3].indices[1] = _ij3[1];
17838vinfos[3].maxsolutions = _nj3;
17839vinfos[4].jointtype = 1;
17840vinfos[4].foffset = j4;
17841vinfos[4].indices[0] = _ij4[0];
17842vinfos[4].indices[1] = _ij4[1];
17843vinfos[4].maxsolutions = _nj4;
17844vinfos[5].jointtype = 1;
17845vinfos[5].foffset = j5;
17846vinfos[5].indices[0] = _ij5[0];
17847vinfos[5].indices[1] = _ij5[1];
17848vinfos[5].maxsolutions = _nj5;
17849std::vector<int> vfree(0);
17850solutions.AddSolution(vinfos,vfree);
17851}
17852}
17853}
17854
17855}
17856
17857}
17858
17859}
17860} while(0);
17861if( bgotonextstatement )
17862{
17863bool bgotonextstatement = true;
17864do
17865{
17866IkReal x1987=((1.0000000008)*new_r00);
17867IkReal x1989 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
17868if(IKabs(x1989)==0){
17869continue;
17870}
17871IkReal x1988=pow(x1989,-0.5);
17872CheckValue<IkReal> x1990 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1987),IKFAST_ATAN2_MAGTHRESH);
17873if(!x1990.valid){
17874continue;
17875}
17876IkReal gconst26=((-1.0)*(x1990.value));
17877IkReal gconst27=((-1.0)*new_r10*x1988);
17878IkReal gconst28=(x1987*x1988);
17879CheckValue<IkReal> x1991 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
17880if(!x1991.valid){
17881continue;
17882}
17883evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1991.value)+j3)))), 6.28318530717959)));
17884if( IKabs(evalcond[0]) < 0.0000050000000000 )
17885{
17886bgotonextstatement=false;
17887{
17888IkReal j5eval[3];
17889IkReal x1992=((1.0000000008)*new_r00);
17890IkReal x1993=x1988;
17891sj4=-4.0e-5;
17892cj4=-1.0;
17893j4=3.14163265;
17894sj3=gconst27;
17895cj3=gconst28;
17896CheckValue<IkReal> x1994 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
17897if(!x1994.valid){
17898continue;
17899}
17900j3=((-1.0)*(x1994.value));
17901CheckValue<IkReal> x1995 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1992),IKFAST_ATAN2_MAGTHRESH);
17902if(!x1995.valid){
17903continue;
17904}
17905IkReal gconst26=((-1.0)*(x1995.value));
17906IkReal gconst27=((-1.0)*new_r10*x1993);
17907IkReal gconst28=(x1992*x1993);
17908IkReal x1996=new_r00*new_r00;
17909IkReal x1997=(new_r01*new_r10);
17910IkReal x1998=(x1997+(((-1.0)*new_r00*new_r11)));
17911IkReal x2001 = ((((625000000.0)*(new_r10*new_r10)))+(((625000001.0)*x1996)));
17912if(IKabs(x2001)==0){
17913continue;
17914}
17915IkReal x1999=pow(x2001,-0.5);
17916IkReal x2000=(new_r10*x1999);
17917j5eval[0]=x1998;
17918j5eval[1]=IKsign(x1998);
17919j5eval[2]=((IKabs(((((25000.00002)*new_r00*x2000))+(((-25000.0)*new_r11*x2000)))))+(IKabs(((((25000.0)*x1997*x1999))+(((-25000.00002)*x1996*x1999))))));
17920if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
17921{
17922{
17923IkReal j5eval[1];
17924IkReal x2002=((1.0000000008)*new_r00);
17925IkReal x2003=x1988;
17926sj4=-4.0e-5;
17927cj4=-1.0;
17928j4=3.14163265;
17929sj3=gconst27;
17930cj3=gconst28;
17931CheckValue<IkReal> x2004 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
17932if(!x2004.valid){
17933continue;
17934}
17935j3=((-1.0)*(x2004.value));
17936CheckValue<IkReal> x2005 = IKatan2WithCheck(IkReal(new_r10),IkReal(x2002),IKFAST_ATAN2_MAGTHRESH);
17937if(!x2005.valid){
17938continue;
17939}
17940IkReal gconst26=((-1.0)*(x2005.value));
17941IkReal gconst27=((-1.0)*new_r10*x2003);
17942IkReal gconst28=(x2002*x2003);
17943j5eval[0]=new_r00;
17944if( IKabs(j5eval[0]) < 0.0000010000000000 )
17945{
17946{
17947IkReal j5eval[2];
17948IkReal x2006=((1.0000000008)*new_r00);
17949IkReal x2007=x1988;
17950sj4=-4.0e-5;
17951cj4=-1.0;
17952j4=3.14163265;
17953sj3=gconst27;
17954cj3=gconst28;
17955CheckValue<IkReal> x2008 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
17956if(!x2008.valid){
17957continue;
17958}
17959j3=((-1.0)*(x2008.value));
17960CheckValue<IkReal> x2009 = IKatan2WithCheck(IkReal(new_r10),IkReal(x2006),IKFAST_ATAN2_MAGTHRESH);
17961if(!x2009.valid){
17962continue;
17963}
17964IkReal gconst26=((-1.0)*(x2009.value));
17965IkReal gconst27=((-1.0)*new_r10*x2007);
17966IkReal gconst28=(x2006*x2007);
17967j5eval[0]=new_r00;
17968IkReal x2010 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
17969if(IKabs(x2010)==0){
17970continue;
17971}
17972j5eval[1]=((1.6e-9)*new_r00*new_r10*(pow(x2010,-0.5)));
17973if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
17974{
17975{
17976IkReal evalcond[1];
17977bool bgotonextstatement = true;
17978do
17979{
17980evalcond[0]=IKabs(new_r00);
17981if( IKabs(evalcond[0]) < 0.0000050000000000 )
17982{
17983bgotonextstatement=false;
17984{
17985IkReal j5eval[1];
17986CheckValue<IkReal> x2012 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17987if(!x2012.valid){
17988continue;
17989}
17990IkReal x2011=((-1.0)*(x2012.value));
17991sj4=-4.0e-5;
17992cj4=-1.0;
17993j4=3.14163265;
17994sj3=gconst27;
17995cj3=gconst28;
17996j3=x2011;
17997new_r00=0;
17998IkReal gconst26=x2011;
17999IkReal x2013 = new_r10*new_r10;
18000if(IKabs(x2013)==0){
18001continue;
18002}
18003IkReal gconst27=((-1.0)*new_r10*(pow(x2013,-0.5)));
18004IkReal gconst28=0;
18005j5eval[0]=new_r10;
18006if( IKabs(j5eval[0]) < 0.0000010000000000 )
18007{
18008{
18009IkReal j5array[1], cj5array[1], sj5array[1];
18010bool j5valid[1]={false};
18011_nj5 = 1;
18012CheckValue<IkReal> x2015=IKPowWithIntegerCheck(gconst27,-1);
18013if(!x2015.valid){
18014continue;
18015}
18016IkReal x2014=x2015.value;
18017if( IKabs(((0.9999999992)*new_r11*x2014)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x2014)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*x2014))+IKsqr(((-1.0)*new_r10*x2014))-1) <= IKFAST_SINCOS_THRESH )
18018 continue;
18019j5array[0]=IKatan2(((0.9999999992)*new_r11*x2014), ((-1.0)*new_r10*x2014));
18020sj5array[0]=IKsin(j5array[0]);
18021cj5array[0]=IKcos(j5array[0]);
18022if( j5array[0] > IKPI )
18023{
18024 j5array[0]-=IK2PI;
18025}
18026else if( j5array[0] < -IKPI )
18027{ j5array[0]+=IK2PI;
18028}
18029j5valid[0] = true;
18030for(int ij5 = 0; ij5 < 1; ++ij5)
18031{
18032if( !j5valid[ij5] )
18033{
18034 continue;
18035}
18036_ij5[0] = ij5; _ij5[1] = -1;
18037for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18038{
18039if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18040{
18041 j5valid[iij5]=false; _ij5[1] = iij5; break;
18042}
18043}
18044j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18045{
18046IkReal evalcond[10];
18047IkReal x2016=IKsin(j5);
18048IkReal x2017=IKcos(j5);
18049IkReal x2018=((1.0000000008)*x2016);
18050IkReal x2019=(gconst27*x2017);
18051IkReal x2020=(new_r01*x2017);
18052evalcond[0]=(gconst27*x2016);
18053evalcond[1]=((-1.0)*new_r10*x2016);
18054evalcond[2]=(gconst27+((new_r10*x2017)));
18055evalcond[3]=(x2019+new_r10);
18056evalcond[4]=(new_r10*x2018);
18057evalcond[5]=(((new_r11*x2017))+((new_r01*x2016)));
18058evalcond[6]=((((1.0000000008)*x2019))+new_r01);
18059evalcond[7]=(new_r11+(((-1.0)*gconst27*x2018)));
18060evalcond[8]=(x2020+(((1.0000000008)*gconst27))+(((-1.0)*new_r11*x2016)));
18061evalcond[9]=(((new_r11*x2018))+(((-1.0000000008)*x2020))+(((-1.0)*gconst27)));
18062if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
18063{
18064continue;
18065}
18066}
18067
18068{
18069std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18070vinfos[0].jointtype = 1;
18071vinfos[0].foffset = j0;
18072vinfos[0].indices[0] = _ij0[0];
18073vinfos[0].indices[1] = _ij0[1];
18074vinfos[0].maxsolutions = _nj0;
18075vinfos[1].jointtype = 1;
18076vinfos[1].foffset = j1;
18077vinfos[1].indices[0] = _ij1[0];
18078vinfos[1].indices[1] = _ij1[1];
18079vinfos[1].maxsolutions = _nj1;
18080vinfos[2].jointtype = 1;
18081vinfos[2].foffset = j2;
18082vinfos[2].indices[0] = _ij2[0];
18083vinfos[2].indices[1] = _ij2[1];
18084vinfos[2].maxsolutions = _nj2;
18085vinfos[3].jointtype = 1;
18086vinfos[3].foffset = j3;
18087vinfos[3].indices[0] = _ij3[0];
18088vinfos[3].indices[1] = _ij3[1];
18089vinfos[3].maxsolutions = _nj3;
18090vinfos[4].jointtype = 1;
18091vinfos[4].foffset = j4;
18092vinfos[4].indices[0] = _ij4[0];
18093vinfos[4].indices[1] = _ij4[1];
18094vinfos[4].maxsolutions = _nj4;
18095vinfos[5].jointtype = 1;
18096vinfos[5].foffset = j5;
18097vinfos[5].indices[0] = _ij5[0];
18098vinfos[5].indices[1] = _ij5[1];
18099vinfos[5].maxsolutions = _nj5;
18100std::vector<int> vfree(0);
18101solutions.AddSolution(vinfos,vfree);
18102}
18103}
18104}
18105
18106} else
18107{
18108{
18109IkReal j5array[1], cj5array[1], sj5array[1];
18110bool j5valid[1]={false};
18111_nj5 = 1;
18112CheckValue<IkReal> x2021=IKPowWithIntegerCheck(gconst27,-1);
18113if(!x2021.valid){
18114continue;
18115}
18116CheckValue<IkReal> x2022=IKPowWithIntegerCheck(new_r10,-1);
18117if(!x2022.valid){
18118continue;
18119}
18120if( IKabs(((0.9999999992)*new_r11*(x2021.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst27*(x2022.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*(x2021.value)))+IKsqr(((-1.0)*gconst27*(x2022.value)))-1) <= IKFAST_SINCOS_THRESH )
18121 continue;
18122j5array[0]=IKatan2(((0.9999999992)*new_r11*(x2021.value)), ((-1.0)*gconst27*(x2022.value)));
18123sj5array[0]=IKsin(j5array[0]);
18124cj5array[0]=IKcos(j5array[0]);
18125if( j5array[0] > IKPI )
18126{
18127 j5array[0]-=IK2PI;
18128}
18129else if( j5array[0] < -IKPI )
18130{ j5array[0]+=IK2PI;
18131}
18132j5valid[0] = true;
18133for(int ij5 = 0; ij5 < 1; ++ij5)
18134{
18135if( !j5valid[ij5] )
18136{
18137 continue;
18138}
18139_ij5[0] = ij5; _ij5[1] = -1;
18140for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18141{
18142if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18143{
18144 j5valid[iij5]=false; _ij5[1] = iij5; break;
18145}
18146}
18147j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18148{
18149IkReal evalcond[10];
18150IkReal x2023=IKsin(j5);
18151IkReal x2024=IKcos(j5);
18152IkReal x2025=((1.0000000008)*x2023);
18153IkReal x2026=(gconst27*x2024);
18154IkReal x2027=(new_r01*x2024);
18155evalcond[0]=(gconst27*x2023);
18156evalcond[1]=((-1.0)*new_r10*x2023);
18157evalcond[2]=(((new_r10*x2024))+gconst27);
18158evalcond[3]=(x2026+new_r10);
18159evalcond[4]=(new_r10*x2025);
18160evalcond[5]=(((new_r01*x2023))+((new_r11*x2024)));
18161evalcond[6]=((((1.0000000008)*x2026))+new_r01);
18162evalcond[7]=((((-1.0)*gconst27*x2025))+new_r11);
18163evalcond[8]=(x2027+(((1.0000000008)*gconst27))+(((-1.0)*new_r11*x2023)));
18164evalcond[9]=((((-1.0000000008)*x2027))+((new_r11*x2025))+(((-1.0)*gconst27)));
18165if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
18166{
18167continue;
18168}
18169}
18170
18171{
18172std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18173vinfos[0].jointtype = 1;
18174vinfos[0].foffset = j0;
18175vinfos[0].indices[0] = _ij0[0];
18176vinfos[0].indices[1] = _ij0[1];
18177vinfos[0].maxsolutions = _nj0;
18178vinfos[1].jointtype = 1;
18179vinfos[1].foffset = j1;
18180vinfos[1].indices[0] = _ij1[0];
18181vinfos[1].indices[1] = _ij1[1];
18182vinfos[1].maxsolutions = _nj1;
18183vinfos[2].jointtype = 1;
18184vinfos[2].foffset = j2;
18185vinfos[2].indices[0] = _ij2[0];
18186vinfos[2].indices[1] = _ij2[1];
18187vinfos[2].maxsolutions = _nj2;
18188vinfos[3].jointtype = 1;
18189vinfos[3].foffset = j3;
18190vinfos[3].indices[0] = _ij3[0];
18191vinfos[3].indices[1] = _ij3[1];
18192vinfos[3].maxsolutions = _nj3;
18193vinfos[4].jointtype = 1;
18194vinfos[4].foffset = j4;
18195vinfos[4].indices[0] = _ij4[0];
18196vinfos[4].indices[1] = _ij4[1];
18197vinfos[4].maxsolutions = _nj4;
18198vinfos[5].jointtype = 1;
18199vinfos[5].foffset = j5;
18200vinfos[5].indices[0] = _ij5[0];
18201vinfos[5].indices[1] = _ij5[1];
18202vinfos[5].maxsolutions = _nj5;
18203std::vector<int> vfree(0);
18204solutions.AddSolution(vinfos,vfree);
18205}
18206}
18207}
18208
18209}
18210
18211}
18212
18213}
18214} while(0);
18215if( bgotonextstatement )
18216{
18217bool bgotonextstatement = true;
18218do
18219{
18220evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
18221if( IKabs(evalcond[0]) < 0.0000050000000000 )
18222{
18223bgotonextstatement=false;
18224{
18225IkReal j5eval[3];
18226IkReal x2028=((1.0000000008)*new_r00);
18227IkReal x2030 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
18228if(IKabs(x2030)==0){
18229continue;
18230}
18231IkReal x2029=pow(x2030,-0.5);
18232sj4=-4.0e-5;
18233cj4=-1.0;
18234j4=3.14163265;
18235sj3=gconst27;
18236cj3=gconst28;
18237CheckValue<IkReal> x2031 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
18238if(!x2031.valid){
18239continue;
18240}
18241j3=((-1.0)*(x2031.value));
18242new_r11=0;
18243new_r01=0;
18244new_r22=0;
18245new_r20=0;
18246CheckValue<IkReal> x2032 = IKatan2WithCheck(IkReal(new_r10),IkReal(x2028),IKFAST_ATAN2_MAGTHRESH);
18247if(!x2032.valid){
18248continue;
18249}
18250IkReal gconst26=((-1.0)*(x2032.value));
18251IkReal gconst27=((-1.0)*new_r10*x2029);
18252IkReal gconst28=(x2028*x2029);
18253IkReal x2033=new_r10*new_r10;
18254CheckValue<IkReal> x2037=IKPowWithIntegerCheck(((-625000001.0)+x2033),-1);
18255if(!x2037.valid){
18256continue;
18257}
18258IkReal x2034=x2037.value;
18259if((((625000001.0)+(((-1.0)*x2033)))) < -0.00001)
18260continue;
18261IkReal x2035=IKsqrt(((625000001.0)+(((-1.0)*x2033))));
18262IkReal x2036=(x2034*x2035);
18263j5eval[0]=1.0;
18264j5eval[1]=1.0;
18265IkReal x2038 = ((1.0000000016)+(((-1.6e-9)*x2033)));
18266if(IKabs(x2038)==0){
18267continue;
18268}
18269j5eval[2]=((((50000.00004)*(IKabs((new_r00*new_r10*(pow(x2038,-0.5)))))))+(IKabs(((((-1250000001.0)*x2033*x2036))+(((625000001.0)*x2036))))));
18270if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
18271{
18272{
18273IkReal j5eval[1];
18274IkReal x2039=((1.0000000008)*new_r00);
18275IkReal x2041 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
18276if(IKabs(x2041)==0){
18277continue;
18278}
18279IkReal x2040=pow(x2041,-0.5);
18280sj4=-4.0e-5;
18281cj4=-1.0;
18282j4=3.14163265;
18283sj3=gconst27;
18284cj3=gconst28;
18285CheckValue<IkReal> x2042 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
18286if(!x2042.valid){
18287continue;
18288}
18289j3=((-1.0)*(x2042.value));
18290new_r11=0;
18291new_r01=0;
18292new_r22=0;
18293new_r20=0;
18294CheckValue<IkReal> x2043 = IKatan2WithCheck(IkReal(new_r10),IkReal(x2039),IKFAST_ATAN2_MAGTHRESH);
18295if(!x2043.valid){
18296continue;
18297}
18298IkReal gconst26=((-1.0)*(x2043.value));
18299IkReal gconst27=((-1.0)*new_r10*x2040);
18300IkReal gconst28=(x2039*x2040);
18301IkReal x2044=new_r10*new_r10;
18302CheckValue<IkReal> x2047=IKPowWithIntegerCheck(((1.0000000016)+(((-1.6e-9)*x2044))),-1);
18303if(!x2047.valid){
18304continue;
18305}
18306IkReal x2045=x2047.value;
18307IkReal x2046=((625000001.0)*x2045);
18308IkReal x2048=((1.0)+(((-1.0)*x2044)));
18309j5eval[0]=IKsign((((x2046*(x2044*x2044)))+(((-1.0)*x2046*(x2048*x2048)))));
18310if( IKabs(j5eval[0]) < 0.0000010000000000 )
18311{
18312{
18313IkReal j5eval[1];
18314IkReal x2049=((1.0000000008)*new_r00);
18315IkReal x2051 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
18316if(IKabs(x2051)==0){
18317continue;
18318}
18319IkReal x2050=pow(x2051,-0.5);
18320sj4=-4.0e-5;
18321cj4=-1.0;
18322j4=3.14163265;
18323sj3=gconst27;
18324cj3=gconst28;
18325CheckValue<IkReal> x2052 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
18326if(!x2052.valid){
18327continue;
18328}
18329j3=((-1.0)*(x2052.value));
18330new_r11=0;
18331new_r01=0;
18332new_r22=0;
18333new_r20=0;
18334CheckValue<IkReal> x2053 = IKatan2WithCheck(IkReal(new_r10),IkReal(x2049),IKFAST_ATAN2_MAGTHRESH);
18335if(!x2053.valid){
18336continue;
18337}
18338IkReal gconst26=((-1.0)*(x2053.value));
18339IkReal gconst27=((-1.0)*new_r10*x2050);
18340IkReal gconst28=(x2049*x2050);
18341j5eval[0]=new_r00;
18342if( IKabs(j5eval[0]) < 0.0000010000000000 )
18343{
18344continue; // 3 cases reached
18345
18346} else
18347{
18348{
18349IkReal j5array[1], cj5array[1], sj5array[1];
18350bool j5valid[1]={false};
18351_nj5 = 1;
18352CheckValue<IkReal> x2060=IKPowWithIntegerCheck(new_r00,-1);
18353if(!x2060.valid){
18354continue;
18355}
18356IkReal x2054=x2060.value;
18357IkReal x2055=gconst27*gconst27;
18358IkReal x2056=((25000.0)*new_r10);
18359IkReal x2057=((25000.0)*x2055);
18360CheckValue<IkReal> x2061=IKPowWithIntegerCheck(((((-1.0)*gconst27*x2056))+(((25000.00002)*gconst28*new_r00))),-1);
18361if(!x2061.valid){
18362continue;
18363}
18364IkReal x2058=x2061.value;
18365IkReal x2059=(new_r10*x2058);
18366CheckValue<IkReal> x2062=IKPowWithIntegerCheck(((((-25000.0)*gconst27*new_r10))+(((25000.00002)*gconst28*new_r00))),-1);
18367if(!x2062.valid){
18368continue;
18369}
18370CheckValue<IkReal> x2063=IKPowWithIntegerCheck(((((-25000.0)*gconst27*new_r10))+(((25000.00002)*gconst28*new_r00))),-1);
18371if(!x2063.valid){
18372continue;
18373}
18374CheckValue<IkReal> x2064=IKPowWithIntegerCheck(x2054,-2);
18375if(!x2064.valid){
18376continue;
18377}
18378if( IKabs(((((-1.0)*x2054*x2055*x2056*(x2062.value)))+(((-1.0)*gconst27*x2054))+((new_r00*x2056*(x2063.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2058*((x2057+(((-25000.0)*(x2064.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x2054*x2055*x2056*(x2062.value)))+(((-1.0)*gconst27*x2054))+((new_r00*x2056*(x2063.value)))))+IKsqr((x2058*((x2057+(((-25000.0)*(x2064.value)))))))-1) <= IKFAST_SINCOS_THRESH )
18379 continue;
18380j5array[0]=IKatan2(((((-1.0)*x2054*x2055*x2056*(x2062.value)))+(((-1.0)*gconst27*x2054))+((new_r00*x2056*(x2063.value)))), (x2058*((x2057+(((-25000.0)*(x2064.value)))))));
18381sj5array[0]=IKsin(j5array[0]);
18382cj5array[0]=IKcos(j5array[0]);
18383if( j5array[0] > IKPI )
18384{
18385 j5array[0]-=IK2PI;
18386}
18387else if( j5array[0] < -IKPI )
18388{ j5array[0]+=IK2PI;
18389}
18390j5valid[0] = true;
18391for(int ij5 = 0; ij5 < 1; ++ij5)
18392{
18393if( !j5valid[ij5] )
18394{
18395 continue;
18396}
18397_ij5[0] = ij5; _ij5[1] = -1;
18398for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18399{
18400if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18401{
18402 j5valid[iij5]=false; _ij5[1] = iij5; break;
18403}
18404}
18405j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18406{
18407IkReal evalcond[7];
18408IkReal x2065=IKcos(j5);
18409IkReal x2066=IKsin(j5);
18410IkReal x2067=((1.0000000008)*gconst28);
18411IkReal x2068=((1.0)*gconst28);
18412IkReal x2069=((1.0000000008)*x2066);
18413IkReal x2070=(gconst27*x2065);
18414IkReal x2071=(new_r00*x2065);
18415evalcond[0]=(gconst27+((new_r10*x2065))+((new_r00*x2066)));
18416evalcond[1]=(((gconst27*x2066))+new_r00+((x2065*x2067)));
18417evalcond[2]=(x2070+new_r10+(((-1.0)*x2066*x2067)));
18418evalcond[3]=((((1.0000000008)*x2070))+(((-1.0)*x2066*x2068)));
18419evalcond[4]=((((-1.0)*gconst27*x2069))+(((-1.0)*x2065*x2068)));
18420evalcond[5]=(x2067+x2071+(((-1.0)*new_r10*x2066)));
18421evalcond[6]=((((-1.0000000008)*x2071))+(((-1.0)*x2068))+((new_r10*x2069)));
18422if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18423{
18424continue;
18425}
18426}
18427
18428{
18429std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18430vinfos[0].jointtype = 1;
18431vinfos[0].foffset = j0;
18432vinfos[0].indices[0] = _ij0[0];
18433vinfos[0].indices[1] = _ij0[1];
18434vinfos[0].maxsolutions = _nj0;
18435vinfos[1].jointtype = 1;
18436vinfos[1].foffset = j1;
18437vinfos[1].indices[0] = _ij1[0];
18438vinfos[1].indices[1] = _ij1[1];
18439vinfos[1].maxsolutions = _nj1;
18440vinfos[2].jointtype = 1;
18441vinfos[2].foffset = j2;
18442vinfos[2].indices[0] = _ij2[0];
18443vinfos[2].indices[1] = _ij2[1];
18444vinfos[2].maxsolutions = _nj2;
18445vinfos[3].jointtype = 1;
18446vinfos[3].foffset = j3;
18447vinfos[3].indices[0] = _ij3[0];
18448vinfos[3].indices[1] = _ij3[1];
18449vinfos[3].maxsolutions = _nj3;
18450vinfos[4].jointtype = 1;
18451vinfos[4].foffset = j4;
18452vinfos[4].indices[0] = _ij4[0];
18453vinfos[4].indices[1] = _ij4[1];
18454vinfos[4].maxsolutions = _nj4;
18455vinfos[5].jointtype = 1;
18456vinfos[5].foffset = j5;
18457vinfos[5].indices[0] = _ij5[0];
18458vinfos[5].indices[1] = _ij5[1];
18459vinfos[5].maxsolutions = _nj5;
18460std::vector<int> vfree(0);
18461solutions.AddSolution(vinfos,vfree);
18462}
18463}
18464}
18465
18466}
18467
18468}
18469
18470} else
18471{
18472{
18473IkReal j5array[1], cj5array[1], sj5array[1];
18474bool j5valid[1]={false};
18475_nj5 = 1;
18476IkReal x2072=gconst27*gconst27;
18477IkReal x2073=gconst28*gconst28;
18478IkReal x2074=((625000000.0)*x2073);
18479IkReal x2075=((625000000.5)*gconst28*x2072);
18480CheckValue<IkReal> x2076 = IKatan2WithCheck(IkReal((((gconst27*new_r00*x2074))+((new_r10*x2075)))),IkReal(((((-625000001.0)*new_r10*(gconst27*gconst27*gconst27)))+(((-1.0)*new_r00*x2075)))),IKFAST_ATAN2_MAGTHRESH);
18481if(!x2076.valid){
18482continue;
18483}
18484CheckValue<IkReal> x2077=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x2072*(new_r10*new_r10)))+(((-1.0)*x2074*(new_r00*new_r00))))),-1);
18485if(!x2077.valid){
18486continue;
18487}
18488j5array[0]=((-1.5707963267949)+(x2076.value)+(((1.5707963267949)*(x2077.value))));
18489sj5array[0]=IKsin(j5array[0]);
18490cj5array[0]=IKcos(j5array[0]);
18491if( j5array[0] > IKPI )
18492{
18493 j5array[0]-=IK2PI;
18494}
18495else if( j5array[0] < -IKPI )
18496{ j5array[0]+=IK2PI;
18497}
18498j5valid[0] = true;
18499for(int ij5 = 0; ij5 < 1; ++ij5)
18500{
18501if( !j5valid[ij5] )
18502{
18503 continue;
18504}
18505_ij5[0] = ij5; _ij5[1] = -1;
18506for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18507{
18508if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18509{
18510 j5valid[iij5]=false; _ij5[1] = iij5; break;
18511}
18512}
18513j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18514{
18515IkReal evalcond[7];
18516IkReal x2078=IKcos(j5);
18517IkReal x2079=IKsin(j5);
18518IkReal x2080=((1.0000000008)*gconst28);
18519IkReal x2081=((1.0)*gconst28);
18520IkReal x2082=((1.0000000008)*x2079);
18521IkReal x2083=(gconst27*x2078);
18522IkReal x2084=(new_r00*x2078);
18523evalcond[0]=(gconst27+((new_r00*x2079))+((new_r10*x2078)));
18524evalcond[1]=(((gconst27*x2079))+((x2078*x2080))+new_r00);
18525evalcond[2]=(x2083+(((-1.0)*x2079*x2080))+new_r10);
18526evalcond[3]=((((1.0000000008)*x2083))+(((-1.0)*x2079*x2081)));
18527evalcond[4]=((((-1.0)*x2078*x2081))+(((-1.0)*gconst27*x2082)));
18528evalcond[5]=(x2080+x2084+(((-1.0)*new_r10*x2079)));
18529evalcond[6]=((((-1.0000000008)*x2084))+(((-1.0)*x2081))+((new_r10*x2082)));
18530if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18531{
18532continue;
18533}
18534}
18535
18536{
18537std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18538vinfos[0].jointtype = 1;
18539vinfos[0].foffset = j0;
18540vinfos[0].indices[0] = _ij0[0];
18541vinfos[0].indices[1] = _ij0[1];
18542vinfos[0].maxsolutions = _nj0;
18543vinfos[1].jointtype = 1;
18544vinfos[1].foffset = j1;
18545vinfos[1].indices[0] = _ij1[0];
18546vinfos[1].indices[1] = _ij1[1];
18547vinfos[1].maxsolutions = _nj1;
18548vinfos[2].jointtype = 1;
18549vinfos[2].foffset = j2;
18550vinfos[2].indices[0] = _ij2[0];
18551vinfos[2].indices[1] = _ij2[1];
18552vinfos[2].maxsolutions = _nj2;
18553vinfos[3].jointtype = 1;
18554vinfos[3].foffset = j3;
18555vinfos[3].indices[0] = _ij3[0];
18556vinfos[3].indices[1] = _ij3[1];
18557vinfos[3].maxsolutions = _nj3;
18558vinfos[4].jointtype = 1;
18559vinfos[4].foffset = j4;
18560vinfos[4].indices[0] = _ij4[0];
18561vinfos[4].indices[1] = _ij4[1];
18562vinfos[4].maxsolutions = _nj4;
18563vinfos[5].jointtype = 1;
18564vinfos[5].foffset = j5;
18565vinfos[5].indices[0] = _ij5[0];
18566vinfos[5].indices[1] = _ij5[1];
18567vinfos[5].maxsolutions = _nj5;
18568std::vector<int> vfree(0);
18569solutions.AddSolution(vinfos,vfree);
18570}
18571}
18572}
18573
18574}
18575
18576}
18577
18578} else
18579{
18580{
18581IkReal j5array[1], cj5array[1], sj5array[1];
18582bool j5valid[1]={false};
18583_nj5 = 1;
18584IkReal x2085=((25000.0)*gconst27);
18585IkReal x2086=((25000.00002)*gconst28);
18586CheckValue<IkReal> x2087 = IKatan2WithCheck(IkReal((((new_r10*x2086))+(((-1.0)*new_r00*x2085)))),IkReal(((((-1.0)*new_r10*x2085))+(((-1.0)*new_r00*x2086)))),IKFAST_ATAN2_MAGTHRESH);
18587if(!x2087.valid){
18588continue;
18589}
18590CheckValue<IkReal> x2088=IKPowWithIntegerCheck(IKsign(((((25000.0)*(new_r10*new_r10)))+(((25000.0)*(new_r00*new_r00))))),-1);
18591if(!x2088.valid){
18592continue;
18593}
18594j5array[0]=((-1.5707963267949)+(x2087.value)+(((1.5707963267949)*(x2088.value))));
18595sj5array[0]=IKsin(j5array[0]);
18596cj5array[0]=IKcos(j5array[0]);
18597if( j5array[0] > IKPI )
18598{
18599 j5array[0]-=IK2PI;
18600}
18601else if( j5array[0] < -IKPI )
18602{ j5array[0]+=IK2PI;
18603}
18604j5valid[0] = true;
18605for(int ij5 = 0; ij5 < 1; ++ij5)
18606{
18607if( !j5valid[ij5] )
18608{
18609 continue;
18610}
18611_ij5[0] = ij5; _ij5[1] = -1;
18612for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18613{
18614if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18615{
18616 j5valid[iij5]=false; _ij5[1] = iij5; break;
18617}
18618}
18619j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18620{
18621IkReal evalcond[7];
18622IkReal x2089=IKcos(j5);
18623IkReal x2090=IKsin(j5);
18624IkReal x2091=((1.0000000008)*gconst28);
18625IkReal x2092=((1.0)*gconst28);
18626IkReal x2093=((1.0000000008)*x2090);
18627IkReal x2094=(gconst27*x2089);
18628IkReal x2095=(new_r00*x2089);
18629evalcond[0]=(gconst27+((new_r00*x2090))+((new_r10*x2089)));
18630evalcond[1]=(((gconst27*x2090))+((x2089*x2091))+new_r00);
18631evalcond[2]=((((-1.0)*x2090*x2091))+x2094+new_r10);
18632evalcond[3]=((((-1.0)*x2090*x2092))+(((1.0000000008)*x2094)));
18633evalcond[4]=((((-1.0)*x2089*x2092))+(((-1.0)*gconst27*x2093)));
18634evalcond[5]=(x2095+x2091+(((-1.0)*new_r10*x2090)));
18635evalcond[6]=((((-1.0)*x2092))+((new_r10*x2093))+(((-1.0000000008)*x2095)));
18636if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
18637{
18638continue;
18639}
18640}
18641
18642{
18643std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18644vinfos[0].jointtype = 1;
18645vinfos[0].foffset = j0;
18646vinfos[0].indices[0] = _ij0[0];
18647vinfos[0].indices[1] = _ij0[1];
18648vinfos[0].maxsolutions = _nj0;
18649vinfos[1].jointtype = 1;
18650vinfos[1].foffset = j1;
18651vinfos[1].indices[0] = _ij1[0];
18652vinfos[1].indices[1] = _ij1[1];
18653vinfos[1].maxsolutions = _nj1;
18654vinfos[2].jointtype = 1;
18655vinfos[2].foffset = j2;
18656vinfos[2].indices[0] = _ij2[0];
18657vinfos[2].indices[1] = _ij2[1];
18658vinfos[2].maxsolutions = _nj2;
18659vinfos[3].jointtype = 1;
18660vinfos[3].foffset = j3;
18661vinfos[3].indices[0] = _ij3[0];
18662vinfos[3].indices[1] = _ij3[1];
18663vinfos[3].maxsolutions = _nj3;
18664vinfos[4].jointtype = 1;
18665vinfos[4].foffset = j4;
18666vinfos[4].indices[0] = _ij4[0];
18667vinfos[4].indices[1] = _ij4[1];
18668vinfos[4].maxsolutions = _nj4;
18669vinfos[5].jointtype = 1;
18670vinfos[5].foffset = j5;
18671vinfos[5].indices[0] = _ij5[0];
18672vinfos[5].indices[1] = _ij5[1];
18673vinfos[5].maxsolutions = _nj5;
18674std::vector<int> vfree(0);
18675solutions.AddSolution(vinfos,vfree);
18676}
18677}
18678}
18679
18680}
18681
18682}
18683
18684}
18685} while(0);
18686if( bgotonextstatement )
18687{
18688bool bgotonextstatement = true;
18689do
18690{
18691evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
18692if( IKabs(evalcond[0]) < 0.0000050000000000 )
18693{
18694bgotonextstatement=false;
18695{
18696IkReal j5array[1], cj5array[1], sj5array[1];
18697bool j5valid[1]={false};
18698_nj5 = 1;
18699CheckValue<IkReal> x2097=IKPowWithIntegerCheck(gconst28,-1);
18700if(!x2097.valid){
18701continue;
18702}
18703IkReal x2096=x2097.value;
18704if( IKabs((new_r01*x2096)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r00*x2096)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x2096))+IKsqr(((-0.9999999992)*new_r00*x2096))-1) <= IKFAST_SINCOS_THRESH )
18705 continue;
18706j5array[0]=IKatan2((new_r01*x2096), ((-0.9999999992)*new_r00*x2096));
18707sj5array[0]=IKsin(j5array[0]);
18708cj5array[0]=IKcos(j5array[0]);
18709if( j5array[0] > IKPI )
18710{
18711 j5array[0]-=IK2PI;
18712}
18713else if( j5array[0] < -IKPI )
18714{ j5array[0]+=IK2PI;
18715}
18716j5valid[0] = true;
18717for(int ij5 = 0; ij5 < 1; ++ij5)
18718{
18719if( !j5valid[ij5] )
18720{
18721 continue;
18722}
18723_ij5[0] = ij5; _ij5[1] = -1;
18724for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18725{
18726if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18727{
18728 j5valid[iij5]=false; _ij5[1] = iij5; break;
18729}
18730}
18731j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18732{
18733IkReal evalcond[10];
18734IkReal x2098=IKcos(j5);
18735IkReal x2099=IKsin(j5);
18736IkReal x2100=((1.0)*gconst28);
18737IkReal x2101=((1.0000000008)*gconst28);
18738IkReal x2102=(new_r00*x2098);
18739IkReal x2103=(new_r01*x2098);
18740evalcond[0]=(new_r00*x2099);
18741evalcond[1]=x2103;
18742evalcond[2]=((-1.0)*gconst28*x2098);
18743evalcond[3]=((((-1.0)*x2099*x2100))+new_r01);
18744evalcond[4]=((((-1.0)*x2100))+((new_r01*x2099)));
18745evalcond[5]=((-1.0000000008)*gconst28*x2099);
18746evalcond[6]=((-1.0000000008)*x2103);
18747evalcond[7]=(((x2098*x2101))+new_r00);
18748evalcond[8]=(x2102+x2101);
18749evalcond[9]=((((-1.0)*x2100))+(((-1.0000000008)*x2102)));
18750if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
18751{
18752continue;
18753}
18754}
18755
18756{
18757std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18758vinfos[0].jointtype = 1;
18759vinfos[0].foffset = j0;
18760vinfos[0].indices[0] = _ij0[0];
18761vinfos[0].indices[1] = _ij0[1];
18762vinfos[0].maxsolutions = _nj0;
18763vinfos[1].jointtype = 1;
18764vinfos[1].foffset = j1;
18765vinfos[1].indices[0] = _ij1[0];
18766vinfos[1].indices[1] = _ij1[1];
18767vinfos[1].maxsolutions = _nj1;
18768vinfos[2].jointtype = 1;
18769vinfos[2].foffset = j2;
18770vinfos[2].indices[0] = _ij2[0];
18771vinfos[2].indices[1] = _ij2[1];
18772vinfos[2].maxsolutions = _nj2;
18773vinfos[3].jointtype = 1;
18774vinfos[3].foffset = j3;
18775vinfos[3].indices[0] = _ij3[0];
18776vinfos[3].indices[1] = _ij3[1];
18777vinfos[3].maxsolutions = _nj3;
18778vinfos[4].jointtype = 1;
18779vinfos[4].foffset = j4;
18780vinfos[4].indices[0] = _ij4[0];
18781vinfos[4].indices[1] = _ij4[1];
18782vinfos[4].maxsolutions = _nj4;
18783vinfos[5].jointtype = 1;
18784vinfos[5].foffset = j5;
18785vinfos[5].indices[0] = _ij5[0];
18786vinfos[5].indices[1] = _ij5[1];
18787vinfos[5].maxsolutions = _nj5;
18788std::vector<int> vfree(0);
18789solutions.AddSolution(vinfos,vfree);
18790}
18791}
18792}
18793
18794}
18795} while(0);
18796if( bgotonextstatement )
18797{
18798bool bgotonextstatement = true;
18799do
18800{
18801if( 1 )
18802{
18803bgotonextstatement=false;
18804continue; // branch miss [j5]
18805
18806}
18807} while(0);
18808if( bgotonextstatement )
18809{
18810}
18811}
18812}
18813}
18814}
18815
18816} else
18817{
18818{
18819IkReal j5array[1], cj5array[1], sj5array[1];
18820bool j5valid[1]={false};
18821_nj5 = 1;
18822CheckValue<IkReal> x2109=IKPowWithIntegerCheck(new_r00,-1);
18823if(!x2109.valid){
18824continue;
18825}
18826IkReal x2104=x2109.value;
18827IkReal x2105=((25000.0)*new_r00);
18828IkReal x2106=(gconst27*x2104);
18829IkReal x2107=((25000.00002)*gconst28);
18830CheckValue<IkReal> x2110=IKPowWithIntegerCheck((((new_r10*x2107))+((gconst27*x2105))),-1);
18831if(!x2110.valid){
18832continue;
18833}
18834IkReal x2108=x2110.value;
18835if( IKabs(((((25000.0)*x2108*(new_r10*new_r10)))+((new_r10*x2106*x2107*x2108))+(((-1.0)*x2106)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2108*(((((-1.0)*gconst27*x2107))+(((-1.0)*new_r10*x2105)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((25000.0)*x2108*(new_r10*new_r10)))+((new_r10*x2106*x2107*x2108))+(((-1.0)*x2106))))+IKsqr((x2108*(((((-1.0)*gconst27*x2107))+(((-1.0)*new_r10*x2105))))))-1) <= IKFAST_SINCOS_THRESH )
18836 continue;
18837j5array[0]=IKatan2(((((25000.0)*x2108*(new_r10*new_r10)))+((new_r10*x2106*x2107*x2108))+(((-1.0)*x2106))), (x2108*(((((-1.0)*gconst27*x2107))+(((-1.0)*new_r10*x2105))))));
18838sj5array[0]=IKsin(j5array[0]);
18839cj5array[0]=IKcos(j5array[0]);
18840if( j5array[0] > IKPI )
18841{
18842 j5array[0]-=IK2PI;
18843}
18844else if( j5array[0] < -IKPI )
18845{ j5array[0]+=IK2PI;
18846}
18847j5valid[0] = true;
18848for(int ij5 = 0; ij5 < 1; ++ij5)
18849{
18850if( !j5valid[ij5] )
18851{
18852 continue;
18853}
18854_ij5[0] = ij5; _ij5[1] = -1;
18855for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18856{
18857if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18858{
18859 j5valid[iij5]=false; _ij5[1] = iij5; break;
18860}
18861}
18862j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18863{
18864IkReal evalcond[10];
18865IkReal x2111=IKcos(j5);
18866IkReal x2112=IKsin(j5);
18867IkReal x2113=((1.0)*gconst28);
18868IkReal x2114=((1.0000000008)*gconst27);
18869IkReal x2115=(new_r11*x2112);
18870IkReal x2116=((1.0000000008)*x2111);
18871IkReal x2117=((1.0000000008)*x2112);
18872evalcond[0]=(((new_r00*x2112))+gconst27+((new_r10*x2111)));
18873evalcond[1]=(((new_r01*x2112))+((new_r11*x2111))+(((-1.0)*x2113)));
18874evalcond[2]=(((gconst28*x2116))+new_r00+((gconst27*x2112)));
18875evalcond[3]=(new_r10+(((-1.0)*gconst28*x2117))+((gconst27*x2111)));
18876evalcond[4]=((((-1.0)*x2112*x2113))+((x2111*x2114))+new_r01);
18877evalcond[5]=((((-1.0)*x2112*x2114))+(((-1.0)*x2111*x2113))+new_r11);
18878evalcond[6]=(((new_r00*x2111))+(((-1.0)*new_r10*x2112))+(((1.0000000008)*gconst28)));
18879evalcond[7]=(((new_r01*x2111))+x2114+(((-1.0)*x2115)));
18880evalcond[8]=((((-1.0)*new_r00*x2116))+(((-1.0)*x2113))+((new_r10*x2117)));
18881evalcond[9]=((((-1.0)*new_r01*x2116))+(((1.0000000008)*x2115))+(((-1.0)*gconst27)));
18882if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
18883{
18884continue;
18885}
18886}
18887
18888{
18889std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18890vinfos[0].jointtype = 1;
18891vinfos[0].foffset = j0;
18892vinfos[0].indices[0] = _ij0[0];
18893vinfos[0].indices[1] = _ij0[1];
18894vinfos[0].maxsolutions = _nj0;
18895vinfos[1].jointtype = 1;
18896vinfos[1].foffset = j1;
18897vinfos[1].indices[0] = _ij1[0];
18898vinfos[1].indices[1] = _ij1[1];
18899vinfos[1].maxsolutions = _nj1;
18900vinfos[2].jointtype = 1;
18901vinfos[2].foffset = j2;
18902vinfos[2].indices[0] = _ij2[0];
18903vinfos[2].indices[1] = _ij2[1];
18904vinfos[2].maxsolutions = _nj2;
18905vinfos[3].jointtype = 1;
18906vinfos[3].foffset = j3;
18907vinfos[3].indices[0] = _ij3[0];
18908vinfos[3].indices[1] = _ij3[1];
18909vinfos[3].maxsolutions = _nj3;
18910vinfos[4].jointtype = 1;
18911vinfos[4].foffset = j4;
18912vinfos[4].indices[0] = _ij4[0];
18913vinfos[4].indices[1] = _ij4[1];
18914vinfos[4].maxsolutions = _nj4;
18915vinfos[5].jointtype = 1;
18916vinfos[5].foffset = j5;
18917vinfos[5].indices[0] = _ij5[0];
18918vinfos[5].indices[1] = _ij5[1];
18919vinfos[5].maxsolutions = _nj5;
18920std::vector<int> vfree(0);
18921solutions.AddSolution(vinfos,vfree);
18922}
18923}
18924}
18925
18926}
18927
18928}
18929
18930} else
18931{
18932{
18933IkReal j5array[1], cj5array[1], sj5array[1];
18934bool j5valid[1]={false};
18935_nj5 = 1;
18936CheckValue<IkReal> x2124=IKPowWithIntegerCheck(new_r00,-1);
18937if(!x2124.valid){
18938continue;
18939}
18940IkReal x2118=x2124.value;
18941IkReal x2119=gconst27*gconst27;
18942IkReal x2120=((25000.0)*new_r10);
18943IkReal x2121=((25000.0)*x2119);
18944CheckValue<IkReal> x2125=IKPowWithIntegerCheck(((((-1.0)*gconst27*x2120))+(((25000.00002)*gconst28*new_r00))),-1);
18945if(!x2125.valid){
18946continue;
18947}
18948IkReal x2122=x2125.value;
18949IkReal x2123=(new_r10*x2122);
18950CheckValue<IkReal> x2126=IKPowWithIntegerCheck(((((-25000.0)*gconst27*new_r10))+(((25000.00002)*gconst28*new_r00))),-1);
18951if(!x2126.valid){
18952continue;
18953}
18954CheckValue<IkReal> x2127=IKPowWithIntegerCheck(((((-25000.0)*gconst27*new_r10))+(((25000.00002)*gconst28*new_r00))),-1);
18955if(!x2127.valid){
18956continue;
18957}
18958CheckValue<IkReal> x2128=IKPowWithIntegerCheck(x2118,-2);
18959if(!x2128.valid){
18960continue;
18961}
18962if( IKabs(((((-1.0)*x2118*x2119*x2120*(x2126.value)))+(((-1.0)*gconst27*x2118))+((new_r00*x2120*(x2127.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2122*(((((-25000.0)*(x2128.value)))+x2121)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x2118*x2119*x2120*(x2126.value)))+(((-1.0)*gconst27*x2118))+((new_r00*x2120*(x2127.value)))))+IKsqr((x2122*(((((-25000.0)*(x2128.value)))+x2121))))-1) <= IKFAST_SINCOS_THRESH )
18963 continue;
18964j5array[0]=IKatan2(((((-1.0)*x2118*x2119*x2120*(x2126.value)))+(((-1.0)*gconst27*x2118))+((new_r00*x2120*(x2127.value)))), (x2122*(((((-25000.0)*(x2128.value)))+x2121))));
18965sj5array[0]=IKsin(j5array[0]);
18966cj5array[0]=IKcos(j5array[0]);
18967if( j5array[0] > IKPI )
18968{
18969 j5array[0]-=IK2PI;
18970}
18971else if( j5array[0] < -IKPI )
18972{ j5array[0]+=IK2PI;
18973}
18974j5valid[0] = true;
18975for(int ij5 = 0; ij5 < 1; ++ij5)
18976{
18977if( !j5valid[ij5] )
18978{
18979 continue;
18980}
18981_ij5[0] = ij5; _ij5[1] = -1;
18982for(int iij5 = ij5+1; iij5 < 1; ++iij5)
18983{
18984if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
18985{
18986 j5valid[iij5]=false; _ij5[1] = iij5; break;
18987}
18988}
18989j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
18990{
18991IkReal evalcond[10];
18992IkReal x2129=IKcos(j5);
18993IkReal x2130=IKsin(j5);
18994IkReal x2131=((1.0)*gconst28);
18995IkReal x2132=((1.0000000008)*gconst27);
18996IkReal x2133=(new_r11*x2130);
18997IkReal x2134=((1.0000000008)*x2129);
18998IkReal x2135=((1.0000000008)*x2130);
18999evalcond[0]=(gconst27+((new_r00*x2130))+((new_r10*x2129)));
19000evalcond[1]=((((-1.0)*x2131))+((new_r11*x2129))+((new_r01*x2130)));
19001evalcond[2]=(((gconst28*x2134))+((gconst27*x2130))+new_r00);
19002evalcond[3]=(((gconst27*x2129))+(((-1.0)*gconst28*x2135))+new_r10);
19003evalcond[4]=((((-1.0)*x2130*x2131))+new_r01+((x2129*x2132)));
19004evalcond[5]=((((-1.0)*x2130*x2132))+(((-1.0)*x2129*x2131))+new_r11);
19005evalcond[6]=((((-1.0)*new_r10*x2130))+(((1.0000000008)*gconst28))+((new_r00*x2129)));
19006evalcond[7]=(x2132+((new_r01*x2129))+(((-1.0)*x2133)));
19007evalcond[8]=(((new_r10*x2135))+(((-1.0)*x2131))+(((-1.0)*new_r00*x2134)));
19008evalcond[9]=((((-1.0)*new_r01*x2134))+(((1.0000000008)*x2133))+(((-1.0)*gconst27)));
19009if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
19010{
19011continue;
19012}
19013}
19014
19015{
19016std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19017vinfos[0].jointtype = 1;
19018vinfos[0].foffset = j0;
19019vinfos[0].indices[0] = _ij0[0];
19020vinfos[0].indices[1] = _ij0[1];
19021vinfos[0].maxsolutions = _nj0;
19022vinfos[1].jointtype = 1;
19023vinfos[1].foffset = j1;
19024vinfos[1].indices[0] = _ij1[0];
19025vinfos[1].indices[1] = _ij1[1];
19026vinfos[1].maxsolutions = _nj1;
19027vinfos[2].jointtype = 1;
19028vinfos[2].foffset = j2;
19029vinfos[2].indices[0] = _ij2[0];
19030vinfos[2].indices[1] = _ij2[1];
19031vinfos[2].maxsolutions = _nj2;
19032vinfos[3].jointtype = 1;
19033vinfos[3].foffset = j3;
19034vinfos[3].indices[0] = _ij3[0];
19035vinfos[3].indices[1] = _ij3[1];
19036vinfos[3].maxsolutions = _nj3;
19037vinfos[4].jointtype = 1;
19038vinfos[4].foffset = j4;
19039vinfos[4].indices[0] = _ij4[0];
19040vinfos[4].indices[1] = _ij4[1];
19041vinfos[4].maxsolutions = _nj4;
19042vinfos[5].jointtype = 1;
19043vinfos[5].foffset = j5;
19044vinfos[5].indices[0] = _ij5[0];
19045vinfos[5].indices[1] = _ij5[1];
19046vinfos[5].maxsolutions = _nj5;
19047std::vector<int> vfree(0);
19048solutions.AddSolution(vinfos,vfree);
19049}
19050}
19051}
19052
19053}
19054
19055}
19056
19057} else
19058{
19059{
19060IkReal j5array[1], cj5array[1], sj5array[1];
19061bool j5valid[1]={false};
19062_nj5 = 1;
19063IkReal x2136=((1.0)*new_r00);
19064CheckValue<IkReal> x2137=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x2136)))),-1);
19065if(!x2137.valid){
19066continue;
19067}
19068CheckValue<IkReal> x2138 = IKatan2WithCheck(IkReal((((gconst28*new_r10))+((gconst27*new_r11)))),IkReal(((((-1.0)*gconst27*new_r01))+(((-1.0)*gconst28*x2136)))),IKFAST_ATAN2_MAGTHRESH);
19069if(!x2138.valid){
19070continue;
19071}
19072j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2137.value)))+(x2138.value));
19073sj5array[0]=IKsin(j5array[0]);
19074cj5array[0]=IKcos(j5array[0]);
19075if( j5array[0] > IKPI )
19076{
19077 j5array[0]-=IK2PI;
19078}
19079else if( j5array[0] < -IKPI )
19080{ j5array[0]+=IK2PI;
19081}
19082j5valid[0] = true;
19083for(int ij5 = 0; ij5 < 1; ++ij5)
19084{
19085if( !j5valid[ij5] )
19086{
19087 continue;
19088}
19089_ij5[0] = ij5; _ij5[1] = -1;
19090for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19091{
19092if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19093{
19094 j5valid[iij5]=false; _ij5[1] = iij5; break;
19095}
19096}
19097j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19098{
19099IkReal evalcond[10];
19100IkReal x2139=IKcos(j5);
19101IkReal x2140=IKsin(j5);
19102IkReal x2141=((1.0)*gconst28);
19103IkReal x2142=((1.0000000008)*gconst27);
19104IkReal x2143=(new_r11*x2140);
19105IkReal x2144=((1.0000000008)*x2139);
19106IkReal x2145=((1.0000000008)*x2140);
19107evalcond[0]=(((new_r00*x2140))+((new_r10*x2139))+gconst27);
19108evalcond[1]=(((new_r11*x2139))+((new_r01*x2140))+(((-1.0)*x2141)));
19109evalcond[2]=(((gconst27*x2140))+new_r00+((gconst28*x2144)));
19110evalcond[3]=(((gconst27*x2139))+new_r10+(((-1.0)*gconst28*x2145)));
19111evalcond[4]=((((-1.0)*x2140*x2141))+new_r01+((x2139*x2142)));
19112evalcond[5]=((((-1.0)*x2140*x2142))+new_r11+(((-1.0)*x2139*x2141)));
19113evalcond[6]=((((1.0000000008)*gconst28))+((new_r00*x2139))+(((-1.0)*new_r10*x2140)));
19114evalcond[7]=((((-1.0)*x2143))+x2142+((new_r01*x2139)));
19115evalcond[8]=((((-1.0)*x2141))+(((-1.0)*new_r00*x2144))+((new_r10*x2145)));
19116evalcond[9]=((((-1.0)*new_r01*x2144))+(((1.0000000008)*x2143))+(((-1.0)*gconst27)));
19117if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
19118{
19119continue;
19120}
19121}
19122
19123{
19124std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19125vinfos[0].jointtype = 1;
19126vinfos[0].foffset = j0;
19127vinfos[0].indices[0] = _ij0[0];
19128vinfos[0].indices[1] = _ij0[1];
19129vinfos[0].maxsolutions = _nj0;
19130vinfos[1].jointtype = 1;
19131vinfos[1].foffset = j1;
19132vinfos[1].indices[0] = _ij1[0];
19133vinfos[1].indices[1] = _ij1[1];
19134vinfos[1].maxsolutions = _nj1;
19135vinfos[2].jointtype = 1;
19136vinfos[2].foffset = j2;
19137vinfos[2].indices[0] = _ij2[0];
19138vinfos[2].indices[1] = _ij2[1];
19139vinfos[2].maxsolutions = _nj2;
19140vinfos[3].jointtype = 1;
19141vinfos[3].foffset = j3;
19142vinfos[3].indices[0] = _ij3[0];
19143vinfos[3].indices[1] = _ij3[1];
19144vinfos[3].maxsolutions = _nj3;
19145vinfos[4].jointtype = 1;
19146vinfos[4].foffset = j4;
19147vinfos[4].indices[0] = _ij4[0];
19148vinfos[4].indices[1] = _ij4[1];
19149vinfos[4].maxsolutions = _nj4;
19150vinfos[5].jointtype = 1;
19151vinfos[5].foffset = j5;
19152vinfos[5].indices[0] = _ij5[0];
19153vinfos[5].indices[1] = _ij5[1];
19154vinfos[5].maxsolutions = _nj5;
19155std::vector<int> vfree(0);
19156solutions.AddSolution(vinfos,vfree);
19157}
19158}
19159}
19160
19161}
19162
19163}
19164
19165}
19166} while(0);
19167if( bgotonextstatement )
19168{
19169bool bgotonextstatement = true;
19170do
19171{
19172IkReal x2147 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
19173if(IKabs(x2147)==0){
19174continue;
19175}
19176IkReal x2146=pow(x2147,-0.5);
19177CheckValue<IkReal> x2148 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19178if(!x2148.valid){
19179continue;
19180}
19181IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2148.value))));
19182IkReal gconst30=((1.0)*new_r10*x2146);
19183IkReal gconst31=((-1.0000000008)*new_r00*x2146);
19184CheckValue<IkReal> x2149 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19185if(!x2149.valid){
19186continue;
19187}
19188evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x2149.value)+j3)))), 6.28318530717959)));
19189if( IKabs(evalcond[0]) < 0.0000050000000000 )
19190{
19191bgotonextstatement=false;
19192{
19193IkReal j5eval[2];
19194IkReal x2150=x2146;
19195sj4=-4.0e-5;
19196cj4=-1.0;
19197j4=3.14163265;
19198sj3=gconst30;
19199cj3=gconst31;
19200CheckValue<IkReal> x2151 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19201if(!x2151.valid){
19202continue;
19203}
19204j3=((3.14159265)+(((-1.0)*(x2151.value))));
19205CheckValue<IkReal> x2152 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19206if(!x2152.valid){
19207continue;
19208}
19209IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2152.value))));
19210IkReal gconst30=((1.0)*new_r10*x2150);
19211IkReal gconst31=((-1.0000000008)*new_r00*x2150);
19212IkReal x2153=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
19213j5eval[0]=x2153;
19214j5eval[1]=IKsign(x2153);
19215if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
19216{
19217{
19218IkReal j5eval[1];
19219IkReal x2154=x2146;
19220sj4=-4.0e-5;
19221cj4=-1.0;
19222j4=3.14163265;
19223sj3=gconst30;
19224cj3=gconst31;
19225CheckValue<IkReal> x2155 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19226if(!x2155.valid){
19227continue;
19228}
19229j3=((3.14159265)+(((-1.0)*(x2155.value))));
19230CheckValue<IkReal> x2156 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19231if(!x2156.valid){
19232continue;
19233}
19234IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2156.value))));
19235IkReal gconst30=((1.0)*new_r10*x2154);
19236IkReal gconst31=((-1.0000000008)*new_r00*x2154);
19237j5eval[0]=new_r00;
19238if( IKabs(j5eval[0]) < 0.0000010000000000 )
19239{
19240{
19241IkReal j5eval[2];
19242IkReal x2157=x2146;
19243sj4=-4.0e-5;
19244cj4=-1.0;
19245j4=3.14163265;
19246sj3=gconst30;
19247cj3=gconst31;
19248CheckValue<IkReal> x2158 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19249if(!x2158.valid){
19250continue;
19251}
19252j3=((3.14159265)+(((-1.0)*(x2158.value))));
19253CheckValue<IkReal> x2159 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19254if(!x2159.valid){
19255continue;
19256}
19257IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2159.value))));
19258IkReal gconst30=((1.0)*new_r10*x2157);
19259IkReal gconst31=((-1.0000000008)*new_r00*x2157);
19260IkReal x2160 = ((((1.0000000016)*(new_r00*new_r00)))+(new_r10*new_r10));
19261if(IKabs(x2160)==0){
19262continue;
19263}
19264j5eval[0]=((-1.60000013238459e-9)*new_r00*new_r10*(pow(x2160,-0.5)));
19265j5eval[1]=new_r00;
19266if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
19267{
19268{
19269IkReal evalcond[1];
19270bool bgotonextstatement = true;
19271do
19272{
19273evalcond[0]=IKabs(new_r00);
19274if( IKabs(evalcond[0]) < 0.0000050000000000 )
19275{
19276bgotonextstatement=false;
19277{
19278IkReal j5eval[1];
19279CheckValue<IkReal> x2162 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
19280if(!x2162.valid){
19281continue;
19282}
19283IkReal x2161=((1.0)*(x2162.value));
19284sj4=-4.0e-5;
19285cj4=-1.0;
19286j4=3.14163265;
19287sj3=gconst30;
19288cj3=gconst31;
19289j3=((3.14159265)+(((-1.0)*x2161)));
19290new_r00=0;
19291IkReal gconst29=((3.14159265358979)+(((-1.0)*x2161)));
19292IkReal x2163 = new_r10*new_r10;
19293if(IKabs(x2163)==0){
19294continue;
19295}
19296IkReal gconst30=((1.0)*new_r10*(pow(x2163,-0.5)));
19297IkReal gconst31=0;
19298j5eval[0]=new_r10;
19299if( IKabs(j5eval[0]) < 0.0000010000000000 )
19300{
19301{
19302IkReal j5array[1], cj5array[1], sj5array[1];
19303bool j5valid[1]={false};
19304_nj5 = 1;
19305CheckValue<IkReal> x2165=IKPowWithIntegerCheck(gconst30,-1);
19306if(!x2165.valid){
19307continue;
19308}
19309IkReal x2164=x2165.value;
19310if( IKabs(((0.9999999992)*new_r11*x2164)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10*x2164)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*x2164))+IKsqr(((-1.0)*new_r10*x2164))-1) <= IKFAST_SINCOS_THRESH )
19311 continue;
19312j5array[0]=IKatan2(((0.9999999992)*new_r11*x2164), ((-1.0)*new_r10*x2164));
19313sj5array[0]=IKsin(j5array[0]);
19314cj5array[0]=IKcos(j5array[0]);
19315if( j5array[0] > IKPI )
19316{
19317 j5array[0]-=IK2PI;
19318}
19319else if( j5array[0] < -IKPI )
19320{ j5array[0]+=IK2PI;
19321}
19322j5valid[0] = true;
19323for(int ij5 = 0; ij5 < 1; ++ij5)
19324{
19325if( !j5valid[ij5] )
19326{
19327 continue;
19328}
19329_ij5[0] = ij5; _ij5[1] = -1;
19330for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19331{
19332if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19333{
19334 j5valid[iij5]=false; _ij5[1] = iij5; break;
19335}
19336}
19337j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19338{
19339IkReal evalcond[10];
19340IkReal x2166=IKsin(j5);
19341IkReal x2167=IKcos(j5);
19342IkReal x2168=((1.0000000008)*x2166);
19343IkReal x2169=(gconst30*x2167);
19344IkReal x2170=(new_r01*x2167);
19345evalcond[0]=(gconst30*x2166);
19346evalcond[1]=((-1.0)*new_r10*x2166);
19347evalcond[2]=(gconst30+((new_r10*x2167)));
19348evalcond[3]=(x2169+new_r10);
19349evalcond[4]=(new_r10*x2168);
19350evalcond[5]=(((new_r11*x2167))+((new_r01*x2166)));
19351evalcond[6]=((((1.0000000008)*x2169))+new_r01);
19352evalcond[7]=((((-1.0)*gconst30*x2168))+new_r11);
19353evalcond[8]=((((-1.0)*new_r11*x2166))+x2170+(((1.0000000008)*gconst30)));
19354evalcond[9]=((((-1.0000000008)*x2170))+((new_r11*x2168))+(((-1.0)*gconst30)));
19355if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
19356{
19357continue;
19358}
19359}
19360
19361{
19362std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19363vinfos[0].jointtype = 1;
19364vinfos[0].foffset = j0;
19365vinfos[0].indices[0] = _ij0[0];
19366vinfos[0].indices[1] = _ij0[1];
19367vinfos[0].maxsolutions = _nj0;
19368vinfos[1].jointtype = 1;
19369vinfos[1].foffset = j1;
19370vinfos[1].indices[0] = _ij1[0];
19371vinfos[1].indices[1] = _ij1[1];
19372vinfos[1].maxsolutions = _nj1;
19373vinfos[2].jointtype = 1;
19374vinfos[2].foffset = j2;
19375vinfos[2].indices[0] = _ij2[0];
19376vinfos[2].indices[1] = _ij2[1];
19377vinfos[2].maxsolutions = _nj2;
19378vinfos[3].jointtype = 1;
19379vinfos[3].foffset = j3;
19380vinfos[3].indices[0] = _ij3[0];
19381vinfos[3].indices[1] = _ij3[1];
19382vinfos[3].maxsolutions = _nj3;
19383vinfos[4].jointtype = 1;
19384vinfos[4].foffset = j4;
19385vinfos[4].indices[0] = _ij4[0];
19386vinfos[4].indices[1] = _ij4[1];
19387vinfos[4].maxsolutions = _nj4;
19388vinfos[5].jointtype = 1;
19389vinfos[5].foffset = j5;
19390vinfos[5].indices[0] = _ij5[0];
19391vinfos[5].indices[1] = _ij5[1];
19392vinfos[5].maxsolutions = _nj5;
19393std::vector<int> vfree(0);
19394solutions.AddSolution(vinfos,vfree);
19395}
19396}
19397}
19398
19399} else
19400{
19401{
19402IkReal j5array[1], cj5array[1], sj5array[1];
19403bool j5valid[1]={false};
19404_nj5 = 1;
19405CheckValue<IkReal> x2171=IKPowWithIntegerCheck(gconst30,-1);
19406if(!x2171.valid){
19407continue;
19408}
19409CheckValue<IkReal> x2172=IKPowWithIntegerCheck(new_r10,-1);
19410if(!x2172.valid){
19411continue;
19412}
19413if( IKabs(((0.9999999992)*new_r11*(x2171.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst30*(x2172.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*(x2171.value)))+IKsqr(((-1.0)*gconst30*(x2172.value)))-1) <= IKFAST_SINCOS_THRESH )
19414 continue;
19415j5array[0]=IKatan2(((0.9999999992)*new_r11*(x2171.value)), ((-1.0)*gconst30*(x2172.value)));
19416sj5array[0]=IKsin(j5array[0]);
19417cj5array[0]=IKcos(j5array[0]);
19418if( j5array[0] > IKPI )
19419{
19420 j5array[0]-=IK2PI;
19421}
19422else if( j5array[0] < -IKPI )
19423{ j5array[0]+=IK2PI;
19424}
19425j5valid[0] = true;
19426for(int ij5 = 0; ij5 < 1; ++ij5)
19427{
19428if( !j5valid[ij5] )
19429{
19430 continue;
19431}
19432_ij5[0] = ij5; _ij5[1] = -1;
19433for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19434{
19435if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19436{
19437 j5valid[iij5]=false; _ij5[1] = iij5; break;
19438}
19439}
19440j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19441{
19442IkReal evalcond[10];
19443IkReal x2173=IKsin(j5);
19444IkReal x2174=IKcos(j5);
19445IkReal x2175=((1.0000000008)*x2173);
19446IkReal x2176=(gconst30*x2174);
19447IkReal x2177=(new_r01*x2174);
19448evalcond[0]=(gconst30*x2173);
19449evalcond[1]=((-1.0)*new_r10*x2173);
19450evalcond[2]=(gconst30+((new_r10*x2174)));
19451evalcond[3]=(x2176+new_r10);
19452evalcond[4]=(new_r10*x2175);
19453evalcond[5]=(((new_r11*x2174))+((new_r01*x2173)));
19454evalcond[6]=((((1.0000000008)*x2176))+new_r01);
19455evalcond[7]=((((-1.0)*gconst30*x2175))+new_r11);
19456evalcond[8]=(x2177+(((-1.0)*new_r11*x2173))+(((1.0000000008)*gconst30)));
19457evalcond[9]=(((new_r11*x2175))+(((-1.0000000008)*x2177))+(((-1.0)*gconst30)));
19458if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
19459{
19460continue;
19461}
19462}
19463
19464{
19465std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19466vinfos[0].jointtype = 1;
19467vinfos[0].foffset = j0;
19468vinfos[0].indices[0] = _ij0[0];
19469vinfos[0].indices[1] = _ij0[1];
19470vinfos[0].maxsolutions = _nj0;
19471vinfos[1].jointtype = 1;
19472vinfos[1].foffset = j1;
19473vinfos[1].indices[0] = _ij1[0];
19474vinfos[1].indices[1] = _ij1[1];
19475vinfos[1].maxsolutions = _nj1;
19476vinfos[2].jointtype = 1;
19477vinfos[2].foffset = j2;
19478vinfos[2].indices[0] = _ij2[0];
19479vinfos[2].indices[1] = _ij2[1];
19480vinfos[2].maxsolutions = _nj2;
19481vinfos[3].jointtype = 1;
19482vinfos[3].foffset = j3;
19483vinfos[3].indices[0] = _ij3[0];
19484vinfos[3].indices[1] = _ij3[1];
19485vinfos[3].maxsolutions = _nj3;
19486vinfos[4].jointtype = 1;
19487vinfos[4].foffset = j4;
19488vinfos[4].indices[0] = _ij4[0];
19489vinfos[4].indices[1] = _ij4[1];
19490vinfos[4].maxsolutions = _nj4;
19491vinfos[5].jointtype = 1;
19492vinfos[5].foffset = j5;
19493vinfos[5].indices[0] = _ij5[0];
19494vinfos[5].indices[1] = _ij5[1];
19495vinfos[5].maxsolutions = _nj5;
19496std::vector<int> vfree(0);
19497solutions.AddSolution(vinfos,vfree);
19498}
19499}
19500}
19501
19502}
19503
19504}
19505
19506}
19507} while(0);
19508if( bgotonextstatement )
19509{
19510bool bgotonextstatement = true;
19511do
19512{
19513evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
19514if( IKabs(evalcond[0]) < 0.0000050000000000 )
19515{
19516bgotonextstatement=false;
19517{
19518IkReal j5eval[3];
19519IkReal x2179 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
19520if(IKabs(x2179)==0){
19521continue;
19522}
19523IkReal x2178=pow(x2179,-0.5);
19524sj4=-4.0e-5;
19525cj4=-1.0;
19526j4=3.14163265;
19527sj3=gconst30;
19528cj3=gconst31;
19529CheckValue<IkReal> x2180 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19530if(!x2180.valid){
19531continue;
19532}
19533j3=((3.14159265)+(((-1.0)*(x2180.value))));
19534new_r11=0;
19535new_r01=0;
19536new_r22=0;
19537new_r20=0;
19538CheckValue<IkReal> x2181 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19539if(!x2181.valid){
19540continue;
19541}
19542IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2181.value))));
19543IkReal gconst30=((1.0)*new_r10*x2178);
19544IkReal gconst31=((-1.0000000008)*new_r00*x2178);
19545IkReal x2182=new_r10*new_r10;
19546CheckValue<IkReal> x2186=IKPowWithIntegerCheck(((-3.90625000625e+17)+(((625000000.0)*x2182))),-1);
19547if(!x2186.valid){
19548continue;
19549}
19550IkReal x2183=x2186.value;
19551if((((625000001.0)+(((-1.0)*x2182)))) < -0.00001)
19552continue;
19553IkReal x2184=IKsqrt(((625000001.0)+(((-1.0)*x2182))));
19554IkReal x2185=(x2183*x2184);
19555j5eval[0]=1.0;
19556j5eval[1]=1.0;
19557IkReal x2187 = ((1.0000000016)+(((-1.6e-9)*x2182)));
19558if(IKabs(x2187)==0){
19559continue;
19560}
19561j5eval[2]=((IKabs(((((-3.90625000625e+17)*x2185))+(((7.81250000625e+17)*x2182*x2185)))))+(IKabs(((50000.00004)*new_r00*new_r10*(pow(x2187,-0.5))))));
19562if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
19563{
19564{
19565IkReal j5eval[1];
19566IkReal x2189 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
19567if(IKabs(x2189)==0){
19568continue;
19569}
19570IkReal x2188=pow(x2189,-0.5);
19571sj4=-4.0e-5;
19572cj4=-1.0;
19573j4=3.14163265;
19574sj3=gconst30;
19575cj3=gconst31;
19576CheckValue<IkReal> x2190 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19577if(!x2190.valid){
19578continue;
19579}
19580j3=((3.14159265)+(((-1.0)*(x2190.value))));
19581new_r11=0;
19582new_r01=0;
19583new_r22=0;
19584new_r20=0;
19585CheckValue<IkReal> x2191 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19586if(!x2191.valid){
19587continue;
19588}
19589IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2191.value))));
19590IkReal gconst30=((1.0)*new_r10*x2188);
19591IkReal gconst31=((-1.0000000008)*new_r00*x2188);
19592IkReal x2192=new_r10*new_r10;
19593CheckValue<IkReal> x2194=IKPowWithIntegerCheck(((1.0000000016)+(((-1.6e-9)*x2192))),-1);
19594if(!x2194.valid){
19595continue;
19596}
19597IkReal x2193=x2194.value;
19598IkReal x2195=((1.0)+(((-1.0)*x2192)));
19599j5eval[0]=IKsign(((((-625000001.0)*x2193*(x2195*x2195)))+(((625000001.0)*x2193*(x2192*x2192)))));
19600if( IKabs(j5eval[0]) < 0.0000010000000000 )
19601{
19602{
19603IkReal j5eval[1];
19604IkReal x2197 = ((1.0000000016)+(((-1.6e-9)*(new_r10*new_r10))));
19605if(IKabs(x2197)==0){
19606continue;
19607}
19608IkReal x2196=pow(x2197,-0.5);
19609sj4=-4.0e-5;
19610cj4=-1.0;
19611j4=3.14163265;
19612sj3=gconst30;
19613cj3=gconst31;
19614CheckValue<IkReal> x2198 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
19615if(!x2198.valid){
19616continue;
19617}
19618j3=((3.14159265)+(((-1.0)*(x2198.value))));
19619new_r11=0;
19620new_r01=0;
19621new_r22=0;
19622new_r20=0;
19623CheckValue<IkReal> x2199 = IKatan2WithCheck(IkReal(new_r10),IkReal(((1.0000000008)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
19624if(!x2199.valid){
19625continue;
19626}
19627IkReal gconst29=((3.14159265358979)+(((-1.0)*(x2199.value))));
19628IkReal gconst30=((1.0)*new_r10*x2196);
19629IkReal gconst31=((-1.0000000008)*new_r00*x2196);
19630j5eval[0]=new_r00;
19631if( IKabs(j5eval[0]) < 0.0000010000000000 )
19632{
19633continue; // 3 cases reached
19634
19635} else
19636{
19637{
19638IkReal j5array[1], cj5array[1], sj5array[1];
19639bool j5valid[1]={false};
19640_nj5 = 1;
19641CheckValue<IkReal> x2206=IKPowWithIntegerCheck(new_r00,-1);
19642if(!x2206.valid){
19643continue;
19644}
19645IkReal x2200=x2206.value;
19646IkReal x2201=gconst30*gconst30;
19647IkReal x2202=((25000.0)*new_r10);
19648IkReal x2203=((25000.0)*x2201);
19649CheckValue<IkReal> x2207=IKPowWithIntegerCheck(((((-1.0)*gconst30*x2202))+(((25000.00002)*gconst31*new_r00))),-1);
19650if(!x2207.valid){
19651continue;
19652}
19653IkReal x2204=x2207.value;
19654IkReal x2205=(new_r10*x2204);
19655CheckValue<IkReal> x2208=IKPowWithIntegerCheck(((((-25000.0)*gconst30*new_r10))+(((25000.00002)*gconst31*new_r00))),-1);
19656if(!x2208.valid){
19657continue;
19658}
19659CheckValue<IkReal> x2209=IKPowWithIntegerCheck(((((-25000.0)*gconst30*new_r10))+(((25000.00002)*gconst31*new_r00))),-1);
19660if(!x2209.valid){
19661continue;
19662}
19663CheckValue<IkReal> x2210=IKPowWithIntegerCheck(x2200,-2);
19664if(!x2210.valid){
19665continue;
19666}
19667if( IKabs(((((-1.0)*gconst30*x2200))+((new_r00*x2202*(x2208.value)))+(((-1.0)*x2200*x2201*x2202*(x2209.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2204*((x2203+(((-25000.0)*(x2210.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*gconst30*x2200))+((new_r00*x2202*(x2208.value)))+(((-1.0)*x2200*x2201*x2202*(x2209.value)))))+IKsqr((x2204*((x2203+(((-25000.0)*(x2210.value)))))))-1) <= IKFAST_SINCOS_THRESH )
19668 continue;
19669j5array[0]=IKatan2(((((-1.0)*gconst30*x2200))+((new_r00*x2202*(x2208.value)))+(((-1.0)*x2200*x2201*x2202*(x2209.value)))), (x2204*((x2203+(((-25000.0)*(x2210.value)))))));
19670sj5array[0]=IKsin(j5array[0]);
19671cj5array[0]=IKcos(j5array[0]);
19672if( j5array[0] > IKPI )
19673{
19674 j5array[0]-=IK2PI;
19675}
19676else if( j5array[0] < -IKPI )
19677{ j5array[0]+=IK2PI;
19678}
19679j5valid[0] = true;
19680for(int ij5 = 0; ij5 < 1; ++ij5)
19681{
19682if( !j5valid[ij5] )
19683{
19684 continue;
19685}
19686_ij5[0] = ij5; _ij5[1] = -1;
19687for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19688{
19689if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19690{
19691 j5valid[iij5]=false; _ij5[1] = iij5; break;
19692}
19693}
19694j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19695{
19696IkReal evalcond[7];
19697IkReal x2211=IKsin(j5);
19698IkReal x2212=IKcos(j5);
19699IkReal x2213=((1.0)*gconst31);
19700IkReal x2214=((1.0000000008)*x2212);
19701IkReal x2215=((1.0000000008)*x2211);
19702evalcond[0]=(gconst30+((new_r00*x2211))+((new_r10*x2212)));
19703evalcond[1]=(((gconst31*x2214))+((gconst30*x2211))+new_r00);
19704evalcond[2]=(((gconst30*x2212))+(((-1.0)*gconst31*x2215))+new_r10);
19705evalcond[3]=(((gconst30*x2214))+(((-1.0)*x2211*x2213)));
19706evalcond[4]=((((-1.0)*gconst30*x2215))+(((-1.0)*x2212*x2213)));
19707evalcond[5]=((((-1.0)*new_r10*x2211))+((new_r00*x2212))+(((1.0000000008)*gconst31)));
19708evalcond[6]=((((-1.0)*x2213))+((new_r10*x2215))+(((-1.0)*new_r00*x2214)));
19709if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
19710{
19711continue;
19712}
19713}
19714
19715{
19716std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19717vinfos[0].jointtype = 1;
19718vinfos[0].foffset = j0;
19719vinfos[0].indices[0] = _ij0[0];
19720vinfos[0].indices[1] = _ij0[1];
19721vinfos[0].maxsolutions = _nj0;
19722vinfos[1].jointtype = 1;
19723vinfos[1].foffset = j1;
19724vinfos[1].indices[0] = _ij1[0];
19725vinfos[1].indices[1] = _ij1[1];
19726vinfos[1].maxsolutions = _nj1;
19727vinfos[2].jointtype = 1;
19728vinfos[2].foffset = j2;
19729vinfos[2].indices[0] = _ij2[0];
19730vinfos[2].indices[1] = _ij2[1];
19731vinfos[2].maxsolutions = _nj2;
19732vinfos[3].jointtype = 1;
19733vinfos[3].foffset = j3;
19734vinfos[3].indices[0] = _ij3[0];
19735vinfos[3].indices[1] = _ij3[1];
19736vinfos[3].maxsolutions = _nj3;
19737vinfos[4].jointtype = 1;
19738vinfos[4].foffset = j4;
19739vinfos[4].indices[0] = _ij4[0];
19740vinfos[4].indices[1] = _ij4[1];
19741vinfos[4].maxsolutions = _nj4;
19742vinfos[5].jointtype = 1;
19743vinfos[5].foffset = j5;
19744vinfos[5].indices[0] = _ij5[0];
19745vinfos[5].indices[1] = _ij5[1];
19746vinfos[5].maxsolutions = _nj5;
19747std::vector<int> vfree(0);
19748solutions.AddSolution(vinfos,vfree);
19749}
19750}
19751}
19752
19753}
19754
19755}
19756
19757} else
19758{
19759{
19760IkReal j5array[1], cj5array[1], sj5array[1];
19761bool j5valid[1]={false};
19762_nj5 = 1;
19763IkReal x2216=gconst30*gconst30;
19764IkReal x2217=gconst31*gconst31;
19765IkReal x2218=((625000000.0)*x2217);
19766IkReal x2219=((625000000.5)*gconst31*x2216);
19767CheckValue<IkReal> x2220=IKPowWithIntegerCheck(IKsign(((((625000001.0)*x2216*(new_r10*new_r10)))+(((-1.0)*x2218*(new_r00*new_r00))))),-1);
19768if(!x2220.valid){
19769continue;
19770}
19771CheckValue<IkReal> x2221 = IKatan2WithCheck(IkReal((((gconst30*new_r00*x2218))+((new_r10*x2219)))),IkReal(((((-625000001.0)*new_r10*(gconst30*gconst30*gconst30)))+(((-1.0)*new_r00*x2219)))),IKFAST_ATAN2_MAGTHRESH);
19772if(!x2221.valid){
19773continue;
19774}
19775j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2220.value)))+(x2221.value));
19776sj5array[0]=IKsin(j5array[0]);
19777cj5array[0]=IKcos(j5array[0]);
19778if( j5array[0] > IKPI )
19779{
19780 j5array[0]-=IK2PI;
19781}
19782else if( j5array[0] < -IKPI )
19783{ j5array[0]+=IK2PI;
19784}
19785j5valid[0] = true;
19786for(int ij5 = 0; ij5 < 1; ++ij5)
19787{
19788if( !j5valid[ij5] )
19789{
19790 continue;
19791}
19792_ij5[0] = ij5; _ij5[1] = -1;
19793for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19794{
19795if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19796{
19797 j5valid[iij5]=false; _ij5[1] = iij5; break;
19798}
19799}
19800j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19801{
19802IkReal evalcond[7];
19803IkReal x2222=IKsin(j5);
19804IkReal x2223=IKcos(j5);
19805IkReal x2224=((1.0)*gconst31);
19806IkReal x2225=((1.0000000008)*x2223);
19807IkReal x2226=((1.0000000008)*x2222);
19808evalcond[0]=(((new_r00*x2222))+((new_r10*x2223))+gconst30);
19809evalcond[1]=(((gconst30*x2222))+((gconst31*x2225))+new_r00);
19810evalcond[2]=(((gconst30*x2223))+(((-1.0)*gconst31*x2226))+new_r10);
19811evalcond[3]=((((-1.0)*x2222*x2224))+((gconst30*x2225)));
19812evalcond[4]=((((-1.0)*x2223*x2224))+(((-1.0)*gconst30*x2226)));
19813evalcond[5]=(((new_r00*x2223))+(((1.0000000008)*gconst31))+(((-1.0)*new_r10*x2222)));
19814evalcond[6]=((((-1.0)*new_r00*x2225))+((new_r10*x2226))+(((-1.0)*x2224)));
19815if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
19816{
19817continue;
19818}
19819}
19820
19821{
19822std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19823vinfos[0].jointtype = 1;
19824vinfos[0].foffset = j0;
19825vinfos[0].indices[0] = _ij0[0];
19826vinfos[0].indices[1] = _ij0[1];
19827vinfos[0].maxsolutions = _nj0;
19828vinfos[1].jointtype = 1;
19829vinfos[1].foffset = j1;
19830vinfos[1].indices[0] = _ij1[0];
19831vinfos[1].indices[1] = _ij1[1];
19832vinfos[1].maxsolutions = _nj1;
19833vinfos[2].jointtype = 1;
19834vinfos[2].foffset = j2;
19835vinfos[2].indices[0] = _ij2[0];
19836vinfos[2].indices[1] = _ij2[1];
19837vinfos[2].maxsolutions = _nj2;
19838vinfos[3].jointtype = 1;
19839vinfos[3].foffset = j3;
19840vinfos[3].indices[0] = _ij3[0];
19841vinfos[3].indices[1] = _ij3[1];
19842vinfos[3].maxsolutions = _nj3;
19843vinfos[4].jointtype = 1;
19844vinfos[4].foffset = j4;
19845vinfos[4].indices[0] = _ij4[0];
19846vinfos[4].indices[1] = _ij4[1];
19847vinfos[4].maxsolutions = _nj4;
19848vinfos[5].jointtype = 1;
19849vinfos[5].foffset = j5;
19850vinfos[5].indices[0] = _ij5[0];
19851vinfos[5].indices[1] = _ij5[1];
19852vinfos[5].maxsolutions = _nj5;
19853std::vector<int> vfree(0);
19854solutions.AddSolution(vinfos,vfree);
19855}
19856}
19857}
19858
19859}
19860
19861}
19862
19863} else
19864{
19865{
19866IkReal j5array[1], cj5array[1], sj5array[1];
19867bool j5valid[1]={false};
19868_nj5 = 1;
19869IkReal x2227=((25000.0)*gconst30);
19870IkReal x2228=((25000.00002)*gconst31);
19871CheckValue<IkReal> x2229 = IKatan2WithCheck(IkReal(((((-1.0)*new_r00*x2227))+((new_r10*x2228)))),IkReal(((((-1.0)*new_r00*x2228))+(((-1.0)*new_r10*x2227)))),IKFAST_ATAN2_MAGTHRESH);
19872if(!x2229.valid){
19873continue;
19874}
19875CheckValue<IkReal> x2230=IKPowWithIntegerCheck(IKsign(((((25000.0)*(new_r10*new_r10)))+(((25000.0)*(new_r00*new_r00))))),-1);
19876if(!x2230.valid){
19877continue;
19878}
19879j5array[0]=((-1.5707963267949)+(x2229.value)+(((1.5707963267949)*(x2230.value))));
19880sj5array[0]=IKsin(j5array[0]);
19881cj5array[0]=IKcos(j5array[0]);
19882if( j5array[0] > IKPI )
19883{
19884 j5array[0]-=IK2PI;
19885}
19886else if( j5array[0] < -IKPI )
19887{ j5array[0]+=IK2PI;
19888}
19889j5valid[0] = true;
19890for(int ij5 = 0; ij5 < 1; ++ij5)
19891{
19892if( !j5valid[ij5] )
19893{
19894 continue;
19895}
19896_ij5[0] = ij5; _ij5[1] = -1;
19897for(int iij5 = ij5+1; iij5 < 1; ++iij5)
19898{
19899if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
19900{
19901 j5valid[iij5]=false; _ij5[1] = iij5; break;
19902}
19903}
19904j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
19905{
19906IkReal evalcond[7];
19907IkReal x2231=IKsin(j5);
19908IkReal x2232=IKcos(j5);
19909IkReal x2233=((1.0)*gconst31);
19910IkReal x2234=((1.0000000008)*x2232);
19911IkReal x2235=((1.0000000008)*x2231);
19912evalcond[0]=(((new_r00*x2231))+((new_r10*x2232))+gconst30);
19913evalcond[1]=(((gconst31*x2234))+((gconst30*x2231))+new_r00);
19914evalcond[2]=(((gconst30*x2232))+(((-1.0)*gconst31*x2235))+new_r10);
19915evalcond[3]=(((gconst30*x2234))+(((-1.0)*x2231*x2233)));
19916evalcond[4]=((((-1.0)*x2232*x2233))+(((-1.0)*gconst30*x2235)));
19917evalcond[5]=(((new_r00*x2232))+(((1.0000000008)*gconst31))+(((-1.0)*new_r10*x2231)));
19918evalcond[6]=((((-1.0)*new_r00*x2234))+((new_r10*x2235))+(((-1.0)*x2233)));
19919if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH )
19920{
19921continue;
19922}
19923}
19924
19925{
19926std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19927vinfos[0].jointtype = 1;
19928vinfos[0].foffset = j0;
19929vinfos[0].indices[0] = _ij0[0];
19930vinfos[0].indices[1] = _ij0[1];
19931vinfos[0].maxsolutions = _nj0;
19932vinfos[1].jointtype = 1;
19933vinfos[1].foffset = j1;
19934vinfos[1].indices[0] = _ij1[0];
19935vinfos[1].indices[1] = _ij1[1];
19936vinfos[1].maxsolutions = _nj1;
19937vinfos[2].jointtype = 1;
19938vinfos[2].foffset = j2;
19939vinfos[2].indices[0] = _ij2[0];
19940vinfos[2].indices[1] = _ij2[1];
19941vinfos[2].maxsolutions = _nj2;
19942vinfos[3].jointtype = 1;
19943vinfos[3].foffset = j3;
19944vinfos[3].indices[0] = _ij3[0];
19945vinfos[3].indices[1] = _ij3[1];
19946vinfos[3].maxsolutions = _nj3;
19947vinfos[4].jointtype = 1;
19948vinfos[4].foffset = j4;
19949vinfos[4].indices[0] = _ij4[0];
19950vinfos[4].indices[1] = _ij4[1];
19951vinfos[4].maxsolutions = _nj4;
19952vinfos[5].jointtype = 1;
19953vinfos[5].foffset = j5;
19954vinfos[5].indices[0] = _ij5[0];
19955vinfos[5].indices[1] = _ij5[1];
19956vinfos[5].maxsolutions = _nj5;
19957std::vector<int> vfree(0);
19958solutions.AddSolution(vinfos,vfree);
19959}
19960}
19961}
19962
19963}
19964
19965}
19966
19967}
19968} while(0);
19969if( bgotonextstatement )
19970{
19971bool bgotonextstatement = true;
19972do
19973{
19974evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
19975if( IKabs(evalcond[0]) < 0.0000050000000000 )
19976{
19977bgotonextstatement=false;
19978{
19979IkReal j5array[1], cj5array[1], sj5array[1];
19980bool j5valid[1]={false};
19981_nj5 = 1;
19982CheckValue<IkReal> x2237=IKPowWithIntegerCheck(gconst31,-1);
19983if(!x2237.valid){
19984continue;
19985}
19986IkReal x2236=x2237.value;
19987if( IKabs((new_r01*x2236)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r00*x2236)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*x2236))+IKsqr(((-0.9999999992)*new_r00*x2236))-1) <= IKFAST_SINCOS_THRESH )
19988 continue;
19989j5array[0]=IKatan2((new_r01*x2236), ((-0.9999999992)*new_r00*x2236));
19990sj5array[0]=IKsin(j5array[0]);
19991cj5array[0]=IKcos(j5array[0]);
19992if( j5array[0] > IKPI )
19993{
19994 j5array[0]-=IK2PI;
19995}
19996else if( j5array[0] < -IKPI )
19997{ j5array[0]+=IK2PI;
19998}
19999j5valid[0] = true;
20000for(int ij5 = 0; ij5 < 1; ++ij5)
20001{
20002if( !j5valid[ij5] )
20003{
20004 continue;
20005}
20006_ij5[0] = ij5; _ij5[1] = -1;
20007for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20008{
20009if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20010{
20011 j5valid[iij5]=false; _ij5[1] = iij5; break;
20012}
20013}
20014j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20015{
20016IkReal evalcond[10];
20017IkReal x2238=IKcos(j5);
20018IkReal x2239=IKsin(j5);
20019IkReal x2240=((1.0)*gconst31);
20020IkReal x2241=((1.0000000008)*gconst31);
20021IkReal x2242=(new_r00*x2238);
20022IkReal x2243=(new_r01*x2238);
20023evalcond[0]=(new_r00*x2239);
20024evalcond[1]=x2243;
20025evalcond[2]=((-1.0)*gconst31*x2238);
20026evalcond[3]=((((-1.0)*x2239*x2240))+new_r01);
20027evalcond[4]=(((new_r01*x2239))+(((-1.0)*x2240)));
20028evalcond[5]=((-1.0000000008)*gconst31*x2239);
20029evalcond[6]=((-1.0000000008)*x2243);
20030evalcond[7]=(new_r00+((x2238*x2241)));
20031evalcond[8]=(x2241+x2242);
20032evalcond[9]=((((-1.0000000008)*x2242))+(((-1.0)*x2240)));
20033if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20034{
20035continue;
20036}
20037}
20038
20039{
20040std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20041vinfos[0].jointtype = 1;
20042vinfos[0].foffset = j0;
20043vinfos[0].indices[0] = _ij0[0];
20044vinfos[0].indices[1] = _ij0[1];
20045vinfos[0].maxsolutions = _nj0;
20046vinfos[1].jointtype = 1;
20047vinfos[1].foffset = j1;
20048vinfos[1].indices[0] = _ij1[0];
20049vinfos[1].indices[1] = _ij1[1];
20050vinfos[1].maxsolutions = _nj1;
20051vinfos[2].jointtype = 1;
20052vinfos[2].foffset = j2;
20053vinfos[2].indices[0] = _ij2[0];
20054vinfos[2].indices[1] = _ij2[1];
20055vinfos[2].maxsolutions = _nj2;
20056vinfos[3].jointtype = 1;
20057vinfos[3].foffset = j3;
20058vinfos[3].indices[0] = _ij3[0];
20059vinfos[3].indices[1] = _ij3[1];
20060vinfos[3].maxsolutions = _nj3;
20061vinfos[4].jointtype = 1;
20062vinfos[4].foffset = j4;
20063vinfos[4].indices[0] = _ij4[0];
20064vinfos[4].indices[1] = _ij4[1];
20065vinfos[4].maxsolutions = _nj4;
20066vinfos[5].jointtype = 1;
20067vinfos[5].foffset = j5;
20068vinfos[5].indices[0] = _ij5[0];
20069vinfos[5].indices[1] = _ij5[1];
20070vinfos[5].maxsolutions = _nj5;
20071std::vector<int> vfree(0);
20072solutions.AddSolution(vinfos,vfree);
20073}
20074}
20075}
20076
20077}
20078} while(0);
20079if( bgotonextstatement )
20080{
20081bool bgotonextstatement = true;
20082do
20083{
20084if( 1 )
20085{
20086bgotonextstatement=false;
20087continue; // branch miss [j5]
20088
20089}
20090} while(0);
20091if( bgotonextstatement )
20092{
20093}
20094}
20095}
20096}
20097}
20098
20099} else
20100{
20101{
20102IkReal j5array[1], cj5array[1], sj5array[1];
20103bool j5valid[1]={false};
20104_nj5 = 1;
20105CheckValue<IkReal> x2249=IKPowWithIntegerCheck(new_r00,-1);
20106if(!x2249.valid){
20107continue;
20108}
20109IkReal x2244=x2249.value;
20110IkReal x2245=((25000.00002)*gconst31);
20111IkReal x2246=((25000.0)*new_r00);
20112IkReal x2247=(gconst30*x2244);
20113CheckValue<IkReal> x2250=IKPowWithIntegerCheck((((new_r10*x2245))+((gconst30*x2246))),-1);
20114if(!x2250.valid){
20115continue;
20116}
20117IkReal x2248=x2250.value;
20118if( IKabs(((((-1.0)*x2247))+((new_r10*x2245*x2247*x2248))+(((25000.0)*x2248*(new_r10*new_r10))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2248*(((((-1.0)*new_r10*x2246))+(((-1.0)*gconst30*x2245)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x2247))+((new_r10*x2245*x2247*x2248))+(((25000.0)*x2248*(new_r10*new_r10)))))+IKsqr((x2248*(((((-1.0)*new_r10*x2246))+(((-1.0)*gconst30*x2245))))))-1) <= IKFAST_SINCOS_THRESH )
20119 continue;
20120j5array[0]=IKatan2(((((-1.0)*x2247))+((new_r10*x2245*x2247*x2248))+(((25000.0)*x2248*(new_r10*new_r10)))), (x2248*(((((-1.0)*new_r10*x2246))+(((-1.0)*gconst30*x2245))))));
20121sj5array[0]=IKsin(j5array[0]);
20122cj5array[0]=IKcos(j5array[0]);
20123if( j5array[0] > IKPI )
20124{
20125 j5array[0]-=IK2PI;
20126}
20127else if( j5array[0] < -IKPI )
20128{ j5array[0]+=IK2PI;
20129}
20130j5valid[0] = true;
20131for(int ij5 = 0; ij5 < 1; ++ij5)
20132{
20133if( !j5valid[ij5] )
20134{
20135 continue;
20136}
20137_ij5[0] = ij5; _ij5[1] = -1;
20138for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20139{
20140if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20141{
20142 j5valid[iij5]=false; _ij5[1] = iij5; break;
20143}
20144}
20145j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20146{
20147IkReal evalcond[10];
20148IkReal x2251=IKcos(j5);
20149IkReal x2252=IKsin(j5);
20150IkReal x2253=((1.0)*gconst31);
20151IkReal x2254=((1.0000000008)*gconst31);
20152IkReal x2255=(gconst30*x2252);
20153IkReal x2256=(gconst30*x2251);
20154IkReal x2257=(new_r11*x2252);
20155IkReal x2258=(new_r01*x2251);
20156IkReal x2259=(new_r00*x2251);
20157IkReal x2260=(new_r10*x2252);
20158evalcond[0]=(((new_r00*x2252))+gconst30+((new_r10*x2251)));
20159evalcond[1]=((((-1.0)*x2253))+((new_r11*x2251))+((new_r01*x2252)));
20160evalcond[2]=(x2255+new_r00+((x2251*x2254)));
20161evalcond[3]=(x2256+(((-1.0)*x2252*x2254))+new_r10);
20162evalcond[4]=((((-1.0)*x2252*x2253))+new_r01+(((1.0000000008)*x2256)));
20163evalcond[5]=((((-1.0000000008)*x2255))+new_r11+(((-1.0)*x2251*x2253)));
20164evalcond[6]=(x2259+x2254+(((-1.0)*x2260)));
20165evalcond[7]=(x2258+(((-1.0)*x2257))+(((1.0000000008)*gconst30)));
20166evalcond[8]=((((1.0000000008)*x2260))+(((-1.0000000008)*x2259))+(((-1.0)*x2253)));
20167evalcond[9]=((((-1.0000000008)*x2258))+(((-1.0)*gconst30))+(((1.0000000008)*x2257)));
20168if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20169{
20170continue;
20171}
20172}
20173
20174{
20175std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20176vinfos[0].jointtype = 1;
20177vinfos[0].foffset = j0;
20178vinfos[0].indices[0] = _ij0[0];
20179vinfos[0].indices[1] = _ij0[1];
20180vinfos[0].maxsolutions = _nj0;
20181vinfos[1].jointtype = 1;
20182vinfos[1].foffset = j1;
20183vinfos[1].indices[0] = _ij1[0];
20184vinfos[1].indices[1] = _ij1[1];
20185vinfos[1].maxsolutions = _nj1;
20186vinfos[2].jointtype = 1;
20187vinfos[2].foffset = j2;
20188vinfos[2].indices[0] = _ij2[0];
20189vinfos[2].indices[1] = _ij2[1];
20190vinfos[2].maxsolutions = _nj2;
20191vinfos[3].jointtype = 1;
20192vinfos[3].foffset = j3;
20193vinfos[3].indices[0] = _ij3[0];
20194vinfos[3].indices[1] = _ij3[1];
20195vinfos[3].maxsolutions = _nj3;
20196vinfos[4].jointtype = 1;
20197vinfos[4].foffset = j4;
20198vinfos[4].indices[0] = _ij4[0];
20199vinfos[4].indices[1] = _ij4[1];
20200vinfos[4].maxsolutions = _nj4;
20201vinfos[5].jointtype = 1;
20202vinfos[5].foffset = j5;
20203vinfos[5].indices[0] = _ij5[0];
20204vinfos[5].indices[1] = _ij5[1];
20205vinfos[5].maxsolutions = _nj5;
20206std::vector<int> vfree(0);
20207solutions.AddSolution(vinfos,vfree);
20208}
20209}
20210}
20211
20212}
20213
20214}
20215
20216} else
20217{
20218{
20219IkReal j5array[1], cj5array[1], sj5array[1];
20220bool j5valid[1]={false};
20221_nj5 = 1;
20222CheckValue<IkReal> x2267=IKPowWithIntegerCheck(new_r00,-1);
20223if(!x2267.valid){
20224continue;
20225}
20226IkReal x2261=x2267.value;
20227IkReal x2262=gconst30*gconst30;
20228IkReal x2263=((25000.0)*new_r10);
20229IkReal x2264=((25000.0)*x2262);
20230CheckValue<IkReal> x2268=IKPowWithIntegerCheck(((((-1.0)*gconst30*x2263))+(((25000.00002)*gconst31*new_r00))),-1);
20231if(!x2268.valid){
20232continue;
20233}
20234IkReal x2265=x2268.value;
20235IkReal x2266=(new_r10*x2265);
20236CheckValue<IkReal> x2269=IKPowWithIntegerCheck(((((-25000.0)*gconst30*new_r10))+(((25000.00002)*gconst31*new_r00))),-1);
20237if(!x2269.valid){
20238continue;
20239}
20240CheckValue<IkReal> x2270=IKPowWithIntegerCheck(((((-25000.0)*gconst30*new_r10))+(((25000.00002)*gconst31*new_r00))),-1);
20241if(!x2270.valid){
20242continue;
20243}
20244CheckValue<IkReal> x2271=IKPowWithIntegerCheck(x2261,-2);
20245if(!x2271.valid){
20246continue;
20247}
20248if( IKabs(((((-1.0)*x2261*x2262*x2263*(x2269.value)))+((new_r00*x2263*(x2270.value)))+(((-1.0)*gconst30*x2261)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2265*((x2264+(((-25000.0)*(x2271.value))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*x2261*x2262*x2263*(x2269.value)))+((new_r00*x2263*(x2270.value)))+(((-1.0)*gconst30*x2261))))+IKsqr((x2265*((x2264+(((-25000.0)*(x2271.value)))))))-1) <= IKFAST_SINCOS_THRESH )
20249 continue;
20250j5array[0]=IKatan2(((((-1.0)*x2261*x2262*x2263*(x2269.value)))+((new_r00*x2263*(x2270.value)))+(((-1.0)*gconst30*x2261))), (x2265*((x2264+(((-25000.0)*(x2271.value)))))));
20251sj5array[0]=IKsin(j5array[0]);
20252cj5array[0]=IKcos(j5array[0]);
20253if( j5array[0] > IKPI )
20254{
20255 j5array[0]-=IK2PI;
20256}
20257else if( j5array[0] < -IKPI )
20258{ j5array[0]+=IK2PI;
20259}
20260j5valid[0] = true;
20261for(int ij5 = 0; ij5 < 1; ++ij5)
20262{
20263if( !j5valid[ij5] )
20264{
20265 continue;
20266}
20267_ij5[0] = ij5; _ij5[1] = -1;
20268for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20269{
20270if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20271{
20272 j5valid[iij5]=false; _ij5[1] = iij5; break;
20273}
20274}
20275j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20276{
20277IkReal evalcond[10];
20278IkReal x2272=IKcos(j5);
20279IkReal x2273=IKsin(j5);
20280IkReal x2274=((1.0)*gconst31);
20281IkReal x2275=((1.0000000008)*gconst31);
20282IkReal x2276=(gconst30*x2273);
20283IkReal x2277=(gconst30*x2272);
20284IkReal x2278=(new_r11*x2273);
20285IkReal x2279=(new_r01*x2272);
20286IkReal x2280=(new_r00*x2272);
20287IkReal x2281=(new_r10*x2273);
20288evalcond[0]=(((new_r10*x2272))+((new_r00*x2273))+gconst30);
20289evalcond[1]=(((new_r11*x2272))+((new_r01*x2273))+(((-1.0)*x2274)));
20290evalcond[2]=(x2276+((x2272*x2275))+new_r00);
20291evalcond[3]=(x2277+(((-1.0)*x2273*x2275))+new_r10);
20292evalcond[4]=((((-1.0)*x2273*x2274))+(((1.0000000008)*x2277))+new_r01);
20293evalcond[5]=((((-1.0000000008)*x2276))+new_r11+(((-1.0)*x2272*x2274)));
20294evalcond[6]=(x2280+x2275+(((-1.0)*x2281)));
20295evalcond[7]=(x2279+(((1.0000000008)*gconst30))+(((-1.0)*x2278)));
20296evalcond[8]=((((-1.0000000008)*x2280))+(((-1.0)*x2274))+(((1.0000000008)*x2281)));
20297evalcond[9]=((((1.0000000008)*x2278))+(((-1.0000000008)*x2279))+(((-1.0)*gconst30)));
20298if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20299{
20300continue;
20301}
20302}
20303
20304{
20305std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20306vinfos[0].jointtype = 1;
20307vinfos[0].foffset = j0;
20308vinfos[0].indices[0] = _ij0[0];
20309vinfos[0].indices[1] = _ij0[1];
20310vinfos[0].maxsolutions = _nj0;
20311vinfos[1].jointtype = 1;
20312vinfos[1].foffset = j1;
20313vinfos[1].indices[0] = _ij1[0];
20314vinfos[1].indices[1] = _ij1[1];
20315vinfos[1].maxsolutions = _nj1;
20316vinfos[2].jointtype = 1;
20317vinfos[2].foffset = j2;
20318vinfos[2].indices[0] = _ij2[0];
20319vinfos[2].indices[1] = _ij2[1];
20320vinfos[2].maxsolutions = _nj2;
20321vinfos[3].jointtype = 1;
20322vinfos[3].foffset = j3;
20323vinfos[3].indices[0] = _ij3[0];
20324vinfos[3].indices[1] = _ij3[1];
20325vinfos[3].maxsolutions = _nj3;
20326vinfos[4].jointtype = 1;
20327vinfos[4].foffset = j4;
20328vinfos[4].indices[0] = _ij4[0];
20329vinfos[4].indices[1] = _ij4[1];
20330vinfos[4].maxsolutions = _nj4;
20331vinfos[5].jointtype = 1;
20332vinfos[5].foffset = j5;
20333vinfos[5].indices[0] = _ij5[0];
20334vinfos[5].indices[1] = _ij5[1];
20335vinfos[5].maxsolutions = _nj5;
20336std::vector<int> vfree(0);
20337solutions.AddSolution(vinfos,vfree);
20338}
20339}
20340}
20341
20342}
20343
20344}
20345
20346} else
20347{
20348{
20349IkReal j5array[1], cj5array[1], sj5array[1];
20350bool j5valid[1]={false};
20351_nj5 = 1;
20352IkReal x2282=((1.0)*new_r00);
20353CheckValue<IkReal> x2283 = IKatan2WithCheck(IkReal((((gconst30*new_r11))+((gconst31*new_r10)))),IkReal(((((-1.0)*gconst30*new_r01))+(((-1.0)*gconst31*x2282)))),IKFAST_ATAN2_MAGTHRESH);
20354if(!x2283.valid){
20355continue;
20356}
20357CheckValue<IkReal> x2284=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r11*x2282)))),-1);
20358if(!x2284.valid){
20359continue;
20360}
20361j5array[0]=((-1.5707963267949)+(x2283.value)+(((1.5707963267949)*(x2284.value))));
20362sj5array[0]=IKsin(j5array[0]);
20363cj5array[0]=IKcos(j5array[0]);
20364if( j5array[0] > IKPI )
20365{
20366 j5array[0]-=IK2PI;
20367}
20368else if( j5array[0] < -IKPI )
20369{ j5array[0]+=IK2PI;
20370}
20371j5valid[0] = true;
20372for(int ij5 = 0; ij5 < 1; ++ij5)
20373{
20374if( !j5valid[ij5] )
20375{
20376 continue;
20377}
20378_ij5[0] = ij5; _ij5[1] = -1;
20379for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20380{
20381if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20382{
20383 j5valid[iij5]=false; _ij5[1] = iij5; break;
20384}
20385}
20386j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20387{
20388IkReal evalcond[10];
20389IkReal x2285=IKcos(j5);
20390IkReal x2286=IKsin(j5);
20391IkReal x2287=((1.0)*gconst31);
20392IkReal x2288=((1.0000000008)*gconst31);
20393IkReal x2289=(gconst30*x2286);
20394IkReal x2290=(gconst30*x2285);
20395IkReal x2291=(new_r11*x2286);
20396IkReal x2292=(new_r01*x2285);
20397IkReal x2293=(new_r00*x2285);
20398IkReal x2294=(new_r10*x2286);
20399evalcond[0]=(gconst30+((new_r10*x2285))+((new_r00*x2286)));
20400evalcond[1]=((((-1.0)*x2287))+((new_r11*x2285))+((new_r01*x2286)));
20401evalcond[2]=(x2289+new_r00+((x2285*x2288)));
20402evalcond[3]=(x2290+(((-1.0)*x2286*x2288))+new_r10);
20403evalcond[4]=((((-1.0)*x2286*x2287))+new_r01+(((1.0000000008)*x2290)));
20404evalcond[5]=((((-1.0000000008)*x2289))+(((-1.0)*x2285*x2287))+new_r11);
20405evalcond[6]=(x2288+x2293+(((-1.0)*x2294)));
20406evalcond[7]=(x2292+(((-1.0)*x2291))+(((1.0000000008)*gconst30)));
20407evalcond[8]=((((-1.0000000008)*x2293))+(((-1.0)*x2287))+(((1.0000000008)*x2294)));
20408evalcond[9]=((((-1.0000000008)*x2292))+(((-1.0)*gconst30))+(((1.0000000008)*x2291)));
20409if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20410{
20411continue;
20412}
20413}
20414
20415{
20416std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20417vinfos[0].jointtype = 1;
20418vinfos[0].foffset = j0;
20419vinfos[0].indices[0] = _ij0[0];
20420vinfos[0].indices[1] = _ij0[1];
20421vinfos[0].maxsolutions = _nj0;
20422vinfos[1].jointtype = 1;
20423vinfos[1].foffset = j1;
20424vinfos[1].indices[0] = _ij1[0];
20425vinfos[1].indices[1] = _ij1[1];
20426vinfos[1].maxsolutions = _nj1;
20427vinfos[2].jointtype = 1;
20428vinfos[2].foffset = j2;
20429vinfos[2].indices[0] = _ij2[0];
20430vinfos[2].indices[1] = _ij2[1];
20431vinfos[2].maxsolutions = _nj2;
20432vinfos[3].jointtype = 1;
20433vinfos[3].foffset = j3;
20434vinfos[3].indices[0] = _ij3[0];
20435vinfos[3].indices[1] = _ij3[1];
20436vinfos[3].maxsolutions = _nj3;
20437vinfos[4].jointtype = 1;
20438vinfos[4].foffset = j4;
20439vinfos[4].indices[0] = _ij4[0];
20440vinfos[4].indices[1] = _ij4[1];
20441vinfos[4].maxsolutions = _nj4;
20442vinfos[5].jointtype = 1;
20443vinfos[5].foffset = j5;
20444vinfos[5].indices[0] = _ij5[0];
20445vinfos[5].indices[1] = _ij5[1];
20446vinfos[5].maxsolutions = _nj5;
20447std::vector<int> vfree(0);
20448solutions.AddSolution(vinfos,vfree);
20449}
20450}
20451}
20452
20453}
20454
20455}
20456
20457}
20458} while(0);
20459if( bgotonextstatement )
20460{
20461bool bgotonextstatement = true;
20462do
20463{
20464evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
20465if( IKabs(evalcond[0]) < 0.0000050000000000 )
20466{
20467bgotonextstatement=false;
20468{
20469IkReal j5eval[1];
20470sj4=-4.0e-5;
20471cj4=-1.0;
20472j4=3.14163265;
20473new_r11=0;
20474new_r01=0;
20475new_r22=0;
20476new_r20=0;
20477j5eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
20478if( IKabs(j5eval[0]) < 0.0000010000000000 )
20479{
20480{
20481IkReal j5eval[1];
20482sj4=-4.0e-5;
20483cj4=-1.0;
20484j4=3.14163265;
20485new_r11=0;
20486new_r01=0;
20487new_r22=0;
20488new_r20=0;
20489j5eval[0]=1.0;
20490if( IKabs(j5eval[0]) < 0.0000010000000000 )
20491{
20492continue; // no branches [j5]
20493
20494} else
20495{
20496{
20497IkReal j5array[2], cj5array[2], sj5array[2];
20498bool j5valid[2]={false};
20499_nj5 = 2;
20500CheckValue<IkReal> x2296 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r00)),IkReal(((1.0000000008)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
20501if(!x2296.valid){
20502continue;
20503}
20504IkReal x2295=x2296.value;
20505j5array[0]=((-1.0)*x2295);
20506sj5array[0]=IKsin(j5array[0]);
20507cj5array[0]=IKcos(j5array[0]);
20508j5array[1]=((3.14159265358979)+(((-1.0)*x2295)));
20509sj5array[1]=IKsin(j5array[1]);
20510cj5array[1]=IKcos(j5array[1]);
20511if( j5array[0] > IKPI )
20512{
20513 j5array[0]-=IK2PI;
20514}
20515else if( j5array[0] < -IKPI )
20516{ j5array[0]+=IK2PI;
20517}
20518j5valid[0] = true;
20519if( j5array[1] > IKPI )
20520{
20521 j5array[1]-=IK2PI;
20522}
20523else if( j5array[1] < -IKPI )
20524{ j5array[1]+=IK2PI;
20525}
20526j5valid[1] = true;
20527for(int ij5 = 0; ij5 < 2; ++ij5)
20528{
20529if( !j5valid[ij5] )
20530{
20531 continue;
20532}
20533_ij5[0] = ij5; _ij5[1] = -1;
20534for(int iij5 = ij5+1; iij5 < 2; ++iij5)
20535{
20536if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20537{
20538 j5valid[iij5]=false; _ij5[1] = iij5; break;
20539}
20540}
20541j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20542{
20543IkReal evalcond[2];
20544IkReal x2297=IKcos(j5);
20545IkReal x2298=IKsin(j5);
20546evalcond[0]=(((new_r00*x2298))+((new_r10*x2297)));
20547evalcond[1]=(((new_r00*x2297))+(((-1.0)*new_r10*x2298)));
20548if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
20549{
20550continue;
20551}
20552}
20553
20554{
20555std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20556vinfos[0].jointtype = 1;
20557vinfos[0].foffset = j0;
20558vinfos[0].indices[0] = _ij0[0];
20559vinfos[0].indices[1] = _ij0[1];
20560vinfos[0].maxsolutions = _nj0;
20561vinfos[1].jointtype = 1;
20562vinfos[1].foffset = j1;
20563vinfos[1].indices[0] = _ij1[0];
20564vinfos[1].indices[1] = _ij1[1];
20565vinfos[1].maxsolutions = _nj1;
20566vinfos[2].jointtype = 1;
20567vinfos[2].foffset = j2;
20568vinfos[2].indices[0] = _ij2[0];
20569vinfos[2].indices[1] = _ij2[1];
20570vinfos[2].maxsolutions = _nj2;
20571vinfos[3].jointtype = 1;
20572vinfos[3].foffset = j3;
20573vinfos[3].indices[0] = _ij3[0];
20574vinfos[3].indices[1] = _ij3[1];
20575vinfos[3].maxsolutions = _nj3;
20576vinfos[4].jointtype = 1;
20577vinfos[4].foffset = j4;
20578vinfos[4].indices[0] = _ij4[0];
20579vinfos[4].indices[1] = _ij4[1];
20580vinfos[4].maxsolutions = _nj4;
20581vinfos[5].jointtype = 1;
20582vinfos[5].foffset = j5;
20583vinfos[5].indices[0] = _ij5[0];
20584vinfos[5].indices[1] = _ij5[1];
20585vinfos[5].maxsolutions = _nj5;
20586std::vector<int> vfree(0);
20587solutions.AddSolution(vinfos,vfree);
20588}
20589}
20590}
20591
20592}
20593
20594}
20595
20596} else
20597{
20598{
20599IkReal j5array[2], cj5array[2], sj5array[2];
20600bool j5valid[2]={false};
20601_nj5 = 2;
20602CheckValue<IkReal> x2300 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
20603if(!x2300.valid){
20604continue;
20605}
20606IkReal x2299=x2300.value;
20607j5array[0]=((-1.0)*x2299);
20608sj5array[0]=IKsin(j5array[0]);
20609cj5array[0]=IKcos(j5array[0]);
20610j5array[1]=((3.14159265358979)+(((-1.0)*x2299)));
20611sj5array[1]=IKsin(j5array[1]);
20612cj5array[1]=IKcos(j5array[1]);
20613if( j5array[0] > IKPI )
20614{
20615 j5array[0]-=IK2PI;
20616}
20617else if( j5array[0] < -IKPI )
20618{ j5array[0]+=IK2PI;
20619}
20620j5valid[0] = true;
20621if( j5array[1] > IKPI )
20622{
20623 j5array[1]-=IK2PI;
20624}
20625else if( j5array[1] < -IKPI )
20626{ j5array[1]+=IK2PI;
20627}
20628j5valid[1] = true;
20629for(int ij5 = 0; ij5 < 2; ++ij5)
20630{
20631if( !j5valid[ij5] )
20632{
20633 continue;
20634}
20635_ij5[0] = ij5; _ij5[1] = -1;
20636for(int iij5 = ij5+1; iij5 < 2; ++iij5)
20637{
20638if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20639{
20640 j5valid[iij5]=false; _ij5[1] = iij5; break;
20641}
20642}
20643j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20644{
20645IkReal evalcond[2];
20646IkReal x2301=IKsin(j5);
20647IkReal x2302=IKcos(j5);
20648IkReal x2303=(new_r00*x2302);
20649IkReal x2304=(new_r10*x2301);
20650evalcond[0]=((((-1.0)*x2304))+x2303);
20651evalcond[1]=((((1.0000000008)*x2304))+(((-1.0000000008)*x2303)));
20652if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
20653{
20654continue;
20655}
20656}
20657
20658{
20659std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20660vinfos[0].jointtype = 1;
20661vinfos[0].foffset = j0;
20662vinfos[0].indices[0] = _ij0[0];
20663vinfos[0].indices[1] = _ij0[1];
20664vinfos[0].maxsolutions = _nj0;
20665vinfos[1].jointtype = 1;
20666vinfos[1].foffset = j1;
20667vinfos[1].indices[0] = _ij1[0];
20668vinfos[1].indices[1] = _ij1[1];
20669vinfos[1].maxsolutions = _nj1;
20670vinfos[2].jointtype = 1;
20671vinfos[2].foffset = j2;
20672vinfos[2].indices[0] = _ij2[0];
20673vinfos[2].indices[1] = _ij2[1];
20674vinfos[2].maxsolutions = _nj2;
20675vinfos[3].jointtype = 1;
20676vinfos[3].foffset = j3;
20677vinfos[3].indices[0] = _ij3[0];
20678vinfos[3].indices[1] = _ij3[1];
20679vinfos[3].maxsolutions = _nj3;
20680vinfos[4].jointtype = 1;
20681vinfos[4].foffset = j4;
20682vinfos[4].indices[0] = _ij4[0];
20683vinfos[4].indices[1] = _ij4[1];
20684vinfos[4].maxsolutions = _nj4;
20685vinfos[5].jointtype = 1;
20686vinfos[5].foffset = j5;
20687vinfos[5].indices[0] = _ij5[0];
20688vinfos[5].indices[1] = _ij5[1];
20689vinfos[5].maxsolutions = _nj5;
20690std::vector<int> vfree(0);
20691solutions.AddSolution(vinfos,vfree);
20692}
20693}
20694}
20695
20696}
20697
20698}
20699
20700}
20701} while(0);
20702if( bgotonextstatement )
20703{
20704bool bgotonextstatement = true;
20705do
20706{
20707evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
20708if( IKabs(evalcond[0]) < 0.0000050000000000 )
20709{
20710bgotonextstatement=false;
20711{
20712IkReal j5eval[1];
20713sj4=-4.0e-5;
20714cj4=-1.0;
20715j4=3.14163265;
20716new_r11=0;
20717new_r10=0;
20718new_r22=0;
20719new_r02=0;
20720j5eval[0]=new_r00;
20721if( IKabs(j5eval[0]) < 0.0000010000000000 )
20722{
20723{
20724IkReal j5eval[2];
20725sj4=-4.0e-5;
20726cj4=-1.0;
20727j4=3.14163265;
20728new_r11=0;
20729new_r10=0;
20730new_r22=0;
20731new_r02=0;
20732j5eval[0]=new_r00;
20733j5eval[1]=new_r01;
20734if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
20735{
20736continue; // no branches [j5]
20737
20738} else
20739{
20740{
20741IkReal j5array[1], cj5array[1], sj5array[1];
20742bool j5valid[1]={false};
20743_nj5 = 1;
20744CheckValue<IkReal> x2305=IKPowWithIntegerCheck(new_r00,-1);
20745if(!x2305.valid){
20746continue;
20747}
20748CheckValue<IkReal> x2306=IKPowWithIntegerCheck(new_r01,-1);
20749if(!x2306.valid){
20750continue;
20751}
20752if( IKabs(((-1.0)*sj3*(x2305.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0000000008)*sj3*(x2306.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj3*(x2305.value)))+IKsqr(((-1.0000000008)*sj3*(x2306.value)))-1) <= IKFAST_SINCOS_THRESH )
20753 continue;
20754j5array[0]=IKatan2(((-1.0)*sj3*(x2305.value)), ((-1.0000000008)*sj3*(x2306.value)));
20755sj5array[0]=IKsin(j5array[0]);
20756cj5array[0]=IKcos(j5array[0]);
20757if( j5array[0] > IKPI )
20758{
20759 j5array[0]-=IK2PI;
20760}
20761else if( j5array[0] < -IKPI )
20762{ j5array[0]+=IK2PI;
20763}
20764j5valid[0] = true;
20765for(int ij5 = 0; ij5 < 1; ++ij5)
20766{
20767if( !j5valid[ij5] )
20768{
20769 continue;
20770}
20771_ij5[0] = ij5; _ij5[1] = -1;
20772for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20773{
20774if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20775{
20776 j5valid[iij5]=false; _ij5[1] = iij5; break;
20777}
20778}
20779j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20780{
20781IkReal evalcond[10];
20782IkReal x2307=IKsin(j5);
20783IkReal x2308=IKcos(j5);
20784IkReal x2309=((1.0)*cj3);
20785IkReal x2310=((1.0000000008)*cj3);
20786IkReal x2311=((1.0000000008)*sj3);
20787IkReal x2312=(new_r00*x2308);
20788IkReal x2313=(sj3*x2308);
20789IkReal x2314=(new_r01*x2308);
20790evalcond[0]=(((new_r00*x2307))+sj3);
20791evalcond[1]=((((-1.0)*x2309))+((new_r01*x2307)));
20792evalcond[2]=(x2312+x2310);
20793evalcond[3]=(x2314+x2311);
20794evalcond[4]=((((-1.0000000008)*x2312))+(((-1.0)*x2309)));
20795evalcond[5]=((((-1.0)*sj3))+(((-1.0000000008)*x2314)));
20796evalcond[6]=(x2313+(((-1.0)*x2307*x2310)));
20797evalcond[7]=(((x2308*x2310))+((sj3*x2307))+new_r00);
20798evalcond[8]=((((-1.0)*x2308*x2309))+(((-1.0)*x2307*x2311)));
20799evalcond[9]=(((x2308*x2311))+new_r01+(((-1.0)*x2307*x2309)));
20800if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20801{
20802continue;
20803}
20804}
20805
20806{
20807std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20808vinfos[0].jointtype = 1;
20809vinfos[0].foffset = j0;
20810vinfos[0].indices[0] = _ij0[0];
20811vinfos[0].indices[1] = _ij0[1];
20812vinfos[0].maxsolutions = _nj0;
20813vinfos[1].jointtype = 1;
20814vinfos[1].foffset = j1;
20815vinfos[1].indices[0] = _ij1[0];
20816vinfos[1].indices[1] = _ij1[1];
20817vinfos[1].maxsolutions = _nj1;
20818vinfos[2].jointtype = 1;
20819vinfos[2].foffset = j2;
20820vinfos[2].indices[0] = _ij2[0];
20821vinfos[2].indices[1] = _ij2[1];
20822vinfos[2].maxsolutions = _nj2;
20823vinfos[3].jointtype = 1;
20824vinfos[3].foffset = j3;
20825vinfos[3].indices[0] = _ij3[0];
20826vinfos[3].indices[1] = _ij3[1];
20827vinfos[3].maxsolutions = _nj3;
20828vinfos[4].jointtype = 1;
20829vinfos[4].foffset = j4;
20830vinfos[4].indices[0] = _ij4[0];
20831vinfos[4].indices[1] = _ij4[1];
20832vinfos[4].maxsolutions = _nj4;
20833vinfos[5].jointtype = 1;
20834vinfos[5].foffset = j5;
20835vinfos[5].indices[0] = _ij5[0];
20836vinfos[5].indices[1] = _ij5[1];
20837vinfos[5].maxsolutions = _nj5;
20838std::vector<int> vfree(0);
20839solutions.AddSolution(vinfos,vfree);
20840}
20841}
20842}
20843
20844}
20845
20846}
20847
20848} else
20849{
20850{
20851IkReal j5array[1], cj5array[1], sj5array[1];
20852bool j5valid[1]={false};
20853_nj5 = 1;
20854CheckValue<IkReal> x2316=IKPowWithIntegerCheck(new_r00,-1);
20855if(!x2316.valid){
20856continue;
20857}
20858IkReal x2315=x2316.value;
20859if( IKabs(((-1.0)*sj3*x2315)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0000000008)*cj3*x2315)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*sj3*x2315))+IKsqr(((-1.0000000008)*cj3*x2315))-1) <= IKFAST_SINCOS_THRESH )
20860 continue;
20861j5array[0]=IKatan2(((-1.0)*sj3*x2315), ((-1.0000000008)*cj3*x2315));
20862sj5array[0]=IKsin(j5array[0]);
20863cj5array[0]=IKcos(j5array[0]);
20864if( j5array[0] > IKPI )
20865{
20866 j5array[0]-=IK2PI;
20867}
20868else if( j5array[0] < -IKPI )
20869{ j5array[0]+=IK2PI;
20870}
20871j5valid[0] = true;
20872for(int ij5 = 0; ij5 < 1; ++ij5)
20873{
20874if( !j5valid[ij5] )
20875{
20876 continue;
20877}
20878_ij5[0] = ij5; _ij5[1] = -1;
20879for(int iij5 = ij5+1; iij5 < 1; ++iij5)
20880{
20881if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
20882{
20883 j5valid[iij5]=false; _ij5[1] = iij5; break;
20884}
20885}
20886j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
20887{
20888IkReal evalcond[10];
20889IkReal x2317=IKsin(j5);
20890IkReal x2318=IKcos(j5);
20891IkReal x2319=((1.0)*cj3);
20892IkReal x2320=((1.0000000008)*cj3);
20893IkReal x2321=((1.0000000008)*sj3);
20894IkReal x2322=(new_r00*x2318);
20895IkReal x2323=(sj3*x2318);
20896IkReal x2324=(new_r01*x2318);
20897evalcond[0]=(sj3+((new_r00*x2317)));
20898evalcond[1]=(((new_r01*x2317))+(((-1.0)*x2319)));
20899evalcond[2]=(x2322+x2320);
20900evalcond[3]=(x2321+x2324);
20901evalcond[4]=((((-1.0000000008)*x2322))+(((-1.0)*x2319)));
20902evalcond[5]=((((-1.0)*sj3))+(((-1.0000000008)*x2324)));
20903evalcond[6]=(x2323+(((-1.0)*x2317*x2320)));
20904evalcond[7]=(((sj3*x2317))+((x2318*x2320))+new_r00);
20905evalcond[8]=((((-1.0)*x2318*x2319))+(((-1.0)*x2317*x2321)));
20906evalcond[9]=(((x2318*x2321))+(((-1.0)*x2317*x2319))+new_r01);
20907if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
20908{
20909continue;
20910}
20911}
20912
20913{
20914std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20915vinfos[0].jointtype = 1;
20916vinfos[0].foffset = j0;
20917vinfos[0].indices[0] = _ij0[0];
20918vinfos[0].indices[1] = _ij0[1];
20919vinfos[0].maxsolutions = _nj0;
20920vinfos[1].jointtype = 1;
20921vinfos[1].foffset = j1;
20922vinfos[1].indices[0] = _ij1[0];
20923vinfos[1].indices[1] = _ij1[1];
20924vinfos[1].maxsolutions = _nj1;
20925vinfos[2].jointtype = 1;
20926vinfos[2].foffset = j2;
20927vinfos[2].indices[0] = _ij2[0];
20928vinfos[2].indices[1] = _ij2[1];
20929vinfos[2].maxsolutions = _nj2;
20930vinfos[3].jointtype = 1;
20931vinfos[3].foffset = j3;
20932vinfos[3].indices[0] = _ij3[0];
20933vinfos[3].indices[1] = _ij3[1];
20934vinfos[3].maxsolutions = _nj3;
20935vinfos[4].jointtype = 1;
20936vinfos[4].foffset = j4;
20937vinfos[4].indices[0] = _ij4[0];
20938vinfos[4].indices[1] = _ij4[1];
20939vinfos[4].maxsolutions = _nj4;
20940vinfos[5].jointtype = 1;
20941vinfos[5].foffset = j5;
20942vinfos[5].indices[0] = _ij5[0];
20943vinfos[5].indices[1] = _ij5[1];
20944vinfos[5].maxsolutions = _nj5;
20945std::vector<int> vfree(0);
20946solutions.AddSolution(vinfos,vfree);
20947}
20948}
20949}
20950
20951}
20952
20953}
20954
20955}
20956} while(0);
20957if( bgotonextstatement )
20958{
20959bool bgotonextstatement = true;
20960do
20961{
20962evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
20963if( IKabs(evalcond[0]) < 0.0000050000000000 )
20964{
20965bgotonextstatement=false;
20966{
20967IkReal j5eval[1];
20968sj4=-4.0e-5;
20969cj4=-1.0;
20970j4=3.14163265;
20971new_r00=0;
20972new_r01=0;
20973new_r12=0;
20974new_r22=0;
20975j5eval[0]=new_r10;
20976if( IKabs(j5eval[0]) < 0.0000010000000000 )
20977{
20978{
20979IkReal j5eval[2];
20980sj4=-4.0e-5;
20981cj4=-1.0;
20982j4=3.14163265;
20983new_r00=0;
20984new_r01=0;
20985new_r12=0;
20986new_r22=0;
20987j5eval[0]=new_r11;
20988j5eval[1]=new_r10;
20989if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
20990{
20991continue; // no branches [j5]
20992
20993} else
20994{
20995{
20996IkReal j5array[1], cj5array[1], sj5array[1];
20997bool j5valid[1]={false};
20998_nj5 = 1;
20999CheckValue<IkReal> x2325=IKPowWithIntegerCheck(new_r11,-1);
21000if(!x2325.valid){
21001continue;
21002}
21003CheckValue<IkReal> x2326=IKPowWithIntegerCheck(new_r10,-1);
21004if(!x2326.valid){
21005continue;
21006}
21007if( IKabs(((1.0000000008)*sj3*(x2325.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj3*(x2326.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((1.0000000008)*sj3*(x2325.value)))+IKsqr(((-1.0)*sj3*(x2326.value)))-1) <= IKFAST_SINCOS_THRESH )
21008 continue;
21009j5array[0]=IKatan2(((1.0000000008)*sj3*(x2325.value)), ((-1.0)*sj3*(x2326.value)));
21010sj5array[0]=IKsin(j5array[0]);
21011cj5array[0]=IKcos(j5array[0]);
21012if( j5array[0] > IKPI )
21013{
21014 j5array[0]-=IK2PI;
21015}
21016else if( j5array[0] < -IKPI )
21017{ j5array[0]+=IK2PI;
21018}
21019j5valid[0] = true;
21020for(int ij5 = 0; ij5 < 1; ++ij5)
21021{
21022if( !j5valid[ij5] )
21023{
21024 continue;
21025}
21026_ij5[0] = ij5; _ij5[1] = -1;
21027for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21028{
21029if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21030{
21031 j5valid[iij5]=false; _ij5[1] = iij5; break;
21032}
21033}
21034j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21035{
21036IkReal evalcond[10];
21037IkReal x2327=IKcos(j5);
21038IkReal x2328=IKsin(j5);
21039IkReal x2329=((1.0)*cj3);
21040IkReal x2330=((1.0000000008)*cj3);
21041IkReal x2331=((1.0000000008)*sj3);
21042IkReal x2332=(sj3*x2327);
21043IkReal x2333=(new_r10*x2328);
21044IkReal x2334=(new_r11*x2328);
21045evalcond[0]=(sj3+((new_r10*x2327)));
21046evalcond[1]=(((new_r11*x2327))+(((-1.0)*x2329)));
21047evalcond[2]=(x2330+(((-1.0)*x2333)));
21048evalcond[3]=(x2331+(((-1.0)*x2334)));
21049evalcond[4]=((((1.0000000008)*x2333))+(((-1.0)*x2329)));
21050evalcond[5]=((((-1.0)*sj3))+(((1.0000000008)*x2334)));
21051evalcond[6]=(((sj3*x2328))+((x2327*x2330)));
21052evalcond[7]=((((-1.0)*x2328*x2330))+x2332+new_r10);
21053evalcond[8]=((((-1.0)*x2328*x2329))+((x2327*x2331)));
21054evalcond[9]=((((-1.0)*x2328*x2331))+(((-1.0)*x2327*x2329))+new_r11);
21055if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
21056{
21057continue;
21058}
21059}
21060
21061{
21062std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21063vinfos[0].jointtype = 1;
21064vinfos[0].foffset = j0;
21065vinfos[0].indices[0] = _ij0[0];
21066vinfos[0].indices[1] = _ij0[1];
21067vinfos[0].maxsolutions = _nj0;
21068vinfos[1].jointtype = 1;
21069vinfos[1].foffset = j1;
21070vinfos[1].indices[0] = _ij1[0];
21071vinfos[1].indices[1] = _ij1[1];
21072vinfos[1].maxsolutions = _nj1;
21073vinfos[2].jointtype = 1;
21074vinfos[2].foffset = j2;
21075vinfos[2].indices[0] = _ij2[0];
21076vinfos[2].indices[1] = _ij2[1];
21077vinfos[2].maxsolutions = _nj2;
21078vinfos[3].jointtype = 1;
21079vinfos[3].foffset = j3;
21080vinfos[3].indices[0] = _ij3[0];
21081vinfos[3].indices[1] = _ij3[1];
21082vinfos[3].maxsolutions = _nj3;
21083vinfos[4].jointtype = 1;
21084vinfos[4].foffset = j4;
21085vinfos[4].indices[0] = _ij4[0];
21086vinfos[4].indices[1] = _ij4[1];
21087vinfos[4].maxsolutions = _nj4;
21088vinfos[5].jointtype = 1;
21089vinfos[5].foffset = j5;
21090vinfos[5].indices[0] = _ij5[0];
21091vinfos[5].indices[1] = _ij5[1];
21092vinfos[5].maxsolutions = _nj5;
21093std::vector<int> vfree(0);
21094solutions.AddSolution(vinfos,vfree);
21095}
21096}
21097}
21098
21099}
21100
21101}
21102
21103} else
21104{
21105{
21106IkReal j5array[1], cj5array[1], sj5array[1];
21107bool j5valid[1]={false};
21108_nj5 = 1;
21109CheckValue<IkReal> x2336=IKPowWithIntegerCheck(new_r10,-1);
21110if(!x2336.valid){
21111continue;
21112}
21113IkReal x2335=x2336.value;
21114if( IKabs(((1.0000000008)*cj3*x2335)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj3*x2335)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((1.0000000008)*cj3*x2335))+IKsqr(((-1.0)*sj3*x2335))-1) <= IKFAST_SINCOS_THRESH )
21115 continue;
21116j5array[0]=IKatan2(((1.0000000008)*cj3*x2335), ((-1.0)*sj3*x2335));
21117sj5array[0]=IKsin(j5array[0]);
21118cj5array[0]=IKcos(j5array[0]);
21119if( j5array[0] > IKPI )
21120{
21121 j5array[0]-=IK2PI;
21122}
21123else if( j5array[0] < -IKPI )
21124{ j5array[0]+=IK2PI;
21125}
21126j5valid[0] = true;
21127for(int ij5 = 0; ij5 < 1; ++ij5)
21128{
21129if( !j5valid[ij5] )
21130{
21131 continue;
21132}
21133_ij5[0] = ij5; _ij5[1] = -1;
21134for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21135{
21136if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21137{
21138 j5valid[iij5]=false; _ij5[1] = iij5; break;
21139}
21140}
21141j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21142{
21143IkReal evalcond[10];
21144IkReal x2337=IKcos(j5);
21145IkReal x2338=IKsin(j5);
21146IkReal x2339=((1.0)*cj3);
21147IkReal x2340=((1.0000000008)*cj3);
21148IkReal x2341=((1.0000000008)*sj3);
21149IkReal x2342=(sj3*x2337);
21150IkReal x2343=(new_r10*x2338);
21151IkReal x2344=(new_r11*x2338);
21152evalcond[0]=(sj3+((new_r10*x2337)));
21153evalcond[1]=((((-1.0)*x2339))+((new_r11*x2337)));
21154evalcond[2]=(x2340+(((-1.0)*x2343)));
21155evalcond[3]=(x2341+(((-1.0)*x2344)));
21156evalcond[4]=((((-1.0)*x2339))+(((1.0000000008)*x2343)));
21157evalcond[5]=((((-1.0)*sj3))+(((1.0000000008)*x2344)));
21158evalcond[6]=(((sj3*x2338))+((x2337*x2340)));
21159evalcond[7]=(x2342+new_r10+(((-1.0)*x2338*x2340)));
21160evalcond[8]=((((-1.0)*x2338*x2339))+((x2337*x2341)));
21161evalcond[9]=((((-1.0)*x2337*x2339))+new_r11+(((-1.0)*x2338*x2341)));
21162if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
21163{
21164continue;
21165}
21166}
21167
21168{
21169std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21170vinfos[0].jointtype = 1;
21171vinfos[0].foffset = j0;
21172vinfos[0].indices[0] = _ij0[0];
21173vinfos[0].indices[1] = _ij0[1];
21174vinfos[0].maxsolutions = _nj0;
21175vinfos[1].jointtype = 1;
21176vinfos[1].foffset = j1;
21177vinfos[1].indices[0] = _ij1[0];
21178vinfos[1].indices[1] = _ij1[1];
21179vinfos[1].maxsolutions = _nj1;
21180vinfos[2].jointtype = 1;
21181vinfos[2].foffset = j2;
21182vinfos[2].indices[0] = _ij2[0];
21183vinfos[2].indices[1] = _ij2[1];
21184vinfos[2].maxsolutions = _nj2;
21185vinfos[3].jointtype = 1;
21186vinfos[3].foffset = j3;
21187vinfos[3].indices[0] = _ij3[0];
21188vinfos[3].indices[1] = _ij3[1];
21189vinfos[3].maxsolutions = _nj3;
21190vinfos[4].jointtype = 1;
21191vinfos[4].foffset = j4;
21192vinfos[4].indices[0] = _ij4[0];
21193vinfos[4].indices[1] = _ij4[1];
21194vinfos[4].maxsolutions = _nj4;
21195vinfos[5].jointtype = 1;
21196vinfos[5].foffset = j5;
21197vinfos[5].indices[0] = _ij5[0];
21198vinfos[5].indices[1] = _ij5[1];
21199vinfos[5].maxsolutions = _nj5;
21200std::vector<int> vfree(0);
21201solutions.AddSolution(vinfos,vfree);
21202}
21203}
21204}
21205
21206}
21207
21208}
21209
21210}
21211} while(0);
21212if( bgotonextstatement )
21213{
21214bool bgotonextstatement = true;
21215do
21216{
21217evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
21218if( IKabs(evalcond[0]) < 0.0000050000000000 )
21219{
21220bgotonextstatement=false;
21221{
21222IkReal j5eval[1];
21223sj4=-4.0e-5;
21224cj4=-1.0;
21225j4=3.14163265;
21226new_r00=0;
21227new_r10=0;
21228new_r21=0;
21229new_r22=0;
21230j5eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
21231if( IKabs(j5eval[0]) < 0.0000010000000000 )
21232{
21233{
21234IkReal j5eval[1];
21235sj4=-4.0e-5;
21236cj4=-1.0;
21237j4=3.14163265;
21238new_r00=0;
21239new_r10=0;
21240new_r21=0;
21241new_r22=0;
21242j5eval[0]=1.0;
21243if( IKabs(j5eval[0]) < 0.0000010000000000 )
21244{
21245continue; // no branches [j5]
21246
21247} else
21248{
21249{
21250IkReal j5array[2], cj5array[2], sj5array[2];
21251bool j5valid[2]={false};
21252_nj5 = 2;
21253CheckValue<IkReal> x2346 = IKatan2WithCheck(IkReal(((-1.0000000008)*new_r01)),IkReal(((1.0000000008)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
21254if(!x2346.valid){
21255continue;
21256}
21257IkReal x2345=x2346.value;
21258j5array[0]=((-1.0)*x2345);
21259sj5array[0]=IKsin(j5array[0]);
21260cj5array[0]=IKcos(j5array[0]);
21261j5array[1]=((3.14159265358979)+(((-1.0)*x2345)));
21262sj5array[1]=IKsin(j5array[1]);
21263cj5array[1]=IKcos(j5array[1]);
21264if( j5array[0] > IKPI )
21265{
21266 j5array[0]-=IK2PI;
21267}
21268else if( j5array[0] < -IKPI )
21269{ j5array[0]+=IK2PI;
21270}
21271j5valid[0] = true;
21272if( j5array[1] > IKPI )
21273{
21274 j5array[1]-=IK2PI;
21275}
21276else if( j5array[1] < -IKPI )
21277{ j5array[1]+=IK2PI;
21278}
21279j5valid[1] = true;
21280for(int ij5 = 0; ij5 < 2; ++ij5)
21281{
21282if( !j5valid[ij5] )
21283{
21284 continue;
21285}
21286_ij5[0] = ij5; _ij5[1] = -1;
21287for(int iij5 = ij5+1; iij5 < 2; ++iij5)
21288{
21289if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21290{
21291 j5valid[iij5]=false; _ij5[1] = iij5; break;
21292}
21293}
21294j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21295{
21296IkReal evalcond[2];
21297IkReal x2347=IKcos(j5);
21298IkReal x2348=IKsin(j5);
21299evalcond[0]=(((new_r11*x2347))+((new_r01*x2348)));
21300evalcond[1]=((((-1.0)*new_r11*x2348))+((new_r01*x2347)));
21301if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
21302{
21303continue;
21304}
21305}
21306
21307{
21308std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21309vinfos[0].jointtype = 1;
21310vinfos[0].foffset = j0;
21311vinfos[0].indices[0] = _ij0[0];
21312vinfos[0].indices[1] = _ij0[1];
21313vinfos[0].maxsolutions = _nj0;
21314vinfos[1].jointtype = 1;
21315vinfos[1].foffset = j1;
21316vinfos[1].indices[0] = _ij1[0];
21317vinfos[1].indices[1] = _ij1[1];
21318vinfos[1].maxsolutions = _nj1;
21319vinfos[2].jointtype = 1;
21320vinfos[2].foffset = j2;
21321vinfos[2].indices[0] = _ij2[0];
21322vinfos[2].indices[1] = _ij2[1];
21323vinfos[2].maxsolutions = _nj2;
21324vinfos[3].jointtype = 1;
21325vinfos[3].foffset = j3;
21326vinfos[3].indices[0] = _ij3[0];
21327vinfos[3].indices[1] = _ij3[1];
21328vinfos[3].maxsolutions = _nj3;
21329vinfos[4].jointtype = 1;
21330vinfos[4].foffset = j4;
21331vinfos[4].indices[0] = _ij4[0];
21332vinfos[4].indices[1] = _ij4[1];
21333vinfos[4].maxsolutions = _nj4;
21334vinfos[5].jointtype = 1;
21335vinfos[5].foffset = j5;
21336vinfos[5].indices[0] = _ij5[0];
21337vinfos[5].indices[1] = _ij5[1];
21338vinfos[5].maxsolutions = _nj5;
21339std::vector<int> vfree(0);
21340solutions.AddSolution(vinfos,vfree);
21341}
21342}
21343}
21344
21345}
21346
21347}
21348
21349} else
21350{
21351{
21352IkReal j5array[2], cj5array[2], sj5array[2];
21353bool j5valid[2]={false};
21354_nj5 = 2;
21355CheckValue<IkReal> x2350 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
21356if(!x2350.valid){
21357continue;
21358}
21359IkReal x2349=x2350.value;
21360j5array[0]=((-1.0)*x2349);
21361sj5array[0]=IKsin(j5array[0]);
21362cj5array[0]=IKcos(j5array[0]);
21363j5array[1]=((3.14159265358979)+(((-1.0)*x2349)));
21364sj5array[1]=IKsin(j5array[1]);
21365cj5array[1]=IKcos(j5array[1]);
21366if( j5array[0] > IKPI )
21367{
21368 j5array[0]-=IK2PI;
21369}
21370else if( j5array[0] < -IKPI )
21371{ j5array[0]+=IK2PI;
21372}
21373j5valid[0] = true;
21374if( j5array[1] > IKPI )
21375{
21376 j5array[1]-=IK2PI;
21377}
21378else if( j5array[1] < -IKPI )
21379{ j5array[1]+=IK2PI;
21380}
21381j5valid[1] = true;
21382for(int ij5 = 0; ij5 < 2; ++ij5)
21383{
21384if( !j5valid[ij5] )
21385{
21386 continue;
21387}
21388_ij5[0] = ij5; _ij5[1] = -1;
21389for(int iij5 = ij5+1; iij5 < 2; ++iij5)
21390{
21391if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21392{
21393 j5valid[iij5]=false; _ij5[1] = iij5; break;
21394}
21395}
21396j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21397{
21398IkReal evalcond[2];
21399IkReal x2351=IKsin(j5);
21400IkReal x2352=IKcos(j5);
21401IkReal x2353=(new_r11*x2351);
21402IkReal x2354=(new_r01*x2352);
21403evalcond[0]=(x2354+(((-1.0)*x2353)));
21404evalcond[1]=((((-1.0000000008)*x2354))+(((1.0000000008)*x2353)));
21405if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
21406{
21407continue;
21408}
21409}
21410
21411{
21412std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21413vinfos[0].jointtype = 1;
21414vinfos[0].foffset = j0;
21415vinfos[0].indices[0] = _ij0[0];
21416vinfos[0].indices[1] = _ij0[1];
21417vinfos[0].maxsolutions = _nj0;
21418vinfos[1].jointtype = 1;
21419vinfos[1].foffset = j1;
21420vinfos[1].indices[0] = _ij1[0];
21421vinfos[1].indices[1] = _ij1[1];
21422vinfos[1].maxsolutions = _nj1;
21423vinfos[2].jointtype = 1;
21424vinfos[2].foffset = j2;
21425vinfos[2].indices[0] = _ij2[0];
21426vinfos[2].indices[1] = _ij2[1];
21427vinfos[2].maxsolutions = _nj2;
21428vinfos[3].jointtype = 1;
21429vinfos[3].foffset = j3;
21430vinfos[3].indices[0] = _ij3[0];
21431vinfos[3].indices[1] = _ij3[1];
21432vinfos[3].maxsolutions = _nj3;
21433vinfos[4].jointtype = 1;
21434vinfos[4].foffset = j4;
21435vinfos[4].indices[0] = _ij4[0];
21436vinfos[4].indices[1] = _ij4[1];
21437vinfos[4].maxsolutions = _nj4;
21438vinfos[5].jointtype = 1;
21439vinfos[5].foffset = j5;
21440vinfos[5].indices[0] = _ij5[0];
21441vinfos[5].indices[1] = _ij5[1];
21442vinfos[5].maxsolutions = _nj5;
21443std::vector<int> vfree(0);
21444solutions.AddSolution(vinfos,vfree);
21445}
21446}
21447}
21448
21449}
21450
21451}
21452
21453}
21454} while(0);
21455if( bgotonextstatement )
21456{
21457bool bgotonextstatement = true;
21458do
21459{
21460if( 1 )
21461{
21462bgotonextstatement=false;
21463continue; // branch miss [j5]
21464
21465}
21466} while(0);
21467if( bgotonextstatement )
21468{
21469}
21470}
21471}
21472}
21473}
21474}
21475}
21476}
21477}
21478}
21479
21480} else
21481{
21482{
21483IkReal j5array[1], cj5array[1], sj5array[1];
21484bool j5valid[1]={false};
21485_nj5 = 1;
21486CheckValue<IkReal> x2360=IKPowWithIntegerCheck(new_r00,-1);
21487if(!x2360.valid){
21488continue;
21489}
21490IkReal x2355=x2360.value;
21491IkReal x2356=(sj3*x2355);
21492IkReal x2357=((25000.0)*new_r00);
21493IkReal x2358=((25000.00002)*cj3*new_r10);
21494CheckValue<IkReal> x2361=IKPowWithIntegerCheck((x2358+((sj3*x2357))),-1);
21495if(!x2361.valid){
21496continue;
21497}
21498IkReal x2359=x2361.value;
21499if( IKabs((((x2356*x2358*x2359))+(((25000.0)*x2359*(new_r10*new_r10)))+(((-1.0)*x2356)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2359*(((((-1.0)*new_r10*x2357))+(((-25000.00002)*cj3*sj3)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((x2356*x2358*x2359))+(((25000.0)*x2359*(new_r10*new_r10)))+(((-1.0)*x2356))))+IKsqr((x2359*(((((-1.0)*new_r10*x2357))+(((-25000.00002)*cj3*sj3))))))-1) <= IKFAST_SINCOS_THRESH )
21500 continue;
21501j5array[0]=IKatan2((((x2356*x2358*x2359))+(((25000.0)*x2359*(new_r10*new_r10)))+(((-1.0)*x2356))), (x2359*(((((-1.0)*new_r10*x2357))+(((-25000.00002)*cj3*sj3))))));
21502sj5array[0]=IKsin(j5array[0]);
21503cj5array[0]=IKcos(j5array[0]);
21504if( j5array[0] > IKPI )
21505{
21506 j5array[0]-=IK2PI;
21507}
21508else if( j5array[0] < -IKPI )
21509{ j5array[0]+=IK2PI;
21510}
21511j5valid[0] = true;
21512for(int ij5 = 0; ij5 < 1; ++ij5)
21513{
21514if( !j5valid[ij5] )
21515{
21516 continue;
21517}
21518_ij5[0] = ij5; _ij5[1] = -1;
21519for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21520{
21521if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21522{
21523 j5valid[iij5]=false; _ij5[1] = iij5; break;
21524}
21525}
21526j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21527{
21528IkReal evalcond[10];
21529IkReal x2362=IKcos(j5);
21530IkReal x2363=IKsin(j5);
21531IkReal x2364=((1.0)*cj3);
21532IkReal x2365=((1.0000000008)*cj3);
21533IkReal x2366=(cj3*x2362);
21534IkReal x2367=(new_r11*x2363);
21535IkReal x2368=(sj3*x2363);
21536IkReal x2369=(new_r01*x2362);
21537IkReal x2370=(new_r00*x2362);
21538IkReal x2371=(sj3*x2362);
21539IkReal x2372=(new_r10*x2363);
21540evalcond[0]=(((new_r00*x2363))+sj3+((new_r10*x2362)));
21541evalcond[1]=(((new_r01*x2363))+(((-1.0)*x2364))+((new_r11*x2362)));
21542evalcond[2]=(x2368+((x2362*x2365))+new_r00);
21543evalcond[3]=(x2371+new_r10+(((-1.0)*x2363*x2365)));
21544evalcond[4]=((((1.0000000008)*x2371))+new_r01+(((-1.0)*x2363*x2364)));
21545evalcond[5]=((((-1.0000000008)*x2368))+new_r11+(((-1.0)*x2362*x2364)));
21546evalcond[6]=(x2370+x2365+(((-1.0)*x2372)));
21547evalcond[7]=(x2369+(((-1.0)*x2367))+(((1.0000000008)*sj3)));
21548evalcond[8]=((((-1.0000000008)*x2370))+(((1.0000000008)*x2372))+(((-1.0)*x2364)));
21549evalcond[9]=((((-1.0000000008)*x2369))+(((-1.0)*sj3))+(((1.0000000008)*x2367)));
21550if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
21551{
21552continue;
21553}
21554}
21555
21556{
21557std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21558vinfos[0].jointtype = 1;
21559vinfos[0].foffset = j0;
21560vinfos[0].indices[0] = _ij0[0];
21561vinfos[0].indices[1] = _ij0[1];
21562vinfos[0].maxsolutions = _nj0;
21563vinfos[1].jointtype = 1;
21564vinfos[1].foffset = j1;
21565vinfos[1].indices[0] = _ij1[0];
21566vinfos[1].indices[1] = _ij1[1];
21567vinfos[1].maxsolutions = _nj1;
21568vinfos[2].jointtype = 1;
21569vinfos[2].foffset = j2;
21570vinfos[2].indices[0] = _ij2[0];
21571vinfos[2].indices[1] = _ij2[1];
21572vinfos[2].maxsolutions = _nj2;
21573vinfos[3].jointtype = 1;
21574vinfos[3].foffset = j3;
21575vinfos[3].indices[0] = _ij3[0];
21576vinfos[3].indices[1] = _ij3[1];
21577vinfos[3].maxsolutions = _nj3;
21578vinfos[4].jointtype = 1;
21579vinfos[4].foffset = j4;
21580vinfos[4].indices[0] = _ij4[0];
21581vinfos[4].indices[1] = _ij4[1];
21582vinfos[4].maxsolutions = _nj4;
21583vinfos[5].jointtype = 1;
21584vinfos[5].foffset = j5;
21585vinfos[5].indices[0] = _ij5[0];
21586vinfos[5].indices[1] = _ij5[1];
21587vinfos[5].maxsolutions = _nj5;
21588std::vector<int> vfree(0);
21589solutions.AddSolution(vinfos,vfree);
21590}
21591}
21592}
21593
21594}
21595
21596}
21597
21598} else
21599{
21600{
21601IkReal j5array[1], cj5array[1], sj5array[1];
21602bool j5valid[1]={false};
21603_nj5 = 1;
21604CheckValue<IkReal> x2379=IKPowWithIntegerCheck(new_r00,-1);
21605if(!x2379.valid){
21606continue;
21607}
21608IkReal x2373=x2379.value;
21609IkReal x2374=((25000.0)*cj3);
21610IkReal x2375=((25000.0)*new_r01);
21611IkReal x2376=(sj3*x2373);
21612CheckValue<IkReal> x2380=IKPowWithIntegerCheck((((new_r10*x2374))+(((25000.00002)*new_r00*sj3))),-1);
21613if(!x2380.valid){
21614continue;
21615}
21616IkReal x2377=x2380.value;
21617IkReal x2378=(new_r10*x2377);
21618if( IKabs((((x2375*x2378))+((x2374*x2376*x2378))+(((-1.0)*x2376)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((x2377*(((((-1.0)*new_r00*x2375))+(((-1.0)*sj3*x2374)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((x2375*x2378))+((x2374*x2376*x2378))+(((-1.0)*x2376))))+IKsqr((x2377*(((((-1.0)*new_r00*x2375))+(((-1.0)*sj3*x2374))))))-1) <= IKFAST_SINCOS_THRESH )
21619 continue;
21620j5array[0]=IKatan2((((x2375*x2378))+((x2374*x2376*x2378))+(((-1.0)*x2376))), (x2377*(((((-1.0)*new_r00*x2375))+(((-1.0)*sj3*x2374))))));
21621sj5array[0]=IKsin(j5array[0]);
21622cj5array[0]=IKcos(j5array[0]);
21623if( j5array[0] > IKPI )
21624{
21625 j5array[0]-=IK2PI;
21626}
21627else if( j5array[0] < -IKPI )
21628{ j5array[0]+=IK2PI;
21629}
21630j5valid[0] = true;
21631for(int ij5 = 0; ij5 < 1; ++ij5)
21632{
21633if( !j5valid[ij5] )
21634{
21635 continue;
21636}
21637_ij5[0] = ij5; _ij5[1] = -1;
21638for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21639{
21640if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21641{
21642 j5valid[iij5]=false; _ij5[1] = iij5; break;
21643}
21644}
21645j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21646{
21647IkReal evalcond[10];
21648IkReal x2381=IKcos(j5);
21649IkReal x2382=IKsin(j5);
21650IkReal x2383=((1.0)*cj3);
21651IkReal x2384=((1.0000000008)*cj3);
21652IkReal x2385=(cj3*x2381);
21653IkReal x2386=(new_r11*x2382);
21654IkReal x2387=(sj3*x2382);
21655IkReal x2388=(new_r01*x2381);
21656IkReal x2389=(new_r00*x2381);
21657IkReal x2390=(sj3*x2381);
21658IkReal x2391=(new_r10*x2382);
21659evalcond[0]=(((new_r10*x2381))+sj3+((new_r00*x2382)));
21660evalcond[1]=(((new_r11*x2381))+((new_r01*x2382))+(((-1.0)*x2383)));
21661evalcond[2]=(((x2381*x2384))+x2387+new_r00);
21662evalcond[3]=(x2390+(((-1.0)*x2382*x2384))+new_r10);
21663evalcond[4]=((((-1.0)*x2382*x2383))+(((1.0000000008)*x2390))+new_r01);
21664evalcond[5]=((((-1.0)*x2381*x2383))+(((-1.0000000008)*x2387))+new_r11);
21665evalcond[6]=(x2384+x2389+(((-1.0)*x2391)));
21666evalcond[7]=(x2388+(((-1.0)*x2386))+(((1.0000000008)*sj3)));
21667evalcond[8]=((((-1.0)*x2383))+(((1.0000000008)*x2391))+(((-1.0000000008)*x2389)));
21668evalcond[9]=((((-1.0)*sj3))+(((1.0000000008)*x2386))+(((-1.0000000008)*x2388)));
21669if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
21670{
21671continue;
21672}
21673}
21674
21675{
21676std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21677vinfos[0].jointtype = 1;
21678vinfos[0].foffset = j0;
21679vinfos[0].indices[0] = _ij0[0];
21680vinfos[0].indices[1] = _ij0[1];
21681vinfos[0].maxsolutions = _nj0;
21682vinfos[1].jointtype = 1;
21683vinfos[1].foffset = j1;
21684vinfos[1].indices[0] = _ij1[0];
21685vinfos[1].indices[1] = _ij1[1];
21686vinfos[1].maxsolutions = _nj1;
21687vinfos[2].jointtype = 1;
21688vinfos[2].foffset = j2;
21689vinfos[2].indices[0] = _ij2[0];
21690vinfos[2].indices[1] = _ij2[1];
21691vinfos[2].maxsolutions = _nj2;
21692vinfos[3].jointtype = 1;
21693vinfos[3].foffset = j3;
21694vinfos[3].indices[0] = _ij3[0];
21695vinfos[3].indices[1] = _ij3[1];
21696vinfos[3].maxsolutions = _nj3;
21697vinfos[4].jointtype = 1;
21698vinfos[4].foffset = j4;
21699vinfos[4].indices[0] = _ij4[0];
21700vinfos[4].indices[1] = _ij4[1];
21701vinfos[4].maxsolutions = _nj4;
21702vinfos[5].jointtype = 1;
21703vinfos[5].foffset = j5;
21704vinfos[5].indices[0] = _ij5[0];
21705vinfos[5].indices[1] = _ij5[1];
21706vinfos[5].maxsolutions = _nj5;
21707std::vector<int> vfree(0);
21708solutions.AddSolution(vinfos,vfree);
21709}
21710}
21711}
21712
21713}
21714
21715}
21716
21717} else
21718{
21719{
21720IkReal j5array[1], cj5array[1], sj5array[1];
21721bool j5valid[1]={false};
21722_nj5 = 1;
21723IkReal x2392=((1.0)*new_r00);
21724CheckValue<IkReal> x2393 = IKatan2WithCheck(IkReal((((new_r11*sj3))+((cj3*new_r10)))),IkReal(((((-1.0)*new_r01*sj3))+(((-1.0)*cj3*x2392)))),IKFAST_ATAN2_MAGTHRESH);
21725if(!x2393.valid){
21726continue;
21727}
21728CheckValue<IkReal> x2394=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r11*x2392))+((new_r01*new_r10)))),-1);
21729if(!x2394.valid){
21730continue;
21731}
21732j5array[0]=((-1.5707963267949)+(x2393.value)+(((1.5707963267949)*(x2394.value))));
21733sj5array[0]=IKsin(j5array[0]);
21734cj5array[0]=IKcos(j5array[0]);
21735if( j5array[0] > IKPI )
21736{
21737 j5array[0]-=IK2PI;
21738}
21739else if( j5array[0] < -IKPI )
21740{ j5array[0]+=IK2PI;
21741}
21742j5valid[0] = true;
21743for(int ij5 = 0; ij5 < 1; ++ij5)
21744{
21745if( !j5valid[ij5] )
21746{
21747 continue;
21748}
21749_ij5[0] = ij5; _ij5[1] = -1;
21750for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21751{
21752if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21753{
21754 j5valid[iij5]=false; _ij5[1] = iij5; break;
21755}
21756}
21757j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21758{
21759IkReal evalcond[10];
21760IkReal x2395=IKcos(j5);
21761IkReal x2396=IKsin(j5);
21762IkReal x2397=((1.0)*cj3);
21763IkReal x2398=((1.0000000008)*cj3);
21764IkReal x2399=(cj3*x2395);
21765IkReal x2400=(new_r11*x2396);
21766IkReal x2401=(sj3*x2396);
21767IkReal x2402=(new_r01*x2395);
21768IkReal x2403=(new_r00*x2395);
21769IkReal x2404=(sj3*x2395);
21770IkReal x2405=(new_r10*x2396);
21771evalcond[0]=(((new_r10*x2395))+sj3+((new_r00*x2396)));
21772evalcond[1]=(((new_r11*x2395))+((new_r01*x2396))+(((-1.0)*x2397)));
21773evalcond[2]=(x2401+new_r00+((x2395*x2398)));
21774evalcond[3]=(x2404+(((-1.0)*x2396*x2398))+new_r10);
21775evalcond[4]=((((-1.0)*x2396*x2397))+(((1.0000000008)*x2404))+new_r01);
21776evalcond[5]=((((-1.0000000008)*x2401))+new_r11+(((-1.0)*x2395*x2397)));
21777evalcond[6]=((((-1.0)*x2405))+x2403+x2398);
21778evalcond[7]=((((-1.0)*x2400))+x2402+(((1.0000000008)*sj3)));
21779evalcond[8]=((((-1.0000000008)*x2403))+(((1.0000000008)*x2405))+(((-1.0)*x2397)));
21780evalcond[9]=((((-1.0)*sj3))+(((-1.0000000008)*x2402))+(((1.0000000008)*x2400)));
21781if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
21782{
21783continue;
21784}
21785}
21786
21787{
21788std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21789vinfos[0].jointtype = 1;
21790vinfos[0].foffset = j0;
21791vinfos[0].indices[0] = _ij0[0];
21792vinfos[0].indices[1] = _ij0[1];
21793vinfos[0].maxsolutions = _nj0;
21794vinfos[1].jointtype = 1;
21795vinfos[1].foffset = j1;
21796vinfos[1].indices[0] = _ij1[0];
21797vinfos[1].indices[1] = _ij1[1];
21798vinfos[1].maxsolutions = _nj1;
21799vinfos[2].jointtype = 1;
21800vinfos[2].foffset = j2;
21801vinfos[2].indices[0] = _ij2[0];
21802vinfos[2].indices[1] = _ij2[1];
21803vinfos[2].maxsolutions = _nj2;
21804vinfos[3].jointtype = 1;
21805vinfos[3].foffset = j3;
21806vinfos[3].indices[0] = _ij3[0];
21807vinfos[3].indices[1] = _ij3[1];
21808vinfos[3].maxsolutions = _nj3;
21809vinfos[4].jointtype = 1;
21810vinfos[4].foffset = j4;
21811vinfos[4].indices[0] = _ij4[0];
21812vinfos[4].indices[1] = _ij4[1];
21813vinfos[4].maxsolutions = _nj4;
21814vinfos[5].jointtype = 1;
21815vinfos[5].foffset = j5;
21816vinfos[5].indices[0] = _ij5[0];
21817vinfos[5].indices[1] = _ij5[1];
21818vinfos[5].maxsolutions = _nj5;
21819std::vector<int> vfree(0);
21820solutions.AddSolution(vinfos,vfree);
21821}
21822}
21823}
21824
21825}
21826
21827}
21828
21829}
21830} while(0);
21831if( bgotonextstatement )
21832{
21833bool bgotonextstatement = true;
21834do
21835{
21836evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959)));
21837evalcond[1]=new_r20;
21838if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
21839{
21840bgotonextstatement=false;
21841{
21842IkReal j5array[1], cj5array[1], sj5array[1];
21843bool j5valid[1]={false};
21844_nj5 = 1;
21845if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH )
21846 continue;
21847j5array[0]=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r10));
21848sj5array[0]=IKsin(j5array[0]);
21849cj5array[0]=IKcos(j5array[0]);
21850if( j5array[0] > IKPI )
21851{
21852 j5array[0]-=IK2PI;
21853}
21854else if( j5array[0] < -IKPI )
21855{ j5array[0]+=IK2PI;
21856}
21857j5valid[0] = true;
21858for(int ij5 = 0; ij5 < 1; ++ij5)
21859{
21860if( !j5valid[ij5] )
21861{
21862 continue;
21863}
21864_ij5[0] = ij5; _ij5[1] = -1;
21865for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21866{
21867if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21868{
21869 j5valid[iij5]=false; _ij5[1] = iij5; break;
21870}
21871}
21872j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21873{
21874IkReal evalcond[18];
21875IkReal x2406=IKsin(j5);
21876IkReal x2407=IKcos(j5);
21877IkReal x2408=((0.9999999992)*cj4);
21878IkReal x2409=((4.0e-5)*new_r22);
21879IkReal x2410=((1.0000000008)*sj4);
21880IkReal x2411=((3.9999999968e-5)*sj4);
21881IkReal x2412=((3.9999999968e-5)*cj4);
21882IkReal x2413=((0.9999999992)*sj4);
21883IkReal x2414=((1.0)*new_r22);
21884IkReal x2415=(new_r22*x2413);
21885IkReal x2416=(new_r22*x2412);
21886IkReal x2417=(new_r22*x2411);
21887IkReal x2418=(new_r12*x2406);
21888IkReal x2419=(new_r02*x2407);
21889IkReal x2420=(new_r01*x2407);
21890IkReal x2421=(new_r00*x2407);
21891IkReal x2422=(new_r11*x2406);
21892IkReal x2423=(new_r10*x2406);
21893evalcond[0]=(x2406+new_r00);
21894evalcond[1]=(x2407+new_r10);
21895evalcond[2]=(((new_r22*x2406))+new_r11);
21896evalcond[3]=((((-1.0)*x2407*x2414))+new_r01);
21897evalcond[4]=(((new_r12*x2407))+((new_r02*x2406)));
21898evalcond[5]=(((new_r01*x2406))+((new_r11*x2407)));
21899evalcond[6]=((1.0)+((new_r00*x2406))+((new_r10*x2407)));
21900evalcond[7]=(x2421+(((-1.0)*x2423)));
21901evalcond[8]=(((new_r22*x2421))+(((-1.0)*x2414*x2423)));
21902evalcond[9]=(x2420+(((-1.0)*x2414))+(((-1.0)*x2422)));
21903evalcond[10]=((((-1.0)*x2407*x2409))+((x2407*x2410))+new_r02);
21904evalcond[11]=((((-1.0)*x2406*x2410))+new_r12+((x2406*x2409)));
21905evalcond[12]=(x2410+x2419+(((-1.0)*x2409))+(((-1.0)*x2418)));
21906evalcond[13]=((((-1.0)*x2409*x2423))+(((-1.0)*x2410*x2421))+((x2409*x2421))+((x2410*x2423)));
21907evalcond[14]=((-1.0)+(((-4.0e-5)*cj4*sj4))+(((1.59999999872e-9)*cj4*new_r22))+(sj4*sj4)+((new_r22*x2420))+(((-1.0)*x2417))+(((-1.0)*x2414*x2422)));
21908evalcond[15]=((((-1.0)*x2409*x2422))+x2415+(((-1.0)*x2410*x2420))+((x2409*x2420))+(((-1.0)*x2416))+((x2410*x2422)));
21909evalcond[16]=(x2415+(((-1.0)*x2408*x2418))+((x2408*x2419))+(((-1.0)*x2411*x2418))+(((-1.0)*x2416))+((x2411*x2419)));
21910evalcond[17]=((-1.0)+x2417+((new_r22*x2408))+((x2413*x2418))+(((-1.0)*x2412*x2418))+(((-1.0)*x2413*x2419))+((x2412*x2419)));
21911if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
21912{
21913continue;
21914}
21915}
21916
21917{
21918std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21919vinfos[0].jointtype = 1;
21920vinfos[0].foffset = j0;
21921vinfos[0].indices[0] = _ij0[0];
21922vinfos[0].indices[1] = _ij0[1];
21923vinfos[0].maxsolutions = _nj0;
21924vinfos[1].jointtype = 1;
21925vinfos[1].foffset = j1;
21926vinfos[1].indices[0] = _ij1[0];
21927vinfos[1].indices[1] = _ij1[1];
21928vinfos[1].maxsolutions = _nj1;
21929vinfos[2].jointtype = 1;
21930vinfos[2].foffset = j2;
21931vinfos[2].indices[0] = _ij2[0];
21932vinfos[2].indices[1] = _ij2[1];
21933vinfos[2].maxsolutions = _nj2;
21934vinfos[3].jointtype = 1;
21935vinfos[3].foffset = j3;
21936vinfos[3].indices[0] = _ij3[0];
21937vinfos[3].indices[1] = _ij3[1];
21938vinfos[3].maxsolutions = _nj3;
21939vinfos[4].jointtype = 1;
21940vinfos[4].foffset = j4;
21941vinfos[4].indices[0] = _ij4[0];
21942vinfos[4].indices[1] = _ij4[1];
21943vinfos[4].maxsolutions = _nj4;
21944vinfos[5].jointtype = 1;
21945vinfos[5].foffset = j5;
21946vinfos[5].indices[0] = _ij5[0];
21947vinfos[5].indices[1] = _ij5[1];
21948vinfos[5].maxsolutions = _nj5;
21949std::vector<int> vfree(0);
21950solutions.AddSolution(vinfos,vfree);
21951}
21952}
21953}
21954
21955}
21956} while(0);
21957if( bgotonextstatement )
21958{
21959bool bgotonextstatement = true;
21960do
21961{
21962evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959)));
21963evalcond[1]=new_r20;
21964if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
21965{
21966bgotonextstatement=false;
21967{
21968IkReal j5array[1], cj5array[1], sj5array[1];
21969bool j5valid[1]={false};
21970_nj5 = 1;
21971if( IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r00)+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH )
21972 continue;
21973j5array[0]=IKatan2(new_r00, new_r10);
21974sj5array[0]=IKsin(j5array[0]);
21975cj5array[0]=IKcos(j5array[0]);
21976if( j5array[0] > IKPI )
21977{
21978 j5array[0]-=IK2PI;
21979}
21980else if( j5array[0] < -IKPI )
21981{ j5array[0]+=IK2PI;
21982}
21983j5valid[0] = true;
21984for(int ij5 = 0; ij5 < 1; ++ij5)
21985{
21986if( !j5valid[ij5] )
21987{
21988 continue;
21989}
21990_ij5[0] = ij5; _ij5[1] = -1;
21991for(int iij5 = ij5+1; iij5 < 1; ++iij5)
21992{
21993if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
21994{
21995 j5valid[iij5]=false; _ij5[1] = iij5; break;
21996}
21997}
21998j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
21999{
22000IkReal evalcond[18];
22001IkReal x2424=IKcos(j5);
22002IkReal x2425=IKsin(j5);
22003IkReal x2426=((0.9999999992)*cj4);
22004IkReal x2427=((3.9999999968e-5)*cj4);
22005IkReal x2428=((3.9999999968e-5)*sj4);
22006IkReal x2429=((0.9999999992)*sj4);
22007IkReal x2430=(new_r12*x2425);
22008IkReal x2431=(new_r02*x2424);
22009IkReal x2432=(new_r01*x2424);
22010IkReal x2433=(new_r11*x2425);
22011IkReal x2434=(new_r10*x2425);
22012IkReal x2435=(new_r00*x2424);
22013evalcond[0]=((((-1.0)*x2425))+new_r00);
22014evalcond[1]=((((-1.0)*x2424))+new_r10);
22015evalcond[2]=(((new_r12*x2424))+((new_r02*x2425)));
22016evalcond[3]=(((new_r11*x2424))+((new_r01*x2425)));
22017evalcond[4]=((-1.0)+((new_r10*x2424))+((new_r00*x2425)));
22018evalcond[5]=((((-1.0)*x2434))+x2435);
22019evalcond[6]=((((-1.0)*x2424*x2427))+((x2424*x2429))+new_r02);
22020evalcond[7]=((((-1.0)*x2425*x2429))+((x2425*x2427))+new_r12);
22021evalcond[8]=(((x2424*x2426))+((x2424*x2428))+new_r01);
22022evalcond[9]=((((-1.0)*x2425*x2428))+(((-1.0)*x2425*x2426))+new_r11);
22023evalcond[10]=((((-1.0)*x2430))+x2431+x2429+(((-1.0)*x2427)));
22024evalcond[11]=((((-1.0)*x2433))+x2432+x2428+x2426);
22025evalcond[12]=(((x2429*x2434))+(((-1.0)*x2427*x2434))+(((-1.0)*x2429*x2435))+((x2427*x2435)));
22026evalcond[13]=(((x2428*x2435))+(((-1.0)*x2426*x2434))+(((-1.0)*x2428*x2434))+((x2426*x2435)));
22027evalcond[14]=(((x2429*x2433))+((new_r21*x2426))+((new_r21*x2428))+(((-1.0)*x2427*x2433))+(((-1.0)*x2429*x2432))+((x2427*x2432)));
22028evalcond[15]=(((x2428*x2431))+(((-1.0)*x2426*x2430))+((new_r22*x2429))+(((-1.0)*x2428*x2430))+((x2426*x2431))+(((-1.0)*new_r22*x2427)));
22029evalcond[16]=((-1.0)+((x2429*x2430))+(((-1.0)*x2427*x2430))+((new_r22*x2426))+((new_r22*x2428))+(((-1.0)*x2429*x2431))+((x2427*x2431)));
22030evalcond[17]=((1.0)+((x2428*x2432))+((new_r21*x2429))+(((-1.0)*x2426*x2433))+(((-1.0)*new_r21*x2427))+(((-1.0)*x2428*x2433))+((x2426*x2432)));
22031if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
22032{
22033continue;
22034}
22035}
22036
22037{
22038std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22039vinfos[0].jointtype = 1;
22040vinfos[0].foffset = j0;
22041vinfos[0].indices[0] = _ij0[0];
22042vinfos[0].indices[1] = _ij0[1];
22043vinfos[0].maxsolutions = _nj0;
22044vinfos[1].jointtype = 1;
22045vinfos[1].foffset = j1;
22046vinfos[1].indices[0] = _ij1[0];
22047vinfos[1].indices[1] = _ij1[1];
22048vinfos[1].maxsolutions = _nj1;
22049vinfos[2].jointtype = 1;
22050vinfos[2].foffset = j2;
22051vinfos[2].indices[0] = _ij2[0];
22052vinfos[2].indices[1] = _ij2[1];
22053vinfos[2].maxsolutions = _nj2;
22054vinfos[3].jointtype = 1;
22055vinfos[3].foffset = j3;
22056vinfos[3].indices[0] = _ij3[0];
22057vinfos[3].indices[1] = _ij3[1];
22058vinfos[3].maxsolutions = _nj3;
22059vinfos[4].jointtype = 1;
22060vinfos[4].foffset = j4;
22061vinfos[4].indices[0] = _ij4[0];
22062vinfos[4].indices[1] = _ij4[1];
22063vinfos[4].maxsolutions = _nj4;
22064vinfos[5].jointtype = 1;
22065vinfos[5].foffset = j5;
22066vinfos[5].indices[0] = _ij5[0];
22067vinfos[5].indices[1] = _ij5[1];
22068vinfos[5].maxsolutions = _nj5;
22069std::vector<int> vfree(0);
22070solutions.AddSolution(vinfos,vfree);
22071}
22072}
22073}
22074
22075}
22076} while(0);
22077if( bgotonextstatement )
22078{
22079bool bgotonextstatement = true;
22080do
22081{
22082evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j3))), 6.28318530717959)));
22083evalcond[1]=new_r21;
22084if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
22085{
22086bgotonextstatement=false;
22087{
22088IkReal j5array[1], cj5array[1], sj5array[1];
22089bool j5valid[1]={false};
22090_nj5 = 1;
22091if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(new_r11)-1) <= IKFAST_SINCOS_THRESH )
22092 continue;
22093j5array[0]=IKatan2(new_r01, new_r11);
22094sj5array[0]=IKsin(j5array[0]);
22095cj5array[0]=IKcos(j5array[0]);
22096if( j5array[0] > IKPI )
22097{
22098 j5array[0]-=IK2PI;
22099}
22100else if( j5array[0] < -IKPI )
22101{ j5array[0]+=IK2PI;
22102}
22103j5valid[0] = true;
22104for(int ij5 = 0; ij5 < 1; ++ij5)
22105{
22106if( !j5valid[ij5] )
22107{
22108 continue;
22109}
22110_ij5[0] = ij5; _ij5[1] = -1;
22111for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22112{
22113if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22114{
22115 j5valid[iij5]=false; _ij5[1] = iij5; break;
22116}
22117}
22118j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22119{
22120IkReal evalcond[18];
22121IkReal x2436=IKsin(j5);
22122IkReal x2437=IKcos(j5);
22123IkReal x2438=((0.9999999992)*cj4);
22124IkReal x2439=((0.9999999992)*sj4);
22125IkReal x2440=((4.0e-5)*new_r22);
22126IkReal x2441=((3.9999999968e-5)*sj4);
22127IkReal x2442=((3.9999999968e-5)*cj4);
22128IkReal x2443=((1.0000000008)*sj4);
22129IkReal x2444=((1.0)*new_r22);
22130IkReal x2445=(new_r12*x2436);
22131IkReal x2446=(new_r02*x2437);
22132IkReal x2447=(new_r01*x2437);
22133IkReal x2448=(new_r11*x2436);
22134IkReal x2449=(new_r00*x2437);
22135IkReal x2450=(new_r10*x2436);
22136evalcond[0]=(((new_r22*x2436))+new_r10);
22137evalcond[1]=((((-1.0)*x2436))+new_r01);
22138evalcond[2]=((((-1.0)*x2437))+new_r11);
22139evalcond[3]=((((-1.0)*x2437*x2444))+new_r00);
22140evalcond[4]=(((new_r12*x2437))+((new_r02*x2436)));
22141evalcond[5]=(((new_r00*x2436))+((new_r10*x2437)));
22142evalcond[6]=((-1.0)+((new_r01*x2436))+((new_r11*x2437)));
22143evalcond[7]=(x2447+(((-1.0)*x2448)));
22144evalcond[8]=((((-1.0)*x2444*x2448))+((new_r22*x2447)));
22145evalcond[9]=(x2449+(((-1.0)*x2450))+(((-1.0)*x2444)));
22146evalcond[10]=((((-1.0)*x2437*x2440))+((x2437*x2443))+new_r02);
22147evalcond[11]=((((-1.0)*x2436*x2443))+new_r12+((x2436*x2440)));
22148evalcond[12]=(x2443+x2446+(((-1.0)*x2445))+(((-1.0)*x2440)));
22149evalcond[13]=((((-1.0)*x2443*x2447))+((x2443*x2448))+((x2440*x2447))+(((-1.0)*x2440*x2448)));
22150evalcond[14]=((((-1.0)*x2442*x2450))+((x2442*x2449))+((new_r20*x2441))+(((-1.0)*x2439*x2449))+((x2439*x2450))+((new_r20*x2438)));
22151evalcond[15]=(((new_r22*x2439))+(((-1.0)*x2441*x2445))+(((-1.0)*x2438*x2445))+((x2441*x2446))+(((-1.0)*new_r22*x2442))+((x2438*x2446)));
22152evalcond[16]=((-1.0)+((new_r22*x2438))+((x2442*x2446))+(((-1.0)*x2439*x2446))+((new_r22*x2441))+((x2439*x2445))+(((-1.0)*x2442*x2445)));
22153evalcond[17]=((-1.0)+(((-1.0)*new_r20*x2442))+(((-1.0)*x2441*x2450))+(((-1.0)*x2438*x2450))+((x2441*x2449))+((x2438*x2449))+((new_r20*x2439)));
22154if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
22155{
22156continue;
22157}
22158}
22159
22160{
22161std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22162vinfos[0].jointtype = 1;
22163vinfos[0].foffset = j0;
22164vinfos[0].indices[0] = _ij0[0];
22165vinfos[0].indices[1] = _ij0[1];
22166vinfos[0].maxsolutions = _nj0;
22167vinfos[1].jointtype = 1;
22168vinfos[1].foffset = j1;
22169vinfos[1].indices[0] = _ij1[0];
22170vinfos[1].indices[1] = _ij1[1];
22171vinfos[1].maxsolutions = _nj1;
22172vinfos[2].jointtype = 1;
22173vinfos[2].foffset = j2;
22174vinfos[2].indices[0] = _ij2[0];
22175vinfos[2].indices[1] = _ij2[1];
22176vinfos[2].maxsolutions = _nj2;
22177vinfos[3].jointtype = 1;
22178vinfos[3].foffset = j3;
22179vinfos[3].indices[0] = _ij3[0];
22180vinfos[3].indices[1] = _ij3[1];
22181vinfos[3].maxsolutions = _nj3;
22182vinfos[4].jointtype = 1;
22183vinfos[4].foffset = j4;
22184vinfos[4].indices[0] = _ij4[0];
22185vinfos[4].indices[1] = _ij4[1];
22186vinfos[4].maxsolutions = _nj4;
22187vinfos[5].jointtype = 1;
22188vinfos[5].foffset = j5;
22189vinfos[5].indices[0] = _ij5[0];
22190vinfos[5].indices[1] = _ij5[1];
22191vinfos[5].maxsolutions = _nj5;
22192std::vector<int> vfree(0);
22193solutions.AddSolution(vinfos,vfree);
22194}
22195}
22196}
22197
22198}
22199} while(0);
22200if( bgotonextstatement )
22201{
22202bool bgotonextstatement = true;
22203do
22204{
22205evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j3)))), 6.28318530717959)));
22206evalcond[1]=new_r21;
22207if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
22208{
22209bgotonextstatement=false;
22210{
22211IkReal j5array[1], cj5array[1], sj5array[1];
22212bool j5valid[1]={false};
22213_nj5 = 1;
22214if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(((-1.0)*new_r11))-1) <= IKFAST_SINCOS_THRESH )
22215 continue;
22216j5array[0]=IKatan2(((-1.0)*new_r01), ((-1.0)*new_r11));
22217sj5array[0]=IKsin(j5array[0]);
22218cj5array[0]=IKcos(j5array[0]);
22219if( j5array[0] > IKPI )
22220{
22221 j5array[0]-=IK2PI;
22222}
22223else if( j5array[0] < -IKPI )
22224{ j5array[0]+=IK2PI;
22225}
22226j5valid[0] = true;
22227for(int ij5 = 0; ij5 < 1; ++ij5)
22228{
22229if( !j5valid[ij5] )
22230{
22231 continue;
22232}
22233_ij5[0] = ij5; _ij5[1] = -1;
22234for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22235{
22236if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22237{
22238 j5valid[iij5]=false; _ij5[1] = iij5; break;
22239}
22240}
22241j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22242{
22243IkReal evalcond[18];
22244IkReal x2451=IKcos(j5);
22245IkReal x2452=IKsin(j5);
22246IkReal x2453=((0.9999999992)*cj4);
22247IkReal x2454=((0.9999999992)*sj4);
22248IkReal x2455=((3.9999999968e-5)*cj4);
22249IkReal x2456=((3.9999999968e-5)*sj4);
22250IkReal x2457=((1.0)*new_r22);
22251IkReal x2458=(new_r12*x2452);
22252IkReal x2459=(new_r02*x2451);
22253IkReal x2460=(new_r01*x2451);
22254IkReal x2461=(new_r11*x2452);
22255IkReal x2462=(new_r00*x2451);
22256IkReal x2463=(new_r10*x2452);
22257evalcond[0]=(x2452+new_r01);
22258evalcond[1]=(x2451+new_r11);
22259evalcond[2]=(((new_r22*x2451))+new_r00);
22260evalcond[3]=((((-1.0)*x2452*x2457))+new_r10);
22261evalcond[4]=(((new_r12*x2451))+((new_r02*x2452)));
22262evalcond[5]=(((new_r10*x2451))+((new_r00*x2452)));
22263evalcond[6]=((1.0)+((new_r11*x2451))+((new_r01*x2452)));
22264evalcond[7]=(x2460+(((-1.0)*x2461)));
22265evalcond[8]=(x2462+(((-1.0)*x2463))+new_r22);
22266evalcond[9]=((((-1.0)*x2457*x2461))+((new_r22*x2460)));
22267evalcond[10]=((((-1.0)*x2451*x2455))+((x2451*x2454))+new_r02);
22268evalcond[11]=((((-1.0)*x2452*x2454))+((x2452*x2455))+new_r12);
22269evalcond[12]=(x2459+(((25000.0)*new_r22))+(((-625000001.0)*new_r20))+(((-625000000.5)*sj4))+(((-1.0)*x2458)));
22270evalcond[13]=((((-1.0)*x2454*x2460))+(((-1.0)*x2455*x2461))+((x2454*x2461))+((x2455*x2460)));
22271evalcond[14]=((((-1.0)*x2454*x2462))+((new_r20*x2456))+((new_r20*x2453))+(((-1.0)*x2455*x2463))+((x2454*x2463))+((x2455*x2462)));
22272evalcond[15]=((((-1.0)*x2453*x2458))+((x2453*x2459))+(((-1.0)*x2456*x2458))+((x2456*x2459))+((new_r22*x2454))+(((-1.0)*new_r22*x2455)));
22273evalcond[16]=((-1.0)+(((-1.0)*x2454*x2459))+((x2454*x2458))+((new_r22*x2453))+((new_r22*x2456))+((x2455*x2459))+(((-1.0)*x2455*x2458)));
22274evalcond[17]=((1.0)+((new_r20*x2454))+(((-1.0)*new_r20*x2455))+(((-1.0)*x2456*x2463))+((x2453*x2462))+((x2456*x2462))+(((-1.0)*x2453*x2463)));
22275if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
22276{
22277continue;
22278}
22279}
22280
22281{
22282std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22283vinfos[0].jointtype = 1;
22284vinfos[0].foffset = j0;
22285vinfos[0].indices[0] = _ij0[0];
22286vinfos[0].indices[1] = _ij0[1];
22287vinfos[0].maxsolutions = _nj0;
22288vinfos[1].jointtype = 1;
22289vinfos[1].foffset = j1;
22290vinfos[1].indices[0] = _ij1[0];
22291vinfos[1].indices[1] = _ij1[1];
22292vinfos[1].maxsolutions = _nj1;
22293vinfos[2].jointtype = 1;
22294vinfos[2].foffset = j2;
22295vinfos[2].indices[0] = _ij2[0];
22296vinfos[2].indices[1] = _ij2[1];
22297vinfos[2].maxsolutions = _nj2;
22298vinfos[3].jointtype = 1;
22299vinfos[3].foffset = j3;
22300vinfos[3].indices[0] = _ij3[0];
22301vinfos[3].indices[1] = _ij3[1];
22302vinfos[3].maxsolutions = _nj3;
22303vinfos[4].jointtype = 1;
22304vinfos[4].foffset = j4;
22305vinfos[4].indices[0] = _ij4[0];
22306vinfos[4].indices[1] = _ij4[1];
22307vinfos[4].maxsolutions = _nj4;
22308vinfos[5].jointtype = 1;
22309vinfos[5].foffset = j5;
22310vinfos[5].indices[0] = _ij5[0];
22311vinfos[5].indices[1] = _ij5[1];
22312vinfos[5].maxsolutions = _nj5;
22313std::vector<int> vfree(0);
22314solutions.AddSolution(vinfos,vfree);
22315}
22316}
22317}
22318
22319}
22320} while(0);
22321if( bgotonextstatement )
22322{
22323bool bgotonextstatement = true;
22324do
22325{
22326evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
22327if( IKabs(evalcond[0]) < 0.0000050000000000 )
22328{
22329bgotonextstatement=false;
22330{
22331IkReal j5eval[3];
22332new_r00=0;
22333new_r10=0;
22334new_r21=0;
22335new_r22=0;
22336j5eval[0]=sj4;
22337j5eval[1]=IKsign(sj4);
22338j5eval[2]=((1.0)+(new_r12*new_r12)+(((-1.0)*(new_r01*new_r01))));
22339if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
22340{
22341{
22342IkReal j5eval[2];
22343new_r00=0;
22344new_r10=0;
22345new_r21=0;
22346new_r22=0;
22347j5eval[0]=new_r01;
22348j5eval[1]=sj4;
22349if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
22350{
22351{
22352IkReal j5eval[2];
22353new_r00=0;
22354new_r10=0;
22355new_r21=0;
22356new_r22=0;
22357j5eval[0]=sj4;
22358j5eval[1]=new_r11;
22359if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
22360{
22361{
22362IkReal evalcond[5];
22363bool bgotonextstatement = true;
22364do
22365{
22366evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
22367evalcond[1]=new_r02;
22368evalcond[2]=new_r12;
22369evalcond[3]=new_r01;
22370evalcond[4]=new_r11;
22371if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
22372{
22373bgotonextstatement=false;
22374{
22375IkReal j5array[1], cj5array[1], sj5array[1];
22376bool j5valid[1]={false};
22377_nj5 = 1;
22378j5array[0]=0;
22379sj5array[0]=IKsin(j5array[0]);
22380cj5array[0]=IKcos(j5array[0]);
22381if( j5array[0] > IKPI )
22382{
22383 j5array[0]-=IK2PI;
22384}
22385else if( j5array[0] < -IKPI )
22386{ j5array[0]+=IK2PI;
22387}
22388j5valid[0] = true;
22389for(int ij5 = 0; ij5 < 1; ++ij5)
22390{
22391if( !j5valid[ij5] )
22392{
22393 continue;
22394}
22395_ij5[0] = ij5; _ij5[1] = -1;
22396for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22397{
22398if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22399{
22400 j5valid[iij5]=false; _ij5[1] = iij5; break;
22401}
22402}
22403j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22404
22405{
22406std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22407vinfos[0].jointtype = 1;
22408vinfos[0].foffset = j0;
22409vinfos[0].indices[0] = _ij0[0];
22410vinfos[0].indices[1] = _ij0[1];
22411vinfos[0].maxsolutions = _nj0;
22412vinfos[1].jointtype = 1;
22413vinfos[1].foffset = j1;
22414vinfos[1].indices[0] = _ij1[0];
22415vinfos[1].indices[1] = _ij1[1];
22416vinfos[1].maxsolutions = _nj1;
22417vinfos[2].jointtype = 1;
22418vinfos[2].foffset = j2;
22419vinfos[2].indices[0] = _ij2[0];
22420vinfos[2].indices[1] = _ij2[1];
22421vinfos[2].maxsolutions = _nj2;
22422vinfos[3].jointtype = 1;
22423vinfos[3].foffset = j3;
22424vinfos[3].indices[0] = _ij3[0];
22425vinfos[3].indices[1] = _ij3[1];
22426vinfos[3].maxsolutions = _nj3;
22427vinfos[4].jointtype = 1;
22428vinfos[4].foffset = j4;
22429vinfos[4].indices[0] = _ij4[0];
22430vinfos[4].indices[1] = _ij4[1];
22431vinfos[4].maxsolutions = _nj4;
22432vinfos[5].jointtype = 1;
22433vinfos[5].foffset = j5;
22434vinfos[5].indices[0] = _ij5[0];
22435vinfos[5].indices[1] = _ij5[1];
22436vinfos[5].maxsolutions = _nj5;
22437std::vector<int> vfree(0);
22438solutions.AddSolution(vinfos,vfree);
22439}
22440}
22441}
22442
22443}
22444} while(0);
22445if( bgotonextstatement )
22446{
22447bool bgotonextstatement = true;
22448do
22449{
22450evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
22451evalcond[1]=new_r02;
22452evalcond[2]=new_r12;
22453evalcond[3]=new_r01;
22454evalcond[4]=new_r11;
22455if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
22456{
22457bgotonextstatement=false;
22458{
22459IkReal j5array[1], cj5array[1], sj5array[1];
22460bool j5valid[1]={false};
22461_nj5 = 1;
22462j5array[0]=0;
22463sj5array[0]=IKsin(j5array[0]);
22464cj5array[0]=IKcos(j5array[0]);
22465if( j5array[0] > IKPI )
22466{
22467 j5array[0]-=IK2PI;
22468}
22469else if( j5array[0] < -IKPI )
22470{ j5array[0]+=IK2PI;
22471}
22472j5valid[0] = true;
22473for(int ij5 = 0; ij5 < 1; ++ij5)
22474{
22475if( !j5valid[ij5] )
22476{
22477 continue;
22478}
22479_ij5[0] = ij5; _ij5[1] = -1;
22480for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22481{
22482if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22483{
22484 j5valid[iij5]=false; _ij5[1] = iij5; break;
22485}
22486}
22487j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22488
22489{
22490std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22491vinfos[0].jointtype = 1;
22492vinfos[0].foffset = j0;
22493vinfos[0].indices[0] = _ij0[0];
22494vinfos[0].indices[1] = _ij0[1];
22495vinfos[0].maxsolutions = _nj0;
22496vinfos[1].jointtype = 1;
22497vinfos[1].foffset = j1;
22498vinfos[1].indices[0] = _ij1[0];
22499vinfos[1].indices[1] = _ij1[1];
22500vinfos[1].maxsolutions = _nj1;
22501vinfos[2].jointtype = 1;
22502vinfos[2].foffset = j2;
22503vinfos[2].indices[0] = _ij2[0];
22504vinfos[2].indices[1] = _ij2[1];
22505vinfos[2].maxsolutions = _nj2;
22506vinfos[3].jointtype = 1;
22507vinfos[3].foffset = j3;
22508vinfos[3].indices[0] = _ij3[0];
22509vinfos[3].indices[1] = _ij3[1];
22510vinfos[3].maxsolutions = _nj3;
22511vinfos[4].jointtype = 1;
22512vinfos[4].foffset = j4;
22513vinfos[4].indices[0] = _ij4[0];
22514vinfos[4].indices[1] = _ij4[1];
22515vinfos[4].maxsolutions = _nj4;
22516vinfos[5].jointtype = 1;
22517vinfos[5].foffset = j5;
22518vinfos[5].indices[0] = _ij5[0];
22519vinfos[5].indices[1] = _ij5[1];
22520vinfos[5].maxsolutions = _nj5;
22521std::vector<int> vfree(0);
22522solutions.AddSolution(vinfos,vfree);
22523}
22524}
22525}
22526
22527}
22528} while(0);
22529if( bgotonextstatement )
22530{
22531bool bgotonextstatement = true;
22532do
22533{
22534if( 1 )
22535{
22536bgotonextstatement=false;
22537continue; // branch miss [j5]
22538
22539}
22540} while(0);
22541if( bgotonextstatement )
22542{
22543}
22544}
22545}
22546}
22547
22548} else
22549{
22550{
22551IkReal j5array[1], cj5array[1], sj5array[1];
22552bool j5valid[1]={false};
22553_nj5 = 1;
22554CheckValue<IkReal> x2466=IKPowWithIntegerCheck(sj4,-1);
22555if(!x2466.valid){
22556continue;
22557}
22558IkReal x2464=x2466.value;
22559IkReal x2465=(new_r12*x2464);
22560CheckValue<IkReal> x2467=IKPowWithIntegerCheck(new_r11,-1);
22561if(!x2467.valid){
22562continue;
22563}
22564if( IKabs(((0.9999999992)*x2465)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*new_r01*x2465*(x2467.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*x2465))+IKsqr(((-0.9999999992)*new_r01*x2465*(x2467.value)))-1) <= IKFAST_SINCOS_THRESH )
22565 continue;
22566j5array[0]=IKatan2(((0.9999999992)*x2465), ((-0.9999999992)*new_r01*x2465*(x2467.value)));
22567sj5array[0]=IKsin(j5array[0]);
22568cj5array[0]=IKcos(j5array[0]);
22569if( j5array[0] > IKPI )
22570{
22571 j5array[0]-=IK2PI;
22572}
22573else if( j5array[0] < -IKPI )
22574{ j5array[0]+=IK2PI;
22575}
22576j5valid[0] = true;
22577for(int ij5 = 0; ij5 < 1; ++ij5)
22578{
22579if( !j5valid[ij5] )
22580{
22581 continue;
22582}
22583_ij5[0] = ij5; _ij5[1] = -1;
22584for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22585{
22586if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22587{
22588 j5valid[iij5]=false; _ij5[1] = iij5; break;
22589}
22590}
22591j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22592{
22593IkReal evalcond[10];
22594IkReal x2468=IKcos(j5);
22595IkReal x2469=IKsin(j5);
22596IkReal x2470=((0.9999999992)*cj4);
22597IkReal x2471=((3.9999999968e-5)*sj4);
22598IkReal x2472=((1.0000000008)*sj4);
22599IkReal x2473=(new_r12*x2469);
22600IkReal x2474=(new_r02*x2468);
22601IkReal x2475=(new_r11*x2469);
22602IkReal x2476=(new_r01*x2468);
22603evalcond[0]=(((new_r02*x2469))+((new_r12*x2468)));
22604evalcond[1]=(((new_r01*x2469))+((new_r11*x2468)));
22605evalcond[2]=(((x2468*x2472))+new_r02);
22606evalcond[3]=((((-1.0)*x2469*x2472))+new_r12);
22607evalcond[4]=(x2476+(((-1.0)*x2475)));
22608evalcond[5]=(x2474+x2472+(((-1.0)*x2473)));
22609evalcond[6]=((((-1.0)*x2472*x2476))+((x2472*x2475)));
22610evalcond[7]=((-1.0)+(((-1.0)*x2472*x2474))+((x2472*x2473)));
22611evalcond[8]=(((x2471*x2474))+(((-1.0)*x2470*x2473))+(((-1.0)*x2471*x2473))+((x2470*x2474)));
22612evalcond[9]=(((x2471*x2476))+(((-1.0)*x2470*x2475))+(((-1.0)*x2471*x2475))+((x2470*x2476)));
22613if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
22614{
22615continue;
22616}
22617}
22618
22619{
22620std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22621vinfos[0].jointtype = 1;
22622vinfos[0].foffset = j0;
22623vinfos[0].indices[0] = _ij0[0];
22624vinfos[0].indices[1] = _ij0[1];
22625vinfos[0].maxsolutions = _nj0;
22626vinfos[1].jointtype = 1;
22627vinfos[1].foffset = j1;
22628vinfos[1].indices[0] = _ij1[0];
22629vinfos[1].indices[1] = _ij1[1];
22630vinfos[1].maxsolutions = _nj1;
22631vinfos[2].jointtype = 1;
22632vinfos[2].foffset = j2;
22633vinfos[2].indices[0] = _ij2[0];
22634vinfos[2].indices[1] = _ij2[1];
22635vinfos[2].maxsolutions = _nj2;
22636vinfos[3].jointtype = 1;
22637vinfos[3].foffset = j3;
22638vinfos[3].indices[0] = _ij3[0];
22639vinfos[3].indices[1] = _ij3[1];
22640vinfos[3].maxsolutions = _nj3;
22641vinfos[4].jointtype = 1;
22642vinfos[4].foffset = j4;
22643vinfos[4].indices[0] = _ij4[0];
22644vinfos[4].indices[1] = _ij4[1];
22645vinfos[4].maxsolutions = _nj4;
22646vinfos[5].jointtype = 1;
22647vinfos[5].foffset = j5;
22648vinfos[5].indices[0] = _ij5[0];
22649vinfos[5].indices[1] = _ij5[1];
22650vinfos[5].maxsolutions = _nj5;
22651std::vector<int> vfree(0);
22652solutions.AddSolution(vinfos,vfree);
22653}
22654}
22655}
22656
22657}
22658
22659}
22660
22661} else
22662{
22663{
22664IkReal j5array[1], cj5array[1], sj5array[1];
22665bool j5valid[1]={false};
22666_nj5 = 1;
22667CheckValue<IkReal> x2479=IKPowWithIntegerCheck(sj4,-1);
22668if(!x2479.valid){
22669continue;
22670}
22671IkReal x2477=x2479.value;
22672IkReal x2478=(new_r02*x2477);
22673CheckValue<IkReal> x2480=IKPowWithIntegerCheck(new_r01,-1);
22674if(!x2480.valid){
22675continue;
22676}
22677if( IKabs(((0.9999999992)*new_r11*x2478*(x2480.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.9999999992)*x2478)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.9999999992)*new_r11*x2478*(x2480.value)))+IKsqr(((-0.9999999992)*x2478))-1) <= IKFAST_SINCOS_THRESH )
22678 continue;
22679j5array[0]=IKatan2(((0.9999999992)*new_r11*x2478*(x2480.value)), ((-0.9999999992)*x2478));
22680sj5array[0]=IKsin(j5array[0]);
22681cj5array[0]=IKcos(j5array[0]);
22682if( j5array[0] > IKPI )
22683{
22684 j5array[0]-=IK2PI;
22685}
22686else if( j5array[0] < -IKPI )
22687{ j5array[0]+=IK2PI;
22688}
22689j5valid[0] = true;
22690for(int ij5 = 0; ij5 < 1; ++ij5)
22691{
22692if( !j5valid[ij5] )
22693{
22694 continue;
22695}
22696_ij5[0] = ij5; _ij5[1] = -1;
22697for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22698{
22699if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22700{
22701 j5valid[iij5]=false; _ij5[1] = iij5; break;
22702}
22703}
22704j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22705{
22706IkReal evalcond[10];
22707IkReal x2481=IKcos(j5);
22708IkReal x2482=IKsin(j5);
22709IkReal x2483=((0.9999999992)*cj4);
22710IkReal x2484=((3.9999999968e-5)*sj4);
22711IkReal x2485=((1.0000000008)*sj4);
22712IkReal x2486=(new_r12*x2482);
22713IkReal x2487=(new_r02*x2481);
22714IkReal x2488=(new_r11*x2482);
22715IkReal x2489=(new_r01*x2481);
22716evalcond[0]=(((new_r02*x2482))+((new_r12*x2481)));
22717evalcond[1]=(((new_r01*x2482))+((new_r11*x2481)));
22718evalcond[2]=(((x2481*x2485))+new_r02);
22719evalcond[3]=((((-1.0)*x2482*x2485))+new_r12);
22720evalcond[4]=(x2489+(((-1.0)*x2488)));
22721evalcond[5]=(x2487+x2485+(((-1.0)*x2486)));
22722evalcond[6]=(((x2485*x2488))+(((-1.0)*x2485*x2489)));
22723evalcond[7]=((-1.0)+((x2485*x2486))+(((-1.0)*x2485*x2487)));
22724evalcond[8]=(((x2483*x2487))+((x2484*x2487))+(((-1.0)*x2484*x2486))+(((-1.0)*x2483*x2486)));
22725evalcond[9]=(((x2483*x2489))+((x2484*x2489))+(((-1.0)*x2484*x2488))+(((-1.0)*x2483*x2488)));
22726if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
22727{
22728continue;
22729}
22730}
22731
22732{
22733std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22734vinfos[0].jointtype = 1;
22735vinfos[0].foffset = j0;
22736vinfos[0].indices[0] = _ij0[0];
22737vinfos[0].indices[1] = _ij0[1];
22738vinfos[0].maxsolutions = _nj0;
22739vinfos[1].jointtype = 1;
22740vinfos[1].foffset = j1;
22741vinfos[1].indices[0] = _ij1[0];
22742vinfos[1].indices[1] = _ij1[1];
22743vinfos[1].maxsolutions = _nj1;
22744vinfos[2].jointtype = 1;
22745vinfos[2].foffset = j2;
22746vinfos[2].indices[0] = _ij2[0];
22747vinfos[2].indices[1] = _ij2[1];
22748vinfos[2].maxsolutions = _nj2;
22749vinfos[3].jointtype = 1;
22750vinfos[3].foffset = j3;
22751vinfos[3].indices[0] = _ij3[0];
22752vinfos[3].indices[1] = _ij3[1];
22753vinfos[3].maxsolutions = _nj3;
22754vinfos[4].jointtype = 1;
22755vinfos[4].foffset = j4;
22756vinfos[4].indices[0] = _ij4[0];
22757vinfos[4].indices[1] = _ij4[1];
22758vinfos[4].maxsolutions = _nj4;
22759vinfos[5].jointtype = 1;
22760vinfos[5].foffset = j5;
22761vinfos[5].indices[0] = _ij5[0];
22762vinfos[5].indices[1] = _ij5[1];
22763vinfos[5].maxsolutions = _nj5;
22764std::vector<int> vfree(0);
22765solutions.AddSolution(vinfos,vfree);
22766}
22767}
22768}
22769
22770}
22771
22772}
22773
22774} else
22775{
22776{
22777IkReal j5array[1], cj5array[1], sj5array[1];
22778bool j5valid[1]={false};
22779_nj5 = 1;
22780CheckValue<IkReal> x2490 = IKatan2WithCheck(IkReal(((625000000.5)*new_r12)),IkReal(((-625000000.5)*new_r02)),IKFAST_ATAN2_MAGTHRESH);
22781if(!x2490.valid){
22782continue;
22783}
22784CheckValue<IkReal> x2491=IKPowWithIntegerCheck(IKsign(sj4),-1);
22785if(!x2491.valid){
22786continue;
22787}
22788j5array[0]=((-1.5707963267949)+(x2490.value)+(((1.5707963267949)*(x2491.value))));
22789sj5array[0]=IKsin(j5array[0]);
22790cj5array[0]=IKcos(j5array[0]);
22791if( j5array[0] > IKPI )
22792{
22793 j5array[0]-=IK2PI;
22794}
22795else if( j5array[0] < -IKPI )
22796{ j5array[0]+=IK2PI;
22797}
22798j5valid[0] = true;
22799for(int ij5 = 0; ij5 < 1; ++ij5)
22800{
22801if( !j5valid[ij5] )
22802{
22803 continue;
22804}
22805_ij5[0] = ij5; _ij5[1] = -1;
22806for(int iij5 = ij5+1; iij5 < 1; ++iij5)
22807{
22808if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22809{
22810 j5valid[iij5]=false; _ij5[1] = iij5; break;
22811}
22812}
22813j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22814{
22815IkReal evalcond[10];
22816IkReal x2492=IKcos(j5);
22817IkReal x2493=IKsin(j5);
22818IkReal x2494=((0.9999999992)*cj4);
22819IkReal x2495=((3.9999999968e-5)*sj4);
22820IkReal x2496=((1.0000000008)*sj4);
22821IkReal x2497=(new_r12*x2493);
22822IkReal x2498=(new_r02*x2492);
22823IkReal x2499=(new_r11*x2493);
22824IkReal x2500=(new_r01*x2492);
22825evalcond[0]=(((new_r02*x2493))+((new_r12*x2492)));
22826evalcond[1]=(((new_r01*x2493))+((new_r11*x2492)));
22827evalcond[2]=(((x2492*x2496))+new_r02);
22828evalcond[3]=((((-1.0)*x2493*x2496))+new_r12);
22829evalcond[4]=(x2500+(((-1.0)*x2499)));
22830evalcond[5]=(x2498+x2496+(((-1.0)*x2497)));
22831evalcond[6]=(((x2496*x2499))+(((-1.0)*x2496*x2500)));
22832evalcond[7]=((-1.0)+(((-1.0)*x2496*x2498))+((x2496*x2497)));
22833evalcond[8]=((((-1.0)*x2495*x2497))+((x2494*x2498))+(((-1.0)*x2494*x2497))+((x2495*x2498)));
22834evalcond[9]=((((-1.0)*x2495*x2499))+((x2494*x2500))+(((-1.0)*x2494*x2499))+((x2495*x2500)));
22835if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH )
22836{
22837continue;
22838}
22839}
22840
22841{
22842std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22843vinfos[0].jointtype = 1;
22844vinfos[0].foffset = j0;
22845vinfos[0].indices[0] = _ij0[0];
22846vinfos[0].indices[1] = _ij0[1];
22847vinfos[0].maxsolutions = _nj0;
22848vinfos[1].jointtype = 1;
22849vinfos[1].foffset = j1;
22850vinfos[1].indices[0] = _ij1[0];
22851vinfos[1].indices[1] = _ij1[1];
22852vinfos[1].maxsolutions = _nj1;
22853vinfos[2].jointtype = 1;
22854vinfos[2].foffset = j2;
22855vinfos[2].indices[0] = _ij2[0];
22856vinfos[2].indices[1] = _ij2[1];
22857vinfos[2].maxsolutions = _nj2;
22858vinfos[3].jointtype = 1;
22859vinfos[3].foffset = j3;
22860vinfos[3].indices[0] = _ij3[0];
22861vinfos[3].indices[1] = _ij3[1];
22862vinfos[3].maxsolutions = _nj3;
22863vinfos[4].jointtype = 1;
22864vinfos[4].foffset = j4;
22865vinfos[4].indices[0] = _ij4[0];
22866vinfos[4].indices[1] = _ij4[1];
22867vinfos[4].maxsolutions = _nj4;
22868vinfos[5].jointtype = 1;
22869vinfos[5].foffset = j5;
22870vinfos[5].indices[0] = _ij5[0];
22871vinfos[5].indices[1] = _ij5[1];
22872vinfos[5].maxsolutions = _nj5;
22873std::vector<int> vfree(0);
22874solutions.AddSolution(vinfos,vfree);
22875}
22876}
22877}
22878
22879}
22880
22881}
22882
22883}
22884} while(0);
22885if( bgotonextstatement )
22886{
22887bool bgotonextstatement = true;
22888do
22889{
22890evalcond[0]=((IKabs(new_r00))+(IKabs(new_r02)));
22891if( IKabs(evalcond[0]) < 0.0000050000000000 )
22892{
22893bgotonextstatement=false;
22894{
22895IkReal j5eval[1];
22896new_r00=0;
22897new_r02=0;
22898new_r11=0;
22899new_r21=0;
22900j5eval[0]=cj3;
22901if( IKabs(j5eval[0]) < 0.0000010000000000 )
22902{
22903{
22904IkReal j5eval[1];
22905new_r00=0;
22906new_r02=0;
22907new_r11=0;
22908new_r21=0;
22909j5eval[0]=new_r01;
22910if( IKabs(j5eval[0]) < 0.0000010000000000 )
22911{
22912{
22913IkReal j5eval[1];
22914new_r00=0;
22915new_r02=0;
22916new_r11=0;
22917new_r21=0;
22918j5eval[0]=((((25000.0)*cj3*cj4))+((cj3*sj4)));
22919if( IKabs(j5eval[0]) < 0.0000010000000000 )
22920{
22921{
22922IkReal evalcond[5];
22923bool bgotonextstatement = true;
22924do
22925{
22926evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959)));
22927evalcond[1]=new_r12;
22928evalcond[2]=new_r20;
22929evalcond[3]=new_r10;
22930evalcond[4]=new_r01;
22931if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
22932{
22933bgotonextstatement=false;
22934{
22935IkReal j5eval[1];
22936new_r00=0;
22937new_r02=0;
22938new_r11=0;
22939new_r21=0;
22940sj3=1.0;
22941cj3=0;
22942j3=1.5707963267949;
22943j5eval[0]=IKabs(((((-25000.0)*sj4))+cj4));
22944if( IKabs(j5eval[0]) < 0.0000000100000000 )
22945{
22946continue; // no branches [j5]
22947
22948} else
22949{
22950IkReal op[2+1], zeror[2];
22951int numroots;
22952IkReal x2501=((25000.0)*sj4);
22953op[0]=((((-1.0)*x2501))+cj4);
22954op[1]=0;
22955op[2]=(x2501+(((-1.0)*cj4)));
22956polyroots2(op,zeror,numroots);
22957IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
22958int numsolutions = 0;
22959for(int ij5 = 0; ij5 < numroots; ++ij5)
22960{
22961IkReal htj5 = zeror[ij5];
22962tempj5array[0]=((2.0)*(atan(htj5)));
22963for(int kj5 = 0; kj5 < 1; ++kj5)
22964{
22965j5array[numsolutions] = tempj5array[kj5];
22966if( j5array[numsolutions] > IKPI )
22967{
22968 j5array[numsolutions]-=IK2PI;
22969}
22970else if( j5array[numsolutions] < -IKPI )
22971{
22972 j5array[numsolutions]+=IK2PI;
22973}
22974sj5array[numsolutions] = IKsin(j5array[numsolutions]);
22975cj5array[numsolutions] = IKcos(j5array[numsolutions]);
22976numsolutions++;
22977}
22978}
22979bool j5valid[2]={true,true};
22980_nj5 = 2;
22981for(int ij5 = 0; ij5 < numsolutions; ++ij5)
22982 {
22983if( !j5valid[ij5] )
22984{
22985 continue;
22986}
22987 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
22988htj5 = IKtan(j5/2);
22989
22990_ij5[0] = ij5; _ij5[1] = -1;
22991for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
22992{
22993if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
22994{
22995 j5valid[iij5]=false; _ij5[1] = iij5; break;
22996}
22997}
22998{
22999std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23000vinfos[0].jointtype = 1;
23001vinfos[0].foffset = j0;
23002vinfos[0].indices[0] = _ij0[0];
23003vinfos[0].indices[1] = _ij0[1];
23004vinfos[0].maxsolutions = _nj0;
23005vinfos[1].jointtype = 1;
23006vinfos[1].foffset = j1;
23007vinfos[1].indices[0] = _ij1[0];
23008vinfos[1].indices[1] = _ij1[1];
23009vinfos[1].maxsolutions = _nj1;
23010vinfos[2].jointtype = 1;
23011vinfos[2].foffset = j2;
23012vinfos[2].indices[0] = _ij2[0];
23013vinfos[2].indices[1] = _ij2[1];
23014vinfos[2].maxsolutions = _nj2;
23015vinfos[3].jointtype = 1;
23016vinfos[3].foffset = j3;
23017vinfos[3].indices[0] = _ij3[0];
23018vinfos[3].indices[1] = _ij3[1];
23019vinfos[3].maxsolutions = _nj3;
23020vinfos[4].jointtype = 1;
23021vinfos[4].foffset = j4;
23022vinfos[4].indices[0] = _ij4[0];
23023vinfos[4].indices[1] = _ij4[1];
23024vinfos[4].maxsolutions = _nj4;
23025vinfos[5].jointtype = 1;
23026vinfos[5].foffset = j5;
23027vinfos[5].indices[0] = _ij5[0];
23028vinfos[5].indices[1] = _ij5[1];
23029vinfos[5].maxsolutions = _nj5;
23030std::vector<int> vfree(0);
23031solutions.AddSolution(vinfos,vfree);
23032}
23033 }
23034
23035}
23036
23037}
23038
23039}
23040} while(0);
23041if( bgotonextstatement )
23042{
23043bool bgotonextstatement = true;
23044do
23045{
23046evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959)));
23047evalcond[1]=new_r12;
23048evalcond[2]=new_r20;
23049evalcond[3]=new_r10;
23050evalcond[4]=new_r01;
23051if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
23052{
23053bgotonextstatement=false;
23054{
23055IkReal j5eval[1];
23056new_r00=0;
23057new_r02=0;
23058new_r11=0;
23059new_r21=0;
23060sj3=-1.0;
23061cj3=0;
23062j3=-1.5707963267949;
23063j5eval[0]=IKabs(((((-25000.0)*sj4))+cj4));
23064if( IKabs(j5eval[0]) < 0.0000000100000000 )
23065{
23066continue; // no branches [j5]
23067
23068} else
23069{
23070IkReal op[2+1], zeror[2];
23071int numroots;
23072IkReal x2502=((25000.0)*sj4);
23073op[0]=((((-1.0)*x2502))+cj4);
23074op[1]=0;
23075op[2]=(x2502+(((-1.0)*cj4)));
23076polyroots2(op,zeror,numroots);
23077IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
23078int numsolutions = 0;
23079for(int ij5 = 0; ij5 < numroots; ++ij5)
23080{
23081IkReal htj5 = zeror[ij5];
23082tempj5array[0]=((2.0)*(atan(htj5)));
23083for(int kj5 = 0; kj5 < 1; ++kj5)
23084{
23085j5array[numsolutions] = tempj5array[kj5];
23086if( j5array[numsolutions] > IKPI )
23087{
23088 j5array[numsolutions]-=IK2PI;
23089}
23090else if( j5array[numsolutions] < -IKPI )
23091{
23092 j5array[numsolutions]+=IK2PI;
23093}
23094sj5array[numsolutions] = IKsin(j5array[numsolutions]);
23095cj5array[numsolutions] = IKcos(j5array[numsolutions]);
23096numsolutions++;
23097}
23098}
23099bool j5valid[2]={true,true};
23100_nj5 = 2;
23101for(int ij5 = 0; ij5 < numsolutions; ++ij5)
23102 {
23103if( !j5valid[ij5] )
23104{
23105 continue;
23106}
23107 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23108htj5 = IKtan(j5/2);
23109
23110_ij5[0] = ij5; _ij5[1] = -1;
23111for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
23112{
23113if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23114{
23115 j5valid[iij5]=false; _ij5[1] = iij5; break;
23116}
23117}
23118{
23119std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23120vinfos[0].jointtype = 1;
23121vinfos[0].foffset = j0;
23122vinfos[0].indices[0] = _ij0[0];
23123vinfos[0].indices[1] = _ij0[1];
23124vinfos[0].maxsolutions = _nj0;
23125vinfos[1].jointtype = 1;
23126vinfos[1].foffset = j1;
23127vinfos[1].indices[0] = _ij1[0];
23128vinfos[1].indices[1] = _ij1[1];
23129vinfos[1].maxsolutions = _nj1;
23130vinfos[2].jointtype = 1;
23131vinfos[2].foffset = j2;
23132vinfos[2].indices[0] = _ij2[0];
23133vinfos[2].indices[1] = _ij2[1];
23134vinfos[2].maxsolutions = _nj2;
23135vinfos[3].jointtype = 1;
23136vinfos[3].foffset = j3;
23137vinfos[3].indices[0] = _ij3[0];
23138vinfos[3].indices[1] = _ij3[1];
23139vinfos[3].maxsolutions = _nj3;
23140vinfos[4].jointtype = 1;
23141vinfos[4].foffset = j4;
23142vinfos[4].indices[0] = _ij4[0];
23143vinfos[4].indices[1] = _ij4[1];
23144vinfos[4].maxsolutions = _nj4;
23145vinfos[5].jointtype = 1;
23146vinfos[5].foffset = j5;
23147vinfos[5].indices[0] = _ij5[0];
23148vinfos[5].indices[1] = _ij5[1];
23149vinfos[5].maxsolutions = _nj5;
23150std::vector<int> vfree(0);
23151solutions.AddSolution(vinfos,vfree);
23152}
23153 }
23154
23155}
23156
23157}
23158
23159}
23160} while(0);
23161if( bgotonextstatement )
23162{
23163bool bgotonextstatement = true;
23164do
23165{
23166if( 1 )
23167{
23168bgotonextstatement=false;
23169continue; // branch miss [j5]
23170
23171}
23172} while(0);
23173if( bgotonextstatement )
23174{
23175}
23176}
23177}
23178}
23179
23180} else
23181{
23182{
23183IkReal j5array[2], cj5array[2], sj5array[2];
23184bool j5valid[2]={false};
23185_nj5 = 2;
23186CheckValue<IkReal> x2503=IKPowWithIntegerCheck(((((0.9999999992)*cj3*cj4))+(((3.9999999968e-5)*cj3*sj4))),-1);
23187if(!x2503.valid){
23188continue;
23189}
23190sj5array[0]=((-1.0)*new_r10*(x2503.value));
23191if( sj5array[0] >= -1-IKFAST_SINCOS_THRESH && sj5array[0] <= 1+IKFAST_SINCOS_THRESH )
23192{
23193 j5valid[0] = j5valid[1] = true;
23194 j5array[0] = IKasin(sj5array[0]);
23195 cj5array[0] = IKcos(j5array[0]);
23196 sj5array[1] = sj5array[0];
23197 j5array[1] = j5array[0] > 0 ? (IKPI-j5array[0]) : (-IKPI-j5array[0]);
23198 cj5array[1] = -cj5array[0];
23199}
23200else if( isnan(sj5array[0]) )
23201{
23202 // probably any value will work
23203 j5valid[0] = true;
23204 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
23205}
23206for(int ij5 = 0; ij5 < 2; ++ij5)
23207{
23208if( !j5valid[ij5] )
23209{
23210 continue;
23211}
23212_ij5[0] = ij5; _ij5[1] = -1;
23213for(int iij5 = ij5+1; iij5 < 2; ++iij5)
23214{
23215if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23216{
23217 j5valid[iij5]=false; _ij5[1] = iij5; break;
23218}
23219}
23220j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23221{
23222IkReal evalcond[15];
23223IkReal x2504=IKcos(j5);
23224IkReal x2505=IKsin(j5);
23225IkReal x2506=((3.9999999968e-5)*cj4);
23226IkReal x2507=((1.0)*cj3);
23227IkReal x2508=(cj3*cj4);
23228IkReal x2509=((25000.00002)*sj4);
23229IkReal x2510=((0.9999999992)*sj4);
23230IkReal x2511=((3.9999999968e-5)*sj4);
23231IkReal x2512=(new_r01*x2504);
23232IkReal x2513=((0.9999999992)*x2504);
23233IkReal x2514=(new_r12*x2505);
23234IkReal x2515=(new_r10*x2505);
23235IkReal x2516=(cj3*x2504);
23236evalcond[0]=(new_r12*x2504);
23237evalcond[1]=(new_r10*x2504);
23238evalcond[2]=x2512;
23239evalcond[3]=((-1.0)*x2514);
23240evalcond[4]=((-1.0)*x2516);
23241evalcond[5]=(new_r01+(((-1.0)*x2505*x2507)));
23242evalcond[6]=(((new_r01*x2505))+(((-1.0)*x2507)));
23243evalcond[7]=(x2509*x2512);
23244evalcond[8]=((-25000.00002)*sj4*x2514);
23245evalcond[9]=(((x2504*x2510))+(((-1.0)*x2504*x2506)));
23246evalcond[10]=((((-1.0)*cj3*x2511))+(((-1.0)*x2515))+(((-0.9999999992)*x2508)));
23247evalcond[11]=((((-1.0)*x2508*x2513))+(((-1.0)*x2511*x2516)));
23248evalcond[12]=((((-1.0)*x2510*x2512))+((x2506*x2512)));
23249CheckValue<IkReal> x2517=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
23250if(!x2517.valid){
23251continue;
23252}
23253evalcond[13]=((((625000001.0)*new_r20*(x2517.value)))+(((-1.0)*x2509*x2515)));
23254evalcond[14]=((((0.9999999992)*cj4*new_r20))+(((-1.0)*x2506*x2515))+((x2510*x2515))+((new_r20*x2511)));
23255if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
23256{
23257continue;
23258}
23259}
23260
23261{
23262std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23263vinfos[0].jointtype = 1;
23264vinfos[0].foffset = j0;
23265vinfos[0].indices[0] = _ij0[0];
23266vinfos[0].indices[1] = _ij0[1];
23267vinfos[0].maxsolutions = _nj0;
23268vinfos[1].jointtype = 1;
23269vinfos[1].foffset = j1;
23270vinfos[1].indices[0] = _ij1[0];
23271vinfos[1].indices[1] = _ij1[1];
23272vinfos[1].maxsolutions = _nj1;
23273vinfos[2].jointtype = 1;
23274vinfos[2].foffset = j2;
23275vinfos[2].indices[0] = _ij2[0];
23276vinfos[2].indices[1] = _ij2[1];
23277vinfos[2].maxsolutions = _nj2;
23278vinfos[3].jointtype = 1;
23279vinfos[3].foffset = j3;
23280vinfos[3].indices[0] = _ij3[0];
23281vinfos[3].indices[1] = _ij3[1];
23282vinfos[3].maxsolutions = _nj3;
23283vinfos[4].jointtype = 1;
23284vinfos[4].foffset = j4;
23285vinfos[4].indices[0] = _ij4[0];
23286vinfos[4].indices[1] = _ij4[1];
23287vinfos[4].maxsolutions = _nj4;
23288vinfos[5].jointtype = 1;
23289vinfos[5].foffset = j5;
23290vinfos[5].indices[0] = _ij5[0];
23291vinfos[5].indices[1] = _ij5[1];
23292vinfos[5].maxsolutions = _nj5;
23293std::vector<int> vfree(0);
23294solutions.AddSolution(vinfos,vfree);
23295}
23296}
23297}
23298
23299}
23300
23301}
23302
23303} else
23304{
23305{
23306IkReal j5array[2], cj5array[2], sj5array[2];
23307bool j5valid[2]={false};
23308_nj5 = 2;
23309CheckValue<IkReal> x2518=IKPowWithIntegerCheck(new_r01,-1);
23310if(!x2518.valid){
23311continue;
23312}
23313sj5array[0]=(cj3*(x2518.value));
23314if( sj5array[0] >= -1-IKFAST_SINCOS_THRESH && sj5array[0] <= 1+IKFAST_SINCOS_THRESH )
23315{
23316 j5valid[0] = j5valid[1] = true;
23317 j5array[0] = IKasin(sj5array[0]);
23318 cj5array[0] = IKcos(j5array[0]);
23319 sj5array[1] = sj5array[0];
23320 j5array[1] = j5array[0] > 0 ? (IKPI-j5array[0]) : (-IKPI-j5array[0]);
23321 cj5array[1] = -cj5array[0];
23322}
23323else if( isnan(sj5array[0]) )
23324{
23325 // probably any value will work
23326 j5valid[0] = true;
23327 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
23328}
23329for(int ij5 = 0; ij5 < 2; ++ij5)
23330{
23331if( !j5valid[ij5] )
23332{
23333 continue;
23334}
23335_ij5[0] = ij5; _ij5[1] = -1;
23336for(int iij5 = ij5+1; iij5 < 2; ++iij5)
23337{
23338if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23339{
23340 j5valid[iij5]=false; _ij5[1] = iij5; break;
23341}
23342}
23343j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23344{
23345IkReal evalcond[15];
23346IkReal x2519=IKcos(j5);
23347IkReal x2520=IKsin(j5);
23348IkReal x2521=((3.9999999968e-5)*cj4);
23349IkReal x2522=(cj3*cj4);
23350IkReal x2523=((3.9999999968e-5)*cj3);
23351IkReal x2524=(new_r01*x2519);
23352IkReal x2525=((0.9999999992)*x2519);
23353IkReal x2526=(new_r12*x2520);
23354IkReal x2527=(sj4*x2520);
23355IkReal x2528=(new_r10*x2520);
23356evalcond[0]=(new_r12*x2519);
23357evalcond[1]=(new_r10*x2519);
23358evalcond[2]=x2524;
23359evalcond[3]=((-1.0)*x2526);
23360evalcond[4]=((-1.0)*cj3*x2519);
23361evalcond[5]=((((-1.0)*cj3*x2520))+new_r01);
23362evalcond[6]=((25000.00002)*sj4*x2524);
23363evalcond[7]=((-25000.00002)*sj4*x2526);
23364evalcond[8]=(((sj4*x2525))+(((-1.0)*x2519*x2521)));
23365evalcond[9]=((((-1.0)*sj4*x2523))+(((-1.0)*x2528))+(((-0.9999999992)*x2522)));
23366evalcond[10]=((((-1.0)*x2522*x2525))+(((-1.0)*sj4*x2519*x2523)));
23367evalcond[11]=((((-0.9999999992)*sj4*x2524))+((x2521*x2524)));
23368evalcond[12]=((((0.9999999992)*x2520*x2522))+new_r10+((x2523*x2527)));
23369CheckValue<IkReal> x2529=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
23370if(!x2529.valid){
23371continue;
23372}
23373evalcond[13]=((((625000001.0)*new_r20*(x2529.value)))+(((-25000.00002)*new_r10*x2527)));
23374evalcond[14]=((((0.9999999992)*cj4*new_r20))+(((0.9999999992)*new_r10*x2527))+(((3.9999999968e-5)*new_r20*sj4))+(((-1.0)*x2521*x2528)));
23375if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
23376{
23377continue;
23378}
23379}
23380
23381{
23382std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23383vinfos[0].jointtype = 1;
23384vinfos[0].foffset = j0;
23385vinfos[0].indices[0] = _ij0[0];
23386vinfos[0].indices[1] = _ij0[1];
23387vinfos[0].maxsolutions = _nj0;
23388vinfos[1].jointtype = 1;
23389vinfos[1].foffset = j1;
23390vinfos[1].indices[0] = _ij1[0];
23391vinfos[1].indices[1] = _ij1[1];
23392vinfos[1].maxsolutions = _nj1;
23393vinfos[2].jointtype = 1;
23394vinfos[2].foffset = j2;
23395vinfos[2].indices[0] = _ij2[0];
23396vinfos[2].indices[1] = _ij2[1];
23397vinfos[2].maxsolutions = _nj2;
23398vinfos[3].jointtype = 1;
23399vinfos[3].foffset = j3;
23400vinfos[3].indices[0] = _ij3[0];
23401vinfos[3].indices[1] = _ij3[1];
23402vinfos[3].maxsolutions = _nj3;
23403vinfos[4].jointtype = 1;
23404vinfos[4].foffset = j4;
23405vinfos[4].indices[0] = _ij4[0];
23406vinfos[4].indices[1] = _ij4[1];
23407vinfos[4].maxsolutions = _nj4;
23408vinfos[5].jointtype = 1;
23409vinfos[5].foffset = j5;
23410vinfos[5].indices[0] = _ij5[0];
23411vinfos[5].indices[1] = _ij5[1];
23412vinfos[5].maxsolutions = _nj5;
23413std::vector<int> vfree(0);
23414solutions.AddSolution(vinfos,vfree);
23415}
23416}
23417}
23418
23419}
23420
23421}
23422
23423} else
23424{
23425{
23426IkReal j5array[2], cj5array[2], sj5array[2];
23427bool j5valid[2]={false};
23428_nj5 = 2;
23429CheckValue<IkReal> x2530=IKPowWithIntegerCheck(cj3,-1);
23430if(!x2530.valid){
23431continue;
23432}
23433sj5array[0]=(new_r01*(x2530.value));
23434if( sj5array[0] >= -1-IKFAST_SINCOS_THRESH && sj5array[0] <= 1+IKFAST_SINCOS_THRESH )
23435{
23436 j5valid[0] = j5valid[1] = true;
23437 j5array[0] = IKasin(sj5array[0]);
23438 cj5array[0] = IKcos(j5array[0]);
23439 sj5array[1] = sj5array[0];
23440 j5array[1] = j5array[0] > 0 ? (IKPI-j5array[0]) : (-IKPI-j5array[0]);
23441 cj5array[1] = -cj5array[0];
23442}
23443else if( isnan(sj5array[0]) )
23444{
23445 // probably any value will work
23446 j5valid[0] = true;
23447 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
23448}
23449for(int ij5 = 0; ij5 < 2; ++ij5)
23450{
23451if( !j5valid[ij5] )
23452{
23453 continue;
23454}
23455_ij5[0] = ij5; _ij5[1] = -1;
23456for(int iij5 = ij5+1; iij5 < 2; ++iij5)
23457{
23458if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23459{
23460 j5valid[iij5]=false; _ij5[1] = iij5; break;
23461}
23462}
23463j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23464{
23465IkReal evalcond[15];
23466IkReal x2531=IKcos(j5);
23467IkReal x2532=IKsin(j5);
23468IkReal x2533=((3.9999999968e-5)*cj4);
23469IkReal x2534=(cj3*cj4);
23470IkReal x2535=((3.9999999968e-5)*cj3);
23471IkReal x2536=(new_r01*x2531);
23472IkReal x2537=((0.9999999992)*x2531);
23473IkReal x2538=(new_r12*x2532);
23474IkReal x2539=(sj4*x2532);
23475IkReal x2540=(new_r10*x2532);
23476evalcond[0]=(new_r12*x2531);
23477evalcond[1]=(new_r10*x2531);
23478evalcond[2]=x2536;
23479evalcond[3]=((-1.0)*x2538);
23480evalcond[4]=((-1.0)*cj3*x2531);
23481evalcond[5]=(((new_r01*x2532))+(((-1.0)*cj3)));
23482evalcond[6]=((25000.00002)*sj4*x2536);
23483evalcond[7]=((-25000.00002)*sj4*x2538);
23484evalcond[8]=(((sj4*x2537))+(((-1.0)*x2531*x2533)));
23485evalcond[9]=((((-1.0)*x2540))+(((-1.0)*sj4*x2535))+(((-0.9999999992)*x2534)));
23486evalcond[10]=((((-1.0)*x2534*x2537))+(((-1.0)*sj4*x2531*x2535)));
23487evalcond[11]=((((-0.9999999992)*sj4*x2536))+((x2533*x2536)));
23488evalcond[12]=((((0.9999999992)*x2532*x2534))+new_r10+((x2535*x2539)));
23489CheckValue<IkReal> x2541=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
23490if(!x2541.valid){
23491continue;
23492}
23493evalcond[13]=((((-25000.00002)*new_r10*x2539))+(((625000001.0)*new_r20*(x2541.value))));
23494evalcond[14]=((((0.9999999992)*cj4*new_r20))+(((0.9999999992)*new_r10*x2539))+(((-1.0)*x2533*x2540))+(((3.9999999968e-5)*new_r20*sj4)));
23495if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
23496{
23497continue;
23498}
23499}
23500
23501{
23502std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23503vinfos[0].jointtype = 1;
23504vinfos[0].foffset = j0;
23505vinfos[0].indices[0] = _ij0[0];
23506vinfos[0].indices[1] = _ij0[1];
23507vinfos[0].maxsolutions = _nj0;
23508vinfos[1].jointtype = 1;
23509vinfos[1].foffset = j1;
23510vinfos[1].indices[0] = _ij1[0];
23511vinfos[1].indices[1] = _ij1[1];
23512vinfos[1].maxsolutions = _nj1;
23513vinfos[2].jointtype = 1;
23514vinfos[2].foffset = j2;
23515vinfos[2].indices[0] = _ij2[0];
23516vinfos[2].indices[1] = _ij2[1];
23517vinfos[2].maxsolutions = _nj2;
23518vinfos[3].jointtype = 1;
23519vinfos[3].foffset = j3;
23520vinfos[3].indices[0] = _ij3[0];
23521vinfos[3].indices[1] = _ij3[1];
23522vinfos[3].maxsolutions = _nj3;
23523vinfos[4].jointtype = 1;
23524vinfos[4].foffset = j4;
23525vinfos[4].indices[0] = _ij4[0];
23526vinfos[4].indices[1] = _ij4[1];
23527vinfos[4].maxsolutions = _nj4;
23528vinfos[5].jointtype = 1;
23529vinfos[5].foffset = j5;
23530vinfos[5].indices[0] = _ij5[0];
23531vinfos[5].indices[1] = _ij5[1];
23532vinfos[5].maxsolutions = _nj5;
23533std::vector<int> vfree(0);
23534solutions.AddSolution(vinfos,vfree);
23535}
23536}
23537}
23538
23539}
23540
23541}
23542
23543}
23544} while(0);
23545if( bgotonextstatement )
23546{
23547bool bgotonextstatement = true;
23548do
23549{
23550evalcond[0]=((IKabs(new_r12))+(IKabs(new_r10)));
23551if( IKabs(evalcond[0]) < 0.0000050000000000 )
23552{
23553bgotonextstatement=false;
23554{
23555IkReal j5eval[1];
23556new_r10=0;
23557new_r12=0;
23558new_r21=0;
23559new_r01=0;
23560j5eval[0]=cj3;
23561if( IKabs(j5eval[0]) < 0.0000010000000000 )
23562{
23563{
23564IkReal j5eval[1];
23565new_r10=0;
23566new_r12=0;
23567new_r21=0;
23568new_r01=0;
23569j5eval[0]=new_r11;
23570if( IKabs(j5eval[0]) < 0.0000010000000000 )
23571{
23572{
23573IkReal j5eval[1];
23574new_r10=0;
23575new_r12=0;
23576new_r21=0;
23577new_r01=0;
23578j5eval[0]=((((-25000.0)*cj3*cj4))+(((-1.0)*cj3*sj4)));
23579if( IKabs(j5eval[0]) < 0.0000010000000000 )
23580{
23581{
23582IkReal evalcond[5];
23583bool bgotonextstatement = true;
23584do
23585{
23586evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j3)))), 6.28318530717959)));
23587evalcond[1]=new_r02;
23588evalcond[2]=new_r20;
23589evalcond[3]=new_r00;
23590evalcond[4]=new_r11;
23591if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
23592{
23593bgotonextstatement=false;
23594{
23595IkReal j5array[1], cj5array[1], sj5array[1];
23596bool j5valid[1]={false};
23597_nj5 = 1;
23598j5array[0]=0;
23599sj5array[0]=IKsin(j5array[0]);
23600cj5array[0]=IKcos(j5array[0]);
23601if( j5array[0] > IKPI )
23602{
23603 j5array[0]-=IK2PI;
23604}
23605else if( j5array[0] < -IKPI )
23606{ j5array[0]+=IK2PI;
23607}
23608j5valid[0] = true;
23609for(int ij5 = 0; ij5 < 1; ++ij5)
23610{
23611if( !j5valid[ij5] )
23612{
23613 continue;
23614}
23615_ij5[0] = ij5; _ij5[1] = -1;
23616for(int iij5 = ij5+1; iij5 < 1; ++iij5)
23617{
23618if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23619{
23620 j5valid[iij5]=false; _ij5[1] = iij5; break;
23621}
23622}
23623j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23624
23625{
23626std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23627vinfos[0].jointtype = 1;
23628vinfos[0].foffset = j0;
23629vinfos[0].indices[0] = _ij0[0];
23630vinfos[0].indices[1] = _ij0[1];
23631vinfos[0].maxsolutions = _nj0;
23632vinfos[1].jointtype = 1;
23633vinfos[1].foffset = j1;
23634vinfos[1].indices[0] = _ij1[0];
23635vinfos[1].indices[1] = _ij1[1];
23636vinfos[1].maxsolutions = _nj1;
23637vinfos[2].jointtype = 1;
23638vinfos[2].foffset = j2;
23639vinfos[2].indices[0] = _ij2[0];
23640vinfos[2].indices[1] = _ij2[1];
23641vinfos[2].maxsolutions = _nj2;
23642vinfos[3].jointtype = 1;
23643vinfos[3].foffset = j3;
23644vinfos[3].indices[0] = _ij3[0];
23645vinfos[3].indices[1] = _ij3[1];
23646vinfos[3].maxsolutions = _nj3;
23647vinfos[4].jointtype = 1;
23648vinfos[4].foffset = j4;
23649vinfos[4].indices[0] = _ij4[0];
23650vinfos[4].indices[1] = _ij4[1];
23651vinfos[4].maxsolutions = _nj4;
23652vinfos[5].jointtype = 1;
23653vinfos[5].foffset = j5;
23654vinfos[5].indices[0] = _ij5[0];
23655vinfos[5].indices[1] = _ij5[1];
23656vinfos[5].maxsolutions = _nj5;
23657std::vector<int> vfree(0);
23658solutions.AddSolution(vinfos,vfree);
23659}
23660}
23661}
23662
23663}
23664} while(0);
23665if( bgotonextstatement )
23666{
23667bool bgotonextstatement = true;
23668do
23669{
23670evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j3)))), 6.28318530717959)));
23671evalcond[1]=new_r02;
23672evalcond[2]=new_r20;
23673evalcond[3]=new_r00;
23674evalcond[4]=new_r11;
23675if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
23676{
23677bgotonextstatement=false;
23678{
23679IkReal j5array[1], cj5array[1], sj5array[1];
23680bool j5valid[1]={false};
23681_nj5 = 1;
23682j5array[0]=0;
23683sj5array[0]=IKsin(j5array[0]);
23684cj5array[0]=IKcos(j5array[0]);
23685if( j5array[0] > IKPI )
23686{
23687 j5array[0]-=IK2PI;
23688}
23689else if( j5array[0] < -IKPI )
23690{ j5array[0]+=IK2PI;
23691}
23692j5valid[0] = true;
23693for(int ij5 = 0; ij5 < 1; ++ij5)
23694{
23695if( !j5valid[ij5] )
23696{
23697 continue;
23698}
23699_ij5[0] = ij5; _ij5[1] = -1;
23700for(int iij5 = ij5+1; iij5 < 1; ++iij5)
23701{
23702if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23703{
23704 j5valid[iij5]=false; _ij5[1] = iij5; break;
23705}
23706}
23707j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23708
23709{
23710std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23711vinfos[0].jointtype = 1;
23712vinfos[0].foffset = j0;
23713vinfos[0].indices[0] = _ij0[0];
23714vinfos[0].indices[1] = _ij0[1];
23715vinfos[0].maxsolutions = _nj0;
23716vinfos[1].jointtype = 1;
23717vinfos[1].foffset = j1;
23718vinfos[1].indices[0] = _ij1[0];
23719vinfos[1].indices[1] = _ij1[1];
23720vinfos[1].maxsolutions = _nj1;
23721vinfos[2].jointtype = 1;
23722vinfos[2].foffset = j2;
23723vinfos[2].indices[0] = _ij2[0];
23724vinfos[2].indices[1] = _ij2[1];
23725vinfos[2].maxsolutions = _nj2;
23726vinfos[3].jointtype = 1;
23727vinfos[3].foffset = j3;
23728vinfos[3].indices[0] = _ij3[0];
23729vinfos[3].indices[1] = _ij3[1];
23730vinfos[3].maxsolutions = _nj3;
23731vinfos[4].jointtype = 1;
23732vinfos[4].foffset = j4;
23733vinfos[4].indices[0] = _ij4[0];
23734vinfos[4].indices[1] = _ij4[1];
23735vinfos[4].maxsolutions = _nj4;
23736vinfos[5].jointtype = 1;
23737vinfos[5].foffset = j5;
23738vinfos[5].indices[0] = _ij5[0];
23739vinfos[5].indices[1] = _ij5[1];
23740vinfos[5].maxsolutions = _nj5;
23741std::vector<int> vfree(0);
23742solutions.AddSolution(vinfos,vfree);
23743}
23744}
23745}
23746
23747}
23748} while(0);
23749if( bgotonextstatement )
23750{
23751bool bgotonextstatement = true;
23752do
23753{
23754if( 1 )
23755{
23756bgotonextstatement=false;
23757continue; // branch miss [j5]
23758
23759}
23760} while(0);
23761if( bgotonextstatement )
23762{
23763}
23764}
23765}
23766}
23767
23768} else
23769{
23770{
23771IkReal j5array[2], cj5array[2], sj5array[2];
23772bool j5valid[2]={false};
23773_nj5 = 2;
23774CheckValue<IkReal> x2542=IKPowWithIntegerCheck(((((-0.9999999992)*cj3*cj4))+(((-3.9999999968e-5)*cj3*sj4))),-1);
23775if(!x2542.valid){
23776continue;
23777}
23778cj5array[0]=((-1.0)*new_r00*(x2542.value));
23779if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
23780{
23781 j5valid[0] = j5valid[1] = true;
23782 j5array[0] = IKacos(cj5array[0]);
23783 sj5array[0] = IKsin(j5array[0]);
23784 cj5array[1] = cj5array[0];
23785 j5array[1] = -j5array[0];
23786 sj5array[1] = -sj5array[0];
23787}
23788else if( isnan(cj5array[0]) )
23789{
23790 // probably any value will work
23791 j5valid[0] = true;
23792 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
23793}
23794for(int ij5 = 0; ij5 < 2; ++ij5)
23795{
23796if( !j5valid[ij5] )
23797{
23798 continue;
23799}
23800_ij5[0] = ij5; _ij5[1] = -1;
23801for(int iij5 = ij5+1; iij5 < 2; ++iij5)
23802{
23803if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23804{
23805 j5valid[iij5]=false; _ij5[1] = iij5; break;
23806}
23807}
23808j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23809{
23810IkReal evalcond[15];
23811IkReal x2543=IKsin(j5);
23812IkReal x2544=IKcos(j5);
23813IkReal x2545=((3.9999999968e-5)*sj4);
23814IkReal x2546=((1.0)*cj3);
23815IkReal x2547=((0.9999999992)*cj4);
23816IkReal x2548=((25000.00002)*sj4);
23817IkReal x2549=((0.9999999992)*sj4);
23818IkReal x2550=(cj3*x2543);
23819IkReal x2551=(new_r00*x2544);
23820IkReal x2552=(new_r02*x2544);
23821IkReal x2553=((3.9999999968e-5)*cj4*x2543);
23822IkReal x2554=(new_r11*sj4*x2543);
23823evalcond[0]=(new_r02*x2543);
23824evalcond[1]=(new_r00*x2543);
23825evalcond[2]=x2552;
23826evalcond[3]=((-1.0)*new_r11*x2543);
23827evalcond[4]=((-1.0)*x2550);
23828evalcond[5]=((((-1.0)*x2544*x2546))+new_r11);
23829evalcond[6]=((((-1.0)*x2546))+((new_r11*x2544)));
23830evalcond[7]=(x2548*x2552);
23831evalcond[8]=((-25000.00002)*x2554);
23832evalcond[9]=(x2553+(((-1.0)*x2543*x2549)));
23833evalcond[10]=(x2551+(((-1.0)*cj3*x2547))+(((-1.0)*cj3*x2545)));
23834evalcond[11]=(((x2547*x2550))+((x2545*x2550)));
23835evalcond[12]=((((-1.0)*new_r11*x2553))+((new_r11*x2543*x2549)));
23836CheckValue<IkReal> x2555=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
23837if(!x2555.valid){
23838continue;
23839}
23840evalcond[13]=((((625000001.0)*new_r20*(x2555.value)))+((x2548*x2551)));
23841evalcond[14]=((((-1.0)*x2549*x2551))+((new_r20*x2547))+((new_r20*x2545))+(((3.9999999968e-5)*cj4*x2551)));
23842if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
23843{
23844continue;
23845}
23846}
23847
23848{
23849std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23850vinfos[0].jointtype = 1;
23851vinfos[0].foffset = j0;
23852vinfos[0].indices[0] = _ij0[0];
23853vinfos[0].indices[1] = _ij0[1];
23854vinfos[0].maxsolutions = _nj0;
23855vinfos[1].jointtype = 1;
23856vinfos[1].foffset = j1;
23857vinfos[1].indices[0] = _ij1[0];
23858vinfos[1].indices[1] = _ij1[1];
23859vinfos[1].maxsolutions = _nj1;
23860vinfos[2].jointtype = 1;
23861vinfos[2].foffset = j2;
23862vinfos[2].indices[0] = _ij2[0];
23863vinfos[2].indices[1] = _ij2[1];
23864vinfos[2].maxsolutions = _nj2;
23865vinfos[3].jointtype = 1;
23866vinfos[3].foffset = j3;
23867vinfos[3].indices[0] = _ij3[0];
23868vinfos[3].indices[1] = _ij3[1];
23869vinfos[3].maxsolutions = _nj3;
23870vinfos[4].jointtype = 1;
23871vinfos[4].foffset = j4;
23872vinfos[4].indices[0] = _ij4[0];
23873vinfos[4].indices[1] = _ij4[1];
23874vinfos[4].maxsolutions = _nj4;
23875vinfos[5].jointtype = 1;
23876vinfos[5].foffset = j5;
23877vinfos[5].indices[0] = _ij5[0];
23878vinfos[5].indices[1] = _ij5[1];
23879vinfos[5].maxsolutions = _nj5;
23880std::vector<int> vfree(0);
23881solutions.AddSolution(vinfos,vfree);
23882}
23883}
23884}
23885
23886}
23887
23888}
23889
23890} else
23891{
23892{
23893IkReal j5array[2], cj5array[2], sj5array[2];
23894bool j5valid[2]={false};
23895_nj5 = 2;
23896CheckValue<IkReal> x2556=IKPowWithIntegerCheck(new_r11,-1);
23897if(!x2556.valid){
23898continue;
23899}
23900cj5array[0]=(cj3*(x2556.value));
23901if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
23902{
23903 j5valid[0] = j5valid[1] = true;
23904 j5array[0] = IKacos(cj5array[0]);
23905 sj5array[0] = IKsin(j5array[0]);
23906 cj5array[1] = cj5array[0];
23907 j5array[1] = -j5array[0];
23908 sj5array[1] = -sj5array[0];
23909}
23910else if( isnan(cj5array[0]) )
23911{
23912 // probably any value will work
23913 j5valid[0] = true;
23914 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
23915}
23916for(int ij5 = 0; ij5 < 2; ++ij5)
23917{
23918if( !j5valid[ij5] )
23919{
23920 continue;
23921}
23922_ij5[0] = ij5; _ij5[1] = -1;
23923for(int iij5 = ij5+1; iij5 < 2; ++iij5)
23924{
23925if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
23926{
23927 j5valid[iij5]=false; _ij5[1] = iij5; break;
23928}
23929}
23930j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
23931{
23932IkReal evalcond[15];
23933IkReal x2557=IKsin(j5);
23934IkReal x2558=IKcos(j5);
23935IkReal x2559=((3.9999999968e-5)*sj4);
23936IkReal x2560=((0.9999999992)*cj4);
23937IkReal x2561=((25000.00002)*sj4);
23938IkReal x2562=((0.9999999992)*sj4);
23939IkReal x2563=(cj3*x2557);
23940IkReal x2564=(cj3*x2558);
23941IkReal x2565=(new_r00*x2558);
23942IkReal x2566=(new_r02*x2558);
23943IkReal x2567=((3.9999999968e-5)*cj4*x2557);
23944IkReal x2568=(new_r11*sj4*x2557);
23945evalcond[0]=(new_r02*x2557);
23946evalcond[1]=(new_r00*x2557);
23947evalcond[2]=x2566;
23948evalcond[3]=((-1.0)*new_r11*x2557);
23949evalcond[4]=((-1.0)*x2563);
23950evalcond[5]=((((-1.0)*x2564))+new_r11);
23951evalcond[6]=(x2561*x2566);
23952evalcond[7]=((-25000.00002)*x2568);
23953evalcond[8]=(x2567+(((-1.0)*x2557*x2562)));
23954evalcond[9]=(x2565+(((-1.0)*cj3*x2559))+(((-1.0)*cj3*x2560)));
23955evalcond[10]=(((x2560*x2563))+((x2559*x2563)));
23956evalcond[11]=((((-1.0)*new_r11*x2567))+((new_r11*x2557*x2562)));
23957evalcond[12]=((((-1.0)*x2560*x2564))+(((-1.0)*x2559*x2564))+new_r00);
23958CheckValue<IkReal> x2569=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
23959if(!x2569.valid){
23960continue;
23961}
23962evalcond[13]=((((625000001.0)*new_r20*(x2569.value)))+((x2561*x2565)));
23963evalcond[14]=((((3.9999999968e-5)*cj4*x2565))+(((-1.0)*x2562*x2565))+((new_r20*x2559))+((new_r20*x2560)));
23964if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
23965{
23966continue;
23967}
23968}
23969
23970{
23971std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23972vinfos[0].jointtype = 1;
23973vinfos[0].foffset = j0;
23974vinfos[0].indices[0] = _ij0[0];
23975vinfos[0].indices[1] = _ij0[1];
23976vinfos[0].maxsolutions = _nj0;
23977vinfos[1].jointtype = 1;
23978vinfos[1].foffset = j1;
23979vinfos[1].indices[0] = _ij1[0];
23980vinfos[1].indices[1] = _ij1[1];
23981vinfos[1].maxsolutions = _nj1;
23982vinfos[2].jointtype = 1;
23983vinfos[2].foffset = j2;
23984vinfos[2].indices[0] = _ij2[0];
23985vinfos[2].indices[1] = _ij2[1];
23986vinfos[2].maxsolutions = _nj2;
23987vinfos[3].jointtype = 1;
23988vinfos[3].foffset = j3;
23989vinfos[3].indices[0] = _ij3[0];
23990vinfos[3].indices[1] = _ij3[1];
23991vinfos[3].maxsolutions = _nj3;
23992vinfos[4].jointtype = 1;
23993vinfos[4].foffset = j4;
23994vinfos[4].indices[0] = _ij4[0];
23995vinfos[4].indices[1] = _ij4[1];
23996vinfos[4].maxsolutions = _nj4;
23997vinfos[5].jointtype = 1;
23998vinfos[5].foffset = j5;
23999vinfos[5].indices[0] = _ij5[0];
24000vinfos[5].indices[1] = _ij5[1];
24001vinfos[5].maxsolutions = _nj5;
24002std::vector<int> vfree(0);
24003solutions.AddSolution(vinfos,vfree);
24004}
24005}
24006}
24007
24008}
24009
24010}
24011
24012} else
24013{
24014{
24015IkReal j5array[2], cj5array[2], sj5array[2];
24016bool j5valid[2]={false};
24017_nj5 = 2;
24018CheckValue<IkReal> x2570=IKPowWithIntegerCheck(cj3,-1);
24019if(!x2570.valid){
24020continue;
24021}
24022cj5array[0]=(new_r11*(x2570.value));
24023if( cj5array[0] >= -1-IKFAST_SINCOS_THRESH && cj5array[0] <= 1+IKFAST_SINCOS_THRESH )
24024{
24025 j5valid[0] = j5valid[1] = true;
24026 j5array[0] = IKacos(cj5array[0]);
24027 sj5array[0] = IKsin(j5array[0]);
24028 cj5array[1] = cj5array[0];
24029 j5array[1] = -j5array[0];
24030 sj5array[1] = -sj5array[0];
24031}
24032else if( isnan(cj5array[0]) )
24033{
24034 // probably any value will work
24035 j5valid[0] = true;
24036 cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
24037}
24038for(int ij5 = 0; ij5 < 2; ++ij5)
24039{
24040if( !j5valid[ij5] )
24041{
24042 continue;
24043}
24044_ij5[0] = ij5; _ij5[1] = -1;
24045for(int iij5 = ij5+1; iij5 < 2; ++iij5)
24046{
24047if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24048{
24049 j5valid[iij5]=false; _ij5[1] = iij5; break;
24050}
24051}
24052j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24053{
24054IkReal evalcond[15];
24055IkReal x2571=IKsin(j5);
24056IkReal x2572=IKcos(j5);
24057IkReal x2573=((3.9999999968e-5)*sj4);
24058IkReal x2574=((0.9999999992)*cj3);
24059IkReal x2575=((0.9999999992)*cj4);
24060IkReal x2576=((25000.00002)*sj4);
24061IkReal x2577=((0.9999999992)*sj4);
24062IkReal x2578=(cj3*x2571);
24063IkReal x2579=(cj4*x2572);
24064IkReal x2580=(new_r00*x2572);
24065IkReal x2581=(new_r02*x2572);
24066IkReal x2582=((3.9999999968e-5)*cj4*x2571);
24067IkReal x2583=(new_r11*sj4*x2571);
24068evalcond[0]=(new_r02*x2571);
24069evalcond[1]=(new_r00*x2571);
24070evalcond[2]=x2581;
24071evalcond[3]=((-1.0)*new_r11*x2571);
24072evalcond[4]=((-1.0)*x2578);
24073evalcond[5]=(((new_r11*x2572))+(((-1.0)*cj3)));
24074evalcond[6]=(x2576*x2581);
24075evalcond[7]=((-25000.00002)*x2583);
24076evalcond[8]=(x2582+(((-1.0)*x2571*x2577)));
24077evalcond[9]=(x2580+(((-1.0)*cj3*x2573))+(((-1.0)*cj4*x2574)));
24078evalcond[10]=(((x2573*x2578))+((cj4*x2571*x2574)));
24079evalcond[11]=(((new_r11*x2571*x2577))+(((-1.0)*new_r11*x2582)));
24080evalcond[12]=((((-1.0)*cj3*x2572*x2573))+new_r00+(((-1.0)*x2574*x2579)));
24081CheckValue<IkReal> x2584=IKPowWithIntegerCheck(((((25000.00002)*cj4))+(((-625000000.5)*sj4))),-1);
24082if(!x2584.valid){
24083continue;
24084}
24085evalcond[13]=((((625000001.0)*new_r20*(x2584.value)))+((x2576*x2580)));
24086evalcond[14]=((((3.9999999968e-5)*new_r00*x2579))+((new_r20*x2575))+((new_r20*x2573))+(((-1.0)*x2577*x2580)));
24087if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH )
24088{
24089continue;
24090}
24091}
24092
24093{
24094std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24095vinfos[0].jointtype = 1;
24096vinfos[0].foffset = j0;
24097vinfos[0].indices[0] = _ij0[0];
24098vinfos[0].indices[1] = _ij0[1];
24099vinfos[0].maxsolutions = _nj0;
24100vinfos[1].jointtype = 1;
24101vinfos[1].foffset = j1;
24102vinfos[1].indices[0] = _ij1[0];
24103vinfos[1].indices[1] = _ij1[1];
24104vinfos[1].maxsolutions = _nj1;
24105vinfos[2].jointtype = 1;
24106vinfos[2].foffset = j2;
24107vinfos[2].indices[0] = _ij2[0];
24108vinfos[2].indices[1] = _ij2[1];
24109vinfos[2].maxsolutions = _nj2;
24110vinfos[3].jointtype = 1;
24111vinfos[3].foffset = j3;
24112vinfos[3].indices[0] = _ij3[0];
24113vinfos[3].indices[1] = _ij3[1];
24114vinfos[3].maxsolutions = _nj3;
24115vinfos[4].jointtype = 1;
24116vinfos[4].foffset = j4;
24117vinfos[4].indices[0] = _ij4[0];
24118vinfos[4].indices[1] = _ij4[1];
24119vinfos[4].maxsolutions = _nj4;
24120vinfos[5].jointtype = 1;
24121vinfos[5].foffset = j5;
24122vinfos[5].indices[0] = _ij5[0];
24123vinfos[5].indices[1] = _ij5[1];
24124vinfos[5].maxsolutions = _nj5;
24125std::vector<int> vfree(0);
24126solutions.AddSolution(vinfos,vfree);
24127}
24128}
24129}
24130
24131}
24132
24133}
24134
24135}
24136} while(0);
24137if( bgotonextstatement )
24138{
24139bool bgotonextstatement = true;
24140do
24141{
24142evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02)));
24143if( IKabs(evalcond[0]) < 0.0000050000000000 )
24144{
24145bgotonextstatement=false;
24146{
24147IkReal j5eval[1];
24148new_r02=0;
24149new_r12=0;
24150new_r20=0;
24151new_r21=0;
24152j5eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
24153if( IKabs(j5eval[0]) < 0.0000010000000000 )
24154{
24155{
24156IkReal j5eval[1];
24157new_r02=0;
24158new_r12=0;
24159new_r20=0;
24160new_r21=0;
24161j5eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
24162if( IKabs(j5eval[0]) < 0.0000010000000000 )
24163{
24164{
24165IkReal j5eval[3];
24166new_r02=0;
24167new_r12=0;
24168new_r20=0;
24169new_r21=0;
24170j5eval[0]=625000001.0;
24171j5eval[1]=sj4;
24172j5eval[2]=1.0;
24173if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
24174{
24175{
24176IkReal evalcond[5];
24177bool bgotonextstatement = true;
24178do
24179{
24180evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
24181evalcond[1]=new_r00;
24182evalcond[2]=new_r10;
24183evalcond[3]=new_r01;
24184evalcond[4]=new_r11;
24185if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
24186{
24187bgotonextstatement=false;
24188{
24189IkReal j5eval[1];
24190new_r02=0;
24191new_r12=0;
24192new_r20=0;
24193new_r21=0;
24194sj4=0;
24195cj4=1.0;
24196j4=0;
24197j5eval[0]=1.0;
24198if( IKabs(j5eval[0]) < 0.0000000100000000 )
24199{
24200continue; // no branches [j5]
24201
24202} else
24203{
24204IkReal op[2+1], zeror[2];
24205int numroots;
24206op[0]=1.0;
24207op[1]=0;
24208op[2]=-1.0;
24209polyroots2(op,zeror,numroots);
24210IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
24211int numsolutions = 0;
24212for(int ij5 = 0; ij5 < numroots; ++ij5)
24213{
24214IkReal htj5 = zeror[ij5];
24215tempj5array[0]=((2.0)*(atan(htj5)));
24216for(int kj5 = 0; kj5 < 1; ++kj5)
24217{
24218j5array[numsolutions] = tempj5array[kj5];
24219if( j5array[numsolutions] > IKPI )
24220{
24221 j5array[numsolutions]-=IK2PI;
24222}
24223else if( j5array[numsolutions] < -IKPI )
24224{
24225 j5array[numsolutions]+=IK2PI;
24226}
24227sj5array[numsolutions] = IKsin(j5array[numsolutions]);
24228cj5array[numsolutions] = IKcos(j5array[numsolutions]);
24229numsolutions++;
24230}
24231}
24232bool j5valid[2]={true,true};
24233_nj5 = 2;
24234for(int ij5 = 0; ij5 < numsolutions; ++ij5)
24235 {
24236if( !j5valid[ij5] )
24237{
24238 continue;
24239}
24240 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24241htj5 = IKtan(j5/2);
24242
24243_ij5[0] = ij5; _ij5[1] = -1;
24244for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
24245{
24246if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24247{
24248 j5valid[iij5]=false; _ij5[1] = iij5; break;
24249}
24250}
24251{
24252std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24253vinfos[0].jointtype = 1;
24254vinfos[0].foffset = j0;
24255vinfos[0].indices[0] = _ij0[0];
24256vinfos[0].indices[1] = _ij0[1];
24257vinfos[0].maxsolutions = _nj0;
24258vinfos[1].jointtype = 1;
24259vinfos[1].foffset = j1;
24260vinfos[1].indices[0] = _ij1[0];
24261vinfos[1].indices[1] = _ij1[1];
24262vinfos[1].maxsolutions = _nj1;
24263vinfos[2].jointtype = 1;
24264vinfos[2].foffset = j2;
24265vinfos[2].indices[0] = _ij2[0];
24266vinfos[2].indices[1] = _ij2[1];
24267vinfos[2].maxsolutions = _nj2;
24268vinfos[3].jointtype = 1;
24269vinfos[3].foffset = j3;
24270vinfos[3].indices[0] = _ij3[0];
24271vinfos[3].indices[1] = _ij3[1];
24272vinfos[3].maxsolutions = _nj3;
24273vinfos[4].jointtype = 1;
24274vinfos[4].foffset = j4;
24275vinfos[4].indices[0] = _ij4[0];
24276vinfos[4].indices[1] = _ij4[1];
24277vinfos[4].maxsolutions = _nj4;
24278vinfos[5].jointtype = 1;
24279vinfos[5].foffset = j5;
24280vinfos[5].indices[0] = _ij5[0];
24281vinfos[5].indices[1] = _ij5[1];
24282vinfos[5].maxsolutions = _nj5;
24283std::vector<int> vfree(0);
24284solutions.AddSolution(vinfos,vfree);
24285}
24286 }
24287
24288}
24289
24290}
24291
24292}
24293} while(0);
24294if( bgotonextstatement )
24295{
24296bool bgotonextstatement = true;
24297do
24298{
24299evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
24300evalcond[1]=new_r00;
24301evalcond[2]=new_r10;
24302evalcond[3]=new_r01;
24303evalcond[4]=new_r11;
24304if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 )
24305{
24306bgotonextstatement=false;
24307{
24308IkReal j5eval[1];
24309new_r02=0;
24310new_r12=0;
24311new_r20=0;
24312new_r21=0;
24313sj4=0;
24314cj4=-1.0;
24315j4=3.14159265358979;
24316j5eval[0]=1.0;
24317if( IKabs(j5eval[0]) < 0.0000000100000000 )
24318{
24319continue; // no branches [j5]
24320
24321} else
24322{
24323IkReal op[2+1], zeror[2];
24324int numroots;
24325op[0]=-1.0;
24326op[1]=0;
24327op[2]=1.0;
24328polyroots2(op,zeror,numroots);
24329IkReal j5array[2], cj5array[2], sj5array[2], tempj5array[1];
24330int numsolutions = 0;
24331for(int ij5 = 0; ij5 < numroots; ++ij5)
24332{
24333IkReal htj5 = zeror[ij5];
24334tempj5array[0]=((2.0)*(atan(htj5)));
24335for(int kj5 = 0; kj5 < 1; ++kj5)
24336{
24337j5array[numsolutions] = tempj5array[kj5];
24338if( j5array[numsolutions] > IKPI )
24339{
24340 j5array[numsolutions]-=IK2PI;
24341}
24342else if( j5array[numsolutions] < -IKPI )
24343{
24344 j5array[numsolutions]+=IK2PI;
24345}
24346sj5array[numsolutions] = IKsin(j5array[numsolutions]);
24347cj5array[numsolutions] = IKcos(j5array[numsolutions]);
24348numsolutions++;
24349}
24350}
24351bool j5valid[2]={true,true};
24352_nj5 = 2;
24353for(int ij5 = 0; ij5 < numsolutions; ++ij5)
24354 {
24355if( !j5valid[ij5] )
24356{
24357 continue;
24358}
24359 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24360htj5 = IKtan(j5/2);
24361
24362_ij5[0] = ij5; _ij5[1] = -1;
24363for(int iij5 = ij5+1; iij5 < numsolutions; ++iij5)
24364{
24365if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24366{
24367 j5valid[iij5]=false; _ij5[1] = iij5; break;
24368}
24369}
24370{
24371std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24372vinfos[0].jointtype = 1;
24373vinfos[0].foffset = j0;
24374vinfos[0].indices[0] = _ij0[0];
24375vinfos[0].indices[1] = _ij0[1];
24376vinfos[0].maxsolutions = _nj0;
24377vinfos[1].jointtype = 1;
24378vinfos[1].foffset = j1;
24379vinfos[1].indices[0] = _ij1[0];
24380vinfos[1].indices[1] = _ij1[1];
24381vinfos[1].maxsolutions = _nj1;
24382vinfos[2].jointtype = 1;
24383vinfos[2].foffset = j2;
24384vinfos[2].indices[0] = _ij2[0];
24385vinfos[2].indices[1] = _ij2[1];
24386vinfos[2].maxsolutions = _nj2;
24387vinfos[3].jointtype = 1;
24388vinfos[3].foffset = j3;
24389vinfos[3].indices[0] = _ij3[0];
24390vinfos[3].indices[1] = _ij3[1];
24391vinfos[3].maxsolutions = _nj3;
24392vinfos[4].jointtype = 1;
24393vinfos[4].foffset = j4;
24394vinfos[4].indices[0] = _ij4[0];
24395vinfos[4].indices[1] = _ij4[1];
24396vinfos[4].maxsolutions = _nj4;
24397vinfos[5].jointtype = 1;
24398vinfos[5].foffset = j5;
24399vinfos[5].indices[0] = _ij5[0];
24400vinfos[5].indices[1] = _ij5[1];
24401vinfos[5].maxsolutions = _nj5;
24402std::vector<int> vfree(0);
24403solutions.AddSolution(vinfos,vfree);
24404}
24405 }
24406
24407}
24408
24409}
24410
24411}
24412} while(0);
24413if( bgotonextstatement )
24414{
24415bool bgotonextstatement = true;
24416do
24417{
24418if( 1 )
24419{
24420bgotonextstatement=false;
24421continue; // branch miss [j5]
24422
24423}
24424} while(0);
24425if( bgotonextstatement )
24426{
24427}
24428}
24429}
24430}
24431
24432} else
24433{
24434{
24435IkReal j5array[2], cj5array[2], sj5array[2];
24436bool j5valid[2]={false};
24437_nj5 = 2;
24438CheckValue<IkReal> x2586 = IKatan2WithCheck(IkReal(((25000.00002)*new_r00*sj4)),IkReal(((-25000.00002)*new_r10*sj4)),IKFAST_ATAN2_MAGTHRESH);
24439if(!x2586.valid){
24440continue;
24441}
24442IkReal x2585=x2586.value;
24443j5array[0]=((-1.0)*x2585);
24444sj5array[0]=IKsin(j5array[0]);
24445cj5array[0]=IKcos(j5array[0]);
24446j5array[1]=((3.14159265358979)+(((-1.0)*x2585)));
24447sj5array[1]=IKsin(j5array[1]);
24448cj5array[1]=IKcos(j5array[1]);
24449if( j5array[0] > IKPI )
24450{
24451 j5array[0]-=IK2PI;
24452}
24453else if( j5array[0] < -IKPI )
24454{ j5array[0]+=IK2PI;
24455}
24456j5valid[0] = true;
24457if( j5array[1] > IKPI )
24458{
24459 j5array[1]-=IK2PI;
24460}
24461else if( j5array[1] < -IKPI )
24462{ j5array[1]+=IK2PI;
24463}
24464j5valid[1] = true;
24465for(int ij5 = 0; ij5 < 2; ++ij5)
24466{
24467if( !j5valid[ij5] )
24468{
24469 continue;
24470}
24471_ij5[0] = ij5; _ij5[1] = -1;
24472for(int iij5 = ij5+1; iij5 < 2; ++iij5)
24473{
24474if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24475{
24476 j5valid[iij5]=false; _ij5[1] = iij5; break;
24477}
24478}
24479j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24480{
24481IkReal evalcond[9];
24482IkReal x2587=IKcos(j5);
24483IkReal x2588=IKsin(j5);
24484IkReal x2589=((3.9999999968e-5)*cj4);
24485IkReal x2590=((0.9999999992)*sj4);
24486IkReal x2591=((25000.00002)*sj4);
24487IkReal x2592=(new_r01*x2587);
24488IkReal x2593=(new_r11*x2588);
24489IkReal x2594=(new_r00*x2587);
24490IkReal x2595=(new_r10*x2588);
24491evalcond[0]=(((new_r00*x2588))+((new_r10*x2587)));
24492evalcond[1]=(((new_r11*x2587))+((new_r01*x2588)));
24493evalcond[2]=(x2594+(((-1.0)*x2595)));
24494evalcond[3]=(x2592+(((-1.0)*x2593)));
24495evalcond[4]=((((-1.0)*x2587*x2589))+((x2587*x2590)));
24496evalcond[5]=((((-1.0)*x2588*x2590))+((x2588*x2589)));
24497evalcond[6]=(((x2591*x2592))+(((-1.0)*x2591*x2593)));
24498evalcond[7]=((((-1.0)*x2590*x2594))+(((-1.0)*x2589*x2595))+((x2589*x2594))+((x2590*x2595)));
24499evalcond[8]=((((-1.0)*x2590*x2592))+(((-1.0)*x2589*x2593))+((x2589*x2592))+((x2590*x2593)));
24500if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
24501{
24502continue;
24503}
24504}
24505
24506{
24507std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24508vinfos[0].jointtype = 1;
24509vinfos[0].foffset = j0;
24510vinfos[0].indices[0] = _ij0[0];
24511vinfos[0].indices[1] = _ij0[1];
24512vinfos[0].maxsolutions = _nj0;
24513vinfos[1].jointtype = 1;
24514vinfos[1].foffset = j1;
24515vinfos[1].indices[0] = _ij1[0];
24516vinfos[1].indices[1] = _ij1[1];
24517vinfos[1].maxsolutions = _nj1;
24518vinfos[2].jointtype = 1;
24519vinfos[2].foffset = j2;
24520vinfos[2].indices[0] = _ij2[0];
24521vinfos[2].indices[1] = _ij2[1];
24522vinfos[2].maxsolutions = _nj2;
24523vinfos[3].jointtype = 1;
24524vinfos[3].foffset = j3;
24525vinfos[3].indices[0] = _ij3[0];
24526vinfos[3].indices[1] = _ij3[1];
24527vinfos[3].maxsolutions = _nj3;
24528vinfos[4].jointtype = 1;
24529vinfos[4].foffset = j4;
24530vinfos[4].indices[0] = _ij4[0];
24531vinfos[4].indices[1] = _ij4[1];
24532vinfos[4].maxsolutions = _nj4;
24533vinfos[5].jointtype = 1;
24534vinfos[5].foffset = j5;
24535vinfos[5].indices[0] = _ij5[0];
24536vinfos[5].indices[1] = _ij5[1];
24537vinfos[5].maxsolutions = _nj5;
24538std::vector<int> vfree(0);
24539solutions.AddSolution(vinfos,vfree);
24540}
24541}
24542}
24543
24544}
24545
24546}
24547
24548} else
24549{
24550{
24551IkReal j5array[2], cj5array[2], sj5array[2];
24552bool j5valid[2]={false};
24553_nj5 = 2;
24554CheckValue<IkReal> x2597 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
24555if(!x2597.valid){
24556continue;
24557}
24558IkReal x2596=x2597.value;
24559j5array[0]=((-1.0)*x2596);
24560sj5array[0]=IKsin(j5array[0]);
24561cj5array[0]=IKcos(j5array[0]);
24562j5array[1]=((3.14159265358979)+(((-1.0)*x2596)));
24563sj5array[1]=IKsin(j5array[1]);
24564cj5array[1]=IKcos(j5array[1]);
24565if( j5array[0] > IKPI )
24566{
24567 j5array[0]-=IK2PI;
24568}
24569else if( j5array[0] < -IKPI )
24570{ j5array[0]+=IK2PI;
24571}
24572j5valid[0] = true;
24573if( j5array[1] > IKPI )
24574{
24575 j5array[1]-=IK2PI;
24576}
24577else if( j5array[1] < -IKPI )
24578{ j5array[1]+=IK2PI;
24579}
24580j5valid[1] = true;
24581for(int ij5 = 0; ij5 < 2; ++ij5)
24582{
24583if( !j5valid[ij5] )
24584{
24585 continue;
24586}
24587_ij5[0] = ij5; _ij5[1] = -1;
24588for(int iij5 = ij5+1; iij5 < 2; ++iij5)
24589{
24590if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24591{
24592 j5valid[iij5]=false; _ij5[1] = iij5; break;
24593}
24594}
24595j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24596{
24597IkReal evalcond[9];
24598IkReal x2598=IKcos(j5);
24599IkReal x2599=IKsin(j5);
24600IkReal x2600=((3.9999999968e-5)*cj4);
24601IkReal x2601=((25000.00002)*sj4);
24602IkReal x2602=((0.9999999992)*sj4);
24603IkReal x2603=(new_r01*x2598);
24604IkReal x2604=(new_r11*x2599);
24605IkReal x2605=(sj4*x2598);
24606IkReal x2606=(new_r00*x2598);
24607IkReal x2607=(new_r10*x2599);
24608evalcond[0]=(((new_r10*x2598))+((new_r00*x2599)));
24609evalcond[1]=((((-1.0)*x2607))+x2606);
24610evalcond[2]=((((-1.0)*x2604))+x2603);
24611evalcond[3]=(((x2598*x2602))+(((-1.0)*x2598*x2600)));
24612evalcond[4]=(((x2599*x2600))+(((-1.0)*x2599*x2602)));
24613evalcond[5]=((((-1.0)*x2601*x2607))+((x2601*x2606)));
24614evalcond[6]=((((-1.0)*x2601*x2604))+((x2601*x2603)));
24615evalcond[7]=(((x2602*x2607))+(((-1.0)*x2600*x2607))+((x2600*x2606))+(((-1.0)*x2602*x2606)));
24616evalcond[8]=(((x2602*x2604))+(((-1.0)*x2600*x2604))+((x2600*x2603))+(((-1.0)*x2602*x2603)));
24617if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
24618{
24619continue;
24620}
24621}
24622
24623{
24624std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24625vinfos[0].jointtype = 1;
24626vinfos[0].foffset = j0;
24627vinfos[0].indices[0] = _ij0[0];
24628vinfos[0].indices[1] = _ij0[1];
24629vinfos[0].maxsolutions = _nj0;
24630vinfos[1].jointtype = 1;
24631vinfos[1].foffset = j1;
24632vinfos[1].indices[0] = _ij1[0];
24633vinfos[1].indices[1] = _ij1[1];
24634vinfos[1].maxsolutions = _nj1;
24635vinfos[2].jointtype = 1;
24636vinfos[2].foffset = j2;
24637vinfos[2].indices[0] = _ij2[0];
24638vinfos[2].indices[1] = _ij2[1];
24639vinfos[2].maxsolutions = _nj2;
24640vinfos[3].jointtype = 1;
24641vinfos[3].foffset = j3;
24642vinfos[3].indices[0] = _ij3[0];
24643vinfos[3].indices[1] = _ij3[1];
24644vinfos[3].maxsolutions = _nj3;
24645vinfos[4].jointtype = 1;
24646vinfos[4].foffset = j4;
24647vinfos[4].indices[0] = _ij4[0];
24648vinfos[4].indices[1] = _ij4[1];
24649vinfos[4].maxsolutions = _nj4;
24650vinfos[5].jointtype = 1;
24651vinfos[5].foffset = j5;
24652vinfos[5].indices[0] = _ij5[0];
24653vinfos[5].indices[1] = _ij5[1];
24654vinfos[5].maxsolutions = _nj5;
24655std::vector<int> vfree(0);
24656solutions.AddSolution(vinfos,vfree);
24657}
24658}
24659}
24660
24661}
24662
24663}
24664
24665} else
24666{
24667{
24668IkReal j5array[2], cj5array[2], sj5array[2];
24669bool j5valid[2]={false};
24670_nj5 = 2;
24671CheckValue<IkReal> x2609 = IKatan2WithCheck(IkReal(new_r10),IkReal(new_r00),IKFAST_ATAN2_MAGTHRESH);
24672if(!x2609.valid){
24673continue;
24674}
24675IkReal x2608=x2609.value;
24676j5array[0]=((-1.0)*x2608);
24677sj5array[0]=IKsin(j5array[0]);
24678cj5array[0]=IKcos(j5array[0]);
24679j5array[1]=((3.14159265358979)+(((-1.0)*x2608)));
24680sj5array[1]=IKsin(j5array[1]);
24681cj5array[1]=IKcos(j5array[1]);
24682if( j5array[0] > IKPI )
24683{
24684 j5array[0]-=IK2PI;
24685}
24686else if( j5array[0] < -IKPI )
24687{ j5array[0]+=IK2PI;
24688}
24689j5valid[0] = true;
24690if( j5array[1] > IKPI )
24691{
24692 j5array[1]-=IK2PI;
24693}
24694else if( j5array[1] < -IKPI )
24695{ j5array[1]+=IK2PI;
24696}
24697j5valid[1] = true;
24698for(int ij5 = 0; ij5 < 2; ++ij5)
24699{
24700if( !j5valid[ij5] )
24701{
24702 continue;
24703}
24704_ij5[0] = ij5; _ij5[1] = -1;
24705for(int iij5 = ij5+1; iij5 < 2; ++iij5)
24706{
24707if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24708{
24709 j5valid[iij5]=false; _ij5[1] = iij5; break;
24710}
24711}
24712j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24713{
24714IkReal evalcond[9];
24715IkReal x2610=IKcos(j5);
24716IkReal x2611=IKsin(j5);
24717IkReal x2612=((3.9999999968e-5)*cj4);
24718IkReal x2613=((25000.00002)*sj4);
24719IkReal x2614=((0.9999999992)*sj4);
24720IkReal x2615=(new_r01*x2610);
24721IkReal x2616=(new_r11*x2611);
24722IkReal x2617=(sj4*x2610);
24723IkReal x2618=(new_r00*x2610);
24724IkReal x2619=(new_r10*x2611);
24725evalcond[0]=(((new_r11*x2610))+((new_r01*x2611)));
24726evalcond[1]=((((-1.0)*x2619))+x2618);
24727evalcond[2]=((((-1.0)*x2616))+x2615);
24728evalcond[3]=((((-1.0)*x2610*x2612))+((x2610*x2614)));
24729evalcond[4]=((((-1.0)*x2611*x2614))+((x2611*x2612)));
24730evalcond[5]=(((x2613*x2618))+(((-1.0)*x2613*x2619)));
24731evalcond[6]=(((x2613*x2615))+(((-1.0)*x2613*x2616)));
24732evalcond[7]=((((-1.0)*x2612*x2619))+((x2614*x2619))+((x2612*x2618))+(((-1.0)*x2614*x2618)));
24733evalcond[8]=((((-1.0)*x2612*x2616))+((x2614*x2616))+((x2612*x2615))+(((-1.0)*x2614*x2615)));
24734if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH )
24735{
24736continue;
24737}
24738}
24739
24740{
24741std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24742vinfos[0].jointtype = 1;
24743vinfos[0].foffset = j0;
24744vinfos[0].indices[0] = _ij0[0];
24745vinfos[0].indices[1] = _ij0[1];
24746vinfos[0].maxsolutions = _nj0;
24747vinfos[1].jointtype = 1;
24748vinfos[1].foffset = j1;
24749vinfos[1].indices[0] = _ij1[0];
24750vinfos[1].indices[1] = _ij1[1];
24751vinfos[1].maxsolutions = _nj1;
24752vinfos[2].jointtype = 1;
24753vinfos[2].foffset = j2;
24754vinfos[2].indices[0] = _ij2[0];
24755vinfos[2].indices[1] = _ij2[1];
24756vinfos[2].maxsolutions = _nj2;
24757vinfos[3].jointtype = 1;
24758vinfos[3].foffset = j3;
24759vinfos[3].indices[0] = _ij3[0];
24760vinfos[3].indices[1] = _ij3[1];
24761vinfos[3].maxsolutions = _nj3;
24762vinfos[4].jointtype = 1;
24763vinfos[4].foffset = j4;
24764vinfos[4].indices[0] = _ij4[0];
24765vinfos[4].indices[1] = _ij4[1];
24766vinfos[4].maxsolutions = _nj4;
24767vinfos[5].jointtype = 1;
24768vinfos[5].foffset = j5;
24769vinfos[5].indices[0] = _ij5[0];
24770vinfos[5].indices[1] = _ij5[1];
24771vinfos[5].maxsolutions = _nj5;
24772std::vector<int> vfree(0);
24773solutions.AddSolution(vinfos,vfree);
24774}
24775}
24776}
24777
24778}
24779
24780}
24781
24782}
24783} while(0);
24784if( bgotonextstatement )
24785{
24786bool bgotonextstatement = true;
24787do
24788{
24789if( 1 )
24790{
24791bgotonextstatement=false;
24792continue; // branch miss [j5]
24793
24794}
24795} while(0);
24796if( bgotonextstatement )
24797{
24798}
24799}
24800}
24801}
24802}
24803}
24804}
24805}
24806}
24807}
24808}
24809}
24810
24811} else
24812{
24813{
24814IkReal j5array[1], cj5array[1], sj5array[1];
24815bool j5valid[1]={false};
24816_nj5 = 1;
24817CheckValue<IkReal> x2620 = IKatan2WithCheck(IkReal(new_r12),IkReal(((-1.0)*new_r02)),IKFAST_ATAN2_MAGTHRESH);
24818if(!x2620.valid){
24819continue;
24820}
24821CheckValue<IkReal> x2621=IKPowWithIntegerCheck(IKsign(((((-3.9999999968e-5)*cj4))+(((0.9999999992)*sj4)))),-1);
24822if(!x2621.valid){
24823continue;
24824}
24825j5array[0]=((-1.5707963267949)+(x2620.value)+(((1.5707963267949)*(x2621.value))));
24826sj5array[0]=IKsin(j5array[0]);
24827cj5array[0]=IKcos(j5array[0]);
24828if( j5array[0] > IKPI )
24829{
24830 j5array[0]-=IK2PI;
24831}
24832else if( j5array[0] < -IKPI )
24833{ j5array[0]+=IK2PI;
24834}
24835j5valid[0] = true;
24836for(int ij5 = 0; ij5 < 1; ++ij5)
24837{
24838if( !j5valid[ij5] )
24839{
24840 continue;
24841}
24842_ij5[0] = ij5; _ij5[1] = -1;
24843for(int iij5 = ij5+1; iij5 < 1; ++iij5)
24844{
24845if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24846{
24847 j5valid[iij5]=false; _ij5[1] = iij5; break;
24848}
24849}
24850j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24851{
24852IkReal evalcond[18];
24853IkReal x2622=IKcos(j5);
24854IkReal x2623=IKsin(j5);
24855IkReal x2624=((1.0)*cj3);
24856IkReal x2625=((0.9999999992)*cj4);
24857IkReal x2626=((0.9999999992)*sj4);
24858IkReal x2627=((3.9999999968e-5)*cj4);
24859IkReal x2628=((3.9999999968e-5)*sj4);
24860IkReal x2629=(new_r12*x2623);
24861IkReal x2630=(new_r02*x2622);
24862IkReal x2631=(new_r01*x2622);
24863IkReal x2632=(new_r11*x2623);
24864IkReal x2633=(sj3*x2623);
24865IkReal x2634=(sj3*x2622);
24866IkReal x2635=(new_r00*x2622);
24867IkReal x2636=(cj3*x2622);
24868IkReal x2637=(cj3*x2623);
24869IkReal x2638=(new_r10*x2623);
24870evalcond[0]=(((new_r12*x2622))+((new_r02*x2623)));
24871evalcond[1]=(sj3+((new_r10*x2622))+((new_r00*x2623)));
24872evalcond[2]=(((new_r11*x2622))+(((-1.0)*x2624))+((new_r01*x2623)));
24873evalcond[3]=((((-1.0)*x2622*x2627))+((x2622*x2626))+new_r02);
24874evalcond[4]=((((-1.0)*x2623*x2626))+((x2623*x2627))+new_r12);
24875evalcond[5]=((((-1.0)*x2629))+(((-1.0)*x2627))+x2630+x2626);
24876evalcond[6]=((((-1.0)*x2638))+(((-1.0)*cj3*x2628))+(((-1.0)*cj3*x2625))+x2635);
24877evalcond[7]=((((-1.0)*sj3*x2628))+(((-1.0)*sj3*x2625))+(((-1.0)*x2632))+x2631);
24878evalcond[8]=((((-1.0)*x2628*x2636))+new_r00+(((-1.0)*x2625*x2636))+x2633);
24879evalcond[9]=(((x2625*x2637))+((x2628*x2637))+new_r10+x2634);
24880evalcond[10]=((((-1.0)*x2623*x2624))+(((-1.0)*x2628*x2634))+new_r01+(((-1.0)*x2625*x2634)));
24881evalcond[11]=((((-1.0)*x2622*x2624))+((x2625*x2633))+((x2628*x2633))+new_r11);
24882evalcond[12]=(((new_r20*x2625))+((new_r20*x2628))+((x2627*x2635))+(((-1.0)*x2626*x2635))+((x2626*x2638))+(((-1.0)*x2627*x2638)));
24883evalcond[13]=(((new_r21*x2625))+((new_r21*x2628))+((x2627*x2631))+(((-1.0)*x2626*x2631))+((x2626*x2632))+(((-1.0)*x2627*x2632)));
24884evalcond[14]=((((-1.0)*x2625*x2629))+((x2625*x2630))+((new_r22*x2626))+(((-1.0)*new_r22*x2627))+((x2628*x2630))+(((-1.0)*x2628*x2629)));
24885evalcond[15]=((-1.0)+((x2626*x2629))+(((-1.0)*x2627*x2629))+((new_r22*x2628))+((new_r22*x2625))+((x2627*x2630))+(((-1.0)*x2626*x2630)));
24886evalcond[16]=(((new_r20*x2626))+(((-1.0)*x2628*x2638))+((x2625*x2635))+((x2628*x2635))+(((-1.0)*new_r20*x2627))+(((-1.0)*x2624))+(((-1.0)*x2625*x2638)));
24887evalcond[17]=((((-1.0)*sj3))+((new_r21*x2626))+(((-1.0)*x2628*x2632))+((x2625*x2631))+((x2628*x2631))+(((-1.0)*new_r21*x2627))+(((-1.0)*x2625*x2632)));
24888if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
24889{
24890continue;
24891}
24892}
24893
24894{
24895std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24896vinfos[0].jointtype = 1;
24897vinfos[0].foffset = j0;
24898vinfos[0].indices[0] = _ij0[0];
24899vinfos[0].indices[1] = _ij0[1];
24900vinfos[0].maxsolutions = _nj0;
24901vinfos[1].jointtype = 1;
24902vinfos[1].foffset = j1;
24903vinfos[1].indices[0] = _ij1[0];
24904vinfos[1].indices[1] = _ij1[1];
24905vinfos[1].maxsolutions = _nj1;
24906vinfos[2].jointtype = 1;
24907vinfos[2].foffset = j2;
24908vinfos[2].indices[0] = _ij2[0];
24909vinfos[2].indices[1] = _ij2[1];
24910vinfos[2].maxsolutions = _nj2;
24911vinfos[3].jointtype = 1;
24912vinfos[3].foffset = j3;
24913vinfos[3].indices[0] = _ij3[0];
24914vinfos[3].indices[1] = _ij3[1];
24915vinfos[3].maxsolutions = _nj3;
24916vinfos[4].jointtype = 1;
24917vinfos[4].foffset = j4;
24918vinfos[4].indices[0] = _ij4[0];
24919vinfos[4].indices[1] = _ij4[1];
24920vinfos[4].maxsolutions = _nj4;
24921vinfos[5].jointtype = 1;
24922vinfos[5].foffset = j5;
24923vinfos[5].indices[0] = _ij5[0];
24924vinfos[5].indices[1] = _ij5[1];
24925vinfos[5].maxsolutions = _nj5;
24926std::vector<int> vfree(0);
24927solutions.AddSolution(vinfos,vfree);
24928}
24929}
24930}
24931
24932}
24933
24934}
24935
24936} else
24937{
24938{
24939IkReal j5array[1], cj5array[1], sj5array[1];
24940bool j5valid[1]={false};
24941_nj5 = 1;
24942CheckValue<IkReal> x2639=IKPowWithIntegerCheck(IKsign((((new_r01*new_r12))+(((-1.0)*new_r02*new_r11)))),-1);
24943if(!x2639.valid){
24944continue;
24945}
24946CheckValue<IkReal> x2640 = IKatan2WithCheck(IkReal((cj3*new_r12)),IkReal(((-1.0)*cj3*new_r02)),IKFAST_ATAN2_MAGTHRESH);
24947if(!x2640.valid){
24948continue;
24949}
24950j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2639.value)))+(x2640.value));
24951sj5array[0]=IKsin(j5array[0]);
24952cj5array[0]=IKcos(j5array[0]);
24953if( j5array[0] > IKPI )
24954{
24955 j5array[0]-=IK2PI;
24956}
24957else if( j5array[0] < -IKPI )
24958{ j5array[0]+=IK2PI;
24959}
24960j5valid[0] = true;
24961for(int ij5 = 0; ij5 < 1; ++ij5)
24962{
24963if( !j5valid[ij5] )
24964{
24965 continue;
24966}
24967_ij5[0] = ij5; _ij5[1] = -1;
24968for(int iij5 = ij5+1; iij5 < 1; ++iij5)
24969{
24970if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
24971{
24972 j5valid[iij5]=false; _ij5[1] = iij5; break;
24973}
24974}
24975j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
24976{
24977IkReal evalcond[18];
24978IkReal x2641=IKcos(j5);
24979IkReal x2642=IKsin(j5);
24980IkReal x2643=((1.0)*cj3);
24981IkReal x2644=((0.9999999992)*cj4);
24982IkReal x2645=((0.9999999992)*sj4);
24983IkReal x2646=((3.9999999968e-5)*cj4);
24984IkReal x2647=((3.9999999968e-5)*sj4);
24985IkReal x2648=(new_r12*x2642);
24986IkReal x2649=(new_r02*x2641);
24987IkReal x2650=(new_r01*x2641);
24988IkReal x2651=(new_r11*x2642);
24989IkReal x2652=(sj3*x2642);
24990IkReal x2653=(sj3*x2641);
24991IkReal x2654=(new_r00*x2641);
24992IkReal x2655=(cj3*x2641);
24993IkReal x2656=(cj3*x2642);
24994IkReal x2657=(new_r10*x2642);
24995evalcond[0]=(((new_r02*x2642))+((new_r12*x2641)));
24996evalcond[1]=(sj3+((new_r10*x2641))+((new_r00*x2642)));
24997evalcond[2]=(((new_r11*x2641))+((new_r01*x2642))+(((-1.0)*x2643)));
24998evalcond[3]=((((-1.0)*x2641*x2646))+new_r02+((x2641*x2645)));
24999evalcond[4]=((((-1.0)*x2642*x2645))+new_r12+((x2642*x2646)));
25000evalcond[5]=((((-1.0)*x2646))+(((-1.0)*x2648))+x2649+x2645);
25001evalcond[6]=((((-1.0)*cj3*x2644))+(((-1.0)*cj3*x2647))+(((-1.0)*x2657))+x2654);
25002evalcond[7]=((((-1.0)*sj3*x2647))+(((-1.0)*sj3*x2644))+(((-1.0)*x2651))+x2650);
25003evalcond[8]=((((-1.0)*x2644*x2655))+(((-1.0)*x2647*x2655))+new_r00+x2652);
25004evalcond[9]=(((x2644*x2656))+new_r10+((x2647*x2656))+x2653);
25005evalcond[10]=((((-1.0)*x2644*x2653))+(((-1.0)*x2647*x2653))+(((-1.0)*x2642*x2643))+new_r01);
25006evalcond[11]=(((x2644*x2652))+(((-1.0)*x2641*x2643))+new_r11+((x2647*x2652)));
25007evalcond[12]=((((-1.0)*x2645*x2654))+(((-1.0)*x2646*x2657))+((new_r20*x2647))+((new_r20*x2644))+((x2645*x2657))+((x2646*x2654)));
25008evalcond[13]=(((new_r21*x2644))+((new_r21*x2647))+(((-1.0)*x2645*x2650))+(((-1.0)*x2646*x2651))+((x2645*x2651))+((x2646*x2650)));
25009evalcond[14]=((((-1.0)*x2644*x2648))+(((-1.0)*x2647*x2648))+(((-1.0)*new_r22*x2646))+((x2644*x2649))+((x2647*x2649))+((new_r22*x2645)));
25010evalcond[15]=((-1.0)+(((-1.0)*x2646*x2648))+(((-1.0)*x2645*x2649))+((x2645*x2648))+((x2646*x2649))+((new_r22*x2647))+((new_r22*x2644)));
25011evalcond[16]=((((-1.0)*x2644*x2657))+((new_r20*x2645))+(((-1.0)*x2647*x2657))+((x2644*x2654))+(((-1.0)*new_r20*x2646))+(((-1.0)*x2643))+((x2647*x2654)));
25012evalcond[17]=((((-1.0)*sj3))+((new_r21*x2645))+(((-1.0)*x2644*x2651))+(((-1.0)*x2647*x2651))+(((-1.0)*new_r21*x2646))+((x2644*x2650))+((x2647*x2650)));
25013if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
25014{
25015continue;
25016}
25017}
25018
25019{
25020std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
25021vinfos[0].jointtype = 1;
25022vinfos[0].foffset = j0;
25023vinfos[0].indices[0] = _ij0[0];
25024vinfos[0].indices[1] = _ij0[1];
25025vinfos[0].maxsolutions = _nj0;
25026vinfos[1].jointtype = 1;
25027vinfos[1].foffset = j1;
25028vinfos[1].indices[0] = _ij1[0];
25029vinfos[1].indices[1] = _ij1[1];
25030vinfos[1].maxsolutions = _nj1;
25031vinfos[2].jointtype = 1;
25032vinfos[2].foffset = j2;
25033vinfos[2].indices[0] = _ij2[0];
25034vinfos[2].indices[1] = _ij2[1];
25035vinfos[2].maxsolutions = _nj2;
25036vinfos[3].jointtype = 1;
25037vinfos[3].foffset = j3;
25038vinfos[3].indices[0] = _ij3[0];
25039vinfos[3].indices[1] = _ij3[1];
25040vinfos[3].maxsolutions = _nj3;
25041vinfos[4].jointtype = 1;
25042vinfos[4].foffset = j4;
25043vinfos[4].indices[0] = _ij4[0];
25044vinfos[4].indices[1] = _ij4[1];
25045vinfos[4].maxsolutions = _nj4;
25046vinfos[5].jointtype = 1;
25047vinfos[5].foffset = j5;
25048vinfos[5].indices[0] = _ij5[0];
25049vinfos[5].indices[1] = _ij5[1];
25050vinfos[5].maxsolutions = _nj5;
25051std::vector<int> vfree(0);
25052solutions.AddSolution(vinfos,vfree);
25053}
25054}
25055}
25056
25057}
25058
25059}
25060
25061} else
25062{
25063{
25064IkReal j5array[1], cj5array[1], sj5array[1];
25065bool j5valid[1]={false};
25066_nj5 = 1;
25067CheckValue<IkReal> x2658 = IKatan2WithCheck(IkReal((new_r12*sj3)),IkReal(((-1.0)*new_r02*sj3)),IKFAST_ATAN2_MAGTHRESH);
25068if(!x2658.valid){
25069continue;
25070}
25071CheckValue<IkReal> x2659=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r00*new_r12))+((new_r02*new_r10)))),-1);
25072if(!x2659.valid){
25073continue;
25074}
25075j5array[0]=((-1.5707963267949)+(x2658.value)+(((1.5707963267949)*(x2659.value))));
25076sj5array[0]=IKsin(j5array[0]);
25077cj5array[0]=IKcos(j5array[0]);
25078if( j5array[0] > IKPI )
25079{
25080 j5array[0]-=IK2PI;
25081}
25082else if( j5array[0] < -IKPI )
25083{ j5array[0]+=IK2PI;
25084}
25085j5valid[0] = true;
25086for(int ij5 = 0; ij5 < 1; ++ij5)
25087{
25088if( !j5valid[ij5] )
25089{
25090 continue;
25091}
25092_ij5[0] = ij5; _ij5[1] = -1;
25093for(int iij5 = ij5+1; iij5 < 1; ++iij5)
25094{
25095if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
25096{
25097 j5valid[iij5]=false; _ij5[1] = iij5; break;
25098}
25099}
25100j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
25101{
25102IkReal evalcond[18];
25103IkReal x2660=IKcos(j5);
25104IkReal x2661=IKsin(j5);
25105IkReal x2662=((1.0)*cj3);
25106IkReal x2663=((0.9999999992)*cj4);
25107IkReal x2664=((0.9999999992)*sj4);
25108IkReal x2665=((3.9999999968e-5)*cj4);
25109IkReal x2666=((3.9999999968e-5)*sj4);
25110IkReal x2667=(new_r12*x2661);
25111IkReal x2668=(new_r02*x2660);
25112IkReal x2669=(new_r01*x2660);
25113IkReal x2670=(new_r11*x2661);
25114IkReal x2671=(sj3*x2661);
25115IkReal x2672=(sj3*x2660);
25116IkReal x2673=(new_r00*x2660);
25117IkReal x2674=(cj3*x2660);
25118IkReal x2675=(cj3*x2661);
25119IkReal x2676=(new_r10*x2661);
25120evalcond[0]=(((new_r02*x2661))+((new_r12*x2660)));
25121evalcond[1]=(sj3+((new_r10*x2660))+((new_r00*x2661)));
25122evalcond[2]=((((-1.0)*x2662))+((new_r11*x2660))+((new_r01*x2661)));
25123evalcond[3]=((((-1.0)*x2660*x2665))+((x2660*x2664))+new_r02);
25124evalcond[4]=(((x2661*x2665))+new_r12+(((-1.0)*x2661*x2664)));
25125evalcond[5]=((((-1.0)*x2667))+(((-1.0)*x2665))+x2664+x2668);
25126evalcond[6]=((((-1.0)*x2676))+(((-1.0)*cj3*x2663))+(((-1.0)*cj3*x2666))+x2673);
25127evalcond[7]=((((-1.0)*x2670))+(((-1.0)*sj3*x2663))+(((-1.0)*sj3*x2666))+x2669);
25128evalcond[8]=((((-1.0)*x2663*x2674))+(((-1.0)*x2666*x2674))+new_r00+x2671);
25129evalcond[9]=(((x2663*x2675))+((x2666*x2675))+new_r10+x2672);
25130evalcond[10]=((((-1.0)*x2663*x2672))+(((-1.0)*x2666*x2672))+new_r01+(((-1.0)*x2661*x2662)));
25131evalcond[11]=((((-1.0)*x2660*x2662))+((x2663*x2671))+((x2666*x2671))+new_r11);
25132evalcond[12]=(((new_r20*x2666))+((new_r20*x2663))+((x2664*x2676))+(((-1.0)*x2664*x2673))+(((-1.0)*x2665*x2676))+((x2665*x2673)));
25133evalcond[13]=(((x2664*x2670))+(((-1.0)*x2665*x2670))+(((-1.0)*x2664*x2669))+((x2665*x2669))+((new_r21*x2666))+((new_r21*x2663)));
25134evalcond[14]=(((x2663*x2668))+(((-1.0)*new_r22*x2665))+((x2666*x2668))+(((-1.0)*x2663*x2667))+((new_r22*x2664))+(((-1.0)*x2666*x2667)));
25135evalcond[15]=((-1.0)+((x2664*x2667))+(((-1.0)*x2664*x2668))+(((-1.0)*x2665*x2667))+((new_r22*x2663))+((new_r22*x2666))+((x2665*x2668)));
25136evalcond[16]=(((x2663*x2673))+(((-1.0)*new_r20*x2665))+((new_r20*x2664))+((x2666*x2673))+(((-1.0)*x2663*x2676))+(((-1.0)*x2662))+(((-1.0)*x2666*x2676)));
25137evalcond[17]=((((-1.0)*sj3))+((x2663*x2669))+((x2666*x2669))+(((-1.0)*new_r21*x2665))+(((-1.0)*x2663*x2670))+(((-1.0)*x2666*x2670))+((new_r21*x2664)));
25138if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH )
25139{
25140continue;
25141}
25142}
25143
25144{
25145std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
25146vinfos[0].jointtype = 1;
25147vinfos[0].foffset = j0;
25148vinfos[0].indices[0] = _ij0[0];
25149vinfos[0].indices[1] = _ij0[1];
25150vinfos[0].maxsolutions = _nj0;
25151vinfos[1].jointtype = 1;
25152vinfos[1].foffset = j1;
25153vinfos[1].indices[0] = _ij1[0];
25154vinfos[1].indices[1] = _ij1[1];
25155vinfos[1].maxsolutions = _nj1;
25156vinfos[2].jointtype = 1;
25157vinfos[2].foffset = j2;
25158vinfos[2].indices[0] = _ij2[0];
25159vinfos[2].indices[1] = _ij2[1];
25160vinfos[2].maxsolutions = _nj2;
25161vinfos[3].jointtype = 1;
25162vinfos[3].foffset = j3;
25163vinfos[3].indices[0] = _ij3[0];
25164vinfos[3].indices[1] = _ij3[1];
25165vinfos[3].maxsolutions = _nj3;
25166vinfos[4].jointtype = 1;
25167vinfos[4].foffset = j4;
25168vinfos[4].indices[0] = _ij4[0];
25169vinfos[4].indices[1] = _ij4[1];
25170vinfos[4].maxsolutions = _nj4;
25171vinfos[5].jointtype = 1;
25172vinfos[5].foffset = j5;
25173vinfos[5].indices[0] = _ij5[0];
25174vinfos[5].indices[1] = _ij5[1];
25175vinfos[5].maxsolutions = _nj5;
25176std::vector<int> vfree(0);
25177solutions.AddSolution(vinfos,vfree);
25178}
25179}
25180}
25181
25182}
25183
25184}
25185}
25186}
25187
25188}
25189
25190}
25191
25192} else
25193{
25194{
25195IkReal j5array[1], cj5array[1], sj5array[1];
25196bool j5valid[1]={false};
25197_nj5 = 1;
25198CheckValue<IkReal> x2677 = IKatan2WithCheck(IkReal(new_r12),IkReal(((-1.0)*new_r02)),IKFAST_ATAN2_MAGTHRESH);
25199if(!x2677.valid){
25200continue;
25201}
25202CheckValue<IkReal> x2678=IKPowWithIntegerCheck(IKsign(((((-3.9999999968e-5)*cj4))+(((0.9999999992)*sj4)))),-1);
25203if(!x2678.valid){
25204continue;
25205}
25206j5array[0]=((-1.5707963267949)+(x2677.value)+(((1.5707963267949)*(x2678.value))));
25207sj5array[0]=IKsin(j5array[0]);
25208cj5array[0]=IKcos(j5array[0]);
25209if( j5array[0] > IKPI )
25210{
25211 j5array[0]-=IK2PI;
25212}
25213else if( j5array[0] < -IKPI )
25214{ j5array[0]+=IK2PI;
25215}
25216j5valid[0] = true;
25217for(int ij5 = 0; ij5 < 1; ++ij5)
25218{
25219if( !j5valid[ij5] )
25220{
25221 continue;
25222}
25223_ij5[0] = ij5; _ij5[1] = -1;
25224for(int iij5 = ij5+1; iij5 < 1; ++iij5)
25225{
25226if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
25227{
25228 j5valid[iij5]=false; _ij5[1] = iij5; break;
25229}
25230}
25231j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
25232{
25233IkReal evalcond[8];
25234IkReal x2679=IKcos(j5);
25235IkReal x2680=IKsin(j5);
25236IkReal x2681=((0.9999999992)*cj4);
25237IkReal x2682=((3.9999999968e-5)*cj4);
25238IkReal x2683=((0.9999999992)*sj4);
25239IkReal x2684=((3.9999999968e-5)*sj4);
25240IkReal x2685=(new_r12*x2680);
25241IkReal x2686=(new_r02*x2679);
25242IkReal x2687=(new_r01*x2679);
25243IkReal x2688=(new_r11*x2680);
25244IkReal x2689=(new_r00*x2679);
25245IkReal x2690=(new_r10*x2680);
25246evalcond[0]=(((new_r12*x2679))+((new_r02*x2680)));
25247evalcond[1]=((((-1.0)*x2679*x2682))+((x2679*x2683))+new_r02);
25248evalcond[2]=((((-1.0)*x2680*x2683))+new_r12+((x2680*x2682)));
25249evalcond[3]=((((-1.0)*x2682))+(((-1.0)*x2685))+x2686+x2683);
25250evalcond[4]=((((-1.0)*x2683*x2689))+(((-1.0)*x2682*x2690))+((new_r20*x2681))+((new_r20*x2684))+((x2683*x2690))+((x2682*x2689)));
25251evalcond[5]=((((-1.0)*x2683*x2687))+((x2683*x2688))+(((-1.0)*x2682*x2688))+((x2682*x2687))+((new_r21*x2684))+((new_r21*x2681)));
25252evalcond[6]=(((new_r22*x2683))+(((-1.0)*x2684*x2685))+(((-1.0)*new_r22*x2682))+((x2684*x2686))+(((-1.0)*x2681*x2685))+((x2681*x2686)));
25253evalcond[7]=((-1.0)+((new_r22*x2681))+((new_r22*x2684))+(((-1.0)*x2683*x2686))+((x2683*x2685))+(((-1.0)*x2682*x2685))+((x2682*x2686)));
25254if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH )
25255{
25256continue;
25257}
25258}
25259
25260{
25261IkReal j3array[1], cj3array[1], sj3array[1];
25262bool j3valid[1]={false};
25263_nj3 = 1;
25264if( IKabs(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj5*new_r11))+((new_r01*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))))+IKsqr((((cj5*new_r11))+((new_r01*sj5))))-1) <= IKFAST_SINCOS_THRESH )
25265 continue;
25266j3array[0]=IKatan2(((((-1.0)*new_r00*sj5))+(((-1.0)*cj5*new_r10))), (((cj5*new_r11))+((new_r01*sj5))));
25267sj3array[0]=IKsin(j3array[0]);
25268cj3array[0]=IKcos(j3array[0]);
25269if( j3array[0] > IKPI )
25270{
25271 j3array[0]-=IK2PI;
25272}
25273else if( j3array[0] < -IKPI )
25274{ j3array[0]+=IK2PI;
25275}
25276j3valid[0] = true;
25277for(int ij3 = 0; ij3 < 1; ++ij3)
25278{
25279if( !j3valid[ij3] )
25280{
25281 continue;
25282}
25283_ij3[0] = ij3; _ij3[1] = -1;
25284for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25285{
25286if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25287{
25288 j3valid[iij3]=false; _ij3[1] = iij3; break;
25289}
25290}
25291j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25292{
25293IkReal evalcond[12];
25294IkReal x2691=IKcos(j3);
25295IkReal x2692=IKsin(j3);
25296IkReal x2693=((0.9999999992)*cj4);
25297IkReal x2694=((3.9999999968e-5)*cj4);
25298IkReal x2695=(cj5*new_r01);
25299IkReal x2696=((0.9999999992)*sj4);
25300IkReal x2697=(cj5*new_r00);
25301IkReal x2698=((3.9999999968e-5)*sj4);
25302IkReal x2699=(new_r10*sj5);
25303IkReal x2700=(new_r11*sj5);
25304IkReal x2701=((1.0)*x2691);
25305IkReal x2702=(cj5*x2692);
25306IkReal x2703=(sj5*x2691);
25307IkReal x2704=(sj5*x2692);
25308IkReal x2705=(cj5*x2691);
25309IkReal x2706=(x2691*x2698);
25310evalcond[0]=(((cj5*new_r10))+((new_r00*sj5))+x2692);
25311evalcond[1]=(((cj5*new_r11))+((new_r01*sj5))+(((-1.0)*x2701)));
25312evalcond[2]=(((x2691*x2694))+(((-1.0)*x2691*x2696))+new_r20);
25313evalcond[3]=((((-1.0)*x2692*x2696))+new_r21+((x2692*x2694)));
25314evalcond[4]=((((-1.0)*x2691*x2693))+(((-1.0)*x2706))+(((-1.0)*x2699))+x2697);
25315evalcond[5]=((((-1.0)*x2692*x2693))+(((-1.0)*x2692*x2698))+(((-1.0)*x2700))+x2695);
25316evalcond[6]=(x2704+new_r00+(((-1.0)*x2693*x2705))+(((-1.0)*x2698*x2705)));
25317evalcond[7]=(x2702+((x2693*x2703))+((x2698*x2703))+new_r10);
25318evalcond[8]=((((-1.0)*sj5*x2701))+new_r01+(((-1.0)*x2693*x2702))+(((-1.0)*x2698*x2702)));
25319evalcond[9]=((((-1.0)*cj5*x2701))+((x2693*x2704))+((x2698*x2704))+new_r11);
25320evalcond[10]=(((x2697*x2698))+(((-1.0)*new_r20*x2694))+((x2693*x2697))+(((-1.0)*x2698*x2699))+(((-1.0)*x2701))+((new_r20*x2696))+(((-1.0)*x2693*x2699)));
25321evalcond[11]=(((x2693*x2695))+((x2695*x2698))+(((-1.0)*x2692))+((new_r21*x2696))+(((-1.0)*new_r21*x2694))+(((-1.0)*x2693*x2700))+(((-1.0)*x2698*x2700)));
25322if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH )
25323{
25324continue;
25325}
25326}
25327
25328{
25329std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
25330vinfos[0].jointtype = 1;
25331vinfos[0].foffset = j0;
25332vinfos[0].indices[0] = _ij0[0];
25333vinfos[0].indices[1] = _ij0[1];
25334vinfos[0].maxsolutions = _nj0;
25335vinfos[1].jointtype = 1;
25336vinfos[1].foffset = j1;
25337vinfos[1].indices[0] = _ij1[0];
25338vinfos[1].indices[1] = _ij1[1];
25339vinfos[1].maxsolutions = _nj1;
25340vinfos[2].jointtype = 1;
25341vinfos[2].foffset = j2;
25342vinfos[2].indices[0] = _ij2[0];
25343vinfos[2].indices[1] = _ij2[1];
25344vinfos[2].maxsolutions = _nj2;
25345vinfos[3].jointtype = 1;
25346vinfos[3].foffset = j3;
25347vinfos[3].indices[0] = _ij3[0];
25348vinfos[3].indices[1] = _ij3[1];
25349vinfos[3].maxsolutions = _nj3;
25350vinfos[4].jointtype = 1;
25351vinfos[4].foffset = j4;
25352vinfos[4].indices[0] = _ij4[0];
25353vinfos[4].indices[1] = _ij4[1];
25354vinfos[4].maxsolutions = _nj4;
25355vinfos[5].jointtype = 1;
25356vinfos[5].foffset = j5;
25357vinfos[5].indices[0] = _ij5[0];
25358vinfos[5].indices[1] = _ij5[1];
25359vinfos[5].maxsolutions = _nj5;
25360std::vector<int> vfree(0);
25361solutions.AddSolution(vinfos,vfree);
25362}
25363}
25364}
25365}
25366}
25367
25368}
25369
25370}
25371}
25372}
25373}
25374}static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots)
25375{
25376 using std::complex;
25377 if( rawcoeffs[0] == 0 ) {
25378 // solve with one reduced degree
25379 polyroots2(&rawcoeffs[1], &rawroots[0], numroots);
25380 return;
25381 }
25382 IKFAST_ASSERT(rawcoeffs[0] != 0);
25383 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25384 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25385 complex<IkReal> coeffs[3];
25386 const int maxsteps = 110;
25387 for(int i = 0; i < 3; ++i) {
25388 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25389 }
25390 complex<IkReal> roots[3];
25391 IkReal err[3];
25392 roots[0] = complex<IkReal>(1,0);
25393 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25394 err[0] = 1.0;
25395 err[1] = 1.0;
25396 for(int i = 2; i < 3; ++i) {
25397 roots[i] = roots[i-1]*roots[1];
25398 err[i] = 1.0;
25399 }
25400 for(int step = 0; step < maxsteps; ++step) {
25401 bool changed = false;
25402 for(int i = 0; i < 3; ++i) {
25403 if ( err[i] >= tol ) {
25404 changed = true;
25405 // evaluate
25406 complex<IkReal> x = roots[i] + coeffs[0];
25407 for(int j = 1; j < 3; ++j) {
25408 x = roots[i] * x + coeffs[j];
25409 }
25410 for(int j = 0; j < 3; ++j) {
25411 if( i != j ) {
25412 if( roots[i] != roots[j] ) {
25413 x /= (roots[i] - roots[j]);
25414 }
25415 }
25416 }
25417 roots[i] -= x;
25418 err[i] = abs(x);
25419 }
25420 }
25421 if( !changed ) {
25422 break;
25423 }
25424 }
25425
25426 numroots = 0;
25427 bool visited[3] = {false};
25428 for(int i = 0; i < 3; ++i) {
25429 if( !visited[i] ) {
25430 // might be a multiple root, in which case it will have more error than the other roots
25431 // find any neighboring roots, and take the average
25432 complex<IkReal> newroot=roots[i];
25433 int n = 1;
25434 for(int j = i+1; j < 3; ++j) {
25435 // care about error in real much more than imaginary
25436 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25437 newroot += roots[j];
25438 n += 1;
25439 visited[j] = true;
25440 }
25441 }
25442 if( n > 1 ) {
25443 newroot /= n;
25444 }
25445 // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
25446 if( IKabs(imag(newroot)) < tolsqrt ) {
25447 rawroots[numroots++] = real(newroot);
25448 }
25449 }
25450 }
25451}
25452static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) {
25453 IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2];
25454 if( det < 0 ) {
25455 numroots=0;
25456 }
25457 else if( det == 0 ) {
25458 rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0];
25459 numroots = 1;
25460 }
25461 else {
25462 det = IKsqrt(det);
25463 rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]);
25464 rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]);
25465 numroots = 2;
25466 }
25467}
25468static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
25469{
25470 using std::complex;
25471 if( rawcoeffs[0] == 0 ) {
25472 // solve with one reduced degree
25473 polyroots3(&rawcoeffs[1], &rawroots[0], numroots);
25474 return;
25475 }
25476 IKFAST_ASSERT(rawcoeffs[0] != 0);
25477 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25478 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25479 complex<IkReal> coeffs[4];
25480 const int maxsteps = 110;
25481 for(int i = 0; i < 4; ++i) {
25482 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25483 }
25484 complex<IkReal> roots[4];
25485 IkReal err[4];
25486 roots[0] = complex<IkReal>(1,0);
25487 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25488 err[0] = 1.0;
25489 err[1] = 1.0;
25490 for(int i = 2; i < 4; ++i) {
25491 roots[i] = roots[i-1]*roots[1];
25492 err[i] = 1.0;
25493 }
25494 for(int step = 0; step < maxsteps; ++step) {
25495 bool changed = false;
25496 for(int i = 0; i < 4; ++i) {
25497 if ( err[i] >= tol ) {
25498 changed = true;
25499 // evaluate
25500 complex<IkReal> x = roots[i] + coeffs[0];
25501 for(int j = 1; j < 4; ++j) {
25502 x = roots[i] * x + coeffs[j];
25503 }
25504 for(int j = 0; j < 4; ++j) {
25505 if( i != j ) {
25506 if( roots[i] != roots[j] ) {
25507 x /= (roots[i] - roots[j]);
25508 }
25509 }
25510 }
25511 roots[i] -= x;
25512 err[i] = abs(x);
25513 }
25514 }
25515 if( !changed ) {
25516 break;
25517 }
25518 }
25519
25520 numroots = 0;
25521 bool visited[4] = {false};
25522 for(int i = 0; i < 4; ++i) {
25523 if( !visited[i] ) {
25524 // might be a multiple root, in which case it will have more error than the other roots
25525 // find any neighboring roots, and take the average
25526 complex<IkReal> newroot=roots[i];
25527 int n = 1;
25528 for(int j = i+1; j < 4; ++j) {
25529 // care about error in real much more than imaginary
25530 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25531 newroot += roots[j];
25532 n += 1;
25533 visited[j] = true;
25534 }
25535 }
25536 if( n > 1 ) {
25537 newroot /= n;
25538 }
25539 // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
25540 if( IKabs(imag(newroot)) < tolsqrt ) {
25541 rawroots[numroots++] = real(newroot);
25542 }
25543 }
25544 }
25545}
25546};
25547
25548
25549/// solves the inverse kinematics equations.
25550/// \param pfree is an array specifying the free joints of the chain.
25551IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
25552IKSolver solver;
25553return solver.ComputeIk(eetrans,eerot,pfree,solutions);
25554}
25555
25556IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions, void* pOpenRAVEManip) {
25557IKSolver solver;
25558return solver.ComputeIk(eetrans,eerot,pfree,solutions);
25559}
25560
25561IKFAST_API const char* GetKinematicsHash() { return "<robot:GenericRobot - irb4600 (cf95c00c17c4b2b3fc4659a63b598d9c)>"; }
25562
25563IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; }
25564
25565#ifdef IKFAST_NAMESPACE
25566} // end namespace
25567#endif
25568
25569#ifndef IKFAST_NO_MAIN
25570#include <stdio.h>
25571#include <stdlib.h>
25572#ifdef IKFAST_NAMESPACE
25573using namespace IKFAST_NAMESPACE;
25574#endif
25575int main(int argc, char** argv)
25576{
25577 if( argc != 12+GetNumFreeParameters()+1 ) {
25578 printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
25579 "Returns the ik solutions given the transformation of the end effector specified by\n"
25580 "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
25581 "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
25582 return 1;
25583 }
25584
25585 IkSolutionList<IkReal> solutions;
25586 std::vector<IkReal> vfree(GetNumFreeParameters());
25587 IkReal eerot[9],eetrans[3];
25588 eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
25589 eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
25590 eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
25591 for(std::size_t i = 0; i < vfree.size(); ++i)
25592 vfree[i] = atof(argv[13+i]);
25593 bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
25594
25595 if( !bSuccess ) {
25596 fprintf(stderr,"Failed to get ik solution\n");
25597 return -1;
25598 }
25599
25600 printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
25601 std::vector<IkReal> solvalues(GetNumJoints());
25602 for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
25603 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
25604 printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
25605 std::vector<IkReal> vsolfree(sol.GetFree().size());
25606 sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
25607 for( std::size_t j = 0; j < solvalues.size(); ++j)
25608 printf("%.15f, ", solvalues[j]);
25609 printf("\n");
25610 }
25611 return 0;
25612}
25613
25614#endif