blob: 86fae75ebe0caa762259011e1d8c6f8acbb13db5 [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 2018-01-21 23:37:30.503597
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;
302x0=IKcos(j[0]);
303x1=IKcos(j[2]);
304x2=IKsin(j[0]);
305x3=IKsin(j[1]);
306x4=IKsin(j[2]);
307x5=IKcos(j[3]);
308x6=IKcos(j[1]);
309x7=IKsin(j[3]);
310x8=IKcos(j[5]);
311x9=IKsin(j[5]);
312x10=IKcos(j[4]);
313x11=IKsin(j[4]);
314x12=((0.02075)*x3);
315x13=((0.03)*x5);
316x14=((1.0)*x2);
317x15=((1.0)*x6);
318x16=((0.296)*x5);
319x17=((0.03)*x11);
320x18=((0.03)*x7);
321x19=((1.0)*x3);
322x20=((0.02075)*x5);
323x21=((1.0)*x7);
324x22=((0.03)*x10);
325x23=(x0*x4);
326x24=(x0*x6);
327x25=(x2*x4);
328x26=(x6*x7);
329x27=(x2*x6);
330x28=(x0*x1);
331x29=(x1*x3);
332x30=(x1*x5*x6);
333x31=(x10*x4*x6);
334x32=(x19*x28);
335x33=(x0*x15*x5);
336x34=(x14*x5*x6);
337x35=(x14*x3*x4);
338x36=((((-1.0)*x32))+x25);
339x37=((((-1.0)*x35))+x28);
340x38=((((-1.0)*x19*x7))+x30);
341x39=((((-1.0)*x14*x4))+x32);
342x40=(((x19*x23))+((x1*x14)));
343x41=((-1.0)*x40);
344x42=(((x14*x29))+(((1.0)*x23)));
345x43=((-1.0)*x42);
346x44=(((x1*x15*x7))+((x19*x5)));
347x45=(x10*x37);
348x46=(x11*x38);
349x47=(x36*x5);
350x48=(x39*x7);
351x49=(x42*x7);
352x50=(x10*x41);
353x51=(x47+(((-1.0)*x0*x15*x7)));
354x52=(x31+x46);
355x53=((((-1.0)*x14*x26))+((x43*x5)));
356x54=(((x11*x51))+x50);
357x55=(((x11*x53))+x45);
358eerot[0]=(((x8*((x33+(((-1.0)*x21*x39))))))+((x54*x9)));
359eerot[1]=(((x54*x8))+((x9*(((((-1.0)*x33))+x48)))));
360eerot[2]=(((x11*x40))+((x10*x51)));
361eetrans[0]=(((x7*(((((-0.296)*x28*x3))+(((0.296)*x25))))))+((x9*((((x17*x51))+((x22*x41))))))+((x8*(((((-1.0)*x18*x39))+((x13*x24))))))+((x11*((((x20*x36))+(((-0.02075)*x24*x7))))))+(((0.416)*x24))+((x16*x24))+((x10*(((((-0.02075)*x1*x2))+(((-1.0)*x12*x23)))))));
362eerot[3]=(((x55*x9))+((x8*((x34+(((-1.0)*x21*x42)))))));
363eerot[4]=(((x9*(((((-1.0)*x34))+x49))))+((x55*x8)));
364eerot[5]=(((x11*(((((-1.0)*x28))+x35))))+((x10*x53)));
365eetrans[1]=(((x10*(((((-1.0)*x12*x25))+(((0.02075)*x28))))))+((x8*(((((-1.0)*x18*x42))+((x13*x27))))))+((x9*((((x17*x53))+((x22*x37))))))+((x7*(((((-0.296)*x23))+(((-0.296)*x2*x29))))))+((x11*((((x20*x43))+(((-0.02075)*x2*x26))))))+(((0.416)*x27))+((x16*x27)));
366eerot[6]=(((x44*x8))+((x52*x9)));
367eerot[7]=((((-1.0)*x44*x9))+((x52*x8)));
368eerot[8]=(((x10*x38))+(((-1.0)*x11*x15*x4)));
369IkReal x56=(x1*x6);
370eetrans[2]=((0.178)+(((0.02075)*x31))+((x11*(((((-1.0)*x12*x7))+((x20*x56))))))+(((0.416)*x3))+(((0.296)*x1*x26))+((x8*((((x18*x56))+((x13*x3))))))+((x16*x3))+((x9*((((x22*x4*x6))+((x17*x38)))))));
371}
372
373IKFAST_API int GetNumFreeParameters() { return 0; }
374IKFAST_API int* GetFreeParameters() { return NULL; }
375IKFAST_API int GetNumJoints() { return 6; }
376
377IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
378
379IKFAST_API int GetIkType() { return 0x67000001; }
380
381class IKSolver {
382public:
383IkReal 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;
384unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5;
385
386IkReal j100, cj100, sj100;
387unsigned char _ij100[2], _nj100;
388bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
389j0=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;
390for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
391 solutions.Clear();
392r00 = eerot[0*3+0];
393r01 = eerot[0*3+1];
394r02 = eerot[0*3+2];
395r10 = eerot[1*3+0];
396r11 = eerot[1*3+1];
397r12 = eerot[1*3+2];
398r20 = eerot[2*3+0];
399r21 = eerot[2*3+1];
400r22 = eerot[2*3+2];
401px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
402
403new_r00=r01;
404new_r01=((-1.0)*r00);
405new_r02=r02;
406new_px=(px+(((-0.03)*r00)));
407new_r10=r11;
408new_r11=((-1.0)*r10);
409new_r12=r12;
410new_py=(py+(((-0.03)*r10)));
411new_r20=r21;
412new_r21=((-1.0)*r20);
413new_r22=r22;
414new_pz=((-0.178)+(((-0.03)*r20))+pz);
415r00 = 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;
416IkReal x57=((1.0)*px);
417IkReal x58=((1.0)*pz);
418IkReal x59=((1.0)*py);
419pp=((px*px)+(py*py)+(pz*pz));
420npx=(((px*r00))+((py*r10))+((pz*r20)));
421npy=(((px*r01))+((py*r11))+((pz*r21)));
422npz=(((px*r02))+((py*r12))+((pz*r22)));
423rxp0_0=((((-1.0)*r20*x59))+((pz*r10)));
424rxp0_1=(((px*r20))+(((-1.0)*r00*x58)));
425rxp0_2=((((-1.0)*r10*x57))+((py*r00)));
426rxp1_0=((((-1.0)*r21*x59))+((pz*r11)));
427rxp1_1=(((px*r21))+(((-1.0)*r01*x58)));
428rxp1_2=((((-1.0)*r11*x57))+((py*r01)));
429rxp2_0=(((pz*r12))+(((-1.0)*r22*x59)));
430rxp2_1=(((px*r22))+(((-1.0)*r02*x58)));
431rxp2_2=((((-1.0)*r12*x57))+((py*r02)));
432{
433IkReal j4eval[1];
434IkReal x60=pp*pp;
435IkReal x61=npz*npz;
436IkReal x62=((0.030003082397184)*npz);
437IkReal x63=((0.114909184)*npz*pp);
438j4eval[0]=((((2.0)*(IKabs((x63+(((-1.0)*x62)))))))+(((1.95033419776)*(IKabs(x61))))+(IKabs(((-0.00520874343240181)+(((-0.242599591936)*x61))+(((0.361482920448)*pp))+(((-0.692224)*x60)))))+(IKabs(((0.0104174868648036)+(((-1.465135013888)*x61))+(((1.384448)*x60))+(((-0.722965840896)*pp)))))+(((2.0)*(IKabs((x62+(((-1.0)*x63))))))));
439if( IKabs(j4eval[0]) < 0.0000000100000000 )
440{
441continue; // no branches [j3, j4, j5]
442
443} else
444{
445IkReal op[8+1], zeror[8];
446int numroots;
447IkReal x64=npz*npz;
448IkReal x65=pp*pp;
449IkReal x66=((0.030003082397184)*npz);
450IkReal x67=((0.114909184)*npz*pp);
451IkReal x68=(x66+(((-1.0)*x67)));
452IkReal x69=((-0.97516709888)*x64);
453IkReal x70=(x67+(((-1.0)*x66)));
454IkReal x71=((-0.00520874343240181)+(((-0.242599591936)*x64))+(((0.361482920448)*pp))+(((-0.692224)*x65)));
455op[0]=x71;
456op[1]=x68;
457op[2]=x69;
458op[3]=x68;
459op[4]=((0.0104174868648036)+(((-1.465135013888)*x64))+(((1.384448)*x65))+(((-0.722965840896)*pp)));
460op[5]=x70;
461op[6]=x69;
462op[7]=x70;
463op[8]=x71;
464polyroots8(op,zeror,numroots);
465IkReal j4array[8], cj4array[8], sj4array[8], tempj4array[1];
466int numsolutions = 0;
467for(int ij4 = 0; ij4 < numroots; ++ij4)
468{
469IkReal htj4 = zeror[ij4];
470tempj4array[0]=((2.0)*(atan(htj4)));
471for(int kj4 = 0; kj4 < 1; ++kj4)
472{
473j4array[numsolutions] = tempj4array[kj4];
474if( j4array[numsolutions] > IKPI )
475{
476 j4array[numsolutions]-=IK2PI;
477}
478else if( j4array[numsolutions] < -IKPI )
479{
480 j4array[numsolutions]+=IK2PI;
481}
482sj4array[numsolutions] = IKsin(j4array[numsolutions]);
483cj4array[numsolutions] = IKcos(j4array[numsolutions]);
484numsolutions++;
485}
486}
487bool j4valid[8]={true,true,true,true,true,true,true,true};
488_nj4 = 8;
489for(int ij4 = 0; ij4 < numsolutions; ++ij4)
490 {
491if( !j4valid[ij4] )
492{
493 continue;
494}
495 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
496htj4 = IKtan(j4/2);
497
498_ij4[0] = ij4; _ij4[1] = -1;
499for(int iij4 = ij4+1; iij4 < numsolutions; ++iij4)
500{
501if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
502{
503 j4valid[iij4]=false; _ij4[1] = iij4; break;
504}
505}
506{
507IkReal j3eval[1];
508j3eval[0]=cj4;
509if( IKabs(j3eval[0]) < 0.0000010000000000 )
510{
511{
512IkReal j5eval[2];
513IkReal x72=cj4*cj4;
514j5eval[0]=(((x72*(npx*npx)))+((x72*(npy*npy))));
515j5eval[1]=((IKabs((cj4*npy)))+(IKabs((cj4*npx))));
516if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 )
517{
518{
519IkReal evalcond[2];
520bool bgotonextstatement = true;
521do
522{
523evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959)));
524evalcond[1]=npz;
525if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
526{
527bgotonextstatement=false;
528{
529IkReal j3array[2], cj3array[2], sj3array[2];
530bool j3valid[2]={false};
531_nj3 = 2;
532if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH )
533 continue;
534IkReal x73=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp))));
535j3array[0]=((1.50080946872133)+(((-1.0)*x73)));
536sj3array[0]=IKsin(j3array[0]);
537cj3array[0]=IKcos(j3array[0]);
538j3array[1]=((4.64240212231113)+x73);
539sj3array[1]=IKsin(j3array[1]);
540cj3array[1]=IKcos(j3array[1]);
541if( j3array[0] > IKPI )
542{
543 j3array[0]-=IK2PI;
544}
545else if( j3array[0] < -IKPI )
546{ j3array[0]+=IK2PI;
547}
548j3valid[0] = true;
549if( j3array[1] > IKPI )
550{
551 j3array[1]-=IK2PI;
552}
553else if( j3array[1] < -IKPI )
554{ j3array[1]+=IK2PI;
555}
556j3valid[1] = true;
557for(int ij3 = 0; ij3 < 2; ++ij3)
558{
559if( !j3valid[ij3] )
560{
561 continue;
562}
563_ij3[0] = ij3; _ij3[1] = -1;
564for(int iij3 = ij3+1; iij3 < 2; ++iij3)
565{
566if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
567{
568 j3valid[iij3]=false; _ij3[1] = iij3; break;
569}
570}
571j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
572
573{
574IkReal j5eval[3];
575sj4=1.0;
576cj4=0;
577j4=1.5707963267949;
578IkReal x74=((0.416)*cj3);
579IkReal x75=((0.416)*sj3);
580IkReal x76=((npx*npx)+(npy*npy));
581j5eval[0]=x76;
582j5eval[1]=((IKabs(((((-1.0)*npy*x74))+(((-1.0)*npx*x75))+(((0.02075)*npx))+(((-0.296)*npy)))))+(IKabs(((((-1.0)*npx*x74))+(((-0.02075)*npy))+((npy*x75))+(((-0.296)*npx))))));
583j5eval[2]=IKsign(x76);
584if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
585{
586{
587IkReal j5eval[3];
588sj4=1.0;
589cj4=0;
590j4=1.5707963267949;
591IkReal x77=npx*npx;
592IkReal x78=npy*npy;
593IkReal x79=(cj3*npy);
594IkReal x80=(cj3*npx);
595IkReal x81=((2000.0)*pp);
596j5eval[0]=(x77+x78);
597j5eval[1]=IKsign(((((83.0)*x77))+(((83.0)*x78))));
598j5eval[2]=((IKabs(((((492.544)*x79))+(((-24.568)*npx))+(((-34.528)*x80))+(((-1.0)*npy*x81))+(((520.482875)*npy)))))+(IKabs(((((-520.482875)*npx))+(((-492.544)*x80))+(((-24.568)*npy))+(((-34.528)*x79))+((npx*x81))))));
599if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
600{
601continue; // no branches [j5]
602
603} else
604{
605{
606IkReal j5array[1], cj5array[1], sj5array[1];
607bool j5valid[1]={false};
608_nj5 = 1;
609IkReal x82=(cj3*npy);
610IkReal x83=(cj3*npx);
611IkReal x84=((2000.0)*pp);
612CheckValue<IkReal> x85 = IKatan2WithCheck(IkReal(((((-24.568)*npx))+(((-34.528)*x83))+(((-1.0)*npy*x84))+(((492.544)*x82))+(((520.482875)*npy)))),IkReal(((((-520.482875)*npx))+(((-492.544)*x83))+(((-24.568)*npy))+(((-34.528)*x82))+((npx*x84)))),IKFAST_ATAN2_MAGTHRESH);
613if(!x85.valid){
614continue;
615}
616CheckValue<IkReal> x86=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1);
617if(!x86.valid){
618continue;
619}
620j5array[0]=((-1.5707963267949)+(x85.value)+(((1.5707963267949)*(x86.value))));
621sj5array[0]=IKsin(j5array[0]);
622cj5array[0]=IKcos(j5array[0]);
623if( j5array[0] > IKPI )
624{
625 j5array[0]-=IK2PI;
626}
627else if( j5array[0] < -IKPI )
628{ j5array[0]+=IK2PI;
629}
630j5valid[0] = true;
631for(int ij5 = 0; ij5 < 1; ++ij5)
632{
633if( !j5valid[ij5] )
634{
635 continue;
636}
637_ij5[0] = ij5; _ij5[1] = -1;
638for(int iij5 = ij5+1; iij5 < 1; ++iij5)
639{
640if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
641{
642 j5valid[iij5]=false; _ij5[1] = iij5; break;
643}
644}
645j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
646{
647IkReal evalcond[3];
648IkReal x87=IKcos(j5);
649IkReal x88=IKsin(j5);
650IkReal x89=((1.0)*x87);
651IkReal x90=(npy*x88);
652evalcond[0]=((0.02075)+(((-0.416)*sj3))+x90+(((-1.0)*npx*x89)));
653evalcond[1]=((-0.296)+(((-1.0)*npx*x88))+(((-0.416)*cj3))+(((-1.0)*npy*x89)));
654evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x87))+(((-0.246272)*cj3))+pp+(((0.0415)*x90)));
655if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
656{
657continue;
658}
659}
660
661rotationfunction0(solutions);
662}
663}
664
665}
666
667}
668
669} else
670{
671{
672IkReal j5array[1], cj5array[1], sj5array[1];
673bool j5valid[1]={false};
674_nj5 = 1;
675IkReal x1857=((0.416)*cj3);
676IkReal x1858=((0.416)*sj3);
677CheckValue<IkReal> x1859 = IKatan2WithCheck(IkReal(((((-1.0)*npx*x1857))+(((-0.02075)*npy))+((npy*x1858))+(((-0.296)*npx)))),IkReal(((((-1.0)*npy*x1857))+(((-1.0)*npx*x1858))+(((0.02075)*npx))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH);
678if(!x1859.valid){
679continue;
680}
681CheckValue<IkReal> x1860=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1);
682if(!x1860.valid){
683continue;
684}
685j5array[0]=((-1.5707963267949)+(x1859.value)+(((1.5707963267949)*(x1860.value))));
686sj5array[0]=IKsin(j5array[0]);
687cj5array[0]=IKcos(j5array[0]);
688if( j5array[0] > IKPI )
689{
690 j5array[0]-=IK2PI;
691}
692else if( j5array[0] < -IKPI )
693{ j5array[0]+=IK2PI;
694}
695j5valid[0] = true;
696for(int ij5 = 0; ij5 < 1; ++ij5)
697{
698if( !j5valid[ij5] )
699{
700 continue;
701}
702_ij5[0] = ij5; _ij5[1] = -1;
703for(int iij5 = ij5+1; iij5 < 1; ++iij5)
704{
705if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
706{
707 j5valid[iij5]=false; _ij5[1] = iij5; break;
708}
709}
710j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
711{
712IkReal evalcond[3];
713IkReal x1861=IKcos(j5);
714IkReal x1862=IKsin(j5);
715IkReal x1863=((1.0)*x1861);
716IkReal x1864=(npy*x1862);
717evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1863))+x1864);
718evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x1862))+(((-1.0)*npy*x1863)));
719evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((0.0415)*x1864))+(((-0.0415)*npx*x1861)));
720if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
721{
722continue;
723}
724}
725
726rotationfunction0(solutions);
727}
728}
729
730}
731
732}
733}
734}
735
736}
737} while(0);
738if( bgotonextstatement )
739{
740bool bgotonextstatement = true;
741do
742{
743evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959)));
744if( IKabs(evalcond[0]) < 0.0000050000000000 )
745{
746bgotonextstatement=false;
747{
748IkReal j3array[2], cj3array[2], sj3array[2];
749bool j3valid[2]={false};
750_nj3 = 2;
751if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH )
752 continue;
753IkReal x1865=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp))));
754j3array[0]=((1.64078318486846)+(((-1.0)*x1865)));
755sj3array[0]=IKsin(j3array[0]);
756cj3array[0]=IKcos(j3array[0]);
757j3array[1]=((4.78237583845825)+x1865);
758sj3array[1]=IKsin(j3array[1]);
759cj3array[1]=IKcos(j3array[1]);
760if( j3array[0] > IKPI )
761{
762 j3array[0]-=IK2PI;
763}
764else if( j3array[0] < -IKPI )
765{ j3array[0]+=IK2PI;
766}
767j3valid[0] = true;
768if( j3array[1] > IKPI )
769{
770 j3array[1]-=IK2PI;
771}
772else if( j3array[1] < -IKPI )
773{ j3array[1]+=IK2PI;
774}
775j3valid[1] = true;
776for(int ij3 = 0; ij3 < 2; ++ij3)
777{
778if( !j3valid[ij3] )
779{
780 continue;
781}
782_ij3[0] = ij3; _ij3[1] = -1;
783for(int iij3 = ij3+1; iij3 < 2; ++iij3)
784{
785if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
786{
787 j3valid[iij3]=false; _ij3[1] = iij3; break;
788}
789}
790j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
791
792{
793IkReal j5eval[3];
794sj4=-1.0;
795cj4=0;
796j4=-1.5707963267949;
797IkReal x1866=((0.416)*cj3);
798IkReal x1867=((0.416)*sj3);
799IkReal x1868=((npx*npx)+(npy*npy));
800j5eval[0]=x1868;
801j5eval[1]=IKsign(x1868);
802j5eval[2]=((IKabs(((((-0.02075)*npy))+(((-1.0)*npy*x1867))+(((-1.0)*npx*x1866))+(((-0.296)*npx)))))+(IKabs(((((-1.0)*npy*x1866))+(((0.02075)*npx))+((npx*x1867))+(((-0.296)*npy))))));
803if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
804{
805{
806IkReal j5eval[3];
807sj4=-1.0;
808cj4=0;
809j4=-1.5707963267949;
810IkReal x1869=npx*npx;
811IkReal x1870=npy*npy;
812IkReal x1871=(cj3*npy);
813IkReal x1872=(cj3*npx);
814IkReal x1873=((2000.0)*pp);
815j5eval[0]=(x1869+x1870);
816j5eval[1]=IKsign(((((83.0)*x1869))+(((83.0)*x1870))));
817j5eval[2]=((IKabs(((((-1.0)*npy*x1873))+(((-24.568)*npx))+(((-34.528)*x1872))+(((520.482875)*npy))+(((492.544)*x1871)))))+(IKabs((((npx*x1873))+(((-520.482875)*npx))+(((-492.544)*x1872))+(((-24.568)*npy))+(((-34.528)*x1871))))));
818if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
819{
820continue; // no branches [j5]
821
822} else
823{
824{
825IkReal j5array[1], cj5array[1], sj5array[1];
826bool j5valid[1]={false};
827_nj5 = 1;
828IkReal x1874=(cj3*npy);
829IkReal x1875=(cj3*npx);
830IkReal x1876=((2000.0)*pp);
831CheckValue<IkReal> x1877 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1876))+(((-24.568)*npx))+(((-34.528)*x1875))+(((520.482875)*npy))+(((492.544)*x1874)))),IkReal((((npx*x1876))+(((-520.482875)*npx))+(((-492.544)*x1875))+(((-24.568)*npy))+(((-34.528)*x1874)))),IKFAST_ATAN2_MAGTHRESH);
832if(!x1877.valid){
833continue;
834}
835CheckValue<IkReal> x1878=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1);
836if(!x1878.valid){
837continue;
838}
839j5array[0]=((-1.5707963267949)+(x1877.value)+(((1.5707963267949)*(x1878.value))));
840sj5array[0]=IKsin(j5array[0]);
841cj5array[0]=IKcos(j5array[0]);
842if( j5array[0] > IKPI )
843{
844 j5array[0]-=IK2PI;
845}
846else if( j5array[0] < -IKPI )
847{ j5array[0]+=IK2PI;
848}
849j5valid[0] = true;
850for(int ij5 = 0; ij5 < 1; ++ij5)
851{
852if( !j5valid[ij5] )
853{
854 continue;
855}
856_ij5[0] = ij5; _ij5[1] = -1;
857for(int iij5 = ij5+1; iij5 < 1; ++iij5)
858{
859if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
860{
861 j5valid[iij5]=false; _ij5[1] = iij5; break;
862}
863}
864j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
865{
866IkReal evalcond[3];
867IkReal x1879=IKcos(j5);
868IkReal x1880=IKsin(j5);
869IkReal x1881=((1.0)*x1879);
870IkReal x1882=(npy*x1880);
871evalcond[0]=((0.02075)+(((-1.0)*npx*x1881))+x1882+(((0.416)*sj3)));
872evalcond[1]=((-0.296)+(((-1.0)*npx*x1880))+(((-0.416)*cj3))+(((-1.0)*npy*x1881)));
873evalcond[2]=((-0.2602414375)+(((0.0415)*x1882))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1879)));
874if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
875{
876continue;
877}
878}
879
880rotationfunction0(solutions);
881}
882}
883
884}
885
886}
887
888} else
889{
890{
891IkReal j5array[1], cj5array[1], sj5array[1];
892bool j5valid[1]={false};
893_nj5 = 1;
894IkReal x1883=((0.416)*cj3);
895IkReal x1884=((0.416)*sj3);
896CheckValue<IkReal> x1885 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npx*x1883))+(((-0.296)*npx))+(((-1.0)*npy*x1884)))),IkReal(((((0.02075)*npx))+(((-0.296)*npy))+(((-1.0)*npy*x1883))+((npx*x1884)))),IKFAST_ATAN2_MAGTHRESH);
897if(!x1885.valid){
898continue;
899}
900CheckValue<IkReal> x1886=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1);
901if(!x1886.valid){
902continue;
903}
904j5array[0]=((-1.5707963267949)+(x1885.value)+(((1.5707963267949)*(x1886.value))));
905sj5array[0]=IKsin(j5array[0]);
906cj5array[0]=IKcos(j5array[0]);
907if( j5array[0] > IKPI )
908{
909 j5array[0]-=IK2PI;
910}
911else if( j5array[0] < -IKPI )
912{ j5array[0]+=IK2PI;
913}
914j5valid[0] = true;
915for(int ij5 = 0; ij5 < 1; ++ij5)
916{
917if( !j5valid[ij5] )
918{
919 continue;
920}
921_ij5[0] = ij5; _ij5[1] = -1;
922for(int iij5 = ij5+1; iij5 < 1; ++iij5)
923{
924if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
925{
926 j5valid[iij5]=false; _ij5[1] = iij5; break;
927}
928}
929j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
930{
931IkReal evalcond[3];
932IkReal x1887=IKcos(j5);
933IkReal x1888=IKsin(j5);
934IkReal x1889=((1.0)*x1887);
935IkReal x1890=(npy*x1888);
936evalcond[0]=((0.02075)+(((-1.0)*npx*x1889))+x1890+(((0.416)*sj3)));
937evalcond[1]=((-0.296)+(((-1.0)*npx*x1888))+(((-0.416)*cj3))+(((-1.0)*npy*x1889)));
938evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1887))+(((0.0415)*x1890)));
939if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
940{
941continue;
942}
943}
944
945rotationfunction0(solutions);
946}
947}
948
949}
950
951}
952}
953}
954
955}
956} while(0);
957if( bgotonextstatement )
958{
959bool bgotonextstatement = true;
960do
961{
962if( 1 )
963{
964bgotonextstatement=false;
965continue; // branch miss [j3, j5]
966
967}
968} while(0);
969if( bgotonextstatement )
970{
971}
972}
973}
974}
975
976} else
977{
978{
979IkReal j5array[2], cj5array[2], sj5array[2];
980bool j5valid[2]={false};
981_nj5 = 2;
982IkReal x1891=cj4*cj4;
983CheckValue<IkReal> x1894 = IKatan2WithCheck(IkReal(((-1.0)*cj4*npx)),IkReal((cj4*npy)),IKFAST_ATAN2_MAGTHRESH);
984if(!x1894.valid){
985continue;
986}
987IkReal x1892=((1.0)*(x1894.value));
988if(((((x1891*(npy*npy)))+((x1891*(npx*npx))))) < -0.00001)
989continue;
990CheckValue<IkReal> x1895=IKPowWithIntegerCheck(IKabs(IKsqrt((((x1891*(npy*npy)))+((x1891*(npx*npx)))))),-1);
991if(!x1895.valid){
992continue;
993}
994if( (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) < -1-IKFAST_SINCOS_THRESH || (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) > 1+IKFAST_SINCOS_THRESH )
995 continue;
996IkReal x1893=IKasin(((x1895.value)*(((((0.02075)*cj4))+((npz*sj4))))));
997j5array[0]=((((-1.0)*x1893))+(((-1.0)*x1892)));
998sj5array[0]=IKsin(j5array[0]);
999cj5array[0]=IKcos(j5array[0]);
1000j5array[1]=((3.14159265358979)+x1893+(((-1.0)*x1892)));
1001sj5array[1]=IKsin(j5array[1]);
1002cj5array[1]=IKcos(j5array[1]);
1003if( j5array[0] > IKPI )
1004{
1005 j5array[0]-=IK2PI;
1006}
1007else if( j5array[0] < -IKPI )
1008{ j5array[0]+=IK2PI;
1009}
1010j5valid[0] = true;
1011if( j5array[1] > IKPI )
1012{
1013 j5array[1]-=IK2PI;
1014}
1015else if( j5array[1] < -IKPI )
1016{ j5array[1]+=IK2PI;
1017}
1018j5valid[1] = true;
1019for(int ij5 = 0; ij5 < 2; ++ij5)
1020{
1021if( !j5valid[ij5] )
1022{
1023 continue;
1024}
1025_ij5[0] = ij5; _ij5[1] = -1;
1026for(int iij5 = ij5+1; iij5 < 2; ++iij5)
1027{
1028if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1029{
1030 j5valid[iij5]=false; _ij5[1] = iij5; break;
1031}
1032}
1033j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1034
1035{
1036IkReal j3eval[1];
1037j3eval[0]=cj4;
1038if( IKabs(j3eval[0]) < 0.0000010000000000 )
1039{
1040{
1041IkReal j3eval[1];
1042j3eval[0]=sj4;
1043if( IKabs(j3eval[0]) < 0.0000010000000000 )
1044{
1045{
1046IkReal evalcond[2];
1047bool bgotonextstatement = true;
1048do
1049{
1050evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959)));
1051if( IKabs(evalcond[0]) < 0.0000050000000000 )
1052{
1053bgotonextstatement=false;
1054{
1055IkReal j3array[1], cj3array[1], sj3array[1];
1056bool j3valid[1]={false};
1057_nj3 = 1;
1058if( IKabs(((-2.40384615384615)*npz)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.06022025443412)+(((4.06055093555094)*pp)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz))+IKsqr(((-1.06022025443412)+(((4.06055093555094)*pp))))-1) <= IKFAST_SINCOS_THRESH )
1059 continue;
1060j3array[0]=IKatan2(((-2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp))));
1061sj3array[0]=IKsin(j3array[0]);
1062cj3array[0]=IKcos(j3array[0]);
1063if( j3array[0] > IKPI )
1064{
1065 j3array[0]-=IK2PI;
1066}
1067else if( j3array[0] < -IKPI )
1068{ j3array[0]+=IK2PI;
1069}
1070j3valid[0] = true;
1071for(int ij3 = 0; ij3 < 1; ++ij3)
1072{
1073if( !j3valid[ij3] )
1074{
1075 continue;
1076}
1077_ij3[0] = ij3; _ij3[1] = -1;
1078for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1079{
1080if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1081{
1082 j3valid[iij3]=false; _ij3[1] = iij3; break;
1083}
1084}
1085j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1086{
1087IkReal evalcond[3];
1088IkReal x1896=IKcos(j3);
1089evalcond[0]=((-0.2611025625)+(((-0.246272)*x1896))+pp);
1090evalcond[1]=((((-1.0)*npz))+(((-0.416)*(IKsin(j3)))));
1091evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1896)));
1092if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1093{
1094continue;
1095}
1096}
1097
1098rotationfunction0(solutions);
1099}
1100}
1101
1102}
1103} while(0);
1104if( bgotonextstatement )
1105{
1106bool bgotonextstatement = true;
1107do
1108{
1109evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959)));
1110if( IKabs(evalcond[0]) < 0.0000050000000000 )
1111{
1112bgotonextstatement=false;
1113{
1114IkReal j3array[1], cj3array[1], sj3array[1];
1115bool j3valid[1]={false};
1116_nj3 = 1;
1117if( IKabs(((2.40384615384615)*npz)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.06022025443412)+(((4.06055093555094)*pp)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((2.40384615384615)*npz))+IKsqr(((-1.06022025443412)+(((4.06055093555094)*pp))))-1) <= IKFAST_SINCOS_THRESH )
1118 continue;
1119j3array[0]=IKatan2(((2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp))));
1120sj3array[0]=IKsin(j3array[0]);
1121cj3array[0]=IKcos(j3array[0]);
1122if( j3array[0] > IKPI )
1123{
1124 j3array[0]-=IK2PI;
1125}
1126else if( j3array[0] < -IKPI )
1127{ j3array[0]+=IK2PI;
1128}
1129j3valid[0] = true;
1130for(int ij3 = 0; ij3 < 1; ++ij3)
1131{
1132if( !j3valid[ij3] )
1133{
1134 continue;
1135}
1136_ij3[0] = ij3; _ij3[1] = -1;
1137for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1138{
1139if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1140{
1141 j3valid[iij3]=false; _ij3[1] = iij3; break;
1142}
1143}
1144j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1145{
1146IkReal evalcond[3];
1147IkReal x1897=IKcos(j3);
1148evalcond[0]=((-0.2611025625)+(((-0.246272)*x1897))+pp);
1149evalcond[1]=((((-1.0)*npz))+(((0.416)*(IKsin(j3)))));
1150evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1897)));
1151if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1152{
1153continue;
1154}
1155}
1156
1157rotationfunction0(solutions);
1158}
1159}
1160
1161}
1162} while(0);
1163if( bgotonextstatement )
1164{
1165bool bgotonextstatement = true;
1166do
1167{
1168evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959)));
1169evalcond[1]=npz;
1170if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
1171{
1172bgotonextstatement=false;
1173{
1174IkReal j3array[1], cj3array[1], sj3array[1];
1175bool j3valid[1]={false};
1176_nj3 = 1;
1177IkReal x1898=(cj5*npx);
1178IkReal x1899=(npy*sj5);
1179if( IKabs(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899))))+IKsqr(((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899))))-1) <= IKFAST_SINCOS_THRESH )
1180 continue;
1181j3array[0]=IKatan2(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899))), ((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899))));
1182sj3array[0]=IKsin(j3array[0]);
1183cj3array[0]=IKcos(j3array[0]);
1184if( j3array[0] > IKPI )
1185{
1186 j3array[0]-=IK2PI;
1187}
1188else if( j3array[0] < -IKPI )
1189{ j3array[0]+=IK2PI;
1190}
1191j3valid[0] = true;
1192for(int ij3 = 0; ij3 < 1; ++ij3)
1193{
1194if( !j3valid[ij3] )
1195{
1196 continue;
1197}
1198_ij3[0] = ij3; _ij3[1] = -1;
1199for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1200{
1201if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1202{
1203 j3valid[iij3]=false; _ij3[1] = iij3; break;
1204}
1205}
1206j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1207{
1208IkReal evalcond[4];
1209IkReal x1900=IKsin(j3);
1210IkReal x1901=IKcos(j3);
1211IkReal x1902=(cj5*npx);
1212IkReal x1903=(npy*sj5);
1213IkReal x1904=((0.246272)*x1901);
1214evalcond[0]=((-0.2611025625)+(((0.017264)*x1900))+pp+(((-1.0)*x1904)));
1215evalcond[1]=((0.02075)+(((-0.416)*x1900))+(((-1.0)*x1902))+x1903);
1216evalcond[2]=((-0.296)+(((-0.416)*x1901))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5)));
1217evalcond[3]=((-0.2602414375)+(((0.0415)*x1903))+(((-0.0415)*x1902))+pp+(((-1.0)*x1904)));
1218if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
1219{
1220continue;
1221}
1222}
1223
1224rotationfunction0(solutions);
1225}
1226}
1227
1228}
1229} while(0);
1230if( bgotonextstatement )
1231{
1232bool bgotonextstatement = true;
1233do
1234{
1235evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959)));
1236if( IKabs(evalcond[0]) < 0.0000050000000000 )
1237{
1238bgotonextstatement=false;
1239{
1240IkReal j3array[1], cj3array[1], sj3array[1];
1241bool j3valid[1]={false};
1242_nj3 = 1;
1243IkReal x1905=(cj5*npx);
1244IkReal x1906=(npy*sj5);
1245if( IKabs(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906))))+IKsqr(((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906))))-1) <= IKFAST_SINCOS_THRESH )
1246 continue;
1247j3array[0]=IKatan2(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906))), ((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906))));
1248sj3array[0]=IKsin(j3array[0]);
1249cj3array[0]=IKcos(j3array[0]);
1250if( j3array[0] > IKPI )
1251{
1252 j3array[0]-=IK2PI;
1253}
1254else if( j3array[0] < -IKPI )
1255{ j3array[0]+=IK2PI;
1256}
1257j3valid[0] = true;
1258for(int ij3 = 0; ij3 < 1; ++ij3)
1259{
1260if( !j3valid[ij3] )
1261{
1262 continue;
1263}
1264_ij3[0] = ij3; _ij3[1] = -1;
1265for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1266{
1267if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1268{
1269 j3valid[iij3]=false; _ij3[1] = iij3; break;
1270}
1271}
1272j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1273{
1274IkReal evalcond[4];
1275IkReal x1907=IKsin(j3);
1276IkReal x1908=IKcos(j3);
1277IkReal x1909=(cj5*npx);
1278IkReal x1910=(npy*sj5);
1279IkReal x1911=((0.246272)*x1908);
1280evalcond[0]=((-0.2611025625)+(((-0.017264)*x1907))+pp+(((-1.0)*x1911)));
1281evalcond[1]=((0.02075)+(((0.416)*x1907))+(((-1.0)*x1909))+x1910);
1282evalcond[2]=((-0.296)+(((-0.416)*x1908))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5)));
1283evalcond[3]=((-0.2602414375)+(((-0.0415)*x1909))+pp+(((0.0415)*x1910))+(((-1.0)*x1911)));
1284if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
1285{
1286continue;
1287}
1288}
1289
1290rotationfunction0(solutions);
1291}
1292}
1293
1294}
1295} while(0);
1296if( bgotonextstatement )
1297{
1298bool bgotonextstatement = true;
1299do
1300{
1301if( 1 )
1302{
1303bgotonextstatement=false;
1304continue; // branch miss [j3]
1305
1306}
1307} while(0);
1308if( bgotonextstatement )
1309{
1310}
1311}
1312}
1313}
1314}
1315}
1316
1317} else
1318{
1319{
1320IkReal j3array[1], cj3array[1], sj3array[1];
1321bool j3valid[1]={false};
1322_nj3 = 1;
1323IkReal x1912=(npx*sj5);
1324IkReal x1913=(cj5*npy);
1325CheckValue<IkReal> x1914=IKPowWithIntegerCheck(sj4,-1);
1326if(!x1914.valid){
1327continue;
1328}
1329if( IKabs(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp))))))+IKsqr(((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913))))-1) <= IKFAST_SINCOS_THRESH )
1330 continue;
1331j3array[0]=IKatan2(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp))))), ((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913))));
1332sj3array[0]=IKsin(j3array[0]);
1333cj3array[0]=IKcos(j3array[0]);
1334if( j3array[0] > IKPI )
1335{
1336 j3array[0]-=IK2PI;
1337}
1338else if( j3array[0] < -IKPI )
1339{ j3array[0]+=IK2PI;
1340}
1341j3valid[0] = true;
1342for(int ij3 = 0; ij3 < 1; ++ij3)
1343{
1344if( !j3valid[ij3] )
1345{
1346 continue;
1347}
1348_ij3[0] = ij3; _ij3[1] = -1;
1349for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1350{
1351if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1352{
1353 j3valid[iij3]=false; _ij3[1] = iij3; break;
1354}
1355}
1356j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1357{
1358IkReal evalcond[6];
1359IkReal x1915=IKsin(j3);
1360IkReal x1916=IKcos(j3);
1361IkReal x1917=(cj5*npx);
1362IkReal x1918=((1.0)*npz);
1363IkReal x1919=(npy*sj5);
1364IkReal x1920=((0.246272)*x1916);
1365IkReal x1921=((0.416)*x1915);
1366evalcond[0]=((((-1.0)*cj4*x1921))+(((-1.0)*x1918)));
1367evalcond[1]=((-0.2611025625)+(((-1.0)*x1920))+pp+(((0.017264)*sj4*x1915)));
1368evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1916)));
1369evalcond[3]=((0.02075)+(((-1.0)*sj4*x1921))+(((-1.0)*x1917))+x1919);
1370evalcond[4]=((-0.2602414375)+(((-1.0)*x1920))+pp+(((-0.0415)*x1917))+(((0.0415)*x1919)));
1371evalcond[5]=((((-1.0)*cj4*x1918))+((sj4*x1919))+(((-1.0)*x1921))+(((-1.0)*sj4*x1917))+(((0.02075)*sj4)));
1372if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
1373{
1374continue;
1375}
1376}
1377
1378rotationfunction0(solutions);
1379}
1380}
1381
1382}
1383
1384}
1385
1386} else
1387{
1388{
1389IkReal j3array[1], cj3array[1], sj3array[1];
1390bool j3valid[1]={false};
1391_nj3 = 1;
1392CheckValue<IkReal> x1922=IKPowWithIntegerCheck(cj4,-1);
1393if(!x1922.valid){
1394continue;
1395}
1396if( IKabs(((-2.40384615384615)*npz*(x1922.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz*(x1922.value)))+IKsqr(((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5))))-1) <= IKFAST_SINCOS_THRESH )
1397 continue;
1398j3array[0]=IKatan2(((-2.40384615384615)*npz*(x1922.value)), ((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5))));
1399sj3array[0]=IKsin(j3array[0]);
1400cj3array[0]=IKcos(j3array[0]);
1401if( j3array[0] > IKPI )
1402{
1403 j3array[0]-=IK2PI;
1404}
1405else if( j3array[0] < -IKPI )
1406{ j3array[0]+=IK2PI;
1407}
1408j3valid[0] = true;
1409for(int ij3 = 0; ij3 < 1; ++ij3)
1410{
1411if( !j3valid[ij3] )
1412{
1413 continue;
1414}
1415_ij3[0] = ij3; _ij3[1] = -1;
1416for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1417{
1418if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1419{
1420 j3valid[iij3]=false; _ij3[1] = iij3; break;
1421}
1422}
1423j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1424{
1425IkReal evalcond[6];
1426IkReal x1923=IKsin(j3);
1427IkReal x1924=IKcos(j3);
1428IkReal x1925=(cj5*npx);
1429IkReal x1926=((1.0)*npz);
1430IkReal x1927=(npy*sj5);
1431IkReal x1928=((0.246272)*x1924);
1432IkReal x1929=((0.416)*x1923);
1433evalcond[0]=((((-1.0)*cj4*x1929))+(((-1.0)*x1926)));
1434evalcond[1]=((-0.2611025625)+(((-1.0)*x1928))+pp+(((0.017264)*sj4*x1923)));
1435evalcond[2]=((-0.296)+(((-0.416)*x1924))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5)));
1436evalcond[3]=((0.02075)+(((-1.0)*x1925))+(((-1.0)*sj4*x1929))+x1927);
1437evalcond[4]=((-0.2602414375)+(((-0.0415)*x1925))+(((-1.0)*x1928))+pp+(((0.0415)*x1927)));
1438evalcond[5]=(((sj4*x1927))+(((-1.0)*sj4*x1925))+(((-1.0)*cj4*x1926))+(((-1.0)*x1929))+(((0.02075)*sj4)));
1439if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
1440{
1441continue;
1442}
1443}
1444
1445rotationfunction0(solutions);
1446}
1447}
1448
1449}
1450
1451}
1452}
1453}
1454
1455}
1456
1457}
1458
1459} else
1460{
1461{
1462IkReal j3array[1], cj3array[1], sj3array[1];
1463bool j3valid[1]={false};
1464_nj3 = 1;
1465CheckValue<IkReal> x1931=IKPowWithIntegerCheck(cj4,-1);
1466if(!x1931.valid){
1467continue;
1468}
1469IkReal x1930=x1931.value;
1470if( IKabs(((-2.40384615384615)*npz*x1930)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz*x1930))+IKsqr(((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp))))))-1) <= IKFAST_SINCOS_THRESH )
1471 continue;
1472j3array[0]=IKatan2(((-2.40384615384615)*npz*x1930), ((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp))))));
1473sj3array[0]=IKsin(j3array[0]);
1474cj3array[0]=IKcos(j3array[0]);
1475if( j3array[0] > IKPI )
1476{
1477 j3array[0]-=IK2PI;
1478}
1479else if( j3array[0] < -IKPI )
1480{ j3array[0]+=IK2PI;
1481}
1482j3valid[0] = true;
1483for(int ij3 = 0; ij3 < 1; ++ij3)
1484{
1485if( !j3valid[ij3] )
1486{
1487 continue;
1488}
1489_ij3[0] = ij3; _ij3[1] = -1;
1490for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1491{
1492if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1493{
1494 j3valid[iij3]=false; _ij3[1] = iij3; break;
1495}
1496}
1497j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1498{
1499IkReal evalcond[2];
1500IkReal x1932=IKsin(j3);
1501evalcond[0]=((((-0.416)*cj4*x1932))+(((-1.0)*npz)));
1502evalcond[1]=((-0.2611025625)+pp+(((-0.246272)*(IKcos(j3))))+(((0.017264)*sj4*x1932)));
1503if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
1504{
1505continue;
1506}
1507}
1508
1509{
1510IkReal j5eval[3];
1511IkReal x1933=((0.416)*cj3);
1512IkReal x1934=((0.416)*sj3*sj4);
1513IkReal x1935=((npx*npx)+(npy*npy));
1514j5eval[0]=x1935;
1515j5eval[1]=((IKabs(((((-0.02075)*npy))+(((-1.0)*npx*x1933))+(((-0.296)*npx))+((npy*x1934)))))+(IKabs(((((0.02075)*npx))+(((-1.0)*npx*x1934))+(((-0.296)*npy))+(((-1.0)*npy*x1933))))));
1516j5eval[2]=IKsign(x1935);
1517if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1518{
1519{
1520IkReal j5eval[3];
1521IkReal x1936=(npz*sj4);
1522IkReal x1937=(cj4*npy);
1523IkReal x1938=((0.416)*cj3);
1524IkReal x1939=(cj4*npx);
1525IkReal x1940=(((npx*x1939))+((npy*x1937)));
1526j5eval[0]=x1940;
1527j5eval[1]=((IKabs(((((-1.0)*x1937*x1938))+(((0.02075)*x1939))+((npx*x1936))+(((-0.296)*x1937)))))+(IKabs(((((-0.02075)*x1937))+(((-1.0)*npy*x1936))+(((-0.296)*x1939))+(((-1.0)*x1938*x1939))))));
1528j5eval[2]=IKsign(x1940);
1529if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1530{
1531{
1532IkReal j5eval[3];
1533IkReal x1941=npx*npx;
1534IkReal x1942=npy*npy;
1535IkReal x1943=(cj3*npy);
1536IkReal x1944=(cj3*npx);
1537IkReal x1945=((2000.0)*pp);
1538j5eval[0]=(x1942+x1941);
1539j5eval[1]=IKsign(((((83.0)*x1942))+(((83.0)*x1941))));
1540j5eval[2]=((IKabs(((((-1.0)*npy*x1945))+(((-24.568)*npx))+(((492.544)*x1943))+(((520.482875)*npy))+(((-34.528)*x1944)))))+(IKabs(((((-520.482875)*npx))+((npx*x1945))+(((-492.544)*x1944))+(((-24.568)*npy))+(((-34.528)*x1943))))));
1541if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1542{
1543{
1544IkReal evalcond[2];
1545bool bgotonextstatement = true;
1546do
1547{
1548evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959)));
1549evalcond[1]=npz;
1550if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
1551{
1552bgotonextstatement=false;
1553{
1554IkReal j5eval[3];
1555sj4=1.0;
1556cj4=0;
1557j4=1.5707963267949;
1558IkReal x1946=((0.416)*cj3);
1559IkReal x1947=((0.416)*sj3);
1560IkReal x1948=((npx*npx)+(npy*npy));
1561j5eval[0]=x1948;
1562j5eval[1]=((IKabs(((((-1.0)*npx*x1947))+(((-1.0)*npy*x1946))+(((0.02075)*npx))+(((-0.296)*npy)))))+(IKabs(((((-1.0)*npx*x1946))+(((-0.02075)*npy))+((npy*x1947))+(((-0.296)*npx))))));
1563j5eval[2]=IKsign(x1948);
1564if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1565{
1566{
1567IkReal j5eval[3];
1568sj4=1.0;
1569cj4=0;
1570j4=1.5707963267949;
1571IkReal x1949=npx*npx;
1572IkReal x1950=npy*npy;
1573IkReal x1951=(cj3*npy);
1574IkReal x1952=(cj3*npx);
1575IkReal x1953=((2000.0)*pp);
1576j5eval[0]=(x1949+x1950);
1577j5eval[1]=IKsign(((((83.0)*x1950))+(((83.0)*x1949))));
1578j5eval[2]=((IKabs(((((-1.0)*npy*x1953))+(((492.544)*x1951))+(((-24.568)*npx))+(((520.482875)*npy))+(((-34.528)*x1952)))))+(IKabs((((npx*x1953))+(((-520.482875)*npx))+(((-492.544)*x1952))+(((-24.568)*npy))+(((-34.528)*x1951))))));
1579if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1580{
1581continue; // no branches [j5]
1582
1583} else
1584{
1585{
1586IkReal j5array[1], cj5array[1], sj5array[1];
1587bool j5valid[1]={false};
1588_nj5 = 1;
1589IkReal x1954=(cj3*npy);
1590IkReal x1955=(cj3*npx);
1591IkReal x1956=((2000.0)*pp);
1592CheckValue<IkReal> x1957=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1);
1593if(!x1957.valid){
1594continue;
1595}
1596CheckValue<IkReal> x1958 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1956))+(((492.544)*x1954))+(((-24.568)*npx))+(((520.482875)*npy))+(((-34.528)*x1955)))),IkReal((((npx*x1956))+(((-520.482875)*npx))+(((-492.544)*x1955))+(((-24.568)*npy))+(((-34.528)*x1954)))),IKFAST_ATAN2_MAGTHRESH);
1597if(!x1958.valid){
1598continue;
1599}
1600j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1957.value)))+(x1958.value));
1601sj5array[0]=IKsin(j5array[0]);
1602cj5array[0]=IKcos(j5array[0]);
1603if( j5array[0] > IKPI )
1604{
1605 j5array[0]-=IK2PI;
1606}
1607else if( j5array[0] < -IKPI )
1608{ j5array[0]+=IK2PI;
1609}
1610j5valid[0] = true;
1611for(int ij5 = 0; ij5 < 1; ++ij5)
1612{
1613if( !j5valid[ij5] )
1614{
1615 continue;
1616}
1617_ij5[0] = ij5; _ij5[1] = -1;
1618for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1619{
1620if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1621{
1622 j5valid[iij5]=false; _ij5[1] = iij5; break;
1623}
1624}
1625j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1626{
1627IkReal evalcond[3];
1628IkReal x1959=IKcos(j5);
1629IkReal x1960=IKsin(j5);
1630IkReal x1961=((1.0)*x1959);
1631IkReal x1962=(npy*x1960);
1632evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1961))+x1962);
1633evalcond[1]=((-0.296)+(((-1.0)*npx*x1960))+(((-1.0)*npy*x1961))+(((-0.416)*cj3)));
1634evalcond[2]=((-0.2602414375)+(((0.0415)*x1962))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1959)));
1635if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1636{
1637continue;
1638}
1639}
1640
1641rotationfunction0(solutions);
1642}
1643}
1644
1645}
1646
1647}
1648
1649} else
1650{
1651{
1652IkReal j5array[1], cj5array[1], sj5array[1];
1653bool j5valid[1]={false};
1654_nj5 = 1;
1655IkReal x1963=((0.416)*cj3);
1656IkReal x1964=((0.416)*sj3);
1657CheckValue<IkReal> x1965 = IKatan2WithCheck(IkReal(((((-1.0)*npx*x1963))+(((-0.02075)*npy))+((npy*x1964))+(((-0.296)*npx)))),IkReal(((((-1.0)*npx*x1964))+(((-1.0)*npy*x1963))+(((0.02075)*npx))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH);
1658if(!x1965.valid){
1659continue;
1660}
1661CheckValue<IkReal> x1966=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1);
1662if(!x1966.valid){
1663continue;
1664}
1665j5array[0]=((-1.5707963267949)+(x1965.value)+(((1.5707963267949)*(x1966.value))));
1666sj5array[0]=IKsin(j5array[0]);
1667cj5array[0]=IKcos(j5array[0]);
1668if( j5array[0] > IKPI )
1669{
1670 j5array[0]-=IK2PI;
1671}
1672else if( j5array[0] < -IKPI )
1673{ j5array[0]+=IK2PI;
1674}
1675j5valid[0] = true;
1676for(int ij5 = 0; ij5 < 1; ++ij5)
1677{
1678if( !j5valid[ij5] )
1679{
1680 continue;
1681}
1682_ij5[0] = ij5; _ij5[1] = -1;
1683for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1684{
1685if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1686{
1687 j5valid[iij5]=false; _ij5[1] = iij5; break;
1688}
1689}
1690j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1691{
1692IkReal evalcond[3];
1693IkReal x1967=IKcos(j5);
1694IkReal x1968=IKsin(j5);
1695IkReal x1969=((1.0)*x1967);
1696IkReal x1970=(npy*x1968);
1697evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1969))+x1970);
1698evalcond[1]=((-0.296)+(((-1.0)*npx*x1968))+(((-1.0)*npy*x1969))+(((-0.416)*cj3)));
1699evalcond[2]=((-0.2602414375)+(((0.0415)*x1970))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1967)));
1700if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1701{
1702continue;
1703}
1704}
1705
1706rotationfunction0(solutions);
1707}
1708}
1709
1710}
1711
1712}
1713
1714}
1715} while(0);
1716if( bgotonextstatement )
1717{
1718bool bgotonextstatement = true;
1719do
1720{
1721evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959)));
1722if( IKabs(evalcond[0]) < 0.0000050000000000 )
1723{
1724bgotonextstatement=false;
1725{
1726IkReal j5eval[3];
1727sj4=-1.0;
1728cj4=0;
1729j4=-1.5707963267949;
1730IkReal x1971=((0.416)*cj3);
1731IkReal x1972=((0.416)*sj3);
1732IkReal x1973=((npx*npx)+(npy*npy));
1733j5eval[0]=x1973;
1734j5eval[1]=IKsign(x1973);
1735j5eval[2]=((IKabs(((((-1.0)*npx*x1971))+(((-1.0)*npy*x1972))+(((-0.02075)*npy))+(((-0.296)*npx)))))+(IKabs(((((-1.0)*npy*x1971))+((npx*x1972))+(((0.02075)*npx))+(((-0.296)*npy))))));
1736if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1737{
1738{
1739IkReal j5eval[3];
1740sj4=-1.0;
1741cj4=0;
1742j4=-1.5707963267949;
1743IkReal x1974=npx*npx;
1744IkReal x1975=npy*npy;
1745IkReal x1976=(cj3*npy);
1746IkReal x1977=(cj3*npx);
1747IkReal x1978=((2000.0)*pp);
1748j5eval[0]=(x1975+x1974);
1749j5eval[1]=IKsign(((((83.0)*x1974))+(((83.0)*x1975))));
1750j5eval[2]=((IKabs(((((-34.528)*x1976))+(((-520.482875)*npx))+((npx*x1978))+(((-492.544)*x1977))+(((-24.568)*npy)))))+(IKabs(((((-34.528)*x1977))+(((-1.0)*npy*x1978))+(((492.544)*x1976))+(((-24.568)*npx))+(((520.482875)*npy))))));
1751if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 )
1752{
1753continue; // no branches [j5]
1754
1755} else
1756{
1757{
1758IkReal j5array[1], cj5array[1], sj5array[1];
1759bool j5valid[1]={false};
1760_nj5 = 1;
1761IkReal x1979=(cj3*npy);
1762IkReal x1980=(cj3*npx);
1763IkReal x1981=((2000.0)*pp);
1764CheckValue<IkReal> x1982 = IKatan2WithCheck(IkReal(((((492.544)*x1979))+(((-1.0)*npy*x1981))+(((-24.568)*npx))+(((-34.528)*x1980))+(((520.482875)*npy)))),IkReal(((((-34.528)*x1979))+(((-520.482875)*npx))+((npx*x1981))+(((-492.544)*x1980))+(((-24.568)*npy)))),IKFAST_ATAN2_MAGTHRESH);
1765if(!x1982.valid){
1766continue;
1767}
1768CheckValue<IkReal> x1983=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1);
1769if(!x1983.valid){
1770continue;
1771}
1772j5array[0]=((-1.5707963267949)+(x1982.value)+(((1.5707963267949)*(x1983.value))));
1773sj5array[0]=IKsin(j5array[0]);
1774cj5array[0]=IKcos(j5array[0]);
1775if( j5array[0] > IKPI )
1776{
1777 j5array[0]-=IK2PI;
1778}
1779else if( j5array[0] < -IKPI )
1780{ j5array[0]+=IK2PI;
1781}
1782j5valid[0] = true;
1783for(int ij5 = 0; ij5 < 1; ++ij5)
1784{
1785if( !j5valid[ij5] )
1786{
1787 continue;
1788}
1789_ij5[0] = ij5; _ij5[1] = -1;
1790for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1791{
1792if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1793{
1794 j5valid[iij5]=false; _ij5[1] = iij5; break;
1795}
1796}
1797j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1798{
1799IkReal evalcond[3];
1800IkReal x1984=IKcos(j5);
1801IkReal x1985=IKsin(j5);
1802IkReal x1986=((1.0)*x1984);
1803IkReal x1987=(npy*x1985);
1804evalcond[0]=((0.02075)+x1987+(((-1.0)*npx*x1986))+(((0.416)*sj3)));
1805evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npy*x1986))+(((-1.0)*npx*x1985)));
1806evalcond[2]=((-0.2602414375)+(((0.0415)*x1987))+(((-0.0415)*npx*x1984))+(((-0.246272)*cj3))+pp);
1807if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1808{
1809continue;
1810}
1811}
1812
1813rotationfunction0(solutions);
1814}
1815}
1816
1817}
1818
1819}
1820
1821} else
1822{
1823{
1824IkReal j5array[1], cj5array[1], sj5array[1];
1825bool j5valid[1]={false};
1826_nj5 = 1;
1827IkReal x1988=((0.416)*cj3);
1828IkReal x1989=((0.416)*sj3);
1829CheckValue<IkReal> x1990 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npy*x1989))+(((-1.0)*npx*x1988))+(((-0.296)*npx)))),IkReal((((npx*x1989))+(((0.02075)*npx))+(((-1.0)*npy*x1988))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH);
1830if(!x1990.valid){
1831continue;
1832}
1833CheckValue<IkReal> x1991=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1);
1834if(!x1991.valid){
1835continue;
1836}
1837j5array[0]=((-1.5707963267949)+(x1990.value)+(((1.5707963267949)*(x1991.value))));
1838sj5array[0]=IKsin(j5array[0]);
1839cj5array[0]=IKcos(j5array[0]);
1840if( j5array[0] > IKPI )
1841{
1842 j5array[0]-=IK2PI;
1843}
1844else if( j5array[0] < -IKPI )
1845{ j5array[0]+=IK2PI;
1846}
1847j5valid[0] = true;
1848for(int ij5 = 0; ij5 < 1; ++ij5)
1849{
1850if( !j5valid[ij5] )
1851{
1852 continue;
1853}
1854_ij5[0] = ij5; _ij5[1] = -1;
1855for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1856{
1857if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1858{
1859 j5valid[iij5]=false; _ij5[1] = iij5; break;
1860}
1861}
1862j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1863{
1864IkReal evalcond[3];
1865IkReal x1992=IKcos(j5);
1866IkReal x1993=IKsin(j5);
1867IkReal x1994=((1.0)*x1992);
1868IkReal x1995=(npy*x1993);
1869evalcond[0]=((0.02075)+(((-1.0)*npx*x1994))+x1995+(((0.416)*sj3)));
1870evalcond[1]=((-0.296)+(((-1.0)*npy*x1994))+(((-1.0)*npx*x1993))+(((-0.416)*cj3)));
1871evalcond[2]=((-0.2602414375)+(((0.0415)*x1995))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1992)));
1872if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH )
1873{
1874continue;
1875}
1876}
1877
1878rotationfunction0(solutions);
1879}
1880}
1881
1882}
1883
1884}
1885
1886}
1887} while(0);
1888if( bgotonextstatement )
1889{
1890bool bgotonextstatement = true;
1891do
1892{
1893if( 1 )
1894{
1895bgotonextstatement=false;
1896continue; // branch miss [j5]
1897
1898}
1899} while(0);
1900if( bgotonextstatement )
1901{
1902}
1903}
1904}
1905}
1906
1907} else
1908{
1909{
1910IkReal j5array[1], cj5array[1], sj5array[1];
1911bool j5valid[1]={false};
1912_nj5 = 1;
1913IkReal x1996=(cj3*npy);
1914IkReal x1997=(cj3*npx);
1915IkReal x1998=((2000.0)*pp);
1916CheckValue<IkReal> x1999 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1998))+(((-24.568)*npx))+(((-34.528)*x1997))+(((520.482875)*npy))+(((492.544)*x1996)))),IkReal(((((-520.482875)*npx))+(((-24.568)*npy))+(((-492.544)*x1997))+(((-34.528)*x1996))+((npx*x1998)))),IKFAST_ATAN2_MAGTHRESH);
1917if(!x1999.valid){
1918continue;
1919}
1920CheckValue<IkReal> x2000=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1);
1921if(!x2000.valid){
1922continue;
1923}
1924j5array[0]=((-1.5707963267949)+(x1999.value)+(((1.5707963267949)*(x2000.value))));
1925sj5array[0]=IKsin(j5array[0]);
1926cj5array[0]=IKcos(j5array[0]);
1927if( j5array[0] > IKPI )
1928{
1929 j5array[0]-=IK2PI;
1930}
1931else if( j5array[0] < -IKPI )
1932{ j5array[0]+=IK2PI;
1933}
1934j5valid[0] = true;
1935for(int ij5 = 0; ij5 < 1; ++ij5)
1936{
1937if( !j5valid[ij5] )
1938{
1939 continue;
1940}
1941_ij5[0] = ij5; _ij5[1] = -1;
1942for(int iij5 = ij5+1; iij5 < 1; ++iij5)
1943{
1944if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
1945{
1946 j5valid[iij5]=false; _ij5[1] = iij5; break;
1947}
1948}
1949j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
1950{
1951IkReal evalcond[5];
1952IkReal x2001=IKsin(j5);
1953IkReal x2002=IKcos(j5);
1954IkReal x2003=((0.416)*sj3);
1955IkReal x2004=(npy*x2001);
1956IkReal x2005=((1.0)*x2002);
1957evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2001))+(((-1.0)*npy*x2005)));
1958evalcond[1]=((0.02075)+(((-1.0)*npx*x2005))+x2004+(((-1.0)*sj4*x2003)));
1959evalcond[2]=((-0.2602414375)+(((0.0415)*x2004))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2002)));
1960evalcond[3]=(((cj4*x2004))+(((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2005)));
1961evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*x2003))+(((-1.0)*npx*sj4*x2005))+((sj4*x2004))+(((0.02075)*sj4)));
1962if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
1963{
1964continue;
1965}
1966}
1967
1968rotationfunction0(solutions);
1969}
1970}
1971
1972}
1973
1974}
1975
1976} else
1977{
1978{
1979IkReal j5array[1], cj5array[1], sj5array[1];
1980bool j5valid[1]={false};
1981_nj5 = 1;
1982IkReal x2006=(npz*sj4);
1983IkReal x2007=(cj4*npy);
1984IkReal x2008=((0.416)*cj3);
1985IkReal x2009=(cj4*npx);
1986CheckValue<IkReal> x2010=IKPowWithIntegerCheck(IKsign((((npy*x2007))+((npx*x2009)))),-1);
1987if(!x2010.valid){
1988continue;
1989}
1990CheckValue<IkReal> x2011 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x2006))+(((-1.0)*x2008*x2009))+(((-0.296)*x2009))+(((-0.02075)*x2007)))),IkReal(((((-1.0)*x2007*x2008))+(((-0.296)*x2007))+(((0.02075)*x2009))+((npx*x2006)))),IKFAST_ATAN2_MAGTHRESH);
1991if(!x2011.valid){
1992continue;
1993}
1994j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2010.value)))+(x2011.value));
1995sj5array[0]=IKsin(j5array[0]);
1996cj5array[0]=IKcos(j5array[0]);
1997if( j5array[0] > IKPI )
1998{
1999 j5array[0]-=IK2PI;
2000}
2001else if( j5array[0] < -IKPI )
2002{ j5array[0]+=IK2PI;
2003}
2004j5valid[0] = true;
2005for(int ij5 = 0; ij5 < 1; ++ij5)
2006{
2007if( !j5valid[ij5] )
2008{
2009 continue;
2010}
2011_ij5[0] = ij5; _ij5[1] = -1;
2012for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2013{
2014if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2015{
2016 j5valid[iij5]=false; _ij5[1] = iij5; break;
2017}
2018}
2019j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2020{
2021IkReal evalcond[5];
2022IkReal x2012=IKsin(j5);
2023IkReal x2013=IKcos(j5);
2024IkReal x2014=((0.416)*sj3);
2025IkReal x2015=(npy*x2012);
2026IkReal x2016=((1.0)*x2013);
2027evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2012))+(((-1.0)*npy*x2016)));
2028evalcond[1]=((0.02075)+x2015+(((-1.0)*npx*x2016))+(((-1.0)*sj4*x2014)));
2029evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x2013))+(((0.0415)*x2015))+(((-0.246272)*cj3))+pp);
2030evalcond[3]=((((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2016))+((cj4*x2015)));
2031evalcond[4]=((((-1.0)*x2014))+((sj4*x2015))+(((-1.0)*cj4*npz))+(((0.02075)*sj4))+(((-1.0)*npx*sj4*x2016)));
2032if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
2033{
2034continue;
2035}
2036}
2037
2038rotationfunction0(solutions);
2039}
2040}
2041
2042}
2043
2044}
2045
2046} else
2047{
2048{
2049IkReal j5array[1], cj5array[1], sj5array[1];
2050bool j5valid[1]={false};
2051_nj5 = 1;
2052IkReal x2017=((0.416)*cj3);
2053IkReal x2018=((0.416)*sj3*sj4);
2054CheckValue<IkReal> x2019 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npx*x2017))+(((-0.296)*npx))+((npy*x2018)))),IkReal(((((0.02075)*npx))+(((-1.0)*npx*x2018))+(((-1.0)*npy*x2017))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH);
2055if(!x2019.valid){
2056continue;
2057}
2058CheckValue<IkReal> x2020=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1);
2059if(!x2020.valid){
2060continue;
2061}
2062j5array[0]=((-1.5707963267949)+(x2019.value)+(((1.5707963267949)*(x2020.value))));
2063sj5array[0]=IKsin(j5array[0]);
2064cj5array[0]=IKcos(j5array[0]);
2065if( j5array[0] > IKPI )
2066{
2067 j5array[0]-=IK2PI;
2068}
2069else if( j5array[0] < -IKPI )
2070{ j5array[0]+=IK2PI;
2071}
2072j5valid[0] = true;
2073for(int ij5 = 0; ij5 < 1; ++ij5)
2074{
2075if( !j5valid[ij5] )
2076{
2077 continue;
2078}
2079_ij5[0] = ij5; _ij5[1] = -1;
2080for(int iij5 = ij5+1; iij5 < 1; ++iij5)
2081{
2082if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
2083{
2084 j5valid[iij5]=false; _ij5[1] = iij5; break;
2085}
2086}
2087j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
2088{
2089IkReal evalcond[5];
2090IkReal x2021=IKsin(j5);
2091IkReal x2022=IKcos(j5);
2092IkReal x2023=((0.416)*sj3);
2093IkReal x2024=(npy*x2021);
2094IkReal x2025=((1.0)*x2022);
2095evalcond[0]=((-0.296)+(((-1.0)*npx*x2021))+(((-0.416)*cj3))+(((-1.0)*npy*x2025)));
2096evalcond[1]=((0.02075)+x2024+(((-1.0)*sj4*x2023))+(((-1.0)*npx*x2025)));
2097evalcond[2]=((-0.2602414375)+(((0.0415)*x2024))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2022)));
2098evalcond[3]=((((-1.0)*cj4*npx*x2025))+((cj4*x2024))+(((0.02075)*cj4))+((npz*sj4)));
2099evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*npx*sj4*x2025))+(((-1.0)*x2023))+(((0.02075)*sj4))+((sj4*x2024)));
2100if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
2101{
2102continue;
2103}
2104}
2105
2106rotationfunction0(solutions);
2107}
2108}
2109
2110}
2111
2112}
2113}
2114}
2115
2116}
2117
2118}
2119 }
2120
2121}
2122
2123}
2124}
2125return solutions.GetNumSolutions()>0;
2126}
2127inline void rotationfunction0(IkSolutionListBase<IkReal>& solutions) {
2128for(int rotationiter = 0; rotationiter < 1; ++rotationiter) {
2129IkReal x91=((1.0)*sj3);
2130IkReal x92=((1.0)*sj5);
2131IkReal x93=((1.0)*cj5);
2132IkReal x94=((1.0)*sj4);
2133IkReal x95=((((-1.0)*r01*x92))+((cj5*r00)));
2134IkReal x96=(((cj5*r10))+(((-1.0)*r11*x92)));
2135IkReal x97=(((cj5*r20))+(((-1.0)*r21*x92)));
2136IkReal x98=((((-1.0)*r01*x93))+(((-1.0)*r00*x92)));
2137IkReal x99=((((-1.0)*r11*x93))+(((-1.0)*r10*x92)));
2138IkReal x100=((((-1.0)*r21*x93))+(((-1.0)*r20*x92)));
2139IkReal x101=(((sj4*x95))+((cj4*r02)));
2140IkReal x102=(((sj4*x96))+((cj4*r12)));
2141IkReal x103=(((cj4*r22))+((sj4*x97)));
2142new_r00=(((cj4*x95))+(((-1.0)*r02*x94)));
2143new_r01=(((sj3*x98))+((cj3*x101)));
2144new_r02=(((cj3*x98))+(((-1.0)*x101*x91)));
2145new_r10=((((-1.0)*r12*x94))+((cj4*x96)));
2146new_r11=(((sj3*x99))+((cj3*x102)));
2147new_r12=((((-1.0)*x102*x91))+((cj3*x99)));
2148new_r20=((((-1.0)*r22*x94))+((cj4*x97)));
2149new_r21=(((cj3*x103))+((sj3*x100)));
2150new_r22=((((-1.0)*x103*x91))+((cj3*x100)));
2151{
2152IkReal j1array[2], cj1array[2], sj1array[2];
2153bool j1valid[2]={false};
2154_nj1 = 2;
2155sj1array[0]=new_r22;
2156if( sj1array[0] >= -1-IKFAST_SINCOS_THRESH && sj1array[0] <= 1+IKFAST_SINCOS_THRESH )
2157{
2158 j1valid[0] = j1valid[1] = true;
2159 j1array[0] = IKasin(sj1array[0]);
2160 cj1array[0] = IKcos(j1array[0]);
2161 sj1array[1] = sj1array[0];
2162 j1array[1] = j1array[0] > 0 ? (IKPI-j1array[0]) : (-IKPI-j1array[0]);
2163 cj1array[1] = -cj1array[0];
2164}
2165else if( isnan(sj1array[0]) )
2166{
2167 // probably any value will work
2168 j1valid[0] = true;
2169 cj1array[0] = 1; sj1array[0] = 0; j1array[0] = 0;
2170}
2171for(int ij1 = 0; ij1 < 2; ++ij1)
2172{
2173if( !j1valid[ij1] )
2174{
2175 continue;
2176}
2177_ij1[0] = ij1; _ij1[1] = -1;
2178for(int iij1 = ij1+1; iij1 < 2; ++iij1)
2179{
2180if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
2181{
2182 j1valid[iij1]=false; _ij1[1] = iij1; break;
2183}
2184}
2185j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
2186
2187{
2188IkReal j0eval[3];
2189j0eval[0]=cj1;
2190j0eval[1]=IKsign(cj1);
2191j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02)));
2192if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
2193{
2194{
2195IkReal j2eval[3];
2196j2eval[0]=cj1;
2197j2eval[1]=IKsign(cj1);
2198j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
2199if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
2200{
2201{
2202IkReal j0eval[2];
2203j0eval[0]=cj1;
2204j0eval[1]=new_r12;
2205if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
2206{
2207{
2208IkReal evalcond[5];
2209bool bgotonextstatement = true;
2210do
2211{
2212evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959)));
2213evalcond[1]=new_r02;
2214evalcond[2]=new_r12;
2215evalcond[3]=new_r20;
2216evalcond[4]=new_r21;
2217if( 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 )
2218{
2219bgotonextstatement=false;
2220IkReal j2mul = 1;
2221j2=0;
2222j0mul=-1.0;
2223if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
2224 continue;
2225j0=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r01));
2226{
2227std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2228vinfos[0].jointtype = 1;
2229vinfos[0].foffset = j0;
2230vinfos[0].fmul = j0mul;
2231vinfos[0].freeind = 0;
2232vinfos[0].maxsolutions = 0;
2233vinfos[1].jointtype = 1;
2234vinfos[1].foffset = j1;
2235vinfos[1].indices[0] = _ij1[0];
2236vinfos[1].indices[1] = _ij1[1];
2237vinfos[1].maxsolutions = _nj1;
2238vinfos[2].jointtype = 1;
2239vinfos[2].foffset = j2;
2240vinfos[2].fmul = j2mul;
2241vinfos[2].freeind = 0;
2242vinfos[2].maxsolutions = 0;
2243vinfos[3].jointtype = 1;
2244vinfos[3].foffset = j3;
2245vinfos[3].indices[0] = _ij3[0];
2246vinfos[3].indices[1] = _ij3[1];
2247vinfos[3].maxsolutions = _nj3;
2248vinfos[4].jointtype = 1;
2249vinfos[4].foffset = j4;
2250vinfos[4].indices[0] = _ij4[0];
2251vinfos[4].indices[1] = _ij4[1];
2252vinfos[4].maxsolutions = _nj4;
2253vinfos[5].jointtype = 1;
2254vinfos[5].foffset = j5;
2255vinfos[5].indices[0] = _ij5[0];
2256vinfos[5].indices[1] = _ij5[1];
2257vinfos[5].maxsolutions = _nj5;
2258std::vector<int> vfree(1);
2259vfree[0] = 2;
2260solutions.AddSolution(vinfos,vfree);
2261}
2262
2263}
2264} while(0);
2265if( bgotonextstatement )
2266{
2267bool bgotonextstatement = true;
2268do
2269{
2270evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959)));
2271evalcond[1]=new_r02;
2272evalcond[2]=new_r12;
2273evalcond[3]=new_r20;
2274evalcond[4]=new_r21;
2275if( 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 )
2276{
2277bgotonextstatement=false;
2278IkReal j2mul = 1;
2279j2=0;
2280j0mul=1.0;
2281if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH )
2282 continue;
2283j0=IKatan2(((-1.0)*new_r00), new_r01);
2284{
2285std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2286vinfos[0].jointtype = 1;
2287vinfos[0].foffset = j0;
2288vinfos[0].fmul = j0mul;
2289vinfos[0].freeind = 0;
2290vinfos[0].maxsolutions = 0;
2291vinfos[1].jointtype = 1;
2292vinfos[1].foffset = j1;
2293vinfos[1].indices[0] = _ij1[0];
2294vinfos[1].indices[1] = _ij1[1];
2295vinfos[1].maxsolutions = _nj1;
2296vinfos[2].jointtype = 1;
2297vinfos[2].foffset = j2;
2298vinfos[2].fmul = j2mul;
2299vinfos[2].freeind = 0;
2300vinfos[2].maxsolutions = 0;
2301vinfos[3].jointtype = 1;
2302vinfos[3].foffset = j3;
2303vinfos[3].indices[0] = _ij3[0];
2304vinfos[3].indices[1] = _ij3[1];
2305vinfos[3].maxsolutions = _nj3;
2306vinfos[4].jointtype = 1;
2307vinfos[4].foffset = j4;
2308vinfos[4].indices[0] = _ij4[0];
2309vinfos[4].indices[1] = _ij4[1];
2310vinfos[4].maxsolutions = _nj4;
2311vinfos[5].jointtype = 1;
2312vinfos[5].foffset = j5;
2313vinfos[5].indices[0] = _ij5[0];
2314vinfos[5].indices[1] = _ij5[1];
2315vinfos[5].maxsolutions = _nj5;
2316std::vector<int> vfree(1);
2317vfree[0] = 2;
2318solutions.AddSolution(vinfos,vfree);
2319}
2320
2321}
2322} while(0);
2323if( bgotonextstatement )
2324{
2325bool bgotonextstatement = true;
2326do
2327{
2328evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02)));
2329if( IKabs(evalcond[0]) < 0.0000050000000000 )
2330{
2331bgotonextstatement=false;
2332{
2333IkReal j0eval[1];
2334new_r02=0;
2335new_r12=0;
2336new_r20=0;
2337new_r21=0;
2338IkReal x104=new_r22*new_r22;
2339IkReal x105=((16.0)*new_r11);
2340IkReal x106=((16.0)*new_r00);
2341IkReal x107=((16.0)*new_r01);
2342IkReal x108=(new_r10*new_r22);
2343IkReal x109=((8.0)*new_r01);
2344IkReal x110=((16.0)*x104);
2345IkReal x111=(x104*x105);
2346IkReal x112=(x104*x106);
2347j0eval[0]=((IKabs(((((-1.0)*x106))+x112)))+(IKabs(((((32.0)*new_r10))+(((-1.0)*new_r10*x110))+((new_r22*x107)))))+(IKabs((((new_r22*x109))+(((8.0)*new_r10*x104)))))+(IKabs((x109+(((8.0)*x108)))))+(IKabs(((((-1.0)*x105))+x111)))+(IKabs(((((-1.0)*x112))+x106)))+(IKabs(((((32.0)*new_r01*x104))+(((16.0)*x108))+(((-1.0)*x107)))))+(IKabs(((((-1.0)*x111))+x105))));
2348if( IKabs(j0eval[0]) < 0.0000000100000000 )
2349{
2350continue; // no branches [j0, j2]
2351
2352} else
2353{
2354IkReal op[4+1], zeror[4];
2355int numroots;
2356IkReal j0evalpoly[1];
2357IkReal x113=new_r22*new_r22;
2358IkReal x114=((16.0)*new_r11);
2359IkReal x115=(new_r10*new_r22);
2360IkReal x116=(x113*x114);
2361IkReal x117=((((8.0)*x115))+(((8.0)*new_r01)));
2362op[0]=x117;
2363op[1]=((((-1.0)*x114))+x116);
2364op[2]=((((16.0)*x115))+(((-16.0)*new_r01))+(((32.0)*new_r01*x113)));
2365op[3]=((((-1.0)*x116))+x114);
2366op[4]=x117;
2367polyroots4(op,zeror,numroots);
2368IkReal j0array[4], cj0array[4], sj0array[4], tempj0array[1];
2369int numsolutions = 0;
2370for(int ij0 = 0; ij0 < numroots; ++ij0)
2371{
2372IkReal htj0 = zeror[ij0];
2373tempj0array[0]=((2.0)*(atan(htj0)));
2374for(int kj0 = 0; kj0 < 1; ++kj0)
2375{
2376j0array[numsolutions] = tempj0array[kj0];
2377if( j0array[numsolutions] > IKPI )
2378{
2379 j0array[numsolutions]-=IK2PI;
2380}
2381else if( j0array[numsolutions] < -IKPI )
2382{
2383 j0array[numsolutions]+=IK2PI;
2384}
2385sj0array[numsolutions] = IKsin(j0array[numsolutions]);
2386cj0array[numsolutions] = IKcos(j0array[numsolutions]);
2387numsolutions++;
2388}
2389}
2390bool j0valid[4]={true,true,true,true};
2391_nj0 = 4;
2392for(int ij0 = 0; ij0 < numsolutions; ++ij0)
2393 {
2394if( !j0valid[ij0] )
2395{
2396 continue;
2397}
2398 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
2399htj0 = IKtan(j0/2);
2400
2401IkReal x118=new_r22*new_r22;
2402IkReal x119=((16.0)*new_r00);
2403IkReal x120=(new_r01*new_r22);
2404IkReal x121=((8.0)*x120);
2405IkReal x122=((16.0)*x118);
2406IkReal x123=(x118*x119);
2407IkReal x124=((8.0)*new_r10*x118);
2408IkReal x125=(x124+x121);
2409j0evalpoly[0]=((((htj0*htj0)*(((((16.0)*x120))+(((32.0)*new_r10))+(((-1.0)*new_r10*x122))))))+((x125*(htj0*htj0*htj0*htj0)))+x125+(((htj0*htj0*htj0)*(((((-1.0)*x119))+x123))))+((htj0*(((((-1.0)*x123))+x119)))));
2410if( IKabs(j0evalpoly[0]) > 0.0000001000000000 )
2411{
2412 continue;
2413}
2414_ij0[0] = ij0; _ij0[1] = -1;
2415for(int iij0 = ij0+1; iij0 < numsolutions; ++iij0)
2416{
2417if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
2418{
2419 j0valid[iij0]=false; _ij0[1] = iij0; break;
2420}
2421}
2422{
2423IkReal j2eval[3];
2424new_r02=0;
2425new_r12=0;
2426new_r20=0;
2427new_r21=0;
2428IkReal x126=cj0*cj0;
2429IkReal x127=((1.0)*new_r00);
2430IkReal x128=(cj0*new_r22);
2431IkReal x129=((1.0)+((x126*(new_r22*new_r22)))+(((-1.0)*x126)));
2432j2eval[0]=x129;
2433j2eval[1]=((IKabs((((new_r01*sj0))+(((-1.0)*x127*x128)))))+(IKabs(((((-1.0)*new_r01*x128))+(((-1.0)*sj0*x127))))));
2434j2eval[2]=IKsign(x129);
2435if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
2436{
2437{
2438IkReal j2eval[1];
2439new_r02=0;
2440new_r12=0;
2441new_r20=0;
2442new_r21=0;
2443j2eval[0]=new_r22;
2444if( IKabs(j2eval[0]) < 0.0000010000000000 )
2445{
2446{
2447IkReal j2eval[2];
2448new_r02=0;
2449new_r12=0;
2450new_r20=0;
2451new_r21=0;
2452IkReal x130=new_r22*new_r22;
2453j2eval[0]=(((cj0*x130))+(((-1.0)*cj0)));
2454j2eval[1]=((((-1.0)*sj0))+((sj0*x130)));
2455if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 )
2456{
2457{
2458IkReal evalcond[1];
2459bool bgotonextstatement = true;
2460do
2461{
2462evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j0)))), 6.28318530717959)));
2463if( IKabs(evalcond[0]) < 0.0000050000000000 )
2464{
2465bgotonextstatement=false;
2466{
2467IkReal j2array[1], cj2array[1], sj2array[1];
2468bool j2valid[1]={false};
2469_nj2 = 1;
2470if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH )
2471 continue;
2472j2array[0]=IKatan2(new_r01, ((-1.0)*new_r00));
2473sj2array[0]=IKsin(j2array[0]);
2474cj2array[0]=IKcos(j2array[0]);
2475if( j2array[0] > IKPI )
2476{
2477 j2array[0]-=IK2PI;
2478}
2479else if( j2array[0] < -IKPI )
2480{ j2array[0]+=IK2PI;
2481}
2482j2valid[0] = true;
2483for(int ij2 = 0; ij2 < 1; ++ij2)
2484{
2485if( !j2valid[ij2] )
2486{
2487 continue;
2488}
2489_ij2[0] = ij2; _ij2[1] = -1;
2490for(int iij2 = ij2+1; iij2 < 1; ++iij2)
2491{
2492if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
2493{
2494 j2valid[iij2]=false; _ij2[1] = iij2; break;
2495}
2496}
2497j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
2498{
2499IkReal evalcond[4];
2500IkReal x131=IKcos(j2);
2501IkReal x132=IKsin(j2);
2502evalcond[0]=(x131+new_r00);
2503evalcond[1]=((-1.0)*x132);
2504evalcond[2]=((-1.0)*x131);
2505evalcond[3]=(x132+(((-1.0)*new_r01)));
2506if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
2507{
2508continue;
2509}
2510}
2511
2512{
2513std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2514vinfos[0].jointtype = 1;
2515vinfos[0].foffset = j0;
2516vinfos[0].indices[0] = _ij0[0];
2517vinfos[0].indices[1] = _ij0[1];
2518vinfos[0].maxsolutions = _nj0;
2519vinfos[1].jointtype = 1;
2520vinfos[1].foffset = j1;
2521vinfos[1].indices[0] = _ij1[0];
2522vinfos[1].indices[1] = _ij1[1];
2523vinfos[1].maxsolutions = _nj1;
2524vinfos[2].jointtype = 1;
2525vinfos[2].foffset = j2;
2526vinfos[2].indices[0] = _ij2[0];
2527vinfos[2].indices[1] = _ij2[1];
2528vinfos[2].maxsolutions = _nj2;
2529vinfos[3].jointtype = 1;
2530vinfos[3].foffset = j3;
2531vinfos[3].indices[0] = _ij3[0];
2532vinfos[3].indices[1] = _ij3[1];
2533vinfos[3].maxsolutions = _nj3;
2534vinfos[4].jointtype = 1;
2535vinfos[4].foffset = j4;
2536vinfos[4].indices[0] = _ij4[0];
2537vinfos[4].indices[1] = _ij4[1];
2538vinfos[4].maxsolutions = _nj4;
2539vinfos[5].jointtype = 1;
2540vinfos[5].foffset = j5;
2541vinfos[5].indices[0] = _ij5[0];
2542vinfos[5].indices[1] = _ij5[1];
2543vinfos[5].maxsolutions = _nj5;
2544std::vector<int> vfree(0);
2545solutions.AddSolution(vinfos,vfree);
2546}
2547}
2548}
2549
2550}
2551} while(0);
2552if( bgotonextstatement )
2553{
2554bool bgotonextstatement = true;
2555do
2556{
2557evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j0)))), 6.28318530717959)));
2558if( IKabs(evalcond[0]) < 0.0000050000000000 )
2559{
2560bgotonextstatement=false;
2561{
2562IkReal j2array[1], cj2array[1], sj2array[1];
2563bool j2valid[1]={false};
2564_nj2 = 1;
2565if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH )
2566 continue;
2567j2array[0]=IKatan2(((-1.0)*new_r01), new_r00);
2568sj2array[0]=IKsin(j2array[0]);
2569cj2array[0]=IKcos(j2array[0]);
2570if( j2array[0] > IKPI )
2571{
2572 j2array[0]-=IK2PI;
2573}
2574else if( j2array[0] < -IKPI )
2575{ j2array[0]+=IK2PI;
2576}
2577j2valid[0] = true;
2578for(int ij2 = 0; ij2 < 1; ++ij2)
2579{
2580if( !j2valid[ij2] )
2581{
2582 continue;
2583}
2584_ij2[0] = ij2; _ij2[1] = -1;
2585for(int iij2 = ij2+1; iij2 < 1; ++iij2)
2586{
2587if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
2588{
2589 j2valid[iij2]=false; _ij2[1] = iij2; break;
2590}
2591}
2592j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
2593{
2594IkReal evalcond[4];
2595IkReal x133=IKsin(j2);
2596IkReal x134=IKcos(j2);
2597evalcond[0]=(x133+new_r01);
2598evalcond[1]=((-1.0)*x133);
2599evalcond[2]=((-1.0)*x134);
2600evalcond[3]=(x134+(((-1.0)*new_r00)));
2601if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
2602{
2603continue;
2604}
2605}
2606
2607{
2608std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2609vinfos[0].jointtype = 1;
2610vinfos[0].foffset = j0;
2611vinfos[0].indices[0] = _ij0[0];
2612vinfos[0].indices[1] = _ij0[1];
2613vinfos[0].maxsolutions = _nj0;
2614vinfos[1].jointtype = 1;
2615vinfos[1].foffset = j1;
2616vinfos[1].indices[0] = _ij1[0];
2617vinfos[1].indices[1] = _ij1[1];
2618vinfos[1].maxsolutions = _nj1;
2619vinfos[2].jointtype = 1;
2620vinfos[2].foffset = j2;
2621vinfos[2].indices[0] = _ij2[0];
2622vinfos[2].indices[1] = _ij2[1];
2623vinfos[2].maxsolutions = _nj2;
2624vinfos[3].jointtype = 1;
2625vinfos[3].foffset = j3;
2626vinfos[3].indices[0] = _ij3[0];
2627vinfos[3].indices[1] = _ij3[1];
2628vinfos[3].maxsolutions = _nj3;
2629vinfos[4].jointtype = 1;
2630vinfos[4].foffset = j4;
2631vinfos[4].indices[0] = _ij4[0];
2632vinfos[4].indices[1] = _ij4[1];
2633vinfos[4].maxsolutions = _nj4;
2634vinfos[5].jointtype = 1;
2635vinfos[5].foffset = j5;
2636vinfos[5].indices[0] = _ij5[0];
2637vinfos[5].indices[1] = _ij5[1];
2638vinfos[5].maxsolutions = _nj5;
2639std::vector<int> vfree(0);
2640solutions.AddSolution(vinfos,vfree);
2641}
2642}
2643}
2644
2645}
2646} while(0);
2647if( bgotonextstatement )
2648{
2649bool bgotonextstatement = true;
2650do
2651{
2652evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959)));
2653if( IKabs(evalcond[0]) < 0.0000050000000000 )
2654{
2655bgotonextstatement=false;
2656{
2657IkReal j2array[1], cj2array[1], sj2array[1];
2658bool j2valid[1]={false};
2659_nj2 = 1;
2660if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH )
2661 continue;
2662j2array[0]=IKatan2(((-1.0)*new_r11), new_r10);
2663sj2array[0]=IKsin(j2array[0]);
2664cj2array[0]=IKcos(j2array[0]);
2665if( j2array[0] > IKPI )
2666{
2667 j2array[0]-=IK2PI;
2668}
2669else if( j2array[0] < -IKPI )
2670{ j2array[0]+=IK2PI;
2671}
2672j2valid[0] = true;
2673for(int ij2 = 0; ij2 < 1; ++ij2)
2674{
2675if( !j2valid[ij2] )
2676{
2677 continue;
2678}
2679_ij2[0] = ij2; _ij2[1] = -1;
2680for(int iij2 = ij2+1; iij2 < 1; ++iij2)
2681{
2682if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
2683{
2684 j2valid[iij2]=false; _ij2[1] = iij2; break;
2685}
2686}
2687j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
2688{
2689IkReal evalcond[4];
2690IkReal x135=IKsin(j2);
2691IkReal x136=IKcos(j2);
2692evalcond[0]=(x135+new_r11);
2693evalcond[1]=((-1.0)*x135);
2694evalcond[2]=((-1.0)*x136);
2695evalcond[3]=(x136+(((-1.0)*new_r10)));
2696if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
2697{
2698continue;
2699}
2700}
2701
2702{
2703std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2704vinfos[0].jointtype = 1;
2705vinfos[0].foffset = j0;
2706vinfos[0].indices[0] = _ij0[0];
2707vinfos[0].indices[1] = _ij0[1];
2708vinfos[0].maxsolutions = _nj0;
2709vinfos[1].jointtype = 1;
2710vinfos[1].foffset = j1;
2711vinfos[1].indices[0] = _ij1[0];
2712vinfos[1].indices[1] = _ij1[1];
2713vinfos[1].maxsolutions = _nj1;
2714vinfos[2].jointtype = 1;
2715vinfos[2].foffset = j2;
2716vinfos[2].indices[0] = _ij2[0];
2717vinfos[2].indices[1] = _ij2[1];
2718vinfos[2].maxsolutions = _nj2;
2719vinfos[3].jointtype = 1;
2720vinfos[3].foffset = j3;
2721vinfos[3].indices[0] = _ij3[0];
2722vinfos[3].indices[1] = _ij3[1];
2723vinfos[3].maxsolutions = _nj3;
2724vinfos[4].jointtype = 1;
2725vinfos[4].foffset = j4;
2726vinfos[4].indices[0] = _ij4[0];
2727vinfos[4].indices[1] = _ij4[1];
2728vinfos[4].maxsolutions = _nj4;
2729vinfos[5].jointtype = 1;
2730vinfos[5].foffset = j5;
2731vinfos[5].indices[0] = _ij5[0];
2732vinfos[5].indices[1] = _ij5[1];
2733vinfos[5].maxsolutions = _nj5;
2734std::vector<int> vfree(0);
2735solutions.AddSolution(vinfos,vfree);
2736}
2737}
2738}
2739
2740}
2741} while(0);
2742if( bgotonextstatement )
2743{
2744bool bgotonextstatement = true;
2745do
2746{
2747evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959)));
2748if( IKabs(evalcond[0]) < 0.0000050000000000 )
2749{
2750bgotonextstatement=false;
2751{
2752IkReal j2array[1], cj2array[1], sj2array[1];
2753bool j2valid[1]={false};
2754_nj2 = 1;
2755if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH )
2756 continue;
2757j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10));
2758sj2array[0]=IKsin(j2array[0]);
2759cj2array[0]=IKcos(j2array[0]);
2760if( j2array[0] > IKPI )
2761{
2762 j2array[0]-=IK2PI;
2763}
2764else if( j2array[0] < -IKPI )
2765{ j2array[0]+=IK2PI;
2766}
2767j2valid[0] = true;
2768for(int ij2 = 0; ij2 < 1; ++ij2)
2769{
2770if( !j2valid[ij2] )
2771{
2772 continue;
2773}
2774_ij2[0] = ij2; _ij2[1] = -1;
2775for(int iij2 = ij2+1; iij2 < 1; ++iij2)
2776{
2777if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
2778{
2779 j2valid[iij2]=false; _ij2[1] = iij2; break;
2780}
2781}
2782j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
2783{
2784IkReal evalcond[4];
2785IkReal x137=IKcos(j2);
2786IkReal x138=IKsin(j2);
2787evalcond[0]=(x137+new_r10);
2788evalcond[1]=((-1.0)*x138);
2789evalcond[2]=((-1.0)*x137);
2790evalcond[3]=(x138+(((-1.0)*new_r11)));
2791if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH )
2792{
2793continue;
2794}
2795}
2796
2797{
2798std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2799vinfos[0].jointtype = 1;
2800vinfos[0].foffset = j0;
2801vinfos[0].indices[0] = _ij0[0];
2802vinfos[0].indices[1] = _ij0[1];
2803vinfos[0].maxsolutions = _nj0;
2804vinfos[1].jointtype = 1;
2805vinfos[1].foffset = j1;
2806vinfos[1].indices[0] = _ij1[0];
2807vinfos[1].indices[1] = _ij1[1];
2808vinfos[1].maxsolutions = _nj1;
2809vinfos[2].jointtype = 1;
2810vinfos[2].foffset = j2;
2811vinfos[2].indices[0] = _ij2[0];
2812vinfos[2].indices[1] = _ij2[1];
2813vinfos[2].maxsolutions = _nj2;
2814vinfos[3].jointtype = 1;
2815vinfos[3].foffset = j3;
2816vinfos[3].indices[0] = _ij3[0];
2817vinfos[3].indices[1] = _ij3[1];
2818vinfos[3].maxsolutions = _nj3;
2819vinfos[4].jointtype = 1;
2820vinfos[4].foffset = j4;
2821vinfos[4].indices[0] = _ij4[0];
2822vinfos[4].indices[1] = _ij4[1];
2823vinfos[4].maxsolutions = _nj4;
2824vinfos[5].jointtype = 1;
2825vinfos[5].foffset = j5;
2826vinfos[5].indices[0] = _ij5[0];
2827vinfos[5].indices[1] = _ij5[1];
2828vinfos[5].maxsolutions = _nj5;
2829std::vector<int> vfree(0);
2830solutions.AddSolution(vinfos,vfree);
2831}
2832}
2833}
2834
2835}
2836} while(0);
2837if( bgotonextstatement )
2838{
2839bool bgotonextstatement = true;
2840do
2841{
2842CheckValue<IkReal> x139=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
2843if(!x139.valid){
2844continue;
2845}
2846if((((-1.0)*(x139.value))) < -0.00001)
2847continue;
2848IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x139.value)))));
2849evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((((-1.0)*gconst40))+cj0)))+(IKabs(((-1.0)+(IKsign(sj0)))))), 6.28318530717959)));
2850if( IKabs(evalcond[0]) < 0.0000050000000000 )
2851{
2852bgotonextstatement=false;
2853{
2854IkReal j2eval[1];
2855new_r02=0;
2856new_r12=0;
2857new_r20=0;
2858new_r21=0;
2859if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001)
2860continue;
2861sj0=IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40)))));
2862cj0=gconst40;
2863if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH )
2864 continue;
2865j0=IKacos(gconst40);
2866CheckValue<IkReal> x140=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
2867if(!x140.valid){
2868continue;
2869}
2870if((((-1.0)*(x140.value))) < -0.00001)
2871continue;
2872IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x140.value)))));
2873j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
2874if( IKabs(j2eval[0]) < 0.0000010000000000 )
2875{
2876{
2877IkReal j2array[1], cj2array[1], sj2array[1];
2878bool j2valid[1]={false};
2879_nj2 = 1;
2880CheckValue<IkReal> x141=IKPowWithIntegerCheck(gconst40,-1);
2881if(!x141.valid){
2882continue;
2883}
2884if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001)
2885continue;
2886if( IKabs(((-1.0)*new_r11*(x141.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x141.value)))+IKsqr(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10))))-1) <= IKFAST_SINCOS_THRESH )
2887 continue;
2888j2array[0]=IKatan2(((-1.0)*new_r11*(x141.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10))));
2889sj2array[0]=IKsin(j2array[0]);
2890cj2array[0]=IKcos(j2array[0]);
2891if( j2array[0] > IKPI )
2892{
2893 j2array[0]-=IK2PI;
2894}
2895else if( j2array[0] < -IKPI )
2896{ j2array[0]+=IK2PI;
2897}
2898j2valid[0] = true;
2899for(int ij2 = 0; ij2 < 1; ++ij2)
2900{
2901if( !j2valid[ij2] )
2902{
2903 continue;
2904}
2905_ij2[0] = ij2; _ij2[1] = -1;
2906for(int iij2 = ij2+1; iij2 < 1; ++iij2)
2907{
2908if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
2909{
2910 j2valid[iij2]=false; _ij2[1] = iij2; break;
2911}
2912}
2913j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
2914{
2915IkReal evalcond[8];
2916IkReal x142=IKsin(j2);
2917IkReal x143=IKcos(j2);
2918IkReal x144=((1.0)*gconst40);
2919if((((1.0)+(((-1.0)*gconst40*x144)))) < -0.00001)
2920continue;
2921IkReal x145=IKsqrt(((1.0)+(((-1.0)*gconst40*x144))));
2922IkReal x146=((1.0)*x145);
2923evalcond[0]=((-1.0)*x142);
2924evalcond[1]=((-1.0)*x143);
2925evalcond[2]=(((gconst40*x142))+new_r11);
2926evalcond[3]=((((-1.0)*x143*x144))+new_r10);
2927evalcond[4]=(new_r00+((x143*x145)));
2928evalcond[5]=((((-1.0)*x142*x146))+new_r01);
2929evalcond[6]=((((-1.0)*new_r01*x146))+((gconst40*new_r11))+x142);
2930evalcond[7]=(((new_r00*x145))+x143+(((-1.0)*new_r10*x144)));
2931if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
2932{
2933continue;
2934}
2935}
2936
2937{
2938std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
2939vinfos[0].jointtype = 1;
2940vinfos[0].foffset = j0;
2941vinfos[0].indices[0] = _ij0[0];
2942vinfos[0].indices[1] = _ij0[1];
2943vinfos[0].maxsolutions = _nj0;
2944vinfos[1].jointtype = 1;
2945vinfos[1].foffset = j1;
2946vinfos[1].indices[0] = _ij1[0];
2947vinfos[1].indices[1] = _ij1[1];
2948vinfos[1].maxsolutions = _nj1;
2949vinfos[2].jointtype = 1;
2950vinfos[2].foffset = j2;
2951vinfos[2].indices[0] = _ij2[0];
2952vinfos[2].indices[1] = _ij2[1];
2953vinfos[2].maxsolutions = _nj2;
2954vinfos[3].jointtype = 1;
2955vinfos[3].foffset = j3;
2956vinfos[3].indices[0] = _ij3[0];
2957vinfos[3].indices[1] = _ij3[1];
2958vinfos[3].maxsolutions = _nj3;
2959vinfos[4].jointtype = 1;
2960vinfos[4].foffset = j4;
2961vinfos[4].indices[0] = _ij4[0];
2962vinfos[4].indices[1] = _ij4[1];
2963vinfos[4].maxsolutions = _nj4;
2964vinfos[5].jointtype = 1;
2965vinfos[5].foffset = j5;
2966vinfos[5].indices[0] = _ij5[0];
2967vinfos[5].indices[1] = _ij5[1];
2968vinfos[5].maxsolutions = _nj5;
2969std::vector<int> vfree(0);
2970solutions.AddSolution(vinfos,vfree);
2971}
2972}
2973}
2974
2975} else
2976{
2977{
2978IkReal j2array[1], cj2array[1], sj2array[1];
2979bool j2valid[1]={false};
2980_nj2 = 1;
2981CheckValue<IkReal> x147=IKPowWithIntegerCheck(IKsign(gconst40),-1);
2982if(!x147.valid){
2983continue;
2984}
2985CheckValue<IkReal> x148 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
2986if(!x148.valid){
2987continue;
2988}
2989j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x147.value)))+(x148.value));
2990sj2array[0]=IKsin(j2array[0]);
2991cj2array[0]=IKcos(j2array[0]);
2992if( j2array[0] > IKPI )
2993{
2994 j2array[0]-=IK2PI;
2995}
2996else if( j2array[0] < -IKPI )
2997{ j2array[0]+=IK2PI;
2998}
2999j2valid[0] = true;
3000for(int ij2 = 0; ij2 < 1; ++ij2)
3001{
3002if( !j2valid[ij2] )
3003{
3004 continue;
3005}
3006_ij2[0] = ij2; _ij2[1] = -1;
3007for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3008{
3009if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3010{
3011 j2valid[iij2]=false; _ij2[1] = iij2; break;
3012}
3013}
3014j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3015{
3016IkReal evalcond[8];
3017IkReal x149=IKsin(j2);
3018IkReal x150=IKcos(j2);
3019IkReal x151=((1.0)*gconst40);
3020if((((1.0)+(((-1.0)*gconst40*x151)))) < -0.00001)
3021continue;
3022IkReal x152=IKsqrt(((1.0)+(((-1.0)*gconst40*x151))));
3023IkReal x153=((1.0)*x152);
3024evalcond[0]=((-1.0)*x149);
3025evalcond[1]=((-1.0)*x150);
3026evalcond[2]=(((gconst40*x149))+new_r11);
3027evalcond[3]=((((-1.0)*x150*x151))+new_r10);
3028evalcond[4]=(((x150*x152))+new_r00);
3029evalcond[5]=(new_r01+(((-1.0)*x149*x153)));
3030evalcond[6]=(((gconst40*new_r11))+x149+(((-1.0)*new_r01*x153)));
3031evalcond[7]=(((new_r00*x152))+x150+(((-1.0)*new_r10*x151)));
3032if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3033{
3034continue;
3035}
3036}
3037
3038{
3039std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3040vinfos[0].jointtype = 1;
3041vinfos[0].foffset = j0;
3042vinfos[0].indices[0] = _ij0[0];
3043vinfos[0].indices[1] = _ij0[1];
3044vinfos[0].maxsolutions = _nj0;
3045vinfos[1].jointtype = 1;
3046vinfos[1].foffset = j1;
3047vinfos[1].indices[0] = _ij1[0];
3048vinfos[1].indices[1] = _ij1[1];
3049vinfos[1].maxsolutions = _nj1;
3050vinfos[2].jointtype = 1;
3051vinfos[2].foffset = j2;
3052vinfos[2].indices[0] = _ij2[0];
3053vinfos[2].indices[1] = _ij2[1];
3054vinfos[2].maxsolutions = _nj2;
3055vinfos[3].jointtype = 1;
3056vinfos[3].foffset = j3;
3057vinfos[3].indices[0] = _ij3[0];
3058vinfos[3].indices[1] = _ij3[1];
3059vinfos[3].maxsolutions = _nj3;
3060vinfos[4].jointtype = 1;
3061vinfos[4].foffset = j4;
3062vinfos[4].indices[0] = _ij4[0];
3063vinfos[4].indices[1] = _ij4[1];
3064vinfos[4].maxsolutions = _nj4;
3065vinfos[5].jointtype = 1;
3066vinfos[5].foffset = j5;
3067vinfos[5].indices[0] = _ij5[0];
3068vinfos[5].indices[1] = _ij5[1];
3069vinfos[5].maxsolutions = _nj5;
3070std::vector<int> vfree(0);
3071solutions.AddSolution(vinfos,vfree);
3072}
3073}
3074}
3075
3076}
3077
3078}
3079
3080}
3081} while(0);
3082if( bgotonextstatement )
3083{
3084bool bgotonextstatement = true;
3085do
3086{
3087CheckValue<IkReal> x154=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3088if(!x154.valid){
3089continue;
3090}
3091if((((-1.0)*(x154.value))) < -0.00001)
3092continue;
3093IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x154.value)))));
3094evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst40))+cj0)))), 6.28318530717959)));
3095if( IKabs(evalcond[0]) < 0.0000050000000000 )
3096{
3097bgotonextstatement=false;
3098{
3099IkReal j2eval[1];
3100new_r02=0;
3101new_r12=0;
3102new_r20=0;
3103new_r21=0;
3104if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001)
3105continue;
3106sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40)))))));
3107cj0=gconst40;
3108if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH )
3109 continue;
3110j0=((-1.0)*(IKacos(gconst40)));
3111CheckValue<IkReal> x155=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3112if(!x155.valid){
3113continue;
3114}
3115if((((-1.0)*(x155.value))) < -0.00001)
3116continue;
3117IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x155.value)))));
3118j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
3119if( IKabs(j2eval[0]) < 0.0000010000000000 )
3120{
3121{
3122IkReal j2array[1], cj2array[1], sj2array[1];
3123bool j2valid[1]={false};
3124_nj2 = 1;
3125if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001)
3126continue;
3127CheckValue<IkReal> x156=IKPowWithIntegerCheck(gconst40,-1);
3128if(!x156.valid){
3129continue;
3130}
3131if( IKabs(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x156.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11))))+IKsqr((new_r10*(x156.value)))-1) <= IKFAST_SINCOS_THRESH )
3132 continue;
3133j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11))), (new_r10*(x156.value)));
3134sj2array[0]=IKsin(j2array[0]);
3135cj2array[0]=IKcos(j2array[0]);
3136if( j2array[0] > IKPI )
3137{
3138 j2array[0]-=IK2PI;
3139}
3140else if( j2array[0] < -IKPI )
3141{ j2array[0]+=IK2PI;
3142}
3143j2valid[0] = true;
3144for(int ij2 = 0; ij2 < 1; ++ij2)
3145{
3146if( !j2valid[ij2] )
3147{
3148 continue;
3149}
3150_ij2[0] = ij2; _ij2[1] = -1;
3151for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3152{
3153if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3154{
3155 j2valid[iij2]=false; _ij2[1] = iij2; break;
3156}
3157}
3158j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3159{
3160IkReal evalcond[8];
3161IkReal x157=IKsin(j2);
3162IkReal x158=IKcos(j2);
3163IkReal x159=((1.0)*gconst40);
3164if((((1.0)+(((-1.0)*gconst40*x159)))) < -0.00001)
3165continue;
3166IkReal x160=IKsqrt(((1.0)+(((-1.0)*gconst40*x159))));
3167IkReal x161=((1.0)*x160);
3168evalcond[0]=((-1.0)*x157);
3169evalcond[1]=((-1.0)*x158);
3170evalcond[2]=(((gconst40*x157))+new_r11);
3171evalcond[3]=((((-1.0)*x158*x159))+new_r10);
3172evalcond[4]=(((x157*x160))+new_r01);
3173evalcond[5]=((((-1.0)*x158*x161))+new_r00);
3174evalcond[6]=(((new_r01*x160))+((gconst40*new_r11))+x157);
3175evalcond[7]=((((-1.0)*new_r00*x161))+x158+(((-1.0)*new_r10*x159)));
3176if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3177{
3178continue;
3179}
3180}
3181
3182{
3183std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3184vinfos[0].jointtype = 1;
3185vinfos[0].foffset = j0;
3186vinfos[0].indices[0] = _ij0[0];
3187vinfos[0].indices[1] = _ij0[1];
3188vinfos[0].maxsolutions = _nj0;
3189vinfos[1].jointtype = 1;
3190vinfos[1].foffset = j1;
3191vinfos[1].indices[0] = _ij1[0];
3192vinfos[1].indices[1] = _ij1[1];
3193vinfos[1].maxsolutions = _nj1;
3194vinfos[2].jointtype = 1;
3195vinfos[2].foffset = j2;
3196vinfos[2].indices[0] = _ij2[0];
3197vinfos[2].indices[1] = _ij2[1];
3198vinfos[2].maxsolutions = _nj2;
3199vinfos[3].jointtype = 1;
3200vinfos[3].foffset = j3;
3201vinfos[3].indices[0] = _ij3[0];
3202vinfos[3].indices[1] = _ij3[1];
3203vinfos[3].maxsolutions = _nj3;
3204vinfos[4].jointtype = 1;
3205vinfos[4].foffset = j4;
3206vinfos[4].indices[0] = _ij4[0];
3207vinfos[4].indices[1] = _ij4[1];
3208vinfos[4].maxsolutions = _nj4;
3209vinfos[5].jointtype = 1;
3210vinfos[5].foffset = j5;
3211vinfos[5].indices[0] = _ij5[0];
3212vinfos[5].indices[1] = _ij5[1];
3213vinfos[5].maxsolutions = _nj5;
3214std::vector<int> vfree(0);
3215solutions.AddSolution(vinfos,vfree);
3216}
3217}
3218}
3219
3220} else
3221{
3222{
3223IkReal j2array[1], cj2array[1], sj2array[1];
3224bool j2valid[1]={false};
3225_nj2 = 1;
3226CheckValue<IkReal> x162=IKPowWithIntegerCheck(IKsign(gconst40),-1);
3227if(!x162.valid){
3228continue;
3229}
3230CheckValue<IkReal> x163 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
3231if(!x163.valid){
3232continue;
3233}
3234j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x162.value)))+(x163.value));
3235sj2array[0]=IKsin(j2array[0]);
3236cj2array[0]=IKcos(j2array[0]);
3237if( j2array[0] > IKPI )
3238{
3239 j2array[0]-=IK2PI;
3240}
3241else if( j2array[0] < -IKPI )
3242{ j2array[0]+=IK2PI;
3243}
3244j2valid[0] = true;
3245for(int ij2 = 0; ij2 < 1; ++ij2)
3246{
3247if( !j2valid[ij2] )
3248{
3249 continue;
3250}
3251_ij2[0] = ij2; _ij2[1] = -1;
3252for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3253{
3254if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3255{
3256 j2valid[iij2]=false; _ij2[1] = iij2; break;
3257}
3258}
3259j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3260{
3261IkReal evalcond[8];
3262IkReal x164=IKsin(j2);
3263IkReal x165=IKcos(j2);
3264IkReal x166=((1.0)*gconst40);
3265if((((1.0)+(((-1.0)*gconst40*x166)))) < -0.00001)
3266continue;
3267IkReal x167=IKsqrt(((1.0)+(((-1.0)*gconst40*x166))));
3268IkReal x168=((1.0)*x167);
3269evalcond[0]=((-1.0)*x164);
3270evalcond[1]=((-1.0)*x165);
3271evalcond[2]=(new_r11+((gconst40*x164)));
3272evalcond[3]=(new_r10+(((-1.0)*x165*x166)));
3273evalcond[4]=(((x164*x167))+new_r01);
3274evalcond[5]=(new_r00+(((-1.0)*x165*x168)));
3275evalcond[6]=(((new_r01*x167))+((gconst40*new_r11))+x164);
3276evalcond[7]=((((-1.0)*new_r00*x168))+(((-1.0)*new_r10*x166))+x165);
3277if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3278{
3279continue;
3280}
3281}
3282
3283{
3284std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3285vinfos[0].jointtype = 1;
3286vinfos[0].foffset = j0;
3287vinfos[0].indices[0] = _ij0[0];
3288vinfos[0].indices[1] = _ij0[1];
3289vinfos[0].maxsolutions = _nj0;
3290vinfos[1].jointtype = 1;
3291vinfos[1].foffset = j1;
3292vinfos[1].indices[0] = _ij1[0];
3293vinfos[1].indices[1] = _ij1[1];
3294vinfos[1].maxsolutions = _nj1;
3295vinfos[2].jointtype = 1;
3296vinfos[2].foffset = j2;
3297vinfos[2].indices[0] = _ij2[0];
3298vinfos[2].indices[1] = _ij2[1];
3299vinfos[2].maxsolutions = _nj2;
3300vinfos[3].jointtype = 1;
3301vinfos[3].foffset = j3;
3302vinfos[3].indices[0] = _ij3[0];
3303vinfos[3].indices[1] = _ij3[1];
3304vinfos[3].maxsolutions = _nj3;
3305vinfos[4].jointtype = 1;
3306vinfos[4].foffset = j4;
3307vinfos[4].indices[0] = _ij4[0];
3308vinfos[4].indices[1] = _ij4[1];
3309vinfos[4].maxsolutions = _nj4;
3310vinfos[5].jointtype = 1;
3311vinfos[5].foffset = j5;
3312vinfos[5].indices[0] = _ij5[0];
3313vinfos[5].indices[1] = _ij5[1];
3314vinfos[5].maxsolutions = _nj5;
3315std::vector<int> vfree(0);
3316solutions.AddSolution(vinfos,vfree);
3317}
3318}
3319}
3320
3321}
3322
3323}
3324
3325}
3326} while(0);
3327if( bgotonextstatement )
3328{
3329bool bgotonextstatement = true;
3330do
3331{
3332CheckValue<IkReal> x169=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3333if(!x169.valid){
3334continue;
3335}
3336if((((-1.0)*(x169.value))) < -0.00001)
3337continue;
3338IkReal gconst41=IKsqrt(((-1.0)*(x169.value)));
3339evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959)));
3340if( IKabs(evalcond[0]) < 0.0000050000000000 )
3341{
3342bgotonextstatement=false;
3343{
3344IkReal j2eval[1];
3345new_r02=0;
3346new_r12=0;
3347new_r20=0;
3348new_r21=0;
3349if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001)
3350continue;
3351sj0=IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41)))));
3352cj0=gconst41;
3353if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH )
3354 continue;
3355j0=IKacos(gconst41);
3356CheckValue<IkReal> x170=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3357if(!x170.valid){
3358continue;
3359}
3360if((((-1.0)*(x170.value))) < -0.00001)
3361continue;
3362IkReal gconst41=IKsqrt(((-1.0)*(x170.value)));
3363j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
3364if( IKabs(j2eval[0]) < 0.0000010000000000 )
3365{
3366{
3367IkReal j2array[1], cj2array[1], sj2array[1];
3368bool j2valid[1]={false};
3369_nj2 = 1;
3370CheckValue<IkReal> x171=IKPowWithIntegerCheck(gconst41,-1);
3371if(!x171.valid){
3372continue;
3373}
3374if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001)
3375continue;
3376if( IKabs(((-1.0)*new_r11*(x171.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x171.value)))+IKsqr(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10))))-1) <= IKFAST_SINCOS_THRESH )
3377 continue;
3378j2array[0]=IKatan2(((-1.0)*new_r11*(x171.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10))));
3379sj2array[0]=IKsin(j2array[0]);
3380cj2array[0]=IKcos(j2array[0]);
3381if( j2array[0] > IKPI )
3382{
3383 j2array[0]-=IK2PI;
3384}
3385else if( j2array[0] < -IKPI )
3386{ j2array[0]+=IK2PI;
3387}
3388j2valid[0] = true;
3389for(int ij2 = 0; ij2 < 1; ++ij2)
3390{
3391if( !j2valid[ij2] )
3392{
3393 continue;
3394}
3395_ij2[0] = ij2; _ij2[1] = -1;
3396for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3397{
3398if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3399{
3400 j2valid[iij2]=false; _ij2[1] = iij2; break;
3401}
3402}
3403j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3404{
3405IkReal evalcond[8];
3406IkReal x172=IKsin(j2);
3407IkReal x173=IKcos(j2);
3408IkReal x174=((1.0)*gconst41);
3409if((((1.0)+(((-1.0)*gconst41*x174)))) < -0.00001)
3410continue;
3411IkReal x175=IKsqrt(((1.0)+(((-1.0)*gconst41*x174))));
3412IkReal x176=((1.0)*x175);
3413evalcond[0]=((-1.0)*x172);
3414evalcond[1]=((-1.0)*x173);
3415evalcond[2]=(new_r11+((gconst41*x172)));
3416evalcond[3]=(new_r10+(((-1.0)*x173*x174)));
3417evalcond[4]=(((x173*x175))+new_r00);
3418evalcond[5]=(new_r01+(((-1.0)*x172*x176)));
3419evalcond[6]=(((gconst41*new_r11))+x172+(((-1.0)*new_r01*x176)));
3420evalcond[7]=(((new_r00*x175))+(((-1.0)*new_r10*x174))+x173);
3421if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3422{
3423continue;
3424}
3425}
3426
3427{
3428std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3429vinfos[0].jointtype = 1;
3430vinfos[0].foffset = j0;
3431vinfos[0].indices[0] = _ij0[0];
3432vinfos[0].indices[1] = _ij0[1];
3433vinfos[0].maxsolutions = _nj0;
3434vinfos[1].jointtype = 1;
3435vinfos[1].foffset = j1;
3436vinfos[1].indices[0] = _ij1[0];
3437vinfos[1].indices[1] = _ij1[1];
3438vinfos[1].maxsolutions = _nj1;
3439vinfos[2].jointtype = 1;
3440vinfos[2].foffset = j2;
3441vinfos[2].indices[0] = _ij2[0];
3442vinfos[2].indices[1] = _ij2[1];
3443vinfos[2].maxsolutions = _nj2;
3444vinfos[3].jointtype = 1;
3445vinfos[3].foffset = j3;
3446vinfos[3].indices[0] = _ij3[0];
3447vinfos[3].indices[1] = _ij3[1];
3448vinfos[3].maxsolutions = _nj3;
3449vinfos[4].jointtype = 1;
3450vinfos[4].foffset = j4;
3451vinfos[4].indices[0] = _ij4[0];
3452vinfos[4].indices[1] = _ij4[1];
3453vinfos[4].maxsolutions = _nj4;
3454vinfos[5].jointtype = 1;
3455vinfos[5].foffset = j5;
3456vinfos[5].indices[0] = _ij5[0];
3457vinfos[5].indices[1] = _ij5[1];
3458vinfos[5].maxsolutions = _nj5;
3459std::vector<int> vfree(0);
3460solutions.AddSolution(vinfos,vfree);
3461}
3462}
3463}
3464
3465} else
3466{
3467{
3468IkReal j2array[1], cj2array[1], sj2array[1];
3469bool j2valid[1]={false};
3470_nj2 = 1;
3471CheckValue<IkReal> x177=IKPowWithIntegerCheck(IKsign(gconst41),-1);
3472if(!x177.valid){
3473continue;
3474}
3475CheckValue<IkReal> x178 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
3476if(!x178.valid){
3477continue;
3478}
3479j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x177.value)))+(x178.value));
3480sj2array[0]=IKsin(j2array[0]);
3481cj2array[0]=IKcos(j2array[0]);
3482if( j2array[0] > IKPI )
3483{
3484 j2array[0]-=IK2PI;
3485}
3486else if( j2array[0] < -IKPI )
3487{ j2array[0]+=IK2PI;
3488}
3489j2valid[0] = true;
3490for(int ij2 = 0; ij2 < 1; ++ij2)
3491{
3492if( !j2valid[ij2] )
3493{
3494 continue;
3495}
3496_ij2[0] = ij2; _ij2[1] = -1;
3497for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3498{
3499if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3500{
3501 j2valid[iij2]=false; _ij2[1] = iij2; break;
3502}
3503}
3504j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3505{
3506IkReal evalcond[8];
3507IkReal x179=IKsin(j2);
3508IkReal x180=IKcos(j2);
3509IkReal x181=((1.0)*gconst41);
3510if((((1.0)+(((-1.0)*gconst41*x181)))) < -0.00001)
3511continue;
3512IkReal x182=IKsqrt(((1.0)+(((-1.0)*gconst41*x181))));
3513IkReal x183=((1.0)*x182);
3514evalcond[0]=((-1.0)*x179);
3515evalcond[1]=((-1.0)*x180);
3516evalcond[2]=(new_r11+((gconst41*x179)));
3517evalcond[3]=((((-1.0)*x180*x181))+new_r10);
3518evalcond[4]=(((x180*x182))+new_r00);
3519evalcond[5]=(new_r01+(((-1.0)*x179*x183)));
3520evalcond[6]=(((gconst41*new_r11))+x179+(((-1.0)*new_r01*x183)));
3521evalcond[7]=(((new_r00*x182))+x180+(((-1.0)*new_r10*x181)));
3522if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3523{
3524continue;
3525}
3526}
3527
3528{
3529std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3530vinfos[0].jointtype = 1;
3531vinfos[0].foffset = j0;
3532vinfos[0].indices[0] = _ij0[0];
3533vinfos[0].indices[1] = _ij0[1];
3534vinfos[0].maxsolutions = _nj0;
3535vinfos[1].jointtype = 1;
3536vinfos[1].foffset = j1;
3537vinfos[1].indices[0] = _ij1[0];
3538vinfos[1].indices[1] = _ij1[1];
3539vinfos[1].maxsolutions = _nj1;
3540vinfos[2].jointtype = 1;
3541vinfos[2].foffset = j2;
3542vinfos[2].indices[0] = _ij2[0];
3543vinfos[2].indices[1] = _ij2[1];
3544vinfos[2].maxsolutions = _nj2;
3545vinfos[3].jointtype = 1;
3546vinfos[3].foffset = j3;
3547vinfos[3].indices[0] = _ij3[0];
3548vinfos[3].indices[1] = _ij3[1];
3549vinfos[3].maxsolutions = _nj3;
3550vinfos[4].jointtype = 1;
3551vinfos[4].foffset = j4;
3552vinfos[4].indices[0] = _ij4[0];
3553vinfos[4].indices[1] = _ij4[1];
3554vinfos[4].maxsolutions = _nj4;
3555vinfos[5].jointtype = 1;
3556vinfos[5].foffset = j5;
3557vinfos[5].indices[0] = _ij5[0];
3558vinfos[5].indices[1] = _ij5[1];
3559vinfos[5].maxsolutions = _nj5;
3560std::vector<int> vfree(0);
3561solutions.AddSolution(vinfos,vfree);
3562}
3563}
3564}
3565
3566}
3567
3568}
3569
3570}
3571} while(0);
3572if( bgotonextstatement )
3573{
3574bool bgotonextstatement = true;
3575do
3576{
3577CheckValue<IkReal> x184=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3578if(!x184.valid){
3579continue;
3580}
3581if((((-1.0)*(x184.value))) < -0.00001)
3582continue;
3583IkReal gconst41=IKsqrt(((-1.0)*(x184.value)));
3584evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959)));
3585if( IKabs(evalcond[0]) < 0.0000050000000000 )
3586{
3587bgotonextstatement=false;
3588{
3589IkReal j2eval[1];
3590new_r02=0;
3591new_r12=0;
3592new_r20=0;
3593new_r21=0;
3594if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001)
3595continue;
3596sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41)))))));
3597cj0=gconst41;
3598if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH )
3599 continue;
3600j0=((-1.0)*(IKacos(gconst41)));
3601CheckValue<IkReal> x185=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1);
3602if(!x185.valid){
3603continue;
3604}
3605if((((-1.0)*(x185.value))) < -0.00001)
3606continue;
3607IkReal gconst41=IKsqrt(((-1.0)*(x185.value)));
3608j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
3609if( IKabs(j2eval[0]) < 0.0000010000000000 )
3610{
3611{
3612IkReal j2array[1], cj2array[1], sj2array[1];
3613bool j2valid[1]={false};
3614_nj2 = 1;
3615if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001)
3616continue;
3617CheckValue<IkReal> x186=IKPowWithIntegerCheck(gconst41,-1);
3618if(!x186.valid){
3619continue;
3620}
3621if( IKabs(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x186.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11))))+IKsqr((new_r10*(x186.value)))-1) <= IKFAST_SINCOS_THRESH )
3622 continue;
3623j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11))), (new_r10*(x186.value)));
3624sj2array[0]=IKsin(j2array[0]);
3625cj2array[0]=IKcos(j2array[0]);
3626if( j2array[0] > IKPI )
3627{
3628 j2array[0]-=IK2PI;
3629}
3630else if( j2array[0] < -IKPI )
3631{ j2array[0]+=IK2PI;
3632}
3633j2valid[0] = true;
3634for(int ij2 = 0; ij2 < 1; ++ij2)
3635{
3636if( !j2valid[ij2] )
3637{
3638 continue;
3639}
3640_ij2[0] = ij2; _ij2[1] = -1;
3641for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3642{
3643if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3644{
3645 j2valid[iij2]=false; _ij2[1] = iij2; break;
3646}
3647}
3648j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3649{
3650IkReal evalcond[8];
3651IkReal x187=IKsin(j2);
3652IkReal x188=IKcos(j2);
3653IkReal x189=((1.0)*gconst41);
3654if((((1.0)+(((-1.0)*gconst41*x189)))) < -0.00001)
3655continue;
3656IkReal x190=IKsqrt(((1.0)+(((-1.0)*gconst41*x189))));
3657IkReal x191=((1.0)*x190);
3658evalcond[0]=((-1.0)*x187);
3659evalcond[1]=((-1.0)*x188);
3660evalcond[2]=(new_r11+((gconst41*x187)));
3661evalcond[3]=((((-1.0)*x188*x189))+new_r10);
3662evalcond[4]=(((x187*x190))+new_r01);
3663evalcond[5]=((((-1.0)*x188*x191))+new_r00);
3664evalcond[6]=(((new_r01*x190))+((gconst41*new_r11))+x187);
3665evalcond[7]=(x188+(((-1.0)*new_r10*x189))+(((-1.0)*new_r00*x191)));
3666if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3667{
3668continue;
3669}
3670}
3671
3672{
3673std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3674vinfos[0].jointtype = 1;
3675vinfos[0].foffset = j0;
3676vinfos[0].indices[0] = _ij0[0];
3677vinfos[0].indices[1] = _ij0[1];
3678vinfos[0].maxsolutions = _nj0;
3679vinfos[1].jointtype = 1;
3680vinfos[1].foffset = j1;
3681vinfos[1].indices[0] = _ij1[0];
3682vinfos[1].indices[1] = _ij1[1];
3683vinfos[1].maxsolutions = _nj1;
3684vinfos[2].jointtype = 1;
3685vinfos[2].foffset = j2;
3686vinfos[2].indices[0] = _ij2[0];
3687vinfos[2].indices[1] = _ij2[1];
3688vinfos[2].maxsolutions = _nj2;
3689vinfos[3].jointtype = 1;
3690vinfos[3].foffset = j3;
3691vinfos[3].indices[0] = _ij3[0];
3692vinfos[3].indices[1] = _ij3[1];
3693vinfos[3].maxsolutions = _nj3;
3694vinfos[4].jointtype = 1;
3695vinfos[4].foffset = j4;
3696vinfos[4].indices[0] = _ij4[0];
3697vinfos[4].indices[1] = _ij4[1];
3698vinfos[4].maxsolutions = _nj4;
3699vinfos[5].jointtype = 1;
3700vinfos[5].foffset = j5;
3701vinfos[5].indices[0] = _ij5[0];
3702vinfos[5].indices[1] = _ij5[1];
3703vinfos[5].maxsolutions = _nj5;
3704std::vector<int> vfree(0);
3705solutions.AddSolution(vinfos,vfree);
3706}
3707}
3708}
3709
3710} else
3711{
3712{
3713IkReal j2array[1], cj2array[1], sj2array[1];
3714bool j2valid[1]={false};
3715_nj2 = 1;
3716CheckValue<IkReal> x192=IKPowWithIntegerCheck(IKsign(gconst41),-1);
3717if(!x192.valid){
3718continue;
3719}
3720CheckValue<IkReal> x193 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
3721if(!x193.valid){
3722continue;
3723}
3724j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x192.value)))+(x193.value));
3725sj2array[0]=IKsin(j2array[0]);
3726cj2array[0]=IKcos(j2array[0]);
3727if( j2array[0] > IKPI )
3728{
3729 j2array[0]-=IK2PI;
3730}
3731else if( j2array[0] < -IKPI )
3732{ j2array[0]+=IK2PI;
3733}
3734j2valid[0] = true;
3735for(int ij2 = 0; ij2 < 1; ++ij2)
3736{
3737if( !j2valid[ij2] )
3738{
3739 continue;
3740}
3741_ij2[0] = ij2; _ij2[1] = -1;
3742for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3743{
3744if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3745{
3746 j2valid[iij2]=false; _ij2[1] = iij2; break;
3747}
3748}
3749j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3750{
3751IkReal evalcond[8];
3752IkReal x194=IKsin(j2);
3753IkReal x195=IKcos(j2);
3754IkReal x196=((1.0)*gconst41);
3755if((((1.0)+(((-1.0)*gconst41*x196)))) < -0.00001)
3756continue;
3757IkReal x197=IKsqrt(((1.0)+(((-1.0)*gconst41*x196))));
3758IkReal x198=((1.0)*x197);
3759evalcond[0]=((-1.0)*x194);
3760evalcond[1]=((-1.0)*x195);
3761evalcond[2]=(((gconst41*x194))+new_r11);
3762evalcond[3]=((((-1.0)*x195*x196))+new_r10);
3763evalcond[4]=(((x194*x197))+new_r01);
3764evalcond[5]=((((-1.0)*x195*x198))+new_r00);
3765evalcond[6]=(((new_r01*x197))+((gconst41*new_r11))+x194);
3766evalcond[7]=(x195+(((-1.0)*new_r10*x196))+(((-1.0)*new_r00*x198)));
3767if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3768{
3769continue;
3770}
3771}
3772
3773{
3774std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3775vinfos[0].jointtype = 1;
3776vinfos[0].foffset = j0;
3777vinfos[0].indices[0] = _ij0[0];
3778vinfos[0].indices[1] = _ij0[1];
3779vinfos[0].maxsolutions = _nj0;
3780vinfos[1].jointtype = 1;
3781vinfos[1].foffset = j1;
3782vinfos[1].indices[0] = _ij1[0];
3783vinfos[1].indices[1] = _ij1[1];
3784vinfos[1].maxsolutions = _nj1;
3785vinfos[2].jointtype = 1;
3786vinfos[2].foffset = j2;
3787vinfos[2].indices[0] = _ij2[0];
3788vinfos[2].indices[1] = _ij2[1];
3789vinfos[2].maxsolutions = _nj2;
3790vinfos[3].jointtype = 1;
3791vinfos[3].foffset = j3;
3792vinfos[3].indices[0] = _ij3[0];
3793vinfos[3].indices[1] = _ij3[1];
3794vinfos[3].maxsolutions = _nj3;
3795vinfos[4].jointtype = 1;
3796vinfos[4].foffset = j4;
3797vinfos[4].indices[0] = _ij4[0];
3798vinfos[4].indices[1] = _ij4[1];
3799vinfos[4].maxsolutions = _nj4;
3800vinfos[5].jointtype = 1;
3801vinfos[5].foffset = j5;
3802vinfos[5].indices[0] = _ij5[0];
3803vinfos[5].indices[1] = _ij5[1];
3804vinfos[5].maxsolutions = _nj5;
3805std::vector<int> vfree(0);
3806solutions.AddSolution(vinfos,vfree);
3807}
3808}
3809}
3810
3811}
3812
3813}
3814
3815}
3816} while(0);
3817if( bgotonextstatement )
3818{
3819bool bgotonextstatement = true;
3820do
3821{
3822if( 1 )
3823{
3824bgotonextstatement=false;
3825continue; // branch miss [j2]
3826
3827}
3828} while(0);
3829if( bgotonextstatement )
3830{
3831}
3832}
3833}
3834}
3835}
3836}
3837}
3838}
3839}
3840}
3841
3842} else
3843{
3844{
3845IkReal j2array[1], cj2array[1], sj2array[1];
3846bool j2valid[1]={false};
3847_nj2 = 1;
3848IkReal x199=new_r22*new_r22;
3849IkReal x200=((1.0)*new_r22);
3850CheckValue<IkReal> x201=IKPowWithIntegerCheck((((cj0*x199))+(((-1.0)*cj0))),-1);
3851if(!x201.valid){
3852continue;
3853}
3854CheckValue<IkReal> x202=IKPowWithIntegerCheck(((((-1.0)*sj0))+((sj0*x199))),-1);
3855if(!x202.valid){
3856continue;
3857}
3858if( IKabs(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x202.value)*((new_r00+(((-1.0)*new_r11*x200)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11))))+IKsqr(((x202.value)*((new_r00+(((-1.0)*new_r11*x200))))))-1) <= IKFAST_SINCOS_THRESH )
3859 continue;
3860j2array[0]=IKatan2(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11))), ((x202.value)*((new_r00+(((-1.0)*new_r11*x200))))));
3861sj2array[0]=IKsin(j2array[0]);
3862cj2array[0]=IKcos(j2array[0]);
3863if( j2array[0] > IKPI )
3864{
3865 j2array[0]-=IK2PI;
3866}
3867else if( j2array[0] < -IKPI )
3868{ j2array[0]+=IK2PI;
3869}
3870j2valid[0] = true;
3871for(int ij2 = 0; ij2 < 1; ++ij2)
3872{
3873if( !j2valid[ij2] )
3874{
3875 continue;
3876}
3877_ij2[0] = ij2; _ij2[1] = -1;
3878for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3879{
3880if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3881{
3882 j2valid[iij2]=false; _ij2[1] = iij2; break;
3883}
3884}
3885j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3886{
3887IkReal evalcond[10];
3888IkReal x203=IKsin(j2);
3889IkReal x204=IKcos(j2);
3890IkReal x205=((1.0)*sj0);
3891IkReal x206=((1.0)*cj0);
3892IkReal x207=(new_r22*x203);
3893IkReal x208=(new_r22*x204);
3894evalcond[0]=(x203+((cj0*new_r11))+(((-1.0)*new_r01*x205)));
3895evalcond[1]=(((new_r00*sj0))+x204+(((-1.0)*new_r10*x206)));
3896evalcond[2]=(((new_r10*sj0))+x207+((cj0*new_r00)));
3897evalcond[3]=(((new_r11*sj0))+x208+((cj0*new_r01)));
3898evalcond[4]=(((sj0*x204))+((cj0*x207))+new_r00);
3899evalcond[5]=(((sj0*x208))+((cj0*x203))+new_r11);
3900evalcond[6]=((((-1.0)*x203*x205))+((cj0*x208))+new_r01);
3901evalcond[7]=((((-1.0)*x204*x206))+((sj0*x207))+new_r10);
3902evalcond[8]=((((-1.0)*new_r10*new_r22*x205))+(((-1.0)*new_r00*new_r22*x206))+(((-1.0)*x203)));
3903evalcond[9]=((((-1.0)*new_r01*new_r22*x206))+(((-1.0)*new_r11*new_r22*x205))+(((-1.0)*x204)));
3904if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
3905{
3906continue;
3907}
3908}
3909
3910{
3911std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
3912vinfos[0].jointtype = 1;
3913vinfos[0].foffset = j0;
3914vinfos[0].indices[0] = _ij0[0];
3915vinfos[0].indices[1] = _ij0[1];
3916vinfos[0].maxsolutions = _nj0;
3917vinfos[1].jointtype = 1;
3918vinfos[1].foffset = j1;
3919vinfos[1].indices[0] = _ij1[0];
3920vinfos[1].indices[1] = _ij1[1];
3921vinfos[1].maxsolutions = _nj1;
3922vinfos[2].jointtype = 1;
3923vinfos[2].foffset = j2;
3924vinfos[2].indices[0] = _ij2[0];
3925vinfos[2].indices[1] = _ij2[1];
3926vinfos[2].maxsolutions = _nj2;
3927vinfos[3].jointtype = 1;
3928vinfos[3].foffset = j3;
3929vinfos[3].indices[0] = _ij3[0];
3930vinfos[3].indices[1] = _ij3[1];
3931vinfos[3].maxsolutions = _nj3;
3932vinfos[4].jointtype = 1;
3933vinfos[4].foffset = j4;
3934vinfos[4].indices[0] = _ij4[0];
3935vinfos[4].indices[1] = _ij4[1];
3936vinfos[4].maxsolutions = _nj4;
3937vinfos[5].jointtype = 1;
3938vinfos[5].foffset = j5;
3939vinfos[5].indices[0] = _ij5[0];
3940vinfos[5].indices[1] = _ij5[1];
3941vinfos[5].maxsolutions = _nj5;
3942std::vector<int> vfree(0);
3943solutions.AddSolution(vinfos,vfree);
3944}
3945}
3946}
3947
3948}
3949
3950}
3951
3952} else
3953{
3954{
3955IkReal j2array[1], cj2array[1], sj2array[1];
3956bool j2valid[1]={false};
3957_nj2 = 1;
3958IkReal x209=((1.0)*new_r00);
3959CheckValue<IkReal> x210=IKPowWithIntegerCheck(new_r22,-1);
3960if(!x210.valid){
3961continue;
3962}
3963if( IKabs(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r10))+(((-1.0)*sj0*x209)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0))))))+IKsqr((((cj0*new_r10))+(((-1.0)*sj0*x209))))-1) <= IKFAST_SINCOS_THRESH )
3964 continue;
3965j2array[0]=IKatan2(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0))))), (((cj0*new_r10))+(((-1.0)*sj0*x209))));
3966sj2array[0]=IKsin(j2array[0]);
3967cj2array[0]=IKcos(j2array[0]);
3968if( j2array[0] > IKPI )
3969{
3970 j2array[0]-=IK2PI;
3971}
3972else if( j2array[0] < -IKPI )
3973{ j2array[0]+=IK2PI;
3974}
3975j2valid[0] = true;
3976for(int ij2 = 0; ij2 < 1; ++ij2)
3977{
3978if( !j2valid[ij2] )
3979{
3980 continue;
3981}
3982_ij2[0] = ij2; _ij2[1] = -1;
3983for(int iij2 = ij2+1; iij2 < 1; ++iij2)
3984{
3985if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
3986{
3987 j2valid[iij2]=false; _ij2[1] = iij2; break;
3988}
3989}
3990j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
3991{
3992IkReal evalcond[10];
3993IkReal x211=IKsin(j2);
3994IkReal x212=IKcos(j2);
3995IkReal x213=((1.0)*sj0);
3996IkReal x214=((1.0)*cj0);
3997IkReal x215=(new_r22*x211);
3998IkReal x216=(new_r22*x212);
3999evalcond[0]=(x211+(((-1.0)*new_r01*x213))+((cj0*new_r11)));
4000evalcond[1]=(((new_r00*sj0))+(((-1.0)*new_r10*x214))+x212);
4001evalcond[2]=(((new_r10*sj0))+x215+((cj0*new_r00)));
4002evalcond[3]=(((new_r11*sj0))+x216+((cj0*new_r01)));
4003evalcond[4]=(((cj0*x215))+((sj0*x212))+new_r00);
4004evalcond[5]=(((cj0*x211))+((sj0*x216))+new_r11);
4005evalcond[6]=(((cj0*x216))+(((-1.0)*x211*x213))+new_r01);
4006evalcond[7]=(((sj0*x215))+new_r10+(((-1.0)*x212*x214)));
4007evalcond[8]=((((-1.0)*x211))+(((-1.0)*new_r00*new_r22*x214))+(((-1.0)*new_r10*new_r22*x213)));
4008evalcond[9]=((((-1.0)*x212))+(((-1.0)*new_r11*new_r22*x213))+(((-1.0)*new_r01*new_r22*x214)));
4009if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4010{
4011continue;
4012}
4013}
4014
4015{
4016std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4017vinfos[0].jointtype = 1;
4018vinfos[0].foffset = j0;
4019vinfos[0].indices[0] = _ij0[0];
4020vinfos[0].indices[1] = _ij0[1];
4021vinfos[0].maxsolutions = _nj0;
4022vinfos[1].jointtype = 1;
4023vinfos[1].foffset = j1;
4024vinfos[1].indices[0] = _ij1[0];
4025vinfos[1].indices[1] = _ij1[1];
4026vinfos[1].maxsolutions = _nj1;
4027vinfos[2].jointtype = 1;
4028vinfos[2].foffset = j2;
4029vinfos[2].indices[0] = _ij2[0];
4030vinfos[2].indices[1] = _ij2[1];
4031vinfos[2].maxsolutions = _nj2;
4032vinfos[3].jointtype = 1;
4033vinfos[3].foffset = j3;
4034vinfos[3].indices[0] = _ij3[0];
4035vinfos[3].indices[1] = _ij3[1];
4036vinfos[3].maxsolutions = _nj3;
4037vinfos[4].jointtype = 1;
4038vinfos[4].foffset = j4;
4039vinfos[4].indices[0] = _ij4[0];
4040vinfos[4].indices[1] = _ij4[1];
4041vinfos[4].maxsolutions = _nj4;
4042vinfos[5].jointtype = 1;
4043vinfos[5].foffset = j5;
4044vinfos[5].indices[0] = _ij5[0];
4045vinfos[5].indices[1] = _ij5[1];
4046vinfos[5].maxsolutions = _nj5;
4047std::vector<int> vfree(0);
4048solutions.AddSolution(vinfos,vfree);
4049}
4050}
4051}
4052
4053}
4054
4055}
4056
4057} else
4058{
4059{
4060IkReal j2array[1], cj2array[1], sj2array[1];
4061bool j2valid[1]={false};
4062_nj2 = 1;
4063IkReal x217=cj0*cj0;
4064IkReal x218=((1.0)*new_r00);
4065IkReal x219=(cj0*new_r22);
4066CheckValue<IkReal> x220=IKPowWithIntegerCheck(IKsign(((1.0)+(((-1.0)*x217))+((x217*(new_r22*new_r22))))),-1);
4067if(!x220.valid){
4068continue;
4069}
4070CheckValue<IkReal> x221 = IKatan2WithCheck(IkReal((((new_r01*sj0))+(((-1.0)*x218*x219)))),IkReal(((((-1.0)*new_r01*x219))+(((-1.0)*sj0*x218)))),IKFAST_ATAN2_MAGTHRESH);
4071if(!x221.valid){
4072continue;
4073}
4074j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x220.value)))+(x221.value));
4075sj2array[0]=IKsin(j2array[0]);
4076cj2array[0]=IKcos(j2array[0]);
4077if( j2array[0] > IKPI )
4078{
4079 j2array[0]-=IK2PI;
4080}
4081else if( j2array[0] < -IKPI )
4082{ j2array[0]+=IK2PI;
4083}
4084j2valid[0] = true;
4085for(int ij2 = 0; ij2 < 1; ++ij2)
4086{
4087if( !j2valid[ij2] )
4088{
4089 continue;
4090}
4091_ij2[0] = ij2; _ij2[1] = -1;
4092for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4093{
4094if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4095{
4096 j2valid[iij2]=false; _ij2[1] = iij2; break;
4097}
4098}
4099j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4100{
4101IkReal evalcond[10];
4102IkReal x222=IKsin(j2);
4103IkReal x223=IKcos(j2);
4104IkReal x224=((1.0)*sj0);
4105IkReal x225=((1.0)*cj0);
4106IkReal x226=(new_r22*x222);
4107IkReal x227=(new_r22*x223);
4108evalcond[0]=((((-1.0)*new_r01*x224))+x222+((cj0*new_r11)));
4109evalcond[1]=((((-1.0)*new_r10*x225))+((new_r00*sj0))+x223);
4110evalcond[2]=(((new_r10*sj0))+x226+((cj0*new_r00)));
4111evalcond[3]=(((new_r11*sj0))+x227+((cj0*new_r01)));
4112evalcond[4]=(((sj0*x223))+((cj0*x226))+new_r00);
4113evalcond[5]=(((sj0*x227))+((cj0*x222))+new_r11);
4114evalcond[6]=((((-1.0)*x222*x224))+((cj0*x227))+new_r01);
4115evalcond[7]=(((sj0*x226))+(((-1.0)*x223*x225))+new_r10);
4116evalcond[8]=((((-1.0)*new_r00*new_r22*x225))+(((-1.0)*new_r10*new_r22*x224))+(((-1.0)*x222)));
4117evalcond[9]=((((-1.0)*new_r11*new_r22*x224))+(((-1.0)*new_r01*new_r22*x225))+(((-1.0)*x223)));
4118if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4119{
4120continue;
4121}
4122}
4123
4124{
4125std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4126vinfos[0].jointtype = 1;
4127vinfos[0].foffset = j0;
4128vinfos[0].indices[0] = _ij0[0];
4129vinfos[0].indices[1] = _ij0[1];
4130vinfos[0].maxsolutions = _nj0;
4131vinfos[1].jointtype = 1;
4132vinfos[1].foffset = j1;
4133vinfos[1].indices[0] = _ij1[0];
4134vinfos[1].indices[1] = _ij1[1];
4135vinfos[1].maxsolutions = _nj1;
4136vinfos[2].jointtype = 1;
4137vinfos[2].foffset = j2;
4138vinfos[2].indices[0] = _ij2[0];
4139vinfos[2].indices[1] = _ij2[1];
4140vinfos[2].maxsolutions = _nj2;
4141vinfos[3].jointtype = 1;
4142vinfos[3].foffset = j3;
4143vinfos[3].indices[0] = _ij3[0];
4144vinfos[3].indices[1] = _ij3[1];
4145vinfos[3].maxsolutions = _nj3;
4146vinfos[4].jointtype = 1;
4147vinfos[4].foffset = j4;
4148vinfos[4].indices[0] = _ij4[0];
4149vinfos[4].indices[1] = _ij4[1];
4150vinfos[4].maxsolutions = _nj4;
4151vinfos[5].jointtype = 1;
4152vinfos[5].foffset = j5;
4153vinfos[5].indices[0] = _ij5[0];
4154vinfos[5].indices[1] = _ij5[1];
4155vinfos[5].maxsolutions = _nj5;
4156std::vector<int> vfree(0);
4157solutions.AddSolution(vinfos,vfree);
4158}
4159}
4160}
4161
4162}
4163
4164}
4165 }
4166
4167}
4168
4169}
4170
4171}
4172} while(0);
4173if( bgotonextstatement )
4174{
4175bool bgotonextstatement = true;
4176do
4177{
4178if( 1 )
4179{
4180bgotonextstatement=false;
4181continue; // branch miss [j0, j2]
4182
4183}
4184} while(0);
4185if( bgotonextstatement )
4186{
4187}
4188}
4189}
4190}
4191}
4192
4193} else
4194{
4195{
4196IkReal j0array[1], cj0array[1], sj0array[1];
4197bool j0valid[1]={false};
4198_nj0 = 1;
4199CheckValue<IkReal> x229=IKPowWithIntegerCheck(cj1,-1);
4200if(!x229.valid){
4201continue;
4202}
4203IkReal x228=x229.value;
4204CheckValue<IkReal> x230=IKPowWithIntegerCheck(new_r12,-1);
4205if(!x230.valid){
4206continue;
4207}
4208CheckValue<IkReal> x231=IKPowWithIntegerCheck(x228,-2);
4209if(!x231.valid){
4210continue;
4211}
4212if( IKabs((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r02*x228)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value)))))+IKsqr((new_r02*x228))-1) <= IKFAST_SINCOS_THRESH )
4213 continue;
4214j0array[0]=IKatan2((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value)))), (new_r02*x228));
4215sj0array[0]=IKsin(j0array[0]);
4216cj0array[0]=IKcos(j0array[0]);
4217if( j0array[0] > IKPI )
4218{
4219 j0array[0]-=IK2PI;
4220}
4221else if( j0array[0] < -IKPI )
4222{ j0array[0]+=IK2PI;
4223}
4224j0valid[0] = true;
4225for(int ij0 = 0; ij0 < 1; ++ij0)
4226{
4227if( !j0valid[ij0] )
4228{
4229 continue;
4230}
4231_ij0[0] = ij0; _ij0[1] = -1;
4232for(int iij0 = ij0+1; iij0 < 1; ++iij0)
4233{
4234if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
4235{
4236 j0valid[iij0]=false; _ij0[1] = iij0; break;
4237}
4238}
4239j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
4240{
4241IkReal evalcond[8];
4242IkReal x232=IKcos(j0);
4243IkReal x233=IKsin(j0);
4244IkReal x234=(cj1*x232);
4245IkReal x235=(cj1*x233);
4246IkReal x236=((1.0)*x233);
4247IkReal x237=(new_r02*x232);
4248evalcond[0]=(new_r02+(((-1.0)*x234)));
4249evalcond[1]=(new_r12+(((-1.0)*x235)));
4250evalcond[2]=((((-1.0)*new_r02*x236))+((new_r12*x232)));
4251evalcond[3]=(((new_r12*x233))+x237+(((-1.0)*cj1)));
4252evalcond[4]=(((new_r10*x235))+((new_r20*sj1))+((new_r00*x234)));
4253evalcond[5]=(((new_r11*x235))+((new_r01*x234))+((new_r21*sj1)));
4254evalcond[6]=((-1.0)+((new_r02*x234))+((new_r12*x235))+((new_r22*sj1)));
4255evalcond[7]=(((cj1*new_r22))+(((-1.0)*sj1*x237))+(((-1.0)*new_r12*sj1*x236)));
4256if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4257{
4258continue;
4259}
4260}
4261
4262{
4263IkReal j2eval[3];
4264j2eval[0]=cj1;
4265j2eval[1]=IKsign(cj1);
4266j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
4267if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
4268{
4269{
4270IkReal j2eval[2];
4271j2eval[0]=cj1;
4272j2eval[1]=sj0;
4273if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 )
4274{
4275{
4276IkReal j2eval[3];
4277j2eval[0]=cj1;
4278j2eval[1]=sj0;
4279j2eval[2]=sj1;
4280if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
4281{
4282{
4283IkReal evalcond[5];
4284bool bgotonextstatement = true;
4285do
4286{
4287evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959)));
4288evalcond[1]=new_r02;
4289evalcond[2]=new_r12;
4290evalcond[3]=new_r20;
4291evalcond[4]=new_r21;
4292if( 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 )
4293{
4294bgotonextstatement=false;
4295{
4296IkReal j2array[1], cj2array[1], sj2array[1];
4297bool j2valid[1]={false};
4298_nj2 = 1;
4299IkReal x238=((1.0)*cj0);
4300if( IKabs((((new_r01*sj0))+(((-1.0)*new_r00*x238)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+(((-1.0)*new_r00*x238))))+IKsqr(((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238))))-1) <= IKFAST_SINCOS_THRESH )
4301 continue;
4302j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x238))), ((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238))));
4303sj2array[0]=IKsin(j2array[0]);
4304cj2array[0]=IKcos(j2array[0]);
4305if( j2array[0] > IKPI )
4306{
4307 j2array[0]-=IK2PI;
4308}
4309else if( j2array[0] < -IKPI )
4310{ j2array[0]+=IK2PI;
4311}
4312j2valid[0] = true;
4313for(int ij2 = 0; ij2 < 1; ++ij2)
4314{
4315if( !j2valid[ij2] )
4316{
4317 continue;
4318}
4319_ij2[0] = ij2; _ij2[1] = -1;
4320for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4321{
4322if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4323{
4324 j2valid[iij2]=false; _ij2[1] = iij2; break;
4325}
4326}
4327j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4328{
4329IkReal evalcond[8];
4330IkReal x239=IKsin(j2);
4331IkReal x240=IKcos(j2);
4332IkReal x241=((1.0)*cj0);
4333IkReal x242=(sj0*x240);
4334IkReal x243=(cj0*x239);
4335IkReal x244=(sj0*x239);
4336IkReal x245=(x243+x242);
4337evalcond[0]=(((new_r10*sj0))+x239+((cj0*new_r00)));
4338evalcond[1]=(((new_r11*sj0))+x240+((cj0*new_r01)));
4339evalcond[2]=((((-1.0)*new_r01*sj0))+x239+((cj0*new_r11)));
4340evalcond[3]=(((new_r00*sj0))+x240+(((-1.0)*new_r10*x241)));
4341evalcond[4]=(x245+new_r00);
4342evalcond[5]=(x245+new_r11);
4343evalcond[6]=(((cj0*x240))+(((-1.0)*x244))+new_r01);
4344evalcond[7]=(x244+(((-1.0)*x240*x241))+new_r10);
4345if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4346{
4347continue;
4348}
4349}
4350
4351{
4352std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4353vinfos[0].jointtype = 1;
4354vinfos[0].foffset = j0;
4355vinfos[0].indices[0] = _ij0[0];
4356vinfos[0].indices[1] = _ij0[1];
4357vinfos[0].maxsolutions = _nj0;
4358vinfos[1].jointtype = 1;
4359vinfos[1].foffset = j1;
4360vinfos[1].indices[0] = _ij1[0];
4361vinfos[1].indices[1] = _ij1[1];
4362vinfos[1].maxsolutions = _nj1;
4363vinfos[2].jointtype = 1;
4364vinfos[2].foffset = j2;
4365vinfos[2].indices[0] = _ij2[0];
4366vinfos[2].indices[1] = _ij2[1];
4367vinfos[2].maxsolutions = _nj2;
4368vinfos[3].jointtype = 1;
4369vinfos[3].foffset = j3;
4370vinfos[3].indices[0] = _ij3[0];
4371vinfos[3].indices[1] = _ij3[1];
4372vinfos[3].maxsolutions = _nj3;
4373vinfos[4].jointtype = 1;
4374vinfos[4].foffset = j4;
4375vinfos[4].indices[0] = _ij4[0];
4376vinfos[4].indices[1] = _ij4[1];
4377vinfos[4].maxsolutions = _nj4;
4378vinfos[5].jointtype = 1;
4379vinfos[5].foffset = j5;
4380vinfos[5].indices[0] = _ij5[0];
4381vinfos[5].indices[1] = _ij5[1];
4382vinfos[5].maxsolutions = _nj5;
4383std::vector<int> vfree(0);
4384solutions.AddSolution(vinfos,vfree);
4385}
4386}
4387}
4388
4389}
4390} while(0);
4391if( bgotonextstatement )
4392{
4393bool bgotonextstatement = true;
4394do
4395{
4396evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959)));
4397evalcond[1]=new_r02;
4398evalcond[2]=new_r12;
4399evalcond[3]=new_r20;
4400evalcond[4]=new_r21;
4401if( 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 )
4402{
4403bgotonextstatement=false;
4404{
4405IkReal j2array[1], cj2array[1], sj2array[1];
4406bool j2valid[1]={false};
4407_nj2 = 1;
4408if( IKabs((((new_r01*sj0))+((cj0*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r01))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+((cj0*new_r00))))+IKsqr((((cj0*new_r01))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH )
4409 continue;
4410j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0))));
4411sj2array[0]=IKsin(j2array[0]);
4412cj2array[0]=IKcos(j2array[0]);
4413if( j2array[0] > IKPI )
4414{
4415 j2array[0]-=IK2PI;
4416}
4417else if( j2array[0] < -IKPI )
4418{ j2array[0]+=IK2PI;
4419}
4420j2valid[0] = true;
4421for(int ij2 = 0; ij2 < 1; ++ij2)
4422{
4423if( !j2valid[ij2] )
4424{
4425 continue;
4426}
4427_ij2[0] = ij2; _ij2[1] = -1;
4428for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4429{
4430if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4431{
4432 j2valid[iij2]=false; _ij2[1] = iij2; break;
4433}
4434}
4435j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4436{
4437IkReal evalcond[8];
4438IkReal x246=IKsin(j2);
4439IkReal x247=IKcos(j2);
4440IkReal x248=((1.0)*sj0);
4441IkReal x249=((1.0)*cj0);
4442IkReal x250=((1.0)*x247);
4443IkReal x251=(((x246*x248))+((x247*x249)));
4444evalcond[0]=((((-1.0)*new_r01*x248))+x246+((cj0*new_r11)));
4445evalcond[1]=(((new_r00*sj0))+x247+(((-1.0)*new_r10*x249)));
4446evalcond[2]=((((-1.0)*x246))+((new_r10*sj0))+((cj0*new_r00)));
4447evalcond[3]=(((new_r11*sj0))+((cj0*new_r01))+(((-1.0)*x250)));
4448evalcond[4]=(new_r00+((sj0*x247))+(((-1.0)*x246*x249)));
4449evalcond[5]=(((cj0*x246))+new_r11+(((-1.0)*x247*x248)));
4450evalcond[6]=(new_r01+(((-1.0)*x251)));
4451evalcond[7]=(new_r10+(((-1.0)*x251)));
4452if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4453{
4454continue;
4455}
4456}
4457
4458{
4459std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4460vinfos[0].jointtype = 1;
4461vinfos[0].foffset = j0;
4462vinfos[0].indices[0] = _ij0[0];
4463vinfos[0].indices[1] = _ij0[1];
4464vinfos[0].maxsolutions = _nj0;
4465vinfos[1].jointtype = 1;
4466vinfos[1].foffset = j1;
4467vinfos[1].indices[0] = _ij1[0];
4468vinfos[1].indices[1] = _ij1[1];
4469vinfos[1].maxsolutions = _nj1;
4470vinfos[2].jointtype = 1;
4471vinfos[2].foffset = j2;
4472vinfos[2].indices[0] = _ij2[0];
4473vinfos[2].indices[1] = _ij2[1];
4474vinfos[2].maxsolutions = _nj2;
4475vinfos[3].jointtype = 1;
4476vinfos[3].foffset = j3;
4477vinfos[3].indices[0] = _ij3[0];
4478vinfos[3].indices[1] = _ij3[1];
4479vinfos[3].maxsolutions = _nj3;
4480vinfos[4].jointtype = 1;
4481vinfos[4].foffset = j4;
4482vinfos[4].indices[0] = _ij4[0];
4483vinfos[4].indices[1] = _ij4[1];
4484vinfos[4].maxsolutions = _nj4;
4485vinfos[5].jointtype = 1;
4486vinfos[5].foffset = j5;
4487vinfos[5].indices[0] = _ij5[0];
4488vinfos[5].indices[1] = _ij5[1];
4489vinfos[5].maxsolutions = _nj5;
4490std::vector<int> vfree(0);
4491solutions.AddSolution(vinfos,vfree);
4492}
4493}
4494}
4495
4496}
4497} while(0);
4498if( bgotonextstatement )
4499{
4500bool bgotonextstatement = true;
4501do
4502{
4503evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959)));
4504evalcond[1]=new_r12;
4505if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4506{
4507bgotonextstatement=false;
4508{
4509IkReal j2array[1], cj2array[1], sj2array[1];
4510bool j2valid[1]={false};
4511_nj2 = 1;
4512if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH )
4513 continue;
4514j2array[0]=IKatan2(((-1.0)*new_r11), new_r10);
4515sj2array[0]=IKsin(j2array[0]);
4516cj2array[0]=IKcos(j2array[0]);
4517if( j2array[0] > IKPI )
4518{
4519 j2array[0]-=IK2PI;
4520}
4521else if( j2array[0] < -IKPI )
4522{ j2array[0]+=IK2PI;
4523}
4524j2valid[0] = true;
4525for(int ij2 = 0; ij2 < 1; ++ij2)
4526{
4527if( !j2valid[ij2] )
4528{
4529 continue;
4530}
4531_ij2[0] = ij2; _ij2[1] = -1;
4532for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4533{
4534if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4535{
4536 j2valid[iij2]=false; _ij2[1] = iij2; break;
4537}
4538}
4539j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4540{
4541IkReal evalcond[8];
4542IkReal x252=IKsin(j2);
4543IkReal x253=IKcos(j2);
4544IkReal x254=((1.0)*sj1);
4545IkReal x255=((1.0)*cj1);
4546evalcond[0]=(x252+new_r11);
4547evalcond[1]=(x253+(((-1.0)*new_r10)));
4548evalcond[2]=(((sj1*x252))+new_r00);
4549evalcond[3]=(((sj1*x253))+new_r01);
4550evalcond[4]=((((-1.0)*x252*x255))+new_r20);
4551evalcond[5]=(new_r21+(((-1.0)*x253*x255)));
4552evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x254))+(((-1.0)*x252)));
4553evalcond[7]=((((-1.0)*new_r01*x254))+((cj1*new_r21))+(((-1.0)*x253)));
4554if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4555{
4556continue;
4557}
4558}
4559
4560{
4561std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4562vinfos[0].jointtype = 1;
4563vinfos[0].foffset = j0;
4564vinfos[0].indices[0] = _ij0[0];
4565vinfos[0].indices[1] = _ij0[1];
4566vinfos[0].maxsolutions = _nj0;
4567vinfos[1].jointtype = 1;
4568vinfos[1].foffset = j1;
4569vinfos[1].indices[0] = _ij1[0];
4570vinfos[1].indices[1] = _ij1[1];
4571vinfos[1].maxsolutions = _nj1;
4572vinfos[2].jointtype = 1;
4573vinfos[2].foffset = j2;
4574vinfos[2].indices[0] = _ij2[0];
4575vinfos[2].indices[1] = _ij2[1];
4576vinfos[2].maxsolutions = _nj2;
4577vinfos[3].jointtype = 1;
4578vinfos[3].foffset = j3;
4579vinfos[3].indices[0] = _ij3[0];
4580vinfos[3].indices[1] = _ij3[1];
4581vinfos[3].maxsolutions = _nj3;
4582vinfos[4].jointtype = 1;
4583vinfos[4].foffset = j4;
4584vinfos[4].indices[0] = _ij4[0];
4585vinfos[4].indices[1] = _ij4[1];
4586vinfos[4].maxsolutions = _nj4;
4587vinfos[5].jointtype = 1;
4588vinfos[5].foffset = j5;
4589vinfos[5].indices[0] = _ij5[0];
4590vinfos[5].indices[1] = _ij5[1];
4591vinfos[5].maxsolutions = _nj5;
4592std::vector<int> vfree(0);
4593solutions.AddSolution(vinfos,vfree);
4594}
4595}
4596}
4597
4598}
4599} while(0);
4600if( bgotonextstatement )
4601{
4602bool bgotonextstatement = true;
4603do
4604{
4605evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959)));
4606evalcond[1]=new_r12;
4607if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4608{
4609bgotonextstatement=false;
4610{
4611IkReal j2array[1], cj2array[1], sj2array[1];
4612bool j2valid[1]={false};
4613_nj2 = 1;
4614if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH )
4615 continue;
4616j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10));
4617sj2array[0]=IKsin(j2array[0]);
4618cj2array[0]=IKcos(j2array[0]);
4619if( j2array[0] > IKPI )
4620{
4621 j2array[0]-=IK2PI;
4622}
4623else if( j2array[0] < -IKPI )
4624{ j2array[0]+=IK2PI;
4625}
4626j2valid[0] = true;
4627for(int ij2 = 0; ij2 < 1; ++ij2)
4628{
4629if( !j2valid[ij2] )
4630{
4631 continue;
4632}
4633_ij2[0] = ij2; _ij2[1] = -1;
4634for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4635{
4636if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4637{
4638 j2valid[iij2]=false; _ij2[1] = iij2; break;
4639}
4640}
4641j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4642{
4643IkReal evalcond[8];
4644IkReal x256=IKsin(j2);
4645IkReal x257=IKcos(j2);
4646IkReal x258=((1.0)*cj1);
4647evalcond[0]=(x257+new_r10);
4648evalcond[1]=(x256+(((-1.0)*new_r11)));
4649evalcond[2]=((((-1.0)*x256*x258))+new_r20);
4650evalcond[3]=((((-1.0)*x257*x258))+new_r21);
4651evalcond[4]=(((sj1*x256))+(((-1.0)*new_r00)));
4652evalcond[5]=(((sj1*x257))+(((-1.0)*new_r01)));
4653evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x256)));
4654evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x257)));
4655if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4656{
4657continue;
4658}
4659}
4660
4661{
4662std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4663vinfos[0].jointtype = 1;
4664vinfos[0].foffset = j0;
4665vinfos[0].indices[0] = _ij0[0];
4666vinfos[0].indices[1] = _ij0[1];
4667vinfos[0].maxsolutions = _nj0;
4668vinfos[1].jointtype = 1;
4669vinfos[1].foffset = j1;
4670vinfos[1].indices[0] = _ij1[0];
4671vinfos[1].indices[1] = _ij1[1];
4672vinfos[1].maxsolutions = _nj1;
4673vinfos[2].jointtype = 1;
4674vinfos[2].foffset = j2;
4675vinfos[2].indices[0] = _ij2[0];
4676vinfos[2].indices[1] = _ij2[1];
4677vinfos[2].maxsolutions = _nj2;
4678vinfos[3].jointtype = 1;
4679vinfos[3].foffset = j3;
4680vinfos[3].indices[0] = _ij3[0];
4681vinfos[3].indices[1] = _ij3[1];
4682vinfos[3].maxsolutions = _nj3;
4683vinfos[4].jointtype = 1;
4684vinfos[4].foffset = j4;
4685vinfos[4].indices[0] = _ij4[0];
4686vinfos[4].indices[1] = _ij4[1];
4687vinfos[4].maxsolutions = _nj4;
4688vinfos[5].jointtype = 1;
4689vinfos[5].foffset = j5;
4690vinfos[5].indices[0] = _ij5[0];
4691vinfos[5].indices[1] = _ij5[1];
4692vinfos[5].maxsolutions = _nj5;
4693std::vector<int> vfree(0);
4694solutions.AddSolution(vinfos,vfree);
4695}
4696}
4697}
4698
4699}
4700} while(0);
4701if( bgotonextstatement )
4702{
4703bool bgotonextstatement = true;
4704do
4705{
4706evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959)));
4707evalcond[1]=new_r22;
4708if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4709{
4710bgotonextstatement=false;
4711{
4712IkReal j2array[1], cj2array[1], sj2array[1];
4713bool j2valid[1]={false};
4714_nj2 = 1;
4715if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH )
4716 continue;
4717j2array[0]=IKatan2(new_r20, new_r21);
4718sj2array[0]=IKsin(j2array[0]);
4719cj2array[0]=IKcos(j2array[0]);
4720if( j2array[0] > IKPI )
4721{
4722 j2array[0]-=IK2PI;
4723}
4724else if( j2array[0] < -IKPI )
4725{ j2array[0]+=IK2PI;
4726}
4727j2valid[0] = true;
4728for(int ij2 = 0; ij2 < 1; ++ij2)
4729{
4730if( !j2valid[ij2] )
4731{
4732 continue;
4733}
4734_ij2[0] = ij2; _ij2[1] = -1;
4735for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4736{
4737if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4738{
4739 j2valid[iij2]=false; _ij2[1] = iij2; break;
4740}
4741}
4742j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4743{
4744IkReal evalcond[8];
4745IkReal x259=IKcos(j2);
4746IkReal x260=IKsin(j2);
4747IkReal x261=((1.0)*sj0);
4748IkReal x262=((1.0)*x259);
4749evalcond[0]=((((-1.0)*x260))+new_r20);
4750evalcond[1]=(new_r21+(((-1.0)*x262)));
4751evalcond[2]=(((sj0*x259))+new_r00);
4752evalcond[3]=(((cj0*x260))+new_r11);
4753evalcond[4]=(new_r01+(((-1.0)*x260*x261)));
4754evalcond[5]=(new_r10+(((-1.0)*new_r02*x262)));
4755evalcond[6]=((((-1.0)*new_r01*x261))+x260+((cj0*new_r11)));
4756evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x259);
4757if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4758{
4759continue;
4760}
4761}
4762
4763{
4764std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4765vinfos[0].jointtype = 1;
4766vinfos[0].foffset = j0;
4767vinfos[0].indices[0] = _ij0[0];
4768vinfos[0].indices[1] = _ij0[1];
4769vinfos[0].maxsolutions = _nj0;
4770vinfos[1].jointtype = 1;
4771vinfos[1].foffset = j1;
4772vinfos[1].indices[0] = _ij1[0];
4773vinfos[1].indices[1] = _ij1[1];
4774vinfos[1].maxsolutions = _nj1;
4775vinfos[2].jointtype = 1;
4776vinfos[2].foffset = j2;
4777vinfos[2].indices[0] = _ij2[0];
4778vinfos[2].indices[1] = _ij2[1];
4779vinfos[2].maxsolutions = _nj2;
4780vinfos[3].jointtype = 1;
4781vinfos[3].foffset = j3;
4782vinfos[3].indices[0] = _ij3[0];
4783vinfos[3].indices[1] = _ij3[1];
4784vinfos[3].maxsolutions = _nj3;
4785vinfos[4].jointtype = 1;
4786vinfos[4].foffset = j4;
4787vinfos[4].indices[0] = _ij4[0];
4788vinfos[4].indices[1] = _ij4[1];
4789vinfos[4].maxsolutions = _nj4;
4790vinfos[5].jointtype = 1;
4791vinfos[5].foffset = j5;
4792vinfos[5].indices[0] = _ij5[0];
4793vinfos[5].indices[1] = _ij5[1];
4794vinfos[5].maxsolutions = _nj5;
4795std::vector<int> vfree(0);
4796solutions.AddSolution(vinfos,vfree);
4797}
4798}
4799}
4800
4801}
4802} while(0);
4803if( bgotonextstatement )
4804{
4805bool bgotonextstatement = true;
4806do
4807{
4808evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959)));
4809evalcond[1]=new_r22;
4810if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
4811{
4812bgotonextstatement=false;
4813{
4814IkReal j2array[1], cj2array[1], sj2array[1];
4815bool j2valid[1]={false};
4816_nj2 = 1;
4817if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH )
4818 continue;
4819j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21));
4820sj2array[0]=IKsin(j2array[0]);
4821cj2array[0]=IKcos(j2array[0]);
4822if( j2array[0] > IKPI )
4823{
4824 j2array[0]-=IK2PI;
4825}
4826else if( j2array[0] < -IKPI )
4827{ j2array[0]+=IK2PI;
4828}
4829j2valid[0] = true;
4830for(int ij2 = 0; ij2 < 1; ++ij2)
4831{
4832if( !j2valid[ij2] )
4833{
4834 continue;
4835}
4836_ij2[0] = ij2; _ij2[1] = -1;
4837for(int iij2 = ij2+1; iij2 < 1; ++iij2)
4838{
4839if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4840{
4841 j2valid[iij2]=false; _ij2[1] = iij2; break;
4842}
4843}
4844j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4845{
4846IkReal evalcond[8];
4847IkReal x263=IKcos(j2);
4848IkReal x264=IKsin(j2);
4849IkReal x265=((1.0)*sj0);
4850evalcond[0]=(x264+new_r20);
4851evalcond[1]=(x263+new_r21);
4852evalcond[2]=(new_r00+((sj0*x263)));
4853evalcond[3]=(((cj0*x264))+new_r11);
4854evalcond[4]=(new_r10+((new_r02*x263)));
4855evalcond[5]=(new_r01+(((-1.0)*x264*x265)));
4856evalcond[6]=((((-1.0)*new_r01*x265))+x264+((cj0*new_r11)));
4857evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x263);
4858if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
4859{
4860continue;
4861}
4862}
4863
4864{
4865std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4866vinfos[0].jointtype = 1;
4867vinfos[0].foffset = j0;
4868vinfos[0].indices[0] = _ij0[0];
4869vinfos[0].indices[1] = _ij0[1];
4870vinfos[0].maxsolutions = _nj0;
4871vinfos[1].jointtype = 1;
4872vinfos[1].foffset = j1;
4873vinfos[1].indices[0] = _ij1[0];
4874vinfos[1].indices[1] = _ij1[1];
4875vinfos[1].maxsolutions = _nj1;
4876vinfos[2].jointtype = 1;
4877vinfos[2].foffset = j2;
4878vinfos[2].indices[0] = _ij2[0];
4879vinfos[2].indices[1] = _ij2[1];
4880vinfos[2].maxsolutions = _nj2;
4881vinfos[3].jointtype = 1;
4882vinfos[3].foffset = j3;
4883vinfos[3].indices[0] = _ij3[0];
4884vinfos[3].indices[1] = _ij3[1];
4885vinfos[3].maxsolutions = _nj3;
4886vinfos[4].jointtype = 1;
4887vinfos[4].foffset = j4;
4888vinfos[4].indices[0] = _ij4[0];
4889vinfos[4].indices[1] = _ij4[1];
4890vinfos[4].maxsolutions = _nj4;
4891vinfos[5].jointtype = 1;
4892vinfos[5].foffset = j5;
4893vinfos[5].indices[0] = _ij5[0];
4894vinfos[5].indices[1] = _ij5[1];
4895vinfos[5].maxsolutions = _nj5;
4896std::vector<int> vfree(0);
4897solutions.AddSolution(vinfos,vfree);
4898}
4899}
4900}
4901
4902}
4903} while(0);
4904if( bgotonextstatement )
4905{
4906bool bgotonextstatement = true;
4907do
4908{
4909evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21)));
4910if( IKabs(evalcond[0]) < 0.0000050000000000 )
4911{
4912bgotonextstatement=false;
4913{
4914IkReal j2eval[1];
4915new_r21=0;
4916new_r20=0;
4917new_r02=0;
4918new_r12=0;
4919j2eval[0]=IKabs(new_r22);
4920if( IKabs(j2eval[0]) < 0.0000000100000000 )
4921{
4922continue; // no branches [j2]
4923
4924} else
4925{
4926IkReal op[2+1], zeror[2];
4927int numroots;
4928op[0]=((-1.0)*new_r22);
4929op[1]=0;
4930op[2]=new_r22;
4931polyroots2(op,zeror,numroots);
4932IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1];
4933int numsolutions = 0;
4934for(int ij2 = 0; ij2 < numroots; ++ij2)
4935{
4936IkReal htj2 = zeror[ij2];
4937tempj2array[0]=((2.0)*(atan(htj2)));
4938for(int kj2 = 0; kj2 < 1; ++kj2)
4939{
4940j2array[numsolutions] = tempj2array[kj2];
4941if( j2array[numsolutions] > IKPI )
4942{
4943 j2array[numsolutions]-=IK2PI;
4944}
4945else if( j2array[numsolutions] < -IKPI )
4946{
4947 j2array[numsolutions]+=IK2PI;
4948}
4949sj2array[numsolutions] = IKsin(j2array[numsolutions]);
4950cj2array[numsolutions] = IKcos(j2array[numsolutions]);
4951numsolutions++;
4952}
4953}
4954bool j2valid[2]={true,true};
4955_nj2 = 2;
4956for(int ij2 = 0; ij2 < numsolutions; ++ij2)
4957 {
4958if( !j2valid[ij2] )
4959{
4960 continue;
4961}
4962 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
4963htj2 = IKtan(j2/2);
4964
4965_ij2[0] = ij2; _ij2[1] = -1;
4966for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2)
4967{
4968if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
4969{
4970 j2valid[iij2]=false; _ij2[1] = iij2; break;
4971}
4972}
4973{
4974std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
4975vinfos[0].jointtype = 1;
4976vinfos[0].foffset = j0;
4977vinfos[0].indices[0] = _ij0[0];
4978vinfos[0].indices[1] = _ij0[1];
4979vinfos[0].maxsolutions = _nj0;
4980vinfos[1].jointtype = 1;
4981vinfos[1].foffset = j1;
4982vinfos[1].indices[0] = _ij1[0];
4983vinfos[1].indices[1] = _ij1[1];
4984vinfos[1].maxsolutions = _nj1;
4985vinfos[2].jointtype = 1;
4986vinfos[2].foffset = j2;
4987vinfos[2].indices[0] = _ij2[0];
4988vinfos[2].indices[1] = _ij2[1];
4989vinfos[2].maxsolutions = _nj2;
4990vinfos[3].jointtype = 1;
4991vinfos[3].foffset = j3;
4992vinfos[3].indices[0] = _ij3[0];
4993vinfos[3].indices[1] = _ij3[1];
4994vinfos[3].maxsolutions = _nj3;
4995vinfos[4].jointtype = 1;
4996vinfos[4].foffset = j4;
4997vinfos[4].indices[0] = _ij4[0];
4998vinfos[4].indices[1] = _ij4[1];
4999vinfos[4].maxsolutions = _nj4;
5000vinfos[5].jointtype = 1;
5001vinfos[5].foffset = j5;
5002vinfos[5].indices[0] = _ij5[0];
5003vinfos[5].indices[1] = _ij5[1];
5004vinfos[5].maxsolutions = _nj5;
5005std::vector<int> vfree(0);
5006solutions.AddSolution(vinfos,vfree);
5007}
5008 }
5009
5010}
5011
5012}
5013
5014}
5015} while(0);
5016if( bgotonextstatement )
5017{
5018bool bgotonextstatement = true;
5019do
5020{
5021if( 1 )
5022{
5023bgotonextstatement=false;
5024continue; // branch miss [j2]
5025
5026}
5027} while(0);
5028if( bgotonextstatement )
5029{
5030}
5031}
5032}
5033}
5034}
5035}
5036}
5037}
5038}
5039
5040} else
5041{
5042{
5043IkReal j2array[1], cj2array[1], sj2array[1];
5044bool j2valid[1]={false};
5045_nj2 = 1;
5046CheckValue<IkReal> x267=IKPowWithIntegerCheck(cj1,-1);
5047if(!x267.valid){
5048continue;
5049}
5050IkReal x266=x267.value;
5051CheckValue<IkReal> x268=IKPowWithIntegerCheck(sj0,-1);
5052if(!x268.valid){
5053continue;
5054}
5055CheckValue<IkReal> x269=IKPowWithIntegerCheck(sj1,-1);
5056if(!x269.valid){
5057continue;
5058}
5059if( IKabs((new_r20*x266)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x266))+IKsqr((x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))))-1) <= IKFAST_SINCOS_THRESH )
5060 continue;
5061j2array[0]=IKatan2((new_r20*x266), (x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))));
5062sj2array[0]=IKsin(j2array[0]);
5063cj2array[0]=IKcos(j2array[0]);
5064if( j2array[0] > IKPI )
5065{
5066 j2array[0]-=IK2PI;
5067}
5068else if( j2array[0] < -IKPI )
5069{ j2array[0]+=IK2PI;
5070}
5071j2valid[0] = true;
5072for(int ij2 = 0; ij2 < 1; ++ij2)
5073{
5074if( !j2valid[ij2] )
5075{
5076 continue;
5077}
5078_ij2[0] = ij2; _ij2[1] = -1;
5079for(int iij2 = ij2+1; iij2 < 1; ++iij2)
5080{
5081if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
5082{
5083 j2valid[iij2]=false; _ij2[1] = iij2; break;
5084}
5085}
5086j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
5087{
5088IkReal evalcond[12];
5089IkReal x270=IKsin(j2);
5090IkReal x271=IKcos(j2);
5091IkReal x272=((1.0)*sj0);
5092IkReal x273=(cj0*new_r00);
5093IkReal x274=((1.0)*cj0);
5094IkReal x275=((1.0)*x271);
5095IkReal x276=(sj1*x270);
5096IkReal x277=(sj1*x271);
5097IkReal x278=((1.0)*x270);
5098evalcond[0]=((((-1.0)*cj1*x278))+new_r20);
5099evalcond[1]=((((-1.0)*cj1*x275))+new_r21);
5100evalcond[2]=((((-1.0)*new_r01*x272))+x270+((cj0*new_r11)));
5101evalcond[3]=(((new_r00*sj0))+x271+(((-1.0)*new_r10*x274)));
5102evalcond[4]=(((new_r10*sj0))+x276+x273);
5103evalcond[5]=(((new_r11*sj0))+x277+((cj0*new_r01)));
5104evalcond[6]=(new_r00+((sj0*x271))+((cj0*x276)));
5105evalcond[7]=(new_r11+((sj0*x277))+((cj0*x270)));
5106evalcond[8]=((((-1.0)*x270*x272))+new_r01+((cj0*x277)));
5107evalcond[9]=((((-1.0)*x271*x274))+new_r10+((sj0*x276)));
5108evalcond[10]=((((-1.0)*new_r10*sj1*x272))+((cj1*new_r20))+(((-1.0)*sj1*x273))+(((-1.0)*x278)));
5109evalcond[11]=(((cj1*new_r21))+(((-1.0)*x275))+(((-1.0)*new_r11*sj1*x272))+(((-1.0)*new_r01*sj1*x274)));
5110if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
5111{
5112continue;
5113}
5114}
5115
5116{
5117std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5118vinfos[0].jointtype = 1;
5119vinfos[0].foffset = j0;
5120vinfos[0].indices[0] = _ij0[0];
5121vinfos[0].indices[1] = _ij0[1];
5122vinfos[0].maxsolutions = _nj0;
5123vinfos[1].jointtype = 1;
5124vinfos[1].foffset = j1;
5125vinfos[1].indices[0] = _ij1[0];
5126vinfos[1].indices[1] = _ij1[1];
5127vinfos[1].maxsolutions = _nj1;
5128vinfos[2].jointtype = 1;
5129vinfos[2].foffset = j2;
5130vinfos[2].indices[0] = _ij2[0];
5131vinfos[2].indices[1] = _ij2[1];
5132vinfos[2].maxsolutions = _nj2;
5133vinfos[3].jointtype = 1;
5134vinfos[3].foffset = j3;
5135vinfos[3].indices[0] = _ij3[0];
5136vinfos[3].indices[1] = _ij3[1];
5137vinfos[3].maxsolutions = _nj3;
5138vinfos[4].jointtype = 1;
5139vinfos[4].foffset = j4;
5140vinfos[4].indices[0] = _ij4[0];
5141vinfos[4].indices[1] = _ij4[1];
5142vinfos[4].maxsolutions = _nj4;
5143vinfos[5].jointtype = 1;
5144vinfos[5].foffset = j5;
5145vinfos[5].indices[0] = _ij5[0];
5146vinfos[5].indices[1] = _ij5[1];
5147vinfos[5].maxsolutions = _nj5;
5148std::vector<int> vfree(0);
5149solutions.AddSolution(vinfos,vfree);
5150}
5151}
5152}
5153
5154}
5155
5156}
5157
5158} else
5159{
5160{
5161IkReal j2array[1], cj2array[1], sj2array[1];
5162bool j2valid[1]={false};
5163_nj2 = 1;
5164CheckValue<IkReal> x280=IKPowWithIntegerCheck(cj1,-1);
5165if(!x280.valid){
5166continue;
5167}
5168IkReal x279=x280.value;
5169CheckValue<IkReal> x281=IKPowWithIntegerCheck(sj0,-1);
5170if(!x281.valid){
5171continue;
5172}
5173if( IKabs((new_r20*x279)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x279))+IKsqr((x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))))-1) <= IKFAST_SINCOS_THRESH )
5174 continue;
5175j2array[0]=IKatan2((new_r20*x279), (x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))));
5176sj2array[0]=IKsin(j2array[0]);
5177cj2array[0]=IKcos(j2array[0]);
5178if( j2array[0] > IKPI )
5179{
5180 j2array[0]-=IK2PI;
5181}
5182else if( j2array[0] < -IKPI )
5183{ j2array[0]+=IK2PI;
5184}
5185j2valid[0] = true;
5186for(int ij2 = 0; ij2 < 1; ++ij2)
5187{
5188if( !j2valid[ij2] )
5189{
5190 continue;
5191}
5192_ij2[0] = ij2; _ij2[1] = -1;
5193for(int iij2 = ij2+1; iij2 < 1; ++iij2)
5194{
5195if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
5196{
5197 j2valid[iij2]=false; _ij2[1] = iij2; break;
5198}
5199}
5200j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
5201{
5202IkReal evalcond[12];
5203IkReal x282=IKsin(j2);
5204IkReal x283=IKcos(j2);
5205IkReal x284=((1.0)*sj0);
5206IkReal x285=(cj0*new_r00);
5207IkReal x286=((1.0)*cj0);
5208IkReal x287=((1.0)*x283);
5209IkReal x288=(sj1*x282);
5210IkReal x289=(sj1*x283);
5211IkReal x290=((1.0)*x282);
5212evalcond[0]=((((-1.0)*cj1*x290))+new_r20);
5213evalcond[1]=((((-1.0)*cj1*x287))+new_r21);
5214evalcond[2]=(x282+(((-1.0)*new_r01*x284))+((cj0*new_r11)));
5215evalcond[3]=(((new_r00*sj0))+x283+(((-1.0)*new_r10*x286)));
5216evalcond[4]=(((new_r10*sj0))+x288+x285);
5217evalcond[5]=(((new_r11*sj0))+x289+((cj0*new_r01)));
5218evalcond[6]=(((cj0*x288))+((sj0*x283))+new_r00);
5219evalcond[7]=(((cj0*x282))+((sj0*x289))+new_r11);
5220evalcond[8]=(((cj0*x289))+(((-1.0)*x282*x284))+new_r01);
5221evalcond[9]=(((sj0*x288))+new_r10+(((-1.0)*x283*x286)));
5222evalcond[10]=(((cj1*new_r20))+(((-1.0)*x290))+(((-1.0)*new_r10*sj1*x284))+(((-1.0)*sj1*x285)));
5223evalcond[11]=((((-1.0)*new_r01*sj1*x286))+((cj1*new_r21))+(((-1.0)*new_r11*sj1*x284))+(((-1.0)*x287)));
5224if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
5225{
5226continue;
5227}
5228}
5229
5230{
5231std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5232vinfos[0].jointtype = 1;
5233vinfos[0].foffset = j0;
5234vinfos[0].indices[0] = _ij0[0];
5235vinfos[0].indices[1] = _ij0[1];
5236vinfos[0].maxsolutions = _nj0;
5237vinfos[1].jointtype = 1;
5238vinfos[1].foffset = j1;
5239vinfos[1].indices[0] = _ij1[0];
5240vinfos[1].indices[1] = _ij1[1];
5241vinfos[1].maxsolutions = _nj1;
5242vinfos[2].jointtype = 1;
5243vinfos[2].foffset = j2;
5244vinfos[2].indices[0] = _ij2[0];
5245vinfos[2].indices[1] = _ij2[1];
5246vinfos[2].maxsolutions = _nj2;
5247vinfos[3].jointtype = 1;
5248vinfos[3].foffset = j3;
5249vinfos[3].indices[0] = _ij3[0];
5250vinfos[3].indices[1] = _ij3[1];
5251vinfos[3].maxsolutions = _nj3;
5252vinfos[4].jointtype = 1;
5253vinfos[4].foffset = j4;
5254vinfos[4].indices[0] = _ij4[0];
5255vinfos[4].indices[1] = _ij4[1];
5256vinfos[4].maxsolutions = _nj4;
5257vinfos[5].jointtype = 1;
5258vinfos[5].foffset = j5;
5259vinfos[5].indices[0] = _ij5[0];
5260vinfos[5].indices[1] = _ij5[1];
5261vinfos[5].maxsolutions = _nj5;
5262std::vector<int> vfree(0);
5263solutions.AddSolution(vinfos,vfree);
5264}
5265}
5266}
5267
5268}
5269
5270}
5271
5272} else
5273{
5274{
5275IkReal j2array[1], cj2array[1], sj2array[1];
5276bool j2valid[1]={false};
5277_nj2 = 1;
5278CheckValue<IkReal> x291=IKPowWithIntegerCheck(IKsign(cj1),-1);
5279if(!x291.valid){
5280continue;
5281}
5282CheckValue<IkReal> x292 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH);
5283if(!x292.valid){
5284continue;
5285}
5286j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x291.value)))+(x292.value));
5287sj2array[0]=IKsin(j2array[0]);
5288cj2array[0]=IKcos(j2array[0]);
5289if( j2array[0] > IKPI )
5290{
5291 j2array[0]-=IK2PI;
5292}
5293else if( j2array[0] < -IKPI )
5294{ j2array[0]+=IK2PI;
5295}
5296j2valid[0] = true;
5297for(int ij2 = 0; ij2 < 1; ++ij2)
5298{
5299if( !j2valid[ij2] )
5300{
5301 continue;
5302}
5303_ij2[0] = ij2; _ij2[1] = -1;
5304for(int iij2 = ij2+1; iij2 < 1; ++iij2)
5305{
5306if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
5307{
5308 j2valid[iij2]=false; _ij2[1] = iij2; break;
5309}
5310}
5311j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
5312{
5313IkReal evalcond[12];
5314IkReal x293=IKsin(j2);
5315IkReal x294=IKcos(j2);
5316IkReal x295=((1.0)*sj0);
5317IkReal x296=(cj0*new_r00);
5318IkReal x297=((1.0)*cj0);
5319IkReal x298=((1.0)*x294);
5320IkReal x299=(sj1*x293);
5321IkReal x300=(sj1*x294);
5322IkReal x301=((1.0)*x293);
5323evalcond[0]=((((-1.0)*cj1*x301))+new_r20);
5324evalcond[1]=((((-1.0)*cj1*x298))+new_r21);
5325evalcond[2]=((((-1.0)*new_r01*x295))+x293+((cj0*new_r11)));
5326evalcond[3]=((((-1.0)*new_r10*x297))+((new_r00*sj0))+x294);
5327evalcond[4]=(((new_r10*sj0))+x299+x296);
5328evalcond[5]=(((new_r11*sj0))+x300+((cj0*new_r01)));
5329evalcond[6]=(((sj0*x294))+new_r00+((cj0*x299)));
5330evalcond[7]=(((sj0*x300))+new_r11+((cj0*x293)));
5331evalcond[8]=((((-1.0)*x293*x295))+((cj0*x300))+new_r01);
5332evalcond[9]=(((sj0*x299))+new_r10+(((-1.0)*x294*x297)));
5333evalcond[10]=((((-1.0)*new_r10*sj1*x295))+(((-1.0)*sj1*x296))+((cj1*new_r20))+(((-1.0)*x301)));
5334evalcond[11]=((((-1.0)*new_r11*sj1*x295))+((cj1*new_r21))+(((-1.0)*x298))+(((-1.0)*new_r01*sj1*x297)));
5335if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
5336{
5337continue;
5338}
5339}
5340
5341{
5342std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5343vinfos[0].jointtype = 1;
5344vinfos[0].foffset = j0;
5345vinfos[0].indices[0] = _ij0[0];
5346vinfos[0].indices[1] = _ij0[1];
5347vinfos[0].maxsolutions = _nj0;
5348vinfos[1].jointtype = 1;
5349vinfos[1].foffset = j1;
5350vinfos[1].indices[0] = _ij1[0];
5351vinfos[1].indices[1] = _ij1[1];
5352vinfos[1].maxsolutions = _nj1;
5353vinfos[2].jointtype = 1;
5354vinfos[2].foffset = j2;
5355vinfos[2].indices[0] = _ij2[0];
5356vinfos[2].indices[1] = _ij2[1];
5357vinfos[2].maxsolutions = _nj2;
5358vinfos[3].jointtype = 1;
5359vinfos[3].foffset = j3;
5360vinfos[3].indices[0] = _ij3[0];
5361vinfos[3].indices[1] = _ij3[1];
5362vinfos[3].maxsolutions = _nj3;
5363vinfos[4].jointtype = 1;
5364vinfos[4].foffset = j4;
5365vinfos[4].indices[0] = _ij4[0];
5366vinfos[4].indices[1] = _ij4[1];
5367vinfos[4].maxsolutions = _nj4;
5368vinfos[5].jointtype = 1;
5369vinfos[5].foffset = j5;
5370vinfos[5].indices[0] = _ij5[0];
5371vinfos[5].indices[1] = _ij5[1];
5372vinfos[5].maxsolutions = _nj5;
5373std::vector<int> vfree(0);
5374solutions.AddSolution(vinfos,vfree);
5375}
5376}
5377}
5378
5379}
5380
5381}
5382}
5383}
5384
5385}
5386
5387}
5388
5389} else
5390{
5391{
5392IkReal j2array[1], cj2array[1], sj2array[1];
5393bool j2valid[1]={false};
5394_nj2 = 1;
5395CheckValue<IkReal> x302=IKPowWithIntegerCheck(IKsign(cj1),-1);
5396if(!x302.valid){
5397continue;
5398}
5399CheckValue<IkReal> x303 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH);
5400if(!x303.valid){
5401continue;
5402}
5403j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x302.value)))+(x303.value));
5404sj2array[0]=IKsin(j2array[0]);
5405cj2array[0]=IKcos(j2array[0]);
5406if( j2array[0] > IKPI )
5407{
5408 j2array[0]-=IK2PI;
5409}
5410else if( j2array[0] < -IKPI )
5411{ j2array[0]+=IK2PI;
5412}
5413j2valid[0] = true;
5414for(int ij2 = 0; ij2 < 1; ++ij2)
5415{
5416if( !j2valid[ij2] )
5417{
5418 continue;
5419}
5420_ij2[0] = ij2; _ij2[1] = -1;
5421for(int iij2 = ij2+1; iij2 < 1; ++iij2)
5422{
5423if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
5424{
5425 j2valid[iij2]=false; _ij2[1] = iij2; break;
5426}
5427}
5428j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
5429{
5430IkReal evalcond[2];
5431IkReal x304=((1.0)*cj1);
5432evalcond[0]=((((-1.0)*x304*(IKsin(j2))))+new_r20);
5433evalcond[1]=((((-1.0)*x304*(IKcos(j2))))+new_r21);
5434if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH )
5435{
5436continue;
5437}
5438}
5439
5440{
5441IkReal j0eval[3];
5442j0eval[0]=cj1;
5443j0eval[1]=IKsign(cj1);
5444j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02)));
5445if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5446{
5447{
5448IkReal j0eval[2];
5449j0eval[0]=cj1;
5450j0eval[1]=new_r01;
5451if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
5452{
5453{
5454IkReal evalcond[5];
5455bool bgotonextstatement = true;
5456do
5457{
5458evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959)));
5459evalcond[1]=new_r02;
5460evalcond[2]=new_r12;
5461evalcond[3]=new_r20;
5462evalcond[4]=new_r21;
5463if( 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 )
5464{
5465bgotonextstatement=false;
5466{
5467IkReal j0eval[3];
5468sj1=1.0;
5469cj1=0;
5470j1=1.5707963267949;
5471IkReal x305=(((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)));
5472j0eval[0]=x305;
5473j0eval[1]=((IKabs((((new_r01*sj2))+(((-1.0)*cj2*new_r00)))))+(IKabs((((cj2*new_r10))+(((-1.0)*new_r11*sj2))))));
5474j0eval[2]=IKsign(x305);
5475if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5476{
5477{
5478IkReal j0eval[3];
5479sj1=1.0;
5480cj1=0;
5481j1=1.5707963267949;
5482IkReal x306=(((cj2*new_r01))+(((-1.0)*new_r11*sj2)));
5483j0eval[0]=x306;
5484j0eval[1]=((IKabs((((cj2*sj2))+(((-1.0)*new_r00*new_r01)))))+(IKabs(((((-1.0)*(cj2*cj2)))+((new_r00*new_r11))))));
5485j0eval[2]=IKsign(x306);
5486if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5487{
5488{
5489IkReal j0eval[3];
5490sj1=1.0;
5491cj1=0;
5492j1=1.5707963267949;
5493IkReal x307=((1.0)*sj2);
5494IkReal x308=(((cj2*new_r00))+(((-1.0)*new_r10*x307)));
5495j0eval[0]=x308;
5496j0eval[1]=IKsign(x308);
5497j0eval[2]=((IKabs(((((-1.0)*cj2*x307))+((new_r10*new_r11)))))+(IKabs(((1.0)+(((-1.0)*(cj2*cj2)))+(((-1.0)*new_r00*new_r11))))));
5498if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5499{
5500{
5501IkReal evalcond[1];
5502bool bgotonextstatement = true;
5503do
5504{
5505IkReal x311 = ((new_r10*new_r10)+(new_r00*new_r00));
5506if(IKabs(x311)==0){
5507continue;
5508}
5509IkReal x309=pow(x311,-0.5);
5510IkReal x310=((-1.0)*x309);
5511CheckValue<IkReal> x312 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
5512if(!x312.valid){
5513continue;
5514}
5515IkReal gconst16=((-1.0)*(x312.value));
5516IkReal gconst17=(new_r00*x310);
5517IkReal gconst18=(new_r10*x310);
5518CheckValue<IkReal> x313 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
5519if(!x313.valid){
5520continue;
5521}
5522evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x313.value)+j2)))), 6.28318530717959)));
5523if( IKabs(evalcond[0]) < 0.0000050000000000 )
5524{
5525bgotonextstatement=false;
5526{
5527IkReal j0eval[3];
5528CheckValue<IkReal> x317 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
5529if(!x317.valid){
5530continue;
5531}
5532IkReal x314=((-1.0)*(x317.value));
5533IkReal x315=x309;
5534IkReal x316=((-1.0)*x315);
5535sj1=1.0;
5536cj1=0;
5537j1=1.5707963267949;
5538sj2=gconst17;
5539cj2=gconst18;
5540j2=x314;
5541IkReal gconst16=x314;
5542IkReal gconst17=(new_r00*x316);
5543IkReal gconst18=(new_r10*x316);
5544IkReal x318=new_r10*new_r10;
5545IkReal x319=(new_r00*new_r11);
5546IkReal x320=(x319+(((-1.0)*new_r01*new_r10)));
5547IkReal x321=x309;
5548IkReal x322=((1.0)*x321);
5549j0eval[0]=x320;
5550j0eval[1]=IKsign(x320);
5551j0eval[2]=((IKabs((((new_r00*new_r10*x321))+(((-1.0)*new_r00*new_r01*x322)))))+(IKabs(((((-1.0)*x318*x322))+((x319*x321))))));
5552if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5553{
5554{
5555IkReal j0eval[1];
5556CheckValue<IkReal> x326 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
5557if(!x326.valid){
5558continue;
5559}
5560IkReal x323=((-1.0)*(x326.value));
5561IkReal x324=x309;
5562IkReal x325=((-1.0)*x324);
5563sj1=1.0;
5564cj1=0;
5565j1=1.5707963267949;
5566sj2=gconst17;
5567cj2=gconst18;
5568j2=x323;
5569IkReal gconst16=x323;
5570IkReal gconst17=(new_r00*x325);
5571IkReal gconst18=(new_r10*x325);
5572IkReal x327=new_r10*new_r10;
5573IkReal x328=((1.0)*new_r00);
5574CheckValue<IkReal> x331=IKPowWithIntegerCheck((x327+(new_r00*new_r00)),-1);
5575if(!x331.valid){
5576continue;
5577}
5578IkReal x329=x331.value;
5579IkReal x330=(x327*x329);
5580j0eval[0]=((IKabs((((new_r00*new_r01*x330))+(((-1.0)*new_r10*x328*x329))+((new_r01*x329*(new_r00*new_r00*new_r00))))))+(IKabs((x330+(((-1.0)*new_r11*x328))))));
5581if( IKabs(j0eval[0]) < 0.0000010000000000 )
5582{
5583{
5584IkReal j0eval[3];
5585CheckValue<IkReal> x335 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
5586if(!x335.valid){
5587continue;
5588}
5589IkReal x332=((-1.0)*(x335.value));
5590IkReal x333=x309;
5591IkReal x334=((-1.0)*x333);
5592sj1=1.0;
5593cj1=0;
5594j1=1.5707963267949;
5595sj2=gconst17;
5596cj2=gconst18;
5597j2=x332;
5598IkReal gconst16=x332;
5599IkReal gconst17=(new_r00*x334);
5600IkReal gconst18=(new_r10*x334);
5601IkReal x336=new_r00*new_r00;
5602IkReal x337=(new_r00*new_r01);
5603IkReal x338=(((new_r10*new_r11))+x337);
5604IkReal x339=x309;
5605IkReal x340=(new_r00*x339);
5606j0eval[0]=x338;
5607j0eval[1]=IKsign(x338);
5608j0eval[2]=((IKabs((((new_r11*x340))+(((-1.0)*x336*x339)))))+(IKabs((((x337*x339))+((new_r10*x340))))));
5609if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5610{
5611{
5612IkReal evalcond[3];
5613bool bgotonextstatement = true;
5614do
5615{
5616evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
5617if( IKabs(evalcond[0]) < 0.0000050000000000 )
5618{
5619bgotonextstatement=false;
5620{
5621IkReal j0eval[1];
5622IkReal x341=((-1.0)*new_r10);
5623CheckValue<IkReal> x343 = IKatan2WithCheck(IkReal(0),IkReal(x341),IKFAST_ATAN2_MAGTHRESH);
5624if(!x343.valid){
5625continue;
5626}
5627IkReal x342=((-1.0)*(x343.value));
5628sj1=1.0;
5629cj1=0;
5630j1=1.5707963267949;
5631sj2=gconst17;
5632cj2=gconst18;
5633j2=x342;
5634new_r11=0;
5635new_r00=0;
5636IkReal gconst16=x342;
5637IkReal gconst17=0;
5638IkReal x344 = new_r10*new_r10;
5639if(IKabs(x344)==0){
5640continue;
5641}
5642IkReal gconst18=(x341*(pow(x344,-0.5)));
5643j0eval[0]=new_r10;
5644if( IKabs(j0eval[0]) < 0.0000010000000000 )
5645{
5646{
5647IkReal j0array[2], cj0array[2], sj0array[2];
5648bool j0valid[2]={false};
5649_nj0 = 2;
5650CheckValue<IkReal> x345=IKPowWithIntegerCheck(gconst18,-1);
5651if(!x345.valid){
5652continue;
5653}
5654cj0array[0]=(new_r10*(x345.value));
5655if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
5656{
5657 j0valid[0] = j0valid[1] = true;
5658 j0array[0] = IKacos(cj0array[0]);
5659 sj0array[0] = IKsin(j0array[0]);
5660 cj0array[1] = cj0array[0];
5661 j0array[1] = -j0array[0];
5662 sj0array[1] = -sj0array[0];
5663}
5664else if( isnan(cj0array[0]) )
5665{
5666 // probably any value will work
5667 j0valid[0] = true;
5668 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
5669}
5670for(int ij0 = 0; ij0 < 2; ++ij0)
5671{
5672if( !j0valid[ij0] )
5673{
5674 continue;
5675}
5676_ij0[0] = ij0; _ij0[1] = -1;
5677for(int iij0 = ij0+1; iij0 < 2; ++iij0)
5678{
5679if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
5680{
5681 j0valid[iij0]=false; _ij0[1] = iij0; break;
5682}
5683}
5684j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
5685{
5686IkReal evalcond[6];
5687IkReal x346=IKsin(j0);
5688IkReal x347=IKcos(j0);
5689evalcond[0]=(new_r10*x346);
5690evalcond[1]=(gconst18*x346);
5691evalcond[2]=((-1.0)*new_r01*x346);
5692evalcond[3]=(gconst18+((new_r01*x347)));
5693evalcond[4]=(((gconst18*x347))+new_r01);
5694evalcond[5]=(gconst18+(((-1.0)*new_r10*x347)));
5695if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5696{
5697continue;
5698}
5699}
5700
5701{
5702std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5703vinfos[0].jointtype = 1;
5704vinfos[0].foffset = j0;
5705vinfos[0].indices[0] = _ij0[0];
5706vinfos[0].indices[1] = _ij0[1];
5707vinfos[0].maxsolutions = _nj0;
5708vinfos[1].jointtype = 1;
5709vinfos[1].foffset = j1;
5710vinfos[1].indices[0] = _ij1[0];
5711vinfos[1].indices[1] = _ij1[1];
5712vinfos[1].maxsolutions = _nj1;
5713vinfos[2].jointtype = 1;
5714vinfos[2].foffset = j2;
5715vinfos[2].indices[0] = _ij2[0];
5716vinfos[2].indices[1] = _ij2[1];
5717vinfos[2].maxsolutions = _nj2;
5718vinfos[3].jointtype = 1;
5719vinfos[3].foffset = j3;
5720vinfos[3].indices[0] = _ij3[0];
5721vinfos[3].indices[1] = _ij3[1];
5722vinfos[3].maxsolutions = _nj3;
5723vinfos[4].jointtype = 1;
5724vinfos[4].foffset = j4;
5725vinfos[4].indices[0] = _ij4[0];
5726vinfos[4].indices[1] = _ij4[1];
5727vinfos[4].maxsolutions = _nj4;
5728vinfos[5].jointtype = 1;
5729vinfos[5].foffset = j5;
5730vinfos[5].indices[0] = _ij5[0];
5731vinfos[5].indices[1] = _ij5[1];
5732vinfos[5].maxsolutions = _nj5;
5733std::vector<int> vfree(0);
5734solutions.AddSolution(vinfos,vfree);
5735}
5736}
5737}
5738
5739} else
5740{
5741{
5742IkReal j0array[2], cj0array[2], sj0array[2];
5743bool j0valid[2]={false};
5744_nj0 = 2;
5745CheckValue<IkReal> x348=IKPowWithIntegerCheck(new_r10,-1);
5746if(!x348.valid){
5747continue;
5748}
5749cj0array[0]=(gconst18*(x348.value));
5750if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
5751{
5752 j0valid[0] = j0valid[1] = true;
5753 j0array[0] = IKacos(cj0array[0]);
5754 sj0array[0] = IKsin(j0array[0]);
5755 cj0array[1] = cj0array[0];
5756 j0array[1] = -j0array[0];
5757 sj0array[1] = -sj0array[0];
5758}
5759else if( isnan(cj0array[0]) )
5760{
5761 // probably any value will work
5762 j0valid[0] = true;
5763 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
5764}
5765for(int ij0 = 0; ij0 < 2; ++ij0)
5766{
5767if( !j0valid[ij0] )
5768{
5769 continue;
5770}
5771_ij0[0] = ij0; _ij0[1] = -1;
5772for(int iij0 = ij0+1; iij0 < 2; ++iij0)
5773{
5774if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
5775{
5776 j0valid[iij0]=false; _ij0[1] = iij0; break;
5777}
5778}
5779j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
5780{
5781IkReal evalcond[6];
5782IkReal x349=IKsin(j0);
5783IkReal x350=IKcos(j0);
5784IkReal x351=(gconst18*x350);
5785evalcond[0]=(new_r10*x349);
5786evalcond[1]=(gconst18*x349);
5787evalcond[2]=((-1.0)*new_r01*x349);
5788evalcond[3]=(((new_r01*x350))+gconst18);
5789evalcond[4]=(x351+new_r01);
5790evalcond[5]=((((-1.0)*x351))+new_r10);
5791if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5792{
5793continue;
5794}
5795}
5796
5797{
5798std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5799vinfos[0].jointtype = 1;
5800vinfos[0].foffset = j0;
5801vinfos[0].indices[0] = _ij0[0];
5802vinfos[0].indices[1] = _ij0[1];
5803vinfos[0].maxsolutions = _nj0;
5804vinfos[1].jointtype = 1;
5805vinfos[1].foffset = j1;
5806vinfos[1].indices[0] = _ij1[0];
5807vinfos[1].indices[1] = _ij1[1];
5808vinfos[1].maxsolutions = _nj1;
5809vinfos[2].jointtype = 1;
5810vinfos[2].foffset = j2;
5811vinfos[2].indices[0] = _ij2[0];
5812vinfos[2].indices[1] = _ij2[1];
5813vinfos[2].maxsolutions = _nj2;
5814vinfos[3].jointtype = 1;
5815vinfos[3].foffset = j3;
5816vinfos[3].indices[0] = _ij3[0];
5817vinfos[3].indices[1] = _ij3[1];
5818vinfos[3].maxsolutions = _nj3;
5819vinfos[4].jointtype = 1;
5820vinfos[4].foffset = j4;
5821vinfos[4].indices[0] = _ij4[0];
5822vinfos[4].indices[1] = _ij4[1];
5823vinfos[4].maxsolutions = _nj4;
5824vinfos[5].jointtype = 1;
5825vinfos[5].foffset = j5;
5826vinfos[5].indices[0] = _ij5[0];
5827vinfos[5].indices[1] = _ij5[1];
5828vinfos[5].maxsolutions = _nj5;
5829std::vector<int> vfree(0);
5830solutions.AddSolution(vinfos,vfree);
5831}
5832}
5833}
5834
5835}
5836
5837}
5838
5839}
5840} while(0);
5841if( bgotonextstatement )
5842{
5843bool bgotonextstatement = true;
5844do
5845{
5846evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
5847evalcond[1]=gconst17;
5848evalcond[2]=gconst18;
5849if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
5850{
5851bgotonextstatement=false;
5852{
5853IkReal j0eval[3];
5854IkReal x352=((-1.0)*new_r10);
5855CheckValue<IkReal> x354 = IKatan2WithCheck(IkReal(new_r00),IkReal(x352),IKFAST_ATAN2_MAGTHRESH);
5856if(!x354.valid){
5857continue;
5858}
5859IkReal x353=((-1.0)*(x354.value));
5860sj1=1.0;
5861cj1=0;
5862j1=1.5707963267949;
5863sj2=gconst17;
5864cj2=gconst18;
5865j2=x353;
5866new_r11=0;
5867new_r01=0;
5868new_r22=0;
5869new_r20=0;
5870IkReal gconst16=x353;
5871IkReal gconst17=((-1.0)*new_r00);
5872IkReal gconst18=x352;
5873j0eval[0]=1.0;
5874j0eval[1]=1.0;
5875j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10))));
5876if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5877{
5878{
5879IkReal j0eval[3];
5880IkReal x355=((-1.0)*new_r10);
5881CheckValue<IkReal> x357 = IKatan2WithCheck(IkReal(new_r00),IkReal(x355),IKFAST_ATAN2_MAGTHRESH);
5882if(!x357.valid){
5883continue;
5884}
5885IkReal x356=((-1.0)*(x357.value));
5886sj1=1.0;
5887cj1=0;
5888j1=1.5707963267949;
5889sj2=gconst17;
5890cj2=gconst18;
5891j2=x356;
5892new_r11=0;
5893new_r01=0;
5894new_r22=0;
5895new_r20=0;
5896IkReal gconst16=x356;
5897IkReal gconst17=((-1.0)*new_r00);
5898IkReal gconst18=x355;
5899j0eval[0]=1.0;
5900j0eval[1]=1.0;
5901j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10))));
5902if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5903{
5904{
5905IkReal j0eval[3];
5906IkReal x358=((-1.0)*new_r10);
5907CheckValue<IkReal> x360 = IKatan2WithCheck(IkReal(new_r00),IkReal(x358),IKFAST_ATAN2_MAGTHRESH);
5908if(!x360.valid){
5909continue;
5910}
5911IkReal x359=((-1.0)*(x360.value));
5912sj1=1.0;
5913cj1=0;
5914j1=1.5707963267949;
5915sj2=gconst17;
5916cj2=gconst18;
5917j2=x359;
5918new_r11=0;
5919new_r01=0;
5920new_r22=0;
5921new_r20=0;
5922IkReal gconst16=x359;
5923IkReal gconst17=((-1.0)*new_r00);
5924IkReal gconst18=x358;
5925j0eval[0]=-1.0;
5926j0eval[1]=-1.0;
5927j0eval[2]=((IKabs(((-1.0)+(new_r10*new_r10))))+(IKabs((new_r00*new_r10))));
5928if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
5929{
5930continue; // 3 cases reached
5931
5932} else
5933{
5934{
5935IkReal j0array[1], cj0array[1], sj0array[1];
5936bool j0valid[1]={false};
5937_nj0 = 1;
5938CheckValue<IkReal> x361=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst17*gconst17)))+(((-1.0)*(gconst18*gconst18))))),-1);
5939if(!x361.valid){
5940continue;
5941}
5942CheckValue<IkReal> x362 = IKatan2WithCheck(IkReal((gconst18*new_r00)),IkReal((gconst17*new_r00)),IKFAST_ATAN2_MAGTHRESH);
5943if(!x362.valid){
5944continue;
5945}
5946j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x361.value)))+(x362.value));
5947sj0array[0]=IKsin(j0array[0]);
5948cj0array[0]=IKcos(j0array[0]);
5949if( j0array[0] > IKPI )
5950{
5951 j0array[0]-=IK2PI;
5952}
5953else if( j0array[0] < -IKPI )
5954{ j0array[0]+=IK2PI;
5955}
5956j0valid[0] = true;
5957for(int ij0 = 0; ij0 < 1; ++ij0)
5958{
5959if( !j0valid[ij0] )
5960{
5961 continue;
5962}
5963_ij0[0] = ij0; _ij0[1] = -1;
5964for(int iij0 = ij0+1; iij0 < 1; ++iij0)
5965{
5966if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
5967{
5968 j0valid[iij0]=false; _ij0[1] = iij0; break;
5969}
5970}
5971j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
5972{
5973IkReal evalcond[6];
5974IkReal x363=IKcos(j0);
5975IkReal x364=IKsin(j0);
5976IkReal x365=(gconst17*x363);
5977IkReal x366=(gconst18*x364);
5978IkReal x367=((1.0)*x363);
5979IkReal x368=(gconst17*x364);
5980IkReal x369=(x365+x366);
5981evalcond[0]=x369;
5982evalcond[1]=(gconst17+((new_r00*x363))+((new_r10*x364)));
5983evalcond[2]=(x369+new_r00);
5984evalcond[3]=(((gconst18*x363))+(((-1.0)*x368)));
5985evalcond[4]=(gconst18+((new_r00*x364))+(((-1.0)*new_r10*x367)));
5986evalcond[5]=((((-1.0)*gconst18*x367))+x368+new_r10);
5987if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
5988{
5989continue;
5990}
5991}
5992
5993{
5994std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
5995vinfos[0].jointtype = 1;
5996vinfos[0].foffset = j0;
5997vinfos[0].indices[0] = _ij0[0];
5998vinfos[0].indices[1] = _ij0[1];
5999vinfos[0].maxsolutions = _nj0;
6000vinfos[1].jointtype = 1;
6001vinfos[1].foffset = j1;
6002vinfos[1].indices[0] = _ij1[0];
6003vinfos[1].indices[1] = _ij1[1];
6004vinfos[1].maxsolutions = _nj1;
6005vinfos[2].jointtype = 1;
6006vinfos[2].foffset = j2;
6007vinfos[2].indices[0] = _ij2[0];
6008vinfos[2].indices[1] = _ij2[1];
6009vinfos[2].maxsolutions = _nj2;
6010vinfos[3].jointtype = 1;
6011vinfos[3].foffset = j3;
6012vinfos[3].indices[0] = _ij3[0];
6013vinfos[3].indices[1] = _ij3[1];
6014vinfos[3].maxsolutions = _nj3;
6015vinfos[4].jointtype = 1;
6016vinfos[4].foffset = j4;
6017vinfos[4].indices[0] = _ij4[0];
6018vinfos[4].indices[1] = _ij4[1];
6019vinfos[4].maxsolutions = _nj4;
6020vinfos[5].jointtype = 1;
6021vinfos[5].foffset = j5;
6022vinfos[5].indices[0] = _ij5[0];
6023vinfos[5].indices[1] = _ij5[1];
6024vinfos[5].maxsolutions = _nj5;
6025std::vector<int> vfree(0);
6026solutions.AddSolution(vinfos,vfree);
6027}
6028}
6029}
6030
6031}
6032
6033}
6034
6035} else
6036{
6037{
6038IkReal j0array[1], cj0array[1], sj0array[1];
6039bool j0valid[1]={false};
6040_nj0 = 1;
6041CheckValue<IkReal> x370 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(((-1.0)*(gconst18*gconst18))),IKFAST_ATAN2_MAGTHRESH);
6042if(!x370.valid){
6043continue;
6044}
6045CheckValue<IkReal> x371=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1);
6046if(!x371.valid){
6047continue;
6048}
6049j0array[0]=((-1.5707963267949)+(x370.value)+(((1.5707963267949)*(x371.value))));
6050sj0array[0]=IKsin(j0array[0]);
6051cj0array[0]=IKcos(j0array[0]);
6052if( j0array[0] > IKPI )
6053{
6054 j0array[0]-=IK2PI;
6055}
6056else if( j0array[0] < -IKPI )
6057{ j0array[0]+=IK2PI;
6058}
6059j0valid[0] = true;
6060for(int ij0 = 0; ij0 < 1; ++ij0)
6061{
6062if( !j0valid[ij0] )
6063{
6064 continue;
6065}
6066_ij0[0] = ij0; _ij0[1] = -1;
6067for(int iij0 = ij0+1; iij0 < 1; ++iij0)
6068{
6069if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6070{
6071 j0valid[iij0]=false; _ij0[1] = iij0; break;
6072}
6073}
6074j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6075{
6076IkReal evalcond[6];
6077IkReal x372=IKcos(j0);
6078IkReal x373=IKsin(j0);
6079IkReal x374=(gconst17*x372);
6080IkReal x375=(gconst18*x373);
6081IkReal x376=((1.0)*x372);
6082IkReal x377=(gconst17*x373);
6083IkReal x378=(x375+x374);
6084evalcond[0]=x378;
6085evalcond[1]=(gconst17+((new_r00*x372))+((new_r10*x373)));
6086evalcond[2]=(x378+new_r00);
6087evalcond[3]=((((-1.0)*x377))+((gconst18*x372)));
6088evalcond[4]=(gconst18+((new_r00*x373))+(((-1.0)*new_r10*x376)));
6089evalcond[5]=((((-1.0)*gconst18*x376))+x377+new_r10);
6090if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6091{
6092continue;
6093}
6094}
6095
6096{
6097std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6098vinfos[0].jointtype = 1;
6099vinfos[0].foffset = j0;
6100vinfos[0].indices[0] = _ij0[0];
6101vinfos[0].indices[1] = _ij0[1];
6102vinfos[0].maxsolutions = _nj0;
6103vinfos[1].jointtype = 1;
6104vinfos[1].foffset = j1;
6105vinfos[1].indices[0] = _ij1[0];
6106vinfos[1].indices[1] = _ij1[1];
6107vinfos[1].maxsolutions = _nj1;
6108vinfos[2].jointtype = 1;
6109vinfos[2].foffset = j2;
6110vinfos[2].indices[0] = _ij2[0];
6111vinfos[2].indices[1] = _ij2[1];
6112vinfos[2].maxsolutions = _nj2;
6113vinfos[3].jointtype = 1;
6114vinfos[3].foffset = j3;
6115vinfos[3].indices[0] = _ij3[0];
6116vinfos[3].indices[1] = _ij3[1];
6117vinfos[3].maxsolutions = _nj3;
6118vinfos[4].jointtype = 1;
6119vinfos[4].foffset = j4;
6120vinfos[4].indices[0] = _ij4[0];
6121vinfos[4].indices[1] = _ij4[1];
6122vinfos[4].maxsolutions = _nj4;
6123vinfos[5].jointtype = 1;
6124vinfos[5].foffset = j5;
6125vinfos[5].indices[0] = _ij5[0];
6126vinfos[5].indices[1] = _ij5[1];
6127vinfos[5].maxsolutions = _nj5;
6128std::vector<int> vfree(0);
6129solutions.AddSolution(vinfos,vfree);
6130}
6131}
6132}
6133
6134}
6135
6136}
6137
6138} else
6139{
6140{
6141IkReal j0array[1], cj0array[1], sj0array[1];
6142bool j0valid[1]={false};
6143_nj0 = 1;
6144CheckValue<IkReal> x379 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(gconst17*gconst17),IKFAST_ATAN2_MAGTHRESH);
6145if(!x379.valid){
6146continue;
6147}
6148CheckValue<IkReal> x380=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1);
6149if(!x380.valid){
6150continue;
6151}
6152j0array[0]=((-1.5707963267949)+(x379.value)+(((1.5707963267949)*(x380.value))));
6153sj0array[0]=IKsin(j0array[0]);
6154cj0array[0]=IKcos(j0array[0]);
6155if( j0array[0] > IKPI )
6156{
6157 j0array[0]-=IK2PI;
6158}
6159else if( j0array[0] < -IKPI )
6160{ j0array[0]+=IK2PI;
6161}
6162j0valid[0] = true;
6163for(int ij0 = 0; ij0 < 1; ++ij0)
6164{
6165if( !j0valid[ij0] )
6166{
6167 continue;
6168}
6169_ij0[0] = ij0; _ij0[1] = -1;
6170for(int iij0 = ij0+1; iij0 < 1; ++iij0)
6171{
6172if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6173{
6174 j0valid[iij0]=false; _ij0[1] = iij0; break;
6175}
6176}
6177j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6178{
6179IkReal evalcond[6];
6180IkReal x381=IKcos(j0);
6181IkReal x382=IKsin(j0);
6182IkReal x383=(gconst17*x381);
6183IkReal x384=(gconst18*x382);
6184IkReal x385=((1.0)*x381);
6185IkReal x386=(gconst17*x382);
6186IkReal x387=(x384+x383);
6187evalcond[0]=x387;
6188evalcond[1]=(((new_r00*x381))+gconst17+((new_r10*x382)));
6189evalcond[2]=(x387+new_r00);
6190evalcond[3]=((((-1.0)*x386))+((gconst18*x381)));
6191evalcond[4]=((((-1.0)*new_r10*x385))+((new_r00*x382))+gconst18);
6192evalcond[5]=(x386+(((-1.0)*gconst18*x385))+new_r10);
6193if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6194{
6195continue;
6196}
6197}
6198
6199{
6200std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6201vinfos[0].jointtype = 1;
6202vinfos[0].foffset = j0;
6203vinfos[0].indices[0] = _ij0[0];
6204vinfos[0].indices[1] = _ij0[1];
6205vinfos[0].maxsolutions = _nj0;
6206vinfos[1].jointtype = 1;
6207vinfos[1].foffset = j1;
6208vinfos[1].indices[0] = _ij1[0];
6209vinfos[1].indices[1] = _ij1[1];
6210vinfos[1].maxsolutions = _nj1;
6211vinfos[2].jointtype = 1;
6212vinfos[2].foffset = j2;
6213vinfos[2].indices[0] = _ij2[0];
6214vinfos[2].indices[1] = _ij2[1];
6215vinfos[2].maxsolutions = _nj2;
6216vinfos[3].jointtype = 1;
6217vinfos[3].foffset = j3;
6218vinfos[3].indices[0] = _ij3[0];
6219vinfos[3].indices[1] = _ij3[1];
6220vinfos[3].maxsolutions = _nj3;
6221vinfos[4].jointtype = 1;
6222vinfos[4].foffset = j4;
6223vinfos[4].indices[0] = _ij4[0];
6224vinfos[4].indices[1] = _ij4[1];
6225vinfos[4].maxsolutions = _nj4;
6226vinfos[5].jointtype = 1;
6227vinfos[5].foffset = j5;
6228vinfos[5].indices[0] = _ij5[0];
6229vinfos[5].indices[1] = _ij5[1];
6230vinfos[5].maxsolutions = _nj5;
6231std::vector<int> vfree(0);
6232solutions.AddSolution(vinfos,vfree);
6233}
6234}
6235}
6236
6237}
6238
6239}
6240
6241}
6242} while(0);
6243if( bgotonextstatement )
6244{
6245bool bgotonextstatement = true;
6246do
6247{
6248evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
6249if( IKabs(evalcond[0]) < 0.0000050000000000 )
6250{
6251bgotonextstatement=false;
6252{
6253IkReal j0eval[1];
6254CheckValue<IkReal> x389 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
6255if(!x389.valid){
6256continue;
6257}
6258IkReal x388=((-1.0)*(x389.value));
6259sj1=1.0;
6260cj1=0;
6261j1=1.5707963267949;
6262sj2=gconst17;
6263cj2=gconst18;
6264j2=x388;
6265new_r01=0;
6266new_r10=0;
6267IkReal gconst16=x388;
6268IkReal x390 = new_r00*new_r00;
6269if(IKabs(x390)==0){
6270continue;
6271}
6272IkReal gconst17=((-1.0)*new_r00*(pow(x390,-0.5)));
6273IkReal gconst18=0;
6274j0eval[0]=new_r11;
6275if( IKabs(j0eval[0]) < 0.0000010000000000 )
6276{
6277{
6278IkReal j0eval[1];
6279CheckValue<IkReal> x392 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
6280if(!x392.valid){
6281continue;
6282}
6283IkReal x391=((-1.0)*(x392.value));
6284sj1=1.0;
6285cj1=0;
6286j1=1.5707963267949;
6287sj2=gconst17;
6288cj2=gconst18;
6289j2=x391;
6290new_r01=0;
6291new_r10=0;
6292IkReal gconst16=x391;
6293IkReal x393 = new_r00*new_r00;
6294if(IKabs(x393)==0){
6295continue;
6296}
6297IkReal gconst17=((-1.0)*new_r00*(pow(x393,-0.5)));
6298IkReal gconst18=0;
6299j0eval[0]=new_r00;
6300if( IKabs(j0eval[0]) < 0.0000010000000000 )
6301{
6302{
6303IkReal j0array[2], cj0array[2], sj0array[2];
6304bool j0valid[2]={false};
6305_nj0 = 2;
6306CheckValue<IkReal> x394=IKPowWithIntegerCheck(gconst17,-1);
6307if(!x394.valid){
6308continue;
6309}
6310cj0array[0]=((-1.0)*new_r00*(x394.value));
6311if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
6312{
6313 j0valid[0] = j0valid[1] = true;
6314 j0array[0] = IKacos(cj0array[0]);
6315 sj0array[0] = IKsin(j0array[0]);
6316 cj0array[1] = cj0array[0];
6317 j0array[1] = -j0array[0];
6318 sj0array[1] = -sj0array[0];
6319}
6320else if( isnan(cj0array[0]) )
6321{
6322 // probably any value will work
6323 j0valid[0] = true;
6324 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
6325}
6326for(int ij0 = 0; ij0 < 2; ++ij0)
6327{
6328if( !j0valid[ij0] )
6329{
6330 continue;
6331}
6332_ij0[0] = ij0; _ij0[1] = -1;
6333for(int iij0 = ij0+1; iij0 < 2; ++iij0)
6334{
6335if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6336{
6337 j0valid[iij0]=false; _ij0[1] = iij0; break;
6338}
6339}
6340j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6341{
6342IkReal evalcond[6];
6343IkReal x395=IKsin(j0);
6344IkReal x396=IKcos(j0);
6345evalcond[0]=(new_r00*x395);
6346evalcond[1]=(new_r11*x395);
6347evalcond[2]=((-1.0)*gconst17*x395);
6348evalcond[3]=(((new_r11*x396))+gconst17);
6349evalcond[4]=(gconst17+((new_r00*x396)));
6350evalcond[5]=(new_r11+((gconst17*x396)));
6351if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6352{
6353continue;
6354}
6355}
6356
6357{
6358std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6359vinfos[0].jointtype = 1;
6360vinfos[0].foffset = j0;
6361vinfos[0].indices[0] = _ij0[0];
6362vinfos[0].indices[1] = _ij0[1];
6363vinfos[0].maxsolutions = _nj0;
6364vinfos[1].jointtype = 1;
6365vinfos[1].foffset = j1;
6366vinfos[1].indices[0] = _ij1[0];
6367vinfos[1].indices[1] = _ij1[1];
6368vinfos[1].maxsolutions = _nj1;
6369vinfos[2].jointtype = 1;
6370vinfos[2].foffset = j2;
6371vinfos[2].indices[0] = _ij2[0];
6372vinfos[2].indices[1] = _ij2[1];
6373vinfos[2].maxsolutions = _nj2;
6374vinfos[3].jointtype = 1;
6375vinfos[3].foffset = j3;
6376vinfos[3].indices[0] = _ij3[0];
6377vinfos[3].indices[1] = _ij3[1];
6378vinfos[3].maxsolutions = _nj3;
6379vinfos[4].jointtype = 1;
6380vinfos[4].foffset = j4;
6381vinfos[4].indices[0] = _ij4[0];
6382vinfos[4].indices[1] = _ij4[1];
6383vinfos[4].maxsolutions = _nj4;
6384vinfos[5].jointtype = 1;
6385vinfos[5].foffset = j5;
6386vinfos[5].indices[0] = _ij5[0];
6387vinfos[5].indices[1] = _ij5[1];
6388vinfos[5].maxsolutions = _nj5;
6389std::vector<int> vfree(0);
6390solutions.AddSolution(vinfos,vfree);
6391}
6392}
6393}
6394
6395} else
6396{
6397{
6398IkReal j0array[2], cj0array[2], sj0array[2];
6399bool j0valid[2]={false};
6400_nj0 = 2;
6401CheckValue<IkReal> x397=IKPowWithIntegerCheck(new_r00,-1);
6402if(!x397.valid){
6403continue;
6404}
6405cj0array[0]=((-1.0)*gconst17*(x397.value));
6406if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
6407{
6408 j0valid[0] = j0valid[1] = true;
6409 j0array[0] = IKacos(cj0array[0]);
6410 sj0array[0] = IKsin(j0array[0]);
6411 cj0array[1] = cj0array[0];
6412 j0array[1] = -j0array[0];
6413 sj0array[1] = -sj0array[0];
6414}
6415else if( isnan(cj0array[0]) )
6416{
6417 // probably any value will work
6418 j0valid[0] = true;
6419 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
6420}
6421for(int ij0 = 0; ij0 < 2; ++ij0)
6422{
6423if( !j0valid[ij0] )
6424{
6425 continue;
6426}
6427_ij0[0] = ij0; _ij0[1] = -1;
6428for(int iij0 = ij0+1; iij0 < 2; ++iij0)
6429{
6430if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6431{
6432 j0valid[iij0]=false; _ij0[1] = iij0; break;
6433}
6434}
6435j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6436{
6437IkReal evalcond[6];
6438IkReal x398=IKsin(j0);
6439IkReal x399=IKcos(j0);
6440IkReal x400=(gconst17*x399);
6441evalcond[0]=(new_r00*x398);
6442evalcond[1]=(new_r11*x398);
6443evalcond[2]=((-1.0)*gconst17*x398);
6444evalcond[3]=(((new_r11*x399))+gconst17);
6445evalcond[4]=(x400+new_r00);
6446evalcond[5]=(x400+new_r11);
6447if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6448{
6449continue;
6450}
6451}
6452
6453{
6454std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6455vinfos[0].jointtype = 1;
6456vinfos[0].foffset = j0;
6457vinfos[0].indices[0] = _ij0[0];
6458vinfos[0].indices[1] = _ij0[1];
6459vinfos[0].maxsolutions = _nj0;
6460vinfos[1].jointtype = 1;
6461vinfos[1].foffset = j1;
6462vinfos[1].indices[0] = _ij1[0];
6463vinfos[1].indices[1] = _ij1[1];
6464vinfos[1].maxsolutions = _nj1;
6465vinfos[2].jointtype = 1;
6466vinfos[2].foffset = j2;
6467vinfos[2].indices[0] = _ij2[0];
6468vinfos[2].indices[1] = _ij2[1];
6469vinfos[2].maxsolutions = _nj2;
6470vinfos[3].jointtype = 1;
6471vinfos[3].foffset = j3;
6472vinfos[3].indices[0] = _ij3[0];
6473vinfos[3].indices[1] = _ij3[1];
6474vinfos[3].maxsolutions = _nj3;
6475vinfos[4].jointtype = 1;
6476vinfos[4].foffset = j4;
6477vinfos[4].indices[0] = _ij4[0];
6478vinfos[4].indices[1] = _ij4[1];
6479vinfos[4].maxsolutions = _nj4;
6480vinfos[5].jointtype = 1;
6481vinfos[5].foffset = j5;
6482vinfos[5].indices[0] = _ij5[0];
6483vinfos[5].indices[1] = _ij5[1];
6484vinfos[5].maxsolutions = _nj5;
6485std::vector<int> vfree(0);
6486solutions.AddSolution(vinfos,vfree);
6487}
6488}
6489}
6490
6491}
6492
6493}
6494
6495} else
6496{
6497{
6498IkReal j0array[2], cj0array[2], sj0array[2];
6499bool j0valid[2]={false};
6500_nj0 = 2;
6501CheckValue<IkReal> x401=IKPowWithIntegerCheck(new_r11,-1);
6502if(!x401.valid){
6503continue;
6504}
6505cj0array[0]=((-1.0)*gconst17*(x401.value));
6506if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
6507{
6508 j0valid[0] = j0valid[1] = true;
6509 j0array[0] = IKacos(cj0array[0]);
6510 sj0array[0] = IKsin(j0array[0]);
6511 cj0array[1] = cj0array[0];
6512 j0array[1] = -j0array[0];
6513 sj0array[1] = -sj0array[0];
6514}
6515else if( isnan(cj0array[0]) )
6516{
6517 // probably any value will work
6518 j0valid[0] = true;
6519 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
6520}
6521for(int ij0 = 0; ij0 < 2; ++ij0)
6522{
6523if( !j0valid[ij0] )
6524{
6525 continue;
6526}
6527_ij0[0] = ij0; _ij0[1] = -1;
6528for(int iij0 = ij0+1; iij0 < 2; ++iij0)
6529{
6530if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6531{
6532 j0valid[iij0]=false; _ij0[1] = iij0; break;
6533}
6534}
6535j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6536{
6537IkReal evalcond[6];
6538IkReal x402=IKsin(j0);
6539IkReal x403=IKcos(j0);
6540IkReal x404=(gconst17*x403);
6541evalcond[0]=(new_r00*x402);
6542evalcond[1]=(new_r11*x402);
6543evalcond[2]=((-1.0)*gconst17*x402);
6544evalcond[3]=(gconst17+((new_r00*x403)));
6545evalcond[4]=(x404+new_r00);
6546evalcond[5]=(x404+new_r11);
6547if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
6548{
6549continue;
6550}
6551}
6552
6553{
6554std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6555vinfos[0].jointtype = 1;
6556vinfos[0].foffset = j0;
6557vinfos[0].indices[0] = _ij0[0];
6558vinfos[0].indices[1] = _ij0[1];
6559vinfos[0].maxsolutions = _nj0;
6560vinfos[1].jointtype = 1;
6561vinfos[1].foffset = j1;
6562vinfos[1].indices[0] = _ij1[0];
6563vinfos[1].indices[1] = _ij1[1];
6564vinfos[1].maxsolutions = _nj1;
6565vinfos[2].jointtype = 1;
6566vinfos[2].foffset = j2;
6567vinfos[2].indices[0] = _ij2[0];
6568vinfos[2].indices[1] = _ij2[1];
6569vinfos[2].maxsolutions = _nj2;
6570vinfos[3].jointtype = 1;
6571vinfos[3].foffset = j3;
6572vinfos[3].indices[0] = _ij3[0];
6573vinfos[3].indices[1] = _ij3[1];
6574vinfos[3].maxsolutions = _nj3;
6575vinfos[4].jointtype = 1;
6576vinfos[4].foffset = j4;
6577vinfos[4].indices[0] = _ij4[0];
6578vinfos[4].indices[1] = _ij4[1];
6579vinfos[4].maxsolutions = _nj4;
6580vinfos[5].jointtype = 1;
6581vinfos[5].foffset = j5;
6582vinfos[5].indices[0] = _ij5[0];
6583vinfos[5].indices[1] = _ij5[1];
6584vinfos[5].maxsolutions = _nj5;
6585std::vector<int> vfree(0);
6586solutions.AddSolution(vinfos,vfree);
6587}
6588}
6589}
6590
6591}
6592
6593}
6594
6595}
6596} while(0);
6597if( bgotonextstatement )
6598{
6599bool bgotonextstatement = true;
6600do
6601{
6602evalcond[0]=IKabs(new_r00);
6603if( IKabs(evalcond[0]) < 0.0000050000000000 )
6604{
6605bgotonextstatement=false;
6606{
6607IkReal j0eval[1];
6608IkReal x405=((-1.0)*new_r10);
6609CheckValue<IkReal> x407 = IKatan2WithCheck(IkReal(0),IkReal(x405),IKFAST_ATAN2_MAGTHRESH);
6610if(!x407.valid){
6611continue;
6612}
6613IkReal x406=((-1.0)*(x407.value));
6614sj1=1.0;
6615cj1=0;
6616j1=1.5707963267949;
6617sj2=gconst17;
6618cj2=gconst18;
6619j2=x406;
6620new_r00=0;
6621IkReal gconst16=x406;
6622IkReal gconst17=0;
6623IkReal x408 = new_r10*new_r10;
6624if(IKabs(x408)==0){
6625continue;
6626}
6627IkReal gconst18=(x405*(pow(x408,-0.5)));
6628j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
6629if( IKabs(j0eval[0]) < 0.0000010000000000 )
6630{
6631{
6632IkReal j0eval[1];
6633IkReal x409=((-1.0)*new_r10);
6634CheckValue<IkReal> x411 = IKatan2WithCheck(IkReal(0),IkReal(x409),IKFAST_ATAN2_MAGTHRESH);
6635if(!x411.valid){
6636continue;
6637}
6638IkReal x410=((-1.0)*(x411.value));
6639sj1=1.0;
6640cj1=0;
6641j1=1.5707963267949;
6642sj2=gconst17;
6643cj2=gconst18;
6644j2=x410;
6645new_r00=0;
6646IkReal gconst16=x410;
6647IkReal gconst17=0;
6648IkReal x412 = new_r10*new_r10;
6649if(IKabs(x412)==0){
6650continue;
6651}
6652IkReal gconst18=(x409*(pow(x412,-0.5)));
6653j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
6654if( IKabs(j0eval[0]) < 0.0000010000000000 )
6655{
6656{
6657IkReal j0eval[1];
6658IkReal x413=((-1.0)*new_r10);
6659CheckValue<IkReal> x415 = IKatan2WithCheck(IkReal(0),IkReal(x413),IKFAST_ATAN2_MAGTHRESH);
6660if(!x415.valid){
6661continue;
6662}
6663IkReal x414=((-1.0)*(x415.value));
6664sj1=1.0;
6665cj1=0;
6666j1=1.5707963267949;
6667sj2=gconst17;
6668cj2=gconst18;
6669j2=x414;
6670new_r00=0;
6671IkReal gconst16=x414;
6672IkReal gconst17=0;
6673IkReal x416 = new_r10*new_r10;
6674if(IKabs(x416)==0){
6675continue;
6676}
6677IkReal gconst18=(x413*(pow(x416,-0.5)));
6678j0eval[0]=new_r10;
6679if( IKabs(j0eval[0]) < 0.0000010000000000 )
6680{
6681continue; // 3 cases reached
6682
6683} else
6684{
6685{
6686IkReal j0array[1], cj0array[1], sj0array[1];
6687bool j0valid[1]={false};
6688_nj0 = 1;
6689CheckValue<IkReal> x417=IKPowWithIntegerCheck(gconst18,-1);
6690if(!x417.valid){
6691continue;
6692}
6693CheckValue<IkReal> x418=IKPowWithIntegerCheck(new_r10,-1);
6694if(!x418.valid){
6695continue;
6696}
6697if( IKabs(((-1.0)*new_r11*(x417.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst18*(x418.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x417.value)))+IKsqr((gconst18*(x418.value)))-1) <= IKFAST_SINCOS_THRESH )
6698 continue;
6699j0array[0]=IKatan2(((-1.0)*new_r11*(x417.value)), (gconst18*(x418.value)));
6700sj0array[0]=IKsin(j0array[0]);
6701cj0array[0]=IKcos(j0array[0]);
6702if( j0array[0] > IKPI )
6703{
6704 j0array[0]-=IK2PI;
6705}
6706else if( j0array[0] < -IKPI )
6707{ j0array[0]+=IK2PI;
6708}
6709j0valid[0] = true;
6710for(int ij0 = 0; ij0 < 1; ++ij0)
6711{
6712if( !j0valid[ij0] )
6713{
6714 continue;
6715}
6716_ij0[0] = ij0; _ij0[1] = -1;
6717for(int iij0 = ij0+1; iij0 < 1; ++iij0)
6718{
6719if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6720{
6721 j0valid[iij0]=false; _ij0[1] = iij0; break;
6722}
6723}
6724j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6725{
6726IkReal evalcond[8];
6727IkReal x419=IKsin(j0);
6728IkReal x420=IKcos(j0);
6729IkReal x421=(gconst18*x419);
6730IkReal x422=((1.0)*x420);
6731evalcond[0]=(new_r10*x419);
6732evalcond[1]=x421;
6733evalcond[2]=(x421+new_r11);
6734evalcond[3]=(((gconst18*x420))+new_r01);
6735evalcond[4]=(gconst18+(((-1.0)*new_r10*x422)));
6736evalcond[5]=((((-1.0)*gconst18*x422))+new_r10);
6737evalcond[6]=((((-1.0)*new_r01*x419))+((new_r11*x420)));
6738evalcond[7]=(gconst18+((new_r11*x419))+((new_r01*x420)));
6739if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
6740{
6741continue;
6742}
6743}
6744
6745{
6746std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6747vinfos[0].jointtype = 1;
6748vinfos[0].foffset = j0;
6749vinfos[0].indices[0] = _ij0[0];
6750vinfos[0].indices[1] = _ij0[1];
6751vinfos[0].maxsolutions = _nj0;
6752vinfos[1].jointtype = 1;
6753vinfos[1].foffset = j1;
6754vinfos[1].indices[0] = _ij1[0];
6755vinfos[1].indices[1] = _ij1[1];
6756vinfos[1].maxsolutions = _nj1;
6757vinfos[2].jointtype = 1;
6758vinfos[2].foffset = j2;
6759vinfos[2].indices[0] = _ij2[0];
6760vinfos[2].indices[1] = _ij2[1];
6761vinfos[2].maxsolutions = _nj2;
6762vinfos[3].jointtype = 1;
6763vinfos[3].foffset = j3;
6764vinfos[3].indices[0] = _ij3[0];
6765vinfos[3].indices[1] = _ij3[1];
6766vinfos[3].maxsolutions = _nj3;
6767vinfos[4].jointtype = 1;
6768vinfos[4].foffset = j4;
6769vinfos[4].indices[0] = _ij4[0];
6770vinfos[4].indices[1] = _ij4[1];
6771vinfos[4].maxsolutions = _nj4;
6772vinfos[5].jointtype = 1;
6773vinfos[5].foffset = j5;
6774vinfos[5].indices[0] = _ij5[0];
6775vinfos[5].indices[1] = _ij5[1];
6776vinfos[5].maxsolutions = _nj5;
6777std::vector<int> vfree(0);
6778solutions.AddSolution(vinfos,vfree);
6779}
6780}
6781}
6782
6783}
6784
6785}
6786
6787} else
6788{
6789{
6790IkReal j0array[1], cj0array[1], sj0array[1];
6791bool j0valid[1]={false};
6792_nj0 = 1;
6793CheckValue<IkReal> x423=IKPowWithIntegerCheck(IKsign(gconst18),-1);
6794if(!x423.valid){
6795continue;
6796}
6797CheckValue<IkReal> x424 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
6798if(!x424.valid){
6799continue;
6800}
6801j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x423.value)))+(x424.value));
6802sj0array[0]=IKsin(j0array[0]);
6803cj0array[0]=IKcos(j0array[0]);
6804if( j0array[0] > IKPI )
6805{
6806 j0array[0]-=IK2PI;
6807}
6808else if( j0array[0] < -IKPI )
6809{ j0array[0]+=IK2PI;
6810}
6811j0valid[0] = true;
6812for(int ij0 = 0; ij0 < 1; ++ij0)
6813{
6814if( !j0valid[ij0] )
6815{
6816 continue;
6817}
6818_ij0[0] = ij0; _ij0[1] = -1;
6819for(int iij0 = ij0+1; iij0 < 1; ++iij0)
6820{
6821if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6822{
6823 j0valid[iij0]=false; _ij0[1] = iij0; break;
6824}
6825}
6826j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6827{
6828IkReal evalcond[8];
6829IkReal x425=IKsin(j0);
6830IkReal x426=IKcos(j0);
6831IkReal x427=(gconst18*x425);
6832IkReal x428=((1.0)*x426);
6833evalcond[0]=(new_r10*x425);
6834evalcond[1]=x427;
6835evalcond[2]=(x427+new_r11);
6836evalcond[3]=(((gconst18*x426))+new_r01);
6837evalcond[4]=(gconst18+(((-1.0)*new_r10*x428)));
6838evalcond[5]=((((-1.0)*gconst18*x428))+new_r10);
6839evalcond[6]=((((-1.0)*new_r01*x425))+((new_r11*x426)));
6840evalcond[7]=(gconst18+((new_r11*x425))+((new_r01*x426)));
6841if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
6842{
6843continue;
6844}
6845}
6846
6847{
6848std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6849vinfos[0].jointtype = 1;
6850vinfos[0].foffset = j0;
6851vinfos[0].indices[0] = _ij0[0];
6852vinfos[0].indices[1] = _ij0[1];
6853vinfos[0].maxsolutions = _nj0;
6854vinfos[1].jointtype = 1;
6855vinfos[1].foffset = j1;
6856vinfos[1].indices[0] = _ij1[0];
6857vinfos[1].indices[1] = _ij1[1];
6858vinfos[1].maxsolutions = _nj1;
6859vinfos[2].jointtype = 1;
6860vinfos[2].foffset = j2;
6861vinfos[2].indices[0] = _ij2[0];
6862vinfos[2].indices[1] = _ij2[1];
6863vinfos[2].maxsolutions = _nj2;
6864vinfos[3].jointtype = 1;
6865vinfos[3].foffset = j3;
6866vinfos[3].indices[0] = _ij3[0];
6867vinfos[3].indices[1] = _ij3[1];
6868vinfos[3].maxsolutions = _nj3;
6869vinfos[4].jointtype = 1;
6870vinfos[4].foffset = j4;
6871vinfos[4].indices[0] = _ij4[0];
6872vinfos[4].indices[1] = _ij4[1];
6873vinfos[4].maxsolutions = _nj4;
6874vinfos[5].jointtype = 1;
6875vinfos[5].foffset = j5;
6876vinfos[5].indices[0] = _ij5[0];
6877vinfos[5].indices[1] = _ij5[1];
6878vinfos[5].maxsolutions = _nj5;
6879std::vector<int> vfree(0);
6880solutions.AddSolution(vinfos,vfree);
6881}
6882}
6883}
6884
6885}
6886
6887}
6888
6889} else
6890{
6891{
6892IkReal j0array[1], cj0array[1], sj0array[1];
6893bool j0valid[1]={false};
6894_nj0 = 1;
6895CheckValue<IkReal> x429=IKPowWithIntegerCheck(IKsign(gconst18),-1);
6896if(!x429.valid){
6897continue;
6898}
6899CheckValue<IkReal> x430 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
6900if(!x430.valid){
6901continue;
6902}
6903j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x429.value)))+(x430.value));
6904sj0array[0]=IKsin(j0array[0]);
6905cj0array[0]=IKcos(j0array[0]);
6906if( j0array[0] > IKPI )
6907{
6908 j0array[0]-=IK2PI;
6909}
6910else if( j0array[0] < -IKPI )
6911{ j0array[0]+=IK2PI;
6912}
6913j0valid[0] = true;
6914for(int ij0 = 0; ij0 < 1; ++ij0)
6915{
6916if( !j0valid[ij0] )
6917{
6918 continue;
6919}
6920_ij0[0] = ij0; _ij0[1] = -1;
6921for(int iij0 = ij0+1; iij0 < 1; ++iij0)
6922{
6923if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
6924{
6925 j0valid[iij0]=false; _ij0[1] = iij0; break;
6926}
6927}
6928j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
6929{
6930IkReal evalcond[8];
6931IkReal x431=IKsin(j0);
6932IkReal x432=IKcos(j0);
6933IkReal x433=(gconst18*x431);
6934IkReal x434=((1.0)*x432);
6935evalcond[0]=(new_r10*x431);
6936evalcond[1]=x433;
6937evalcond[2]=(x433+new_r11);
6938evalcond[3]=(new_r01+((gconst18*x432)));
6939evalcond[4]=(gconst18+(((-1.0)*new_r10*x434)));
6940evalcond[5]=((((-1.0)*gconst18*x434))+new_r10);
6941evalcond[6]=(((new_r11*x432))+(((-1.0)*new_r01*x431)));
6942evalcond[7]=(((new_r01*x432))+gconst18+((new_r11*x431)));
6943if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
6944{
6945continue;
6946}
6947}
6948
6949{
6950std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
6951vinfos[0].jointtype = 1;
6952vinfos[0].foffset = j0;
6953vinfos[0].indices[0] = _ij0[0];
6954vinfos[0].indices[1] = _ij0[1];
6955vinfos[0].maxsolutions = _nj0;
6956vinfos[1].jointtype = 1;
6957vinfos[1].foffset = j1;
6958vinfos[1].indices[0] = _ij1[0];
6959vinfos[1].indices[1] = _ij1[1];
6960vinfos[1].maxsolutions = _nj1;
6961vinfos[2].jointtype = 1;
6962vinfos[2].foffset = j2;
6963vinfos[2].indices[0] = _ij2[0];
6964vinfos[2].indices[1] = _ij2[1];
6965vinfos[2].maxsolutions = _nj2;
6966vinfos[3].jointtype = 1;
6967vinfos[3].foffset = j3;
6968vinfos[3].indices[0] = _ij3[0];
6969vinfos[3].indices[1] = _ij3[1];
6970vinfos[3].maxsolutions = _nj3;
6971vinfos[4].jointtype = 1;
6972vinfos[4].foffset = j4;
6973vinfos[4].indices[0] = _ij4[0];
6974vinfos[4].indices[1] = _ij4[1];
6975vinfos[4].maxsolutions = _nj4;
6976vinfos[5].jointtype = 1;
6977vinfos[5].foffset = j5;
6978vinfos[5].indices[0] = _ij5[0];
6979vinfos[5].indices[1] = _ij5[1];
6980vinfos[5].maxsolutions = _nj5;
6981std::vector<int> vfree(0);
6982solutions.AddSolution(vinfos,vfree);
6983}
6984}
6985}
6986
6987}
6988
6989}
6990
6991}
6992} while(0);
6993if( bgotonextstatement )
6994{
6995bool bgotonextstatement = true;
6996do
6997{
6998evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
6999if( IKabs(evalcond[0]) < 0.0000050000000000 )
7000{
7001bgotonextstatement=false;
7002{
7003IkReal j0eval[1];
7004CheckValue<IkReal> x436 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
7005if(!x436.valid){
7006continue;
7007}
7008IkReal x435=((-1.0)*(x436.value));
7009sj1=1.0;
7010cj1=0;
7011j1=1.5707963267949;
7012sj2=gconst17;
7013cj2=gconst18;
7014j2=x435;
7015new_r11=0;
7016new_r10=0;
7017new_r22=0;
7018new_r02=0;
7019IkReal gconst16=x435;
7020IkReal x437 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
7021if(IKabs(x437)==0){
7022continue;
7023}
7024IkReal gconst17=((-1.0)*new_r00*(pow(x437,-0.5)));
7025IkReal gconst18=0;
7026j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
7027if( IKabs(j0eval[0]) < 0.0000010000000000 )
7028{
7029{
7030IkReal j0eval[2];
7031CheckValue<IkReal> x439 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
7032if(!x439.valid){
7033continue;
7034}
7035IkReal x438=((-1.0)*(x439.value));
7036sj1=1.0;
7037cj1=0;
7038j1=1.5707963267949;
7039sj2=gconst17;
7040cj2=gconst18;
7041j2=x438;
7042new_r11=0;
7043new_r10=0;
7044new_r22=0;
7045new_r02=0;
7046IkReal gconst16=x438;
7047IkReal x440 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
7048if(IKabs(x440)==0){
7049continue;
7050}
7051IkReal gconst17=((-1.0)*new_r00*(pow(x440,-0.5)));
7052IkReal gconst18=0;
7053j0eval[0]=new_r01;
7054j0eval[1]=new_r00;
7055if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
7056{
7057{
7058IkReal j0eval[1];
7059CheckValue<IkReal> x442 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
7060if(!x442.valid){
7061continue;
7062}
7063IkReal x441=((-1.0)*(x442.value));
7064sj1=1.0;
7065cj1=0;
7066j1=1.5707963267949;
7067sj2=gconst17;
7068cj2=gconst18;
7069j2=x441;
7070new_r11=0;
7071new_r10=0;
7072new_r22=0;
7073new_r02=0;
7074IkReal gconst16=x441;
7075IkReal x443 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
7076if(IKabs(x443)==0){
7077continue;
7078}
7079IkReal gconst17=((-1.0)*new_r00*(pow(x443,-0.5)));
7080IkReal gconst18=0;
7081j0eval[0]=new_r00;
7082if( IKabs(j0eval[0]) < 0.0000010000000000 )
7083{
7084continue; // 3 cases reached
7085
7086} else
7087{
7088{
7089IkReal j0array[1], cj0array[1], sj0array[1];
7090bool j0valid[1]={false};
7091_nj0 = 1;
7092CheckValue<IkReal> x444=IKPowWithIntegerCheck(gconst17,-1);
7093if(!x444.valid){
7094continue;
7095}
7096CheckValue<IkReal> x445=IKPowWithIntegerCheck(new_r00,-1);
7097if(!x445.valid){
7098continue;
7099}
7100if( IKabs((new_r01*(x444.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst17*(x445.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x444.value)))+IKsqr(((-1.0)*gconst17*(x445.value)))-1) <= IKFAST_SINCOS_THRESH )
7101 continue;
7102j0array[0]=IKatan2((new_r01*(x444.value)), ((-1.0)*gconst17*(x445.value)));
7103sj0array[0]=IKsin(j0array[0]);
7104cj0array[0]=IKcos(j0array[0]);
7105if( j0array[0] > IKPI )
7106{
7107 j0array[0]-=IK2PI;
7108}
7109else if( j0array[0] < -IKPI )
7110{ j0array[0]+=IK2PI;
7111}
7112j0valid[0] = true;
7113for(int ij0 = 0; ij0 < 1; ++ij0)
7114{
7115if( !j0valid[ij0] )
7116{
7117 continue;
7118}
7119_ij0[0] = ij0; _ij0[1] = -1;
7120for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7121{
7122if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7123{
7124 j0valid[iij0]=false; _ij0[1] = iij0; break;
7125}
7126}
7127j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7128{
7129IkReal evalcond[8];
7130IkReal x446=IKcos(j0);
7131IkReal x447=IKsin(j0);
7132IkReal x448=(gconst17*x446);
7133IkReal x449=((1.0)*x447);
7134evalcond[0]=(new_r00*x447);
7135evalcond[1]=(new_r01*x446);
7136evalcond[2]=x448;
7137evalcond[3]=(gconst17*x447);
7138evalcond[4]=(((new_r00*x446))+gconst17);
7139evalcond[5]=(x448+new_r00);
7140evalcond[6]=((((-1.0)*new_r01*x449))+gconst17);
7141evalcond[7]=((((-1.0)*gconst17*x449))+new_r01);
7142if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7143{
7144continue;
7145}
7146}
7147
7148{
7149std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7150vinfos[0].jointtype = 1;
7151vinfos[0].foffset = j0;
7152vinfos[0].indices[0] = _ij0[0];
7153vinfos[0].indices[1] = _ij0[1];
7154vinfos[0].maxsolutions = _nj0;
7155vinfos[1].jointtype = 1;
7156vinfos[1].foffset = j1;
7157vinfos[1].indices[0] = _ij1[0];
7158vinfos[1].indices[1] = _ij1[1];
7159vinfos[1].maxsolutions = _nj1;
7160vinfos[2].jointtype = 1;
7161vinfos[2].foffset = j2;
7162vinfos[2].indices[0] = _ij2[0];
7163vinfos[2].indices[1] = _ij2[1];
7164vinfos[2].maxsolutions = _nj2;
7165vinfos[3].jointtype = 1;
7166vinfos[3].foffset = j3;
7167vinfos[3].indices[0] = _ij3[0];
7168vinfos[3].indices[1] = _ij3[1];
7169vinfos[3].maxsolutions = _nj3;
7170vinfos[4].jointtype = 1;
7171vinfos[4].foffset = j4;
7172vinfos[4].indices[0] = _ij4[0];
7173vinfos[4].indices[1] = _ij4[1];
7174vinfos[4].maxsolutions = _nj4;
7175vinfos[5].jointtype = 1;
7176vinfos[5].foffset = j5;
7177vinfos[5].indices[0] = _ij5[0];
7178vinfos[5].indices[1] = _ij5[1];
7179vinfos[5].maxsolutions = _nj5;
7180std::vector<int> vfree(0);
7181solutions.AddSolution(vinfos,vfree);
7182}
7183}
7184}
7185
7186}
7187
7188}
7189
7190} else
7191{
7192{
7193IkReal j0array[1], cj0array[1], sj0array[1];
7194bool j0valid[1]={false};
7195_nj0 = 1;
7196CheckValue<IkReal> x450=IKPowWithIntegerCheck(new_r01,-1);
7197if(!x450.valid){
7198continue;
7199}
7200CheckValue<IkReal> x451=IKPowWithIntegerCheck(new_r00,-1);
7201if(!x451.valid){
7202continue;
7203}
7204if( IKabs((gconst17*(x450.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst17*(x451.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst17*(x450.value)))+IKsqr(((-1.0)*gconst17*(x451.value)))-1) <= IKFAST_SINCOS_THRESH )
7205 continue;
7206j0array[0]=IKatan2((gconst17*(x450.value)), ((-1.0)*gconst17*(x451.value)));
7207sj0array[0]=IKsin(j0array[0]);
7208cj0array[0]=IKcos(j0array[0]);
7209if( j0array[0] > IKPI )
7210{
7211 j0array[0]-=IK2PI;
7212}
7213else if( j0array[0] < -IKPI )
7214{ j0array[0]+=IK2PI;
7215}
7216j0valid[0] = true;
7217for(int ij0 = 0; ij0 < 1; ++ij0)
7218{
7219if( !j0valid[ij0] )
7220{
7221 continue;
7222}
7223_ij0[0] = ij0; _ij0[1] = -1;
7224for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7225{
7226if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7227{
7228 j0valid[iij0]=false; _ij0[1] = iij0; break;
7229}
7230}
7231j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7232{
7233IkReal evalcond[8];
7234IkReal x452=IKcos(j0);
7235IkReal x453=IKsin(j0);
7236IkReal x454=(gconst17*x452);
7237IkReal x455=((1.0)*x453);
7238evalcond[0]=(new_r00*x453);
7239evalcond[1]=(new_r01*x452);
7240evalcond[2]=x454;
7241evalcond[3]=(gconst17*x453);
7242evalcond[4]=(((new_r00*x452))+gconst17);
7243evalcond[5]=(x454+new_r00);
7244evalcond[6]=((((-1.0)*new_r01*x455))+gconst17);
7245evalcond[7]=((((-1.0)*gconst17*x455))+new_r01);
7246if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7247{
7248continue;
7249}
7250}
7251
7252{
7253std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7254vinfos[0].jointtype = 1;
7255vinfos[0].foffset = j0;
7256vinfos[0].indices[0] = _ij0[0];
7257vinfos[0].indices[1] = _ij0[1];
7258vinfos[0].maxsolutions = _nj0;
7259vinfos[1].jointtype = 1;
7260vinfos[1].foffset = j1;
7261vinfos[1].indices[0] = _ij1[0];
7262vinfos[1].indices[1] = _ij1[1];
7263vinfos[1].maxsolutions = _nj1;
7264vinfos[2].jointtype = 1;
7265vinfos[2].foffset = j2;
7266vinfos[2].indices[0] = _ij2[0];
7267vinfos[2].indices[1] = _ij2[1];
7268vinfos[2].maxsolutions = _nj2;
7269vinfos[3].jointtype = 1;
7270vinfos[3].foffset = j3;
7271vinfos[3].indices[0] = _ij3[0];
7272vinfos[3].indices[1] = _ij3[1];
7273vinfos[3].maxsolutions = _nj3;
7274vinfos[4].jointtype = 1;
7275vinfos[4].foffset = j4;
7276vinfos[4].indices[0] = _ij4[0];
7277vinfos[4].indices[1] = _ij4[1];
7278vinfos[4].maxsolutions = _nj4;
7279vinfos[5].jointtype = 1;
7280vinfos[5].foffset = j5;
7281vinfos[5].indices[0] = _ij5[0];
7282vinfos[5].indices[1] = _ij5[1];
7283vinfos[5].maxsolutions = _nj5;
7284std::vector<int> vfree(0);
7285solutions.AddSolution(vinfos,vfree);
7286}
7287}
7288}
7289
7290}
7291
7292}
7293
7294} else
7295{
7296{
7297IkReal j0array[1], cj0array[1], sj0array[1];
7298bool j0valid[1]={false};
7299_nj0 = 1;
7300CheckValue<IkReal> x456=IKPowWithIntegerCheck(IKsign(gconst17),-1);
7301if(!x456.valid){
7302continue;
7303}
7304CheckValue<IkReal> x457 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
7305if(!x457.valid){
7306continue;
7307}
7308j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x456.value)))+(x457.value));
7309sj0array[0]=IKsin(j0array[0]);
7310cj0array[0]=IKcos(j0array[0]);
7311if( j0array[0] > IKPI )
7312{
7313 j0array[0]-=IK2PI;
7314}
7315else if( j0array[0] < -IKPI )
7316{ j0array[0]+=IK2PI;
7317}
7318j0valid[0] = true;
7319for(int ij0 = 0; ij0 < 1; ++ij0)
7320{
7321if( !j0valid[ij0] )
7322{
7323 continue;
7324}
7325_ij0[0] = ij0; _ij0[1] = -1;
7326for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7327{
7328if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7329{
7330 j0valid[iij0]=false; _ij0[1] = iij0; break;
7331}
7332}
7333j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7334{
7335IkReal evalcond[8];
7336IkReal x458=IKcos(j0);
7337IkReal x459=IKsin(j0);
7338IkReal x460=(gconst17*x458);
7339IkReal x461=((1.0)*x459);
7340evalcond[0]=(new_r00*x459);
7341evalcond[1]=(new_r01*x458);
7342evalcond[2]=x460;
7343evalcond[3]=(gconst17*x459);
7344evalcond[4]=(((new_r00*x458))+gconst17);
7345evalcond[5]=(x460+new_r00);
7346evalcond[6]=(gconst17+(((-1.0)*new_r01*x461)));
7347evalcond[7]=((((-1.0)*gconst17*x461))+new_r01);
7348if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7349{
7350continue;
7351}
7352}
7353
7354{
7355std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7356vinfos[0].jointtype = 1;
7357vinfos[0].foffset = j0;
7358vinfos[0].indices[0] = _ij0[0];
7359vinfos[0].indices[1] = _ij0[1];
7360vinfos[0].maxsolutions = _nj0;
7361vinfos[1].jointtype = 1;
7362vinfos[1].foffset = j1;
7363vinfos[1].indices[0] = _ij1[0];
7364vinfos[1].indices[1] = _ij1[1];
7365vinfos[1].maxsolutions = _nj1;
7366vinfos[2].jointtype = 1;
7367vinfos[2].foffset = j2;
7368vinfos[2].indices[0] = _ij2[0];
7369vinfos[2].indices[1] = _ij2[1];
7370vinfos[2].maxsolutions = _nj2;
7371vinfos[3].jointtype = 1;
7372vinfos[3].foffset = j3;
7373vinfos[3].indices[0] = _ij3[0];
7374vinfos[3].indices[1] = _ij3[1];
7375vinfos[3].maxsolutions = _nj3;
7376vinfos[4].jointtype = 1;
7377vinfos[4].foffset = j4;
7378vinfos[4].indices[0] = _ij4[0];
7379vinfos[4].indices[1] = _ij4[1];
7380vinfos[4].maxsolutions = _nj4;
7381vinfos[5].jointtype = 1;
7382vinfos[5].foffset = j5;
7383vinfos[5].indices[0] = _ij5[0];
7384vinfos[5].indices[1] = _ij5[1];
7385vinfos[5].maxsolutions = _nj5;
7386std::vector<int> vfree(0);
7387solutions.AddSolution(vinfos,vfree);
7388}
7389}
7390}
7391
7392}
7393
7394}
7395
7396}
7397} while(0);
7398if( bgotonextstatement )
7399{
7400bool bgotonextstatement = true;
7401do
7402{
7403if( 1 )
7404{
7405bgotonextstatement=false;
7406continue; // branch miss [j0]
7407
7408}
7409} while(0);
7410if( bgotonextstatement )
7411{
7412}
7413}
7414}
7415}
7416}
7417}
7418}
7419
7420} else
7421{
7422{
7423IkReal j0array[1], cj0array[1], sj0array[1];
7424bool j0valid[1]={false};
7425_nj0 = 1;
7426IkReal x462=((1.0)*gconst17);
7427CheckValue<IkReal> x463=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
7428if(!x463.valid){
7429continue;
7430}
7431CheckValue<IkReal> x464 = IKatan2WithCheck(IkReal(((((-1.0)*new_r11*x462))+((gconst17*new_r00)))),IkReal(((((-1.0)*new_r10*x462))+(((-1.0)*new_r01*x462)))),IKFAST_ATAN2_MAGTHRESH);
7432if(!x464.valid){
7433continue;
7434}
7435j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x463.value)))+(x464.value));
7436sj0array[0]=IKsin(j0array[0]);
7437cj0array[0]=IKcos(j0array[0]);
7438if( j0array[0] > IKPI )
7439{
7440 j0array[0]-=IK2PI;
7441}
7442else if( j0array[0] < -IKPI )
7443{ j0array[0]+=IK2PI;
7444}
7445j0valid[0] = true;
7446for(int ij0 = 0; ij0 < 1; ++ij0)
7447{
7448if( !j0valid[ij0] )
7449{
7450 continue;
7451}
7452_ij0[0] = ij0; _ij0[1] = -1;
7453for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7454{
7455if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7456{
7457 j0valid[iij0]=false; _ij0[1] = iij0; break;
7458}
7459}
7460j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7461{
7462IkReal evalcond[8];
7463IkReal x465=IKsin(j0);
7464IkReal x466=IKcos(j0);
7465IkReal x467=(gconst17*x466);
7466IkReal x468=(gconst18*x465);
7467IkReal x469=(gconst17*x465);
7468IkReal x470=((1.0)*x466);
7469IkReal x471=(x468+x467);
7470evalcond[0]=(((new_r10*x465))+((new_r00*x466))+gconst17);
7471evalcond[1]=(((new_r11*x465))+((new_r01*x466))+gconst18);
7472evalcond[2]=(x471+new_r00);
7473evalcond[3]=(x471+new_r11);
7474evalcond[4]=(((new_r11*x466))+gconst17+(((-1.0)*new_r01*x465)));
7475evalcond[5]=(((new_r00*x465))+gconst18+(((-1.0)*new_r10*x470)));
7476evalcond[6]=((((-1.0)*x469))+((gconst18*x466))+new_r01);
7477evalcond[7]=((((-1.0)*gconst18*x470))+x469+new_r10);
7478if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7479{
7480continue;
7481}
7482}
7483
7484{
7485std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7486vinfos[0].jointtype = 1;
7487vinfos[0].foffset = j0;
7488vinfos[0].indices[0] = _ij0[0];
7489vinfos[0].indices[1] = _ij0[1];
7490vinfos[0].maxsolutions = _nj0;
7491vinfos[1].jointtype = 1;
7492vinfos[1].foffset = j1;
7493vinfos[1].indices[0] = _ij1[0];
7494vinfos[1].indices[1] = _ij1[1];
7495vinfos[1].maxsolutions = _nj1;
7496vinfos[2].jointtype = 1;
7497vinfos[2].foffset = j2;
7498vinfos[2].indices[0] = _ij2[0];
7499vinfos[2].indices[1] = _ij2[1];
7500vinfos[2].maxsolutions = _nj2;
7501vinfos[3].jointtype = 1;
7502vinfos[3].foffset = j3;
7503vinfos[3].indices[0] = _ij3[0];
7504vinfos[3].indices[1] = _ij3[1];
7505vinfos[3].maxsolutions = _nj3;
7506vinfos[4].jointtype = 1;
7507vinfos[4].foffset = j4;
7508vinfos[4].indices[0] = _ij4[0];
7509vinfos[4].indices[1] = _ij4[1];
7510vinfos[4].maxsolutions = _nj4;
7511vinfos[5].jointtype = 1;
7512vinfos[5].foffset = j5;
7513vinfos[5].indices[0] = _ij5[0];
7514vinfos[5].indices[1] = _ij5[1];
7515vinfos[5].maxsolutions = _nj5;
7516std::vector<int> vfree(0);
7517solutions.AddSolution(vinfos,vfree);
7518}
7519}
7520}
7521
7522}
7523
7524}
7525
7526} else
7527{
7528{
7529IkReal j0array[1], cj0array[1], sj0array[1];
7530bool j0valid[1]={false};
7531_nj0 = 1;
7532IkReal x472=((1.0)*gconst18);
7533CheckValue<IkReal> x473 = IKatan2WithCheck(IkReal(((((-1.0)*gconst17*x472))+((new_r00*new_r01)))),IkReal(((gconst18*gconst18)+(((-1.0)*new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
7534if(!x473.valid){
7535continue;
7536}
7537CheckValue<IkReal> x474=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r01*x472))+((gconst17*new_r11)))),-1);
7538if(!x474.valid){
7539continue;
7540}
7541j0array[0]=((-1.5707963267949)+(x473.value)+(((1.5707963267949)*(x474.value))));
7542sj0array[0]=IKsin(j0array[0]);
7543cj0array[0]=IKcos(j0array[0]);
7544if( j0array[0] > IKPI )
7545{
7546 j0array[0]-=IK2PI;
7547}
7548else if( j0array[0] < -IKPI )
7549{ j0array[0]+=IK2PI;
7550}
7551j0valid[0] = true;
7552for(int ij0 = 0; ij0 < 1; ++ij0)
7553{
7554if( !j0valid[ij0] )
7555{
7556 continue;
7557}
7558_ij0[0] = ij0; _ij0[1] = -1;
7559for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7560{
7561if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7562{
7563 j0valid[iij0]=false; _ij0[1] = iij0; break;
7564}
7565}
7566j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7567{
7568IkReal evalcond[8];
7569IkReal x475=IKsin(j0);
7570IkReal x476=IKcos(j0);
7571IkReal x477=(gconst17*x476);
7572IkReal x478=(gconst18*x475);
7573IkReal x479=(gconst17*x475);
7574IkReal x480=((1.0)*x476);
7575IkReal x481=(x477+x478);
7576evalcond[0]=(((new_r10*x475))+gconst17+((new_r00*x476)));
7577evalcond[1]=(((new_r01*x476))+gconst18+((new_r11*x475)));
7578evalcond[2]=(x481+new_r00);
7579evalcond[3]=(x481+new_r11);
7580evalcond[4]=(gconst17+((new_r11*x476))+(((-1.0)*new_r01*x475)));
7581evalcond[5]=((((-1.0)*new_r10*x480))+gconst18+((new_r00*x475)));
7582evalcond[6]=((((-1.0)*x479))+((gconst18*x476))+new_r01);
7583evalcond[7]=(x479+(((-1.0)*gconst18*x480))+new_r10);
7584if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7585{
7586continue;
7587}
7588}
7589
7590{
7591std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7592vinfos[0].jointtype = 1;
7593vinfos[0].foffset = j0;
7594vinfos[0].indices[0] = _ij0[0];
7595vinfos[0].indices[1] = _ij0[1];
7596vinfos[0].maxsolutions = _nj0;
7597vinfos[1].jointtype = 1;
7598vinfos[1].foffset = j1;
7599vinfos[1].indices[0] = _ij1[0];
7600vinfos[1].indices[1] = _ij1[1];
7601vinfos[1].maxsolutions = _nj1;
7602vinfos[2].jointtype = 1;
7603vinfos[2].foffset = j2;
7604vinfos[2].indices[0] = _ij2[0];
7605vinfos[2].indices[1] = _ij2[1];
7606vinfos[2].maxsolutions = _nj2;
7607vinfos[3].jointtype = 1;
7608vinfos[3].foffset = j3;
7609vinfos[3].indices[0] = _ij3[0];
7610vinfos[3].indices[1] = _ij3[1];
7611vinfos[3].maxsolutions = _nj3;
7612vinfos[4].jointtype = 1;
7613vinfos[4].foffset = j4;
7614vinfos[4].indices[0] = _ij4[0];
7615vinfos[4].indices[1] = _ij4[1];
7616vinfos[4].maxsolutions = _nj4;
7617vinfos[5].jointtype = 1;
7618vinfos[5].foffset = j5;
7619vinfos[5].indices[0] = _ij5[0];
7620vinfos[5].indices[1] = _ij5[1];
7621vinfos[5].maxsolutions = _nj5;
7622std::vector<int> vfree(0);
7623solutions.AddSolution(vinfos,vfree);
7624}
7625}
7626}
7627
7628}
7629
7630}
7631
7632} else
7633{
7634{
7635IkReal j0array[1], cj0array[1], sj0array[1];
7636bool j0valid[1]={false};
7637_nj0 = 1;
7638CheckValue<IkReal> x482=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1);
7639if(!x482.valid){
7640continue;
7641}
7642CheckValue<IkReal> x483 = IKatan2WithCheck(IkReal(((((-1.0)*gconst18*new_r00))+((gconst17*new_r01)))),IkReal((((gconst18*new_r10))+(((-1.0)*gconst17*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
7643if(!x483.valid){
7644continue;
7645}
7646j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x482.value)))+(x483.value));
7647sj0array[0]=IKsin(j0array[0]);
7648cj0array[0]=IKcos(j0array[0]);
7649if( j0array[0] > IKPI )
7650{
7651 j0array[0]-=IK2PI;
7652}
7653else if( j0array[0] < -IKPI )
7654{ j0array[0]+=IK2PI;
7655}
7656j0valid[0] = true;
7657for(int ij0 = 0; ij0 < 1; ++ij0)
7658{
7659if( !j0valid[ij0] )
7660{
7661 continue;
7662}
7663_ij0[0] = ij0; _ij0[1] = -1;
7664for(int iij0 = ij0+1; iij0 < 1; ++iij0)
7665{
7666if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7667{
7668 j0valid[iij0]=false; _ij0[1] = iij0; break;
7669}
7670}
7671j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7672{
7673IkReal evalcond[8];
7674IkReal x484=IKsin(j0);
7675IkReal x485=IKcos(j0);
7676IkReal x486=(gconst17*x485);
7677IkReal x487=(gconst18*x484);
7678IkReal x488=(gconst17*x484);
7679IkReal x489=((1.0)*x485);
7680IkReal x490=(x487+x486);
7681evalcond[0]=(gconst17+((new_r10*x484))+((new_r00*x485)));
7682evalcond[1]=(((new_r11*x484))+gconst18+((new_r01*x485)));
7683evalcond[2]=(x490+new_r00);
7684evalcond[3]=(x490+new_r11);
7685evalcond[4]=((((-1.0)*new_r01*x484))+((new_r11*x485))+gconst17);
7686evalcond[5]=((((-1.0)*new_r10*x489))+gconst18+((new_r00*x484)));
7687evalcond[6]=((((-1.0)*x488))+new_r01+((gconst18*x485)));
7688evalcond[7]=(x488+(((-1.0)*gconst18*x489))+new_r10);
7689if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
7690{
7691continue;
7692}
7693}
7694
7695{
7696std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7697vinfos[0].jointtype = 1;
7698vinfos[0].foffset = j0;
7699vinfos[0].indices[0] = _ij0[0];
7700vinfos[0].indices[1] = _ij0[1];
7701vinfos[0].maxsolutions = _nj0;
7702vinfos[1].jointtype = 1;
7703vinfos[1].foffset = j1;
7704vinfos[1].indices[0] = _ij1[0];
7705vinfos[1].indices[1] = _ij1[1];
7706vinfos[1].maxsolutions = _nj1;
7707vinfos[2].jointtype = 1;
7708vinfos[2].foffset = j2;
7709vinfos[2].indices[0] = _ij2[0];
7710vinfos[2].indices[1] = _ij2[1];
7711vinfos[2].maxsolutions = _nj2;
7712vinfos[3].jointtype = 1;
7713vinfos[3].foffset = j3;
7714vinfos[3].indices[0] = _ij3[0];
7715vinfos[3].indices[1] = _ij3[1];
7716vinfos[3].maxsolutions = _nj3;
7717vinfos[4].jointtype = 1;
7718vinfos[4].foffset = j4;
7719vinfos[4].indices[0] = _ij4[0];
7720vinfos[4].indices[1] = _ij4[1];
7721vinfos[4].maxsolutions = _nj4;
7722vinfos[5].jointtype = 1;
7723vinfos[5].foffset = j5;
7724vinfos[5].indices[0] = _ij5[0];
7725vinfos[5].indices[1] = _ij5[1];
7726vinfos[5].maxsolutions = _nj5;
7727std::vector<int> vfree(0);
7728solutions.AddSolution(vinfos,vfree);
7729}
7730}
7731}
7732
7733}
7734
7735}
7736
7737}
7738} while(0);
7739if( bgotonextstatement )
7740{
7741bool bgotonextstatement = true;
7742do
7743{
7744IkReal x493 = ((new_r10*new_r10)+(new_r00*new_r00));
7745if(IKabs(x493)==0){
7746continue;
7747}
7748IkReal x491=pow(x493,-0.5);
7749IkReal x492=((1.0)*x491);
7750CheckValue<IkReal> x494 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7751if(!x494.valid){
7752continue;
7753}
7754IkReal gconst19=((3.14159265358979)+(((-1.0)*(x494.value))));
7755IkReal gconst20=(new_r00*x492);
7756IkReal gconst21=(new_r10*x492);
7757CheckValue<IkReal> x495 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7758if(!x495.valid){
7759continue;
7760}
7761evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x495.value)+j2)))), 6.28318530717959)));
7762if( IKabs(evalcond[0]) < 0.0000050000000000 )
7763{
7764bgotonextstatement=false;
7765{
7766IkReal j0eval[3];
7767CheckValue<IkReal> x499 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7768if(!x499.valid){
7769continue;
7770}
7771IkReal x496=((1.0)*(x499.value));
7772IkReal x497=x491;
7773IkReal x498=((1.0)*x497);
7774sj1=1.0;
7775cj1=0;
7776j1=1.5707963267949;
7777sj2=gconst20;
7778cj2=gconst21;
7779j2=((3.14159265)+(((-1.0)*x496)));
7780IkReal gconst19=((3.14159265358979)+(((-1.0)*x496)));
7781IkReal gconst20=(new_r00*x498);
7782IkReal gconst21=(new_r10*x498);
7783IkReal x500=new_r10*new_r10;
7784IkReal x501=((1.0)*new_r10);
7785IkReal x502=(new_r00*new_r11);
7786IkReal x503=((((-1.0)*new_r01*x501))+x502);
7787IkReal x504=x491;
7788IkReal x505=(new_r00*x504);
7789j0eval[0]=x503;
7790j0eval[1]=IKsign(x503);
7791j0eval[2]=((IKabs((((x500*x504))+(((-1.0)*x502*x504)))))+(IKabs(((((-1.0)*x501*x505))+((new_r01*x505))))));
7792if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
7793{
7794{
7795IkReal j0eval[1];
7796CheckValue<IkReal> x509 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7797if(!x509.valid){
7798continue;
7799}
7800IkReal x506=((1.0)*(x509.value));
7801IkReal x507=x491;
7802IkReal x508=((1.0)*x507);
7803sj1=1.0;
7804cj1=0;
7805j1=1.5707963267949;
7806sj2=gconst20;
7807cj2=gconst21;
7808j2=((3.14159265)+(((-1.0)*x506)));
7809IkReal gconst19=((3.14159265358979)+(((-1.0)*x506)));
7810IkReal gconst20=(new_r00*x508);
7811IkReal gconst21=(new_r10*x508);
7812IkReal x510=new_r10*new_r10;
7813IkReal x511=new_r00*new_r00*new_r00;
7814CheckValue<IkReal> x515=IKPowWithIntegerCheck((x510+(new_r00*new_r00)),-1);
7815if(!x515.valid){
7816continue;
7817}
7818IkReal x512=x515.value;
7819IkReal x513=((1.0)*x512);
7820IkReal x514=(x510*x512);
7821j0eval[0]=((IKabs(((((-1.0)*new_r00*new_r11*x510*x513))+x514+(((-1.0)*new_r11*x511*x513)))))+(IKabs((((new_r00*new_r01*x514))+(((-1.0)*new_r00*new_r10*x513))+((new_r01*x511*x512))))));
7822if( IKabs(j0eval[0]) < 0.0000010000000000 )
7823{
7824{
7825IkReal j0eval[3];
7826CheckValue<IkReal> x519 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7827if(!x519.valid){
7828continue;
7829}
7830IkReal x516=((1.0)*(x519.value));
7831IkReal x517=x491;
7832IkReal x518=((1.0)*x517);
7833sj1=1.0;
7834cj1=0;
7835j1=1.5707963267949;
7836sj2=gconst20;
7837cj2=gconst21;
7838j2=((3.14159265)+(((-1.0)*x516)));
7839IkReal gconst19=((3.14159265358979)+(((-1.0)*x516)));
7840IkReal gconst20=(new_r00*x518);
7841IkReal gconst21=(new_r10*x518);
7842IkReal x520=new_r00*new_r00;
7843IkReal x521=(new_r00*new_r01);
7844IkReal x522=(((new_r10*new_r11))+x521);
7845IkReal x523=x491;
7846IkReal x524=((1.0)*x523);
7847j0eval[0]=x522;
7848j0eval[1]=((IKabs(((((-1.0)*new_r00*new_r11*x524))+((x520*x523)))))+(IKabs(((((-1.0)*x521*x524))+(((-1.0)*new_r00*new_r10*x524))))));
7849j0eval[2]=IKsign(x522);
7850if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
7851{
7852{
7853IkReal evalcond[3];
7854bool bgotonextstatement = true;
7855do
7856{
7857evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
7858if( IKabs(evalcond[0]) < 0.0000050000000000 )
7859{
7860bgotonextstatement=false;
7861{
7862IkReal j0eval[1];
7863CheckValue<IkReal> x526 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
7864if(!x526.valid){
7865continue;
7866}
7867IkReal x525=((1.0)*(x526.value));
7868sj1=1.0;
7869cj1=0;
7870j1=1.5707963267949;
7871sj2=gconst20;
7872cj2=gconst21;
7873j2=((3.14159265)+(((-1.0)*x525)));
7874new_r11=0;
7875new_r00=0;
7876IkReal gconst19=((3.14159265358979)+(((-1.0)*x525)));
7877IkReal gconst20=0;
7878IkReal x527 = new_r10*new_r10;
7879if(IKabs(x527)==0){
7880continue;
7881}
7882IkReal gconst21=((1.0)*new_r10*(pow(x527,-0.5)));
7883j0eval[0]=new_r10;
7884if( IKabs(j0eval[0]) < 0.0000010000000000 )
7885{
7886{
7887IkReal j0array[2], cj0array[2], sj0array[2];
7888bool j0valid[2]={false};
7889_nj0 = 2;
7890CheckValue<IkReal> x528=IKPowWithIntegerCheck(gconst21,-1);
7891if(!x528.valid){
7892continue;
7893}
7894cj0array[0]=(new_r10*(x528.value));
7895if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
7896{
7897 j0valid[0] = j0valid[1] = true;
7898 j0array[0] = IKacos(cj0array[0]);
7899 sj0array[0] = IKsin(j0array[0]);
7900 cj0array[1] = cj0array[0];
7901 j0array[1] = -j0array[0];
7902 sj0array[1] = -sj0array[0];
7903}
7904else if( isnan(cj0array[0]) )
7905{
7906 // probably any value will work
7907 j0valid[0] = true;
7908 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
7909}
7910for(int ij0 = 0; ij0 < 2; ++ij0)
7911{
7912if( !j0valid[ij0] )
7913{
7914 continue;
7915}
7916_ij0[0] = ij0; _ij0[1] = -1;
7917for(int iij0 = ij0+1; iij0 < 2; ++iij0)
7918{
7919if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
7920{
7921 j0valid[iij0]=false; _ij0[1] = iij0; break;
7922}
7923}
7924j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
7925{
7926IkReal evalcond[6];
7927IkReal x529=IKsin(j0);
7928IkReal x530=IKcos(j0);
7929evalcond[0]=(new_r10*x529);
7930evalcond[1]=(gconst21*x529);
7931evalcond[2]=((-1.0)*new_r01*x529);
7932evalcond[3]=(((new_r01*x530))+gconst21);
7933evalcond[4]=(new_r01+((gconst21*x530)));
7934evalcond[5]=(gconst21+(((-1.0)*new_r10*x530)));
7935if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
7936{
7937continue;
7938}
7939}
7940
7941{
7942std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
7943vinfos[0].jointtype = 1;
7944vinfos[0].foffset = j0;
7945vinfos[0].indices[0] = _ij0[0];
7946vinfos[0].indices[1] = _ij0[1];
7947vinfos[0].maxsolutions = _nj0;
7948vinfos[1].jointtype = 1;
7949vinfos[1].foffset = j1;
7950vinfos[1].indices[0] = _ij1[0];
7951vinfos[1].indices[1] = _ij1[1];
7952vinfos[1].maxsolutions = _nj1;
7953vinfos[2].jointtype = 1;
7954vinfos[2].foffset = j2;
7955vinfos[2].indices[0] = _ij2[0];
7956vinfos[2].indices[1] = _ij2[1];
7957vinfos[2].maxsolutions = _nj2;
7958vinfos[3].jointtype = 1;
7959vinfos[3].foffset = j3;
7960vinfos[3].indices[0] = _ij3[0];
7961vinfos[3].indices[1] = _ij3[1];
7962vinfos[3].maxsolutions = _nj3;
7963vinfos[4].jointtype = 1;
7964vinfos[4].foffset = j4;
7965vinfos[4].indices[0] = _ij4[0];
7966vinfos[4].indices[1] = _ij4[1];
7967vinfos[4].maxsolutions = _nj4;
7968vinfos[5].jointtype = 1;
7969vinfos[5].foffset = j5;
7970vinfos[5].indices[0] = _ij5[0];
7971vinfos[5].indices[1] = _ij5[1];
7972vinfos[5].maxsolutions = _nj5;
7973std::vector<int> vfree(0);
7974solutions.AddSolution(vinfos,vfree);
7975}
7976}
7977}
7978
7979} else
7980{
7981{
7982IkReal j0array[2], cj0array[2], sj0array[2];
7983bool j0valid[2]={false};
7984_nj0 = 2;
7985CheckValue<IkReal> x531=IKPowWithIntegerCheck(new_r10,-1);
7986if(!x531.valid){
7987continue;
7988}
7989cj0array[0]=(gconst21*(x531.value));
7990if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
7991{
7992 j0valid[0] = j0valid[1] = true;
7993 j0array[0] = IKacos(cj0array[0]);
7994 sj0array[0] = IKsin(j0array[0]);
7995 cj0array[1] = cj0array[0];
7996 j0array[1] = -j0array[0];
7997 sj0array[1] = -sj0array[0];
7998}
7999else if( isnan(cj0array[0]) )
8000{
8001 // probably any value will work
8002 j0valid[0] = true;
8003 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
8004}
8005for(int ij0 = 0; ij0 < 2; ++ij0)
8006{
8007if( !j0valid[ij0] )
8008{
8009 continue;
8010}
8011_ij0[0] = ij0; _ij0[1] = -1;
8012for(int iij0 = ij0+1; iij0 < 2; ++iij0)
8013{
8014if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8015{
8016 j0valid[iij0]=false; _ij0[1] = iij0; break;
8017}
8018}
8019j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8020{
8021IkReal evalcond[6];
8022IkReal x532=IKsin(j0);
8023IkReal x533=IKcos(j0);
8024IkReal x534=(gconst21*x533);
8025evalcond[0]=(new_r10*x532);
8026evalcond[1]=(gconst21*x532);
8027evalcond[2]=((-1.0)*new_r01*x532);
8028evalcond[3]=(((new_r01*x533))+gconst21);
8029evalcond[4]=(x534+new_r01);
8030evalcond[5]=((((-1.0)*x534))+new_r10);
8031if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8032{
8033continue;
8034}
8035}
8036
8037{
8038std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8039vinfos[0].jointtype = 1;
8040vinfos[0].foffset = j0;
8041vinfos[0].indices[0] = _ij0[0];
8042vinfos[0].indices[1] = _ij0[1];
8043vinfos[0].maxsolutions = _nj0;
8044vinfos[1].jointtype = 1;
8045vinfos[1].foffset = j1;
8046vinfos[1].indices[0] = _ij1[0];
8047vinfos[1].indices[1] = _ij1[1];
8048vinfos[1].maxsolutions = _nj1;
8049vinfos[2].jointtype = 1;
8050vinfos[2].foffset = j2;
8051vinfos[2].indices[0] = _ij2[0];
8052vinfos[2].indices[1] = _ij2[1];
8053vinfos[2].maxsolutions = _nj2;
8054vinfos[3].jointtype = 1;
8055vinfos[3].foffset = j3;
8056vinfos[3].indices[0] = _ij3[0];
8057vinfos[3].indices[1] = _ij3[1];
8058vinfos[3].maxsolutions = _nj3;
8059vinfos[4].jointtype = 1;
8060vinfos[4].foffset = j4;
8061vinfos[4].indices[0] = _ij4[0];
8062vinfos[4].indices[1] = _ij4[1];
8063vinfos[4].maxsolutions = _nj4;
8064vinfos[5].jointtype = 1;
8065vinfos[5].foffset = j5;
8066vinfos[5].indices[0] = _ij5[0];
8067vinfos[5].indices[1] = _ij5[1];
8068vinfos[5].maxsolutions = _nj5;
8069std::vector<int> vfree(0);
8070solutions.AddSolution(vinfos,vfree);
8071}
8072}
8073}
8074
8075}
8076
8077}
8078
8079}
8080} while(0);
8081if( bgotonextstatement )
8082{
8083bool bgotonextstatement = true;
8084do
8085{
8086evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
8087evalcond[1]=gconst20;
8088evalcond[2]=gconst21;
8089if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
8090{
8091bgotonextstatement=false;
8092{
8093IkReal j0eval[3];
8094CheckValue<IkReal> x536 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8095if(!x536.valid){
8096continue;
8097}
8098IkReal x535=((1.0)*(x536.value));
8099sj1=1.0;
8100cj1=0;
8101j1=1.5707963267949;
8102sj2=gconst20;
8103cj2=gconst21;
8104j2=((3.14159265)+(((-1.0)*x535)));
8105new_r11=0;
8106new_r01=0;
8107new_r22=0;
8108new_r20=0;
8109IkReal gconst19=((3.14159265358979)+(((-1.0)*x535)));
8110IkReal gconst20=((1.0)*new_r00);
8111IkReal gconst21=((1.0)*new_r10);
8112j0eval[0]=-1.0;
8113j0eval[1]=-1.0;
8114j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
8115if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
8116{
8117{
8118IkReal j0eval[4];
8119CheckValue<IkReal> x538 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8120if(!x538.valid){
8121continue;
8122}
8123IkReal x537=((1.0)*(x538.value));
8124sj1=1.0;
8125cj1=0;
8126j1=1.5707963267949;
8127sj2=gconst20;
8128cj2=gconst21;
8129j2=((3.14159265)+(((-1.0)*x537)));
8130new_r11=0;
8131new_r01=0;
8132new_r22=0;
8133new_r20=0;
8134IkReal gconst19=((3.14159265358979)+(((-1.0)*x537)));
8135IkReal gconst20=((1.0)*new_r00);
8136IkReal gconst21=((1.0)*new_r10);
8137j0eval[0]=-1.0;
8138j0eval[1]=-1.0;
8139j0eval[2]=new_r10;
8140j0eval[3]=1.0;
8141if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 )
8142{
8143{
8144IkReal j0eval[3];
8145CheckValue<IkReal> x540 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8146if(!x540.valid){
8147continue;
8148}
8149IkReal x539=((1.0)*(x540.value));
8150sj1=1.0;
8151cj1=0;
8152j1=1.5707963267949;
8153sj2=gconst20;
8154cj2=gconst21;
8155j2=((3.14159265)+(((-1.0)*x539)));
8156new_r11=0;
8157new_r01=0;
8158new_r22=0;
8159new_r20=0;
8160IkReal gconst19=((3.14159265358979)+(((-1.0)*x539)));
8161IkReal gconst20=((1.0)*new_r00);
8162IkReal gconst21=((1.0)*new_r10);
8163j0eval[0]=-1.0;
8164j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
8165j0eval[2]=-1.0;
8166if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
8167{
8168continue; // 3 cases reached
8169
8170} else
8171{
8172{
8173IkReal j0array[1], cj0array[1], sj0array[1];
8174bool j0valid[1]={false};
8175_nj0 = 1;
8176CheckValue<IkReal> x541 = IKatan2WithCheck(IkReal((gconst21*new_r00)),IkReal((gconst20*new_r00)),IKFAST_ATAN2_MAGTHRESH);
8177if(!x541.valid){
8178continue;
8179}
8180CheckValue<IkReal> x542=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst20*gconst20)))+(((-1.0)*(gconst21*gconst21))))),-1);
8181if(!x542.valid){
8182continue;
8183}
8184j0array[0]=((-1.5707963267949)+(x541.value)+(((1.5707963267949)*(x542.value))));
8185sj0array[0]=IKsin(j0array[0]);
8186cj0array[0]=IKcos(j0array[0]);
8187if( j0array[0] > IKPI )
8188{
8189 j0array[0]-=IK2PI;
8190}
8191else if( j0array[0] < -IKPI )
8192{ j0array[0]+=IK2PI;
8193}
8194j0valid[0] = true;
8195for(int ij0 = 0; ij0 < 1; ++ij0)
8196{
8197if( !j0valid[ij0] )
8198{
8199 continue;
8200}
8201_ij0[0] = ij0; _ij0[1] = -1;
8202for(int iij0 = ij0+1; iij0 < 1; ++iij0)
8203{
8204if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8205{
8206 j0valid[iij0]=false; _ij0[1] = iij0; break;
8207}
8208}
8209j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8210{
8211IkReal evalcond[6];
8212IkReal x543=IKcos(j0);
8213IkReal x544=IKsin(j0);
8214IkReal x545=(gconst21*x544);
8215IkReal x546=(gconst20*x543);
8216IkReal x547=((1.0)*x543);
8217IkReal x548=(gconst20*x544);
8218IkReal x549=(x545+x546);
8219evalcond[0]=x549;
8220evalcond[1]=(((new_r00*x543))+((new_r10*x544))+gconst20);
8221evalcond[2]=(x549+new_r00);
8222evalcond[3]=((((-1.0)*x548))+((gconst21*x543)));
8223evalcond[4]=(((new_r00*x544))+gconst21+(((-1.0)*new_r10*x547)));
8224evalcond[5]=(x548+new_r10+(((-1.0)*gconst21*x547)));
8225if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8226{
8227continue;
8228}
8229}
8230
8231{
8232std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8233vinfos[0].jointtype = 1;
8234vinfos[0].foffset = j0;
8235vinfos[0].indices[0] = _ij0[0];
8236vinfos[0].indices[1] = _ij0[1];
8237vinfos[0].maxsolutions = _nj0;
8238vinfos[1].jointtype = 1;
8239vinfos[1].foffset = j1;
8240vinfos[1].indices[0] = _ij1[0];
8241vinfos[1].indices[1] = _ij1[1];
8242vinfos[1].maxsolutions = _nj1;
8243vinfos[2].jointtype = 1;
8244vinfos[2].foffset = j2;
8245vinfos[2].indices[0] = _ij2[0];
8246vinfos[2].indices[1] = _ij2[1];
8247vinfos[2].maxsolutions = _nj2;
8248vinfos[3].jointtype = 1;
8249vinfos[3].foffset = j3;
8250vinfos[3].indices[0] = _ij3[0];
8251vinfos[3].indices[1] = _ij3[1];
8252vinfos[3].maxsolutions = _nj3;
8253vinfos[4].jointtype = 1;
8254vinfos[4].foffset = j4;
8255vinfos[4].indices[0] = _ij4[0];
8256vinfos[4].indices[1] = _ij4[1];
8257vinfos[4].maxsolutions = _nj4;
8258vinfos[5].jointtype = 1;
8259vinfos[5].foffset = j5;
8260vinfos[5].indices[0] = _ij5[0];
8261vinfos[5].indices[1] = _ij5[1];
8262vinfos[5].maxsolutions = _nj5;
8263std::vector<int> vfree(0);
8264solutions.AddSolution(vinfos,vfree);
8265}
8266}
8267}
8268
8269}
8270
8271}
8272
8273} else
8274{
8275{
8276IkReal j0array[1], cj0array[1], sj0array[1];
8277bool j0valid[1]={false};
8278_nj0 = 1;
8279CheckValue<IkReal> x550 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(((-1.0)*(gconst21*gconst21))),IKFAST_ATAN2_MAGTHRESH);
8280if(!x550.valid){
8281continue;
8282}
8283CheckValue<IkReal> x551=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1);
8284if(!x551.valid){
8285continue;
8286}
8287j0array[0]=((-1.5707963267949)+(x550.value)+(((1.5707963267949)*(x551.value))));
8288sj0array[0]=IKsin(j0array[0]);
8289cj0array[0]=IKcos(j0array[0]);
8290if( j0array[0] > IKPI )
8291{
8292 j0array[0]-=IK2PI;
8293}
8294else if( j0array[0] < -IKPI )
8295{ j0array[0]+=IK2PI;
8296}
8297j0valid[0] = true;
8298for(int ij0 = 0; ij0 < 1; ++ij0)
8299{
8300if( !j0valid[ij0] )
8301{
8302 continue;
8303}
8304_ij0[0] = ij0; _ij0[1] = -1;
8305for(int iij0 = ij0+1; iij0 < 1; ++iij0)
8306{
8307if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8308{
8309 j0valid[iij0]=false; _ij0[1] = iij0; break;
8310}
8311}
8312j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8313{
8314IkReal evalcond[6];
8315IkReal x552=IKcos(j0);
8316IkReal x553=IKsin(j0);
8317IkReal x554=(gconst21*x553);
8318IkReal x555=(gconst20*x552);
8319IkReal x556=((1.0)*x552);
8320IkReal x557=(gconst20*x553);
8321IkReal x558=(x555+x554);
8322evalcond[0]=x558;
8323evalcond[1]=(((new_r10*x553))+gconst20+((new_r00*x552)));
8324evalcond[2]=(x558+new_r00);
8325evalcond[3]=((((-1.0)*x557))+((gconst21*x552)));
8326evalcond[4]=(gconst21+(((-1.0)*new_r10*x556))+((new_r00*x553)));
8327evalcond[5]=(x557+(((-1.0)*gconst21*x556))+new_r10);
8328if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8329{
8330continue;
8331}
8332}
8333
8334{
8335std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8336vinfos[0].jointtype = 1;
8337vinfos[0].foffset = j0;
8338vinfos[0].indices[0] = _ij0[0];
8339vinfos[0].indices[1] = _ij0[1];
8340vinfos[0].maxsolutions = _nj0;
8341vinfos[1].jointtype = 1;
8342vinfos[1].foffset = j1;
8343vinfos[1].indices[0] = _ij1[0];
8344vinfos[1].indices[1] = _ij1[1];
8345vinfos[1].maxsolutions = _nj1;
8346vinfos[2].jointtype = 1;
8347vinfos[2].foffset = j2;
8348vinfos[2].indices[0] = _ij2[0];
8349vinfos[2].indices[1] = _ij2[1];
8350vinfos[2].maxsolutions = _nj2;
8351vinfos[3].jointtype = 1;
8352vinfos[3].foffset = j3;
8353vinfos[3].indices[0] = _ij3[0];
8354vinfos[3].indices[1] = _ij3[1];
8355vinfos[3].maxsolutions = _nj3;
8356vinfos[4].jointtype = 1;
8357vinfos[4].foffset = j4;
8358vinfos[4].indices[0] = _ij4[0];
8359vinfos[4].indices[1] = _ij4[1];
8360vinfos[4].maxsolutions = _nj4;
8361vinfos[5].jointtype = 1;
8362vinfos[5].foffset = j5;
8363vinfos[5].indices[0] = _ij5[0];
8364vinfos[5].indices[1] = _ij5[1];
8365vinfos[5].maxsolutions = _nj5;
8366std::vector<int> vfree(0);
8367solutions.AddSolution(vinfos,vfree);
8368}
8369}
8370}
8371
8372}
8373
8374}
8375
8376} else
8377{
8378{
8379IkReal j0array[1], cj0array[1], sj0array[1];
8380bool j0valid[1]={false};
8381_nj0 = 1;
8382CheckValue<IkReal> x559 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(gconst20*gconst20),IKFAST_ATAN2_MAGTHRESH);
8383if(!x559.valid){
8384continue;
8385}
8386CheckValue<IkReal> x560=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1);
8387if(!x560.valid){
8388continue;
8389}
8390j0array[0]=((-1.5707963267949)+(x559.value)+(((1.5707963267949)*(x560.value))));
8391sj0array[0]=IKsin(j0array[0]);
8392cj0array[0]=IKcos(j0array[0]);
8393if( j0array[0] > IKPI )
8394{
8395 j0array[0]-=IK2PI;
8396}
8397else if( j0array[0] < -IKPI )
8398{ j0array[0]+=IK2PI;
8399}
8400j0valid[0] = true;
8401for(int ij0 = 0; ij0 < 1; ++ij0)
8402{
8403if( !j0valid[ij0] )
8404{
8405 continue;
8406}
8407_ij0[0] = ij0; _ij0[1] = -1;
8408for(int iij0 = ij0+1; iij0 < 1; ++iij0)
8409{
8410if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8411{
8412 j0valid[iij0]=false; _ij0[1] = iij0; break;
8413}
8414}
8415j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8416{
8417IkReal evalcond[6];
8418IkReal x561=IKcos(j0);
8419IkReal x562=IKsin(j0);
8420IkReal x563=(gconst21*x562);
8421IkReal x564=(gconst20*x561);
8422IkReal x565=((1.0)*x561);
8423IkReal x566=(gconst20*x562);
8424IkReal x567=(x564+x563);
8425evalcond[0]=x567;
8426evalcond[1]=(((new_r00*x561))+gconst20+((new_r10*x562)));
8427evalcond[2]=(x567+new_r00);
8428evalcond[3]=(((gconst21*x561))+(((-1.0)*x566)));
8429evalcond[4]=(((new_r00*x562))+gconst21+(((-1.0)*new_r10*x565)));
8430evalcond[5]=((((-1.0)*gconst21*x565))+x566+new_r10);
8431if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8432{
8433continue;
8434}
8435}
8436
8437{
8438std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8439vinfos[0].jointtype = 1;
8440vinfos[0].foffset = j0;
8441vinfos[0].indices[0] = _ij0[0];
8442vinfos[0].indices[1] = _ij0[1];
8443vinfos[0].maxsolutions = _nj0;
8444vinfos[1].jointtype = 1;
8445vinfos[1].foffset = j1;
8446vinfos[1].indices[0] = _ij1[0];
8447vinfos[1].indices[1] = _ij1[1];
8448vinfos[1].maxsolutions = _nj1;
8449vinfos[2].jointtype = 1;
8450vinfos[2].foffset = j2;
8451vinfos[2].indices[0] = _ij2[0];
8452vinfos[2].indices[1] = _ij2[1];
8453vinfos[2].maxsolutions = _nj2;
8454vinfos[3].jointtype = 1;
8455vinfos[3].foffset = j3;
8456vinfos[3].indices[0] = _ij3[0];
8457vinfos[3].indices[1] = _ij3[1];
8458vinfos[3].maxsolutions = _nj3;
8459vinfos[4].jointtype = 1;
8460vinfos[4].foffset = j4;
8461vinfos[4].indices[0] = _ij4[0];
8462vinfos[4].indices[1] = _ij4[1];
8463vinfos[4].maxsolutions = _nj4;
8464vinfos[5].jointtype = 1;
8465vinfos[5].foffset = j5;
8466vinfos[5].indices[0] = _ij5[0];
8467vinfos[5].indices[1] = _ij5[1];
8468vinfos[5].maxsolutions = _nj5;
8469std::vector<int> vfree(0);
8470solutions.AddSolution(vinfos,vfree);
8471}
8472}
8473}
8474
8475}
8476
8477}
8478
8479}
8480} while(0);
8481if( bgotonextstatement )
8482{
8483bool bgotonextstatement = true;
8484do
8485{
8486evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
8487if( IKabs(evalcond[0]) < 0.0000050000000000 )
8488{
8489bgotonextstatement=false;
8490{
8491IkReal j0eval[1];
8492CheckValue<IkReal> x569 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
8493if(!x569.valid){
8494continue;
8495}
8496IkReal x568=((1.0)*(x569.value));
8497sj1=1.0;
8498cj1=0;
8499j1=1.5707963267949;
8500sj2=gconst20;
8501cj2=gconst21;
8502j2=((3.14159265)+(((-1.0)*x568)));
8503new_r01=0;
8504new_r10=0;
8505IkReal gconst19=((3.14159265358979)+(((-1.0)*x568)));
8506IkReal x570 = new_r00*new_r00;
8507if(IKabs(x570)==0){
8508continue;
8509}
8510IkReal gconst20=((1.0)*new_r00*(pow(x570,-0.5)));
8511IkReal gconst21=0;
8512j0eval[0]=new_r11;
8513if( IKabs(j0eval[0]) < 0.0000010000000000 )
8514{
8515{
8516IkReal j0eval[1];
8517CheckValue<IkReal> x572 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
8518if(!x572.valid){
8519continue;
8520}
8521IkReal x571=((1.0)*(x572.value));
8522sj1=1.0;
8523cj1=0;
8524j1=1.5707963267949;
8525sj2=gconst20;
8526cj2=gconst21;
8527j2=((3.14159265)+(((-1.0)*x571)));
8528new_r01=0;
8529new_r10=0;
8530IkReal gconst19=((3.14159265358979)+(((-1.0)*x571)));
8531IkReal x573 = new_r00*new_r00;
8532if(IKabs(x573)==0){
8533continue;
8534}
8535IkReal gconst20=((1.0)*new_r00*(pow(x573,-0.5)));
8536IkReal gconst21=0;
8537j0eval[0]=new_r00;
8538if( IKabs(j0eval[0]) < 0.0000010000000000 )
8539{
8540{
8541IkReal j0array[2], cj0array[2], sj0array[2];
8542bool j0valid[2]={false};
8543_nj0 = 2;
8544CheckValue<IkReal> x574=IKPowWithIntegerCheck(gconst20,-1);
8545if(!x574.valid){
8546continue;
8547}
8548cj0array[0]=((-1.0)*new_r00*(x574.value));
8549if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
8550{
8551 j0valid[0] = j0valid[1] = true;
8552 j0array[0] = IKacos(cj0array[0]);
8553 sj0array[0] = IKsin(j0array[0]);
8554 cj0array[1] = cj0array[0];
8555 j0array[1] = -j0array[0];
8556 sj0array[1] = -sj0array[0];
8557}
8558else if( isnan(cj0array[0]) )
8559{
8560 // probably any value will work
8561 j0valid[0] = true;
8562 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
8563}
8564for(int ij0 = 0; ij0 < 2; ++ij0)
8565{
8566if( !j0valid[ij0] )
8567{
8568 continue;
8569}
8570_ij0[0] = ij0; _ij0[1] = -1;
8571for(int iij0 = ij0+1; iij0 < 2; ++iij0)
8572{
8573if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8574{
8575 j0valid[iij0]=false; _ij0[1] = iij0; break;
8576}
8577}
8578j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8579{
8580IkReal evalcond[6];
8581IkReal x575=IKsin(j0);
8582IkReal x576=IKcos(j0);
8583evalcond[0]=(new_r00*x575);
8584evalcond[1]=(new_r11*x575);
8585evalcond[2]=((-1.0)*gconst20*x575);
8586evalcond[3]=(((new_r11*x576))+gconst20);
8587evalcond[4]=(((new_r00*x576))+gconst20);
8588evalcond[5]=(((gconst20*x576))+new_r11);
8589if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8590{
8591continue;
8592}
8593}
8594
8595{
8596std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8597vinfos[0].jointtype = 1;
8598vinfos[0].foffset = j0;
8599vinfos[0].indices[0] = _ij0[0];
8600vinfos[0].indices[1] = _ij0[1];
8601vinfos[0].maxsolutions = _nj0;
8602vinfos[1].jointtype = 1;
8603vinfos[1].foffset = j1;
8604vinfos[1].indices[0] = _ij1[0];
8605vinfos[1].indices[1] = _ij1[1];
8606vinfos[1].maxsolutions = _nj1;
8607vinfos[2].jointtype = 1;
8608vinfos[2].foffset = j2;
8609vinfos[2].indices[0] = _ij2[0];
8610vinfos[2].indices[1] = _ij2[1];
8611vinfos[2].maxsolutions = _nj2;
8612vinfos[3].jointtype = 1;
8613vinfos[3].foffset = j3;
8614vinfos[3].indices[0] = _ij3[0];
8615vinfos[3].indices[1] = _ij3[1];
8616vinfos[3].maxsolutions = _nj3;
8617vinfos[4].jointtype = 1;
8618vinfos[4].foffset = j4;
8619vinfos[4].indices[0] = _ij4[0];
8620vinfos[4].indices[1] = _ij4[1];
8621vinfos[4].maxsolutions = _nj4;
8622vinfos[5].jointtype = 1;
8623vinfos[5].foffset = j5;
8624vinfos[5].indices[0] = _ij5[0];
8625vinfos[5].indices[1] = _ij5[1];
8626vinfos[5].maxsolutions = _nj5;
8627std::vector<int> vfree(0);
8628solutions.AddSolution(vinfos,vfree);
8629}
8630}
8631}
8632
8633} else
8634{
8635{
8636IkReal j0array[2], cj0array[2], sj0array[2];
8637bool j0valid[2]={false};
8638_nj0 = 2;
8639CheckValue<IkReal> x577=IKPowWithIntegerCheck(new_r00,-1);
8640if(!x577.valid){
8641continue;
8642}
8643cj0array[0]=((-1.0)*gconst20*(x577.value));
8644if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
8645{
8646 j0valid[0] = j0valid[1] = true;
8647 j0array[0] = IKacos(cj0array[0]);
8648 sj0array[0] = IKsin(j0array[0]);
8649 cj0array[1] = cj0array[0];
8650 j0array[1] = -j0array[0];
8651 sj0array[1] = -sj0array[0];
8652}
8653else if( isnan(cj0array[0]) )
8654{
8655 // probably any value will work
8656 j0valid[0] = true;
8657 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
8658}
8659for(int ij0 = 0; ij0 < 2; ++ij0)
8660{
8661if( !j0valid[ij0] )
8662{
8663 continue;
8664}
8665_ij0[0] = ij0; _ij0[1] = -1;
8666for(int iij0 = ij0+1; iij0 < 2; ++iij0)
8667{
8668if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8669{
8670 j0valid[iij0]=false; _ij0[1] = iij0; break;
8671}
8672}
8673j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8674{
8675IkReal evalcond[6];
8676IkReal x578=IKsin(j0);
8677IkReal x579=IKcos(j0);
8678IkReal x580=(gconst20*x579);
8679evalcond[0]=(new_r00*x578);
8680evalcond[1]=(new_r11*x578);
8681evalcond[2]=((-1.0)*gconst20*x578);
8682evalcond[3]=(((new_r11*x579))+gconst20);
8683evalcond[4]=(x580+new_r00);
8684evalcond[5]=(x580+new_r11);
8685if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8686{
8687continue;
8688}
8689}
8690
8691{
8692std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8693vinfos[0].jointtype = 1;
8694vinfos[0].foffset = j0;
8695vinfos[0].indices[0] = _ij0[0];
8696vinfos[0].indices[1] = _ij0[1];
8697vinfos[0].maxsolutions = _nj0;
8698vinfos[1].jointtype = 1;
8699vinfos[1].foffset = j1;
8700vinfos[1].indices[0] = _ij1[0];
8701vinfos[1].indices[1] = _ij1[1];
8702vinfos[1].maxsolutions = _nj1;
8703vinfos[2].jointtype = 1;
8704vinfos[2].foffset = j2;
8705vinfos[2].indices[0] = _ij2[0];
8706vinfos[2].indices[1] = _ij2[1];
8707vinfos[2].maxsolutions = _nj2;
8708vinfos[3].jointtype = 1;
8709vinfos[3].foffset = j3;
8710vinfos[3].indices[0] = _ij3[0];
8711vinfos[3].indices[1] = _ij3[1];
8712vinfos[3].maxsolutions = _nj3;
8713vinfos[4].jointtype = 1;
8714vinfos[4].foffset = j4;
8715vinfos[4].indices[0] = _ij4[0];
8716vinfos[4].indices[1] = _ij4[1];
8717vinfos[4].maxsolutions = _nj4;
8718vinfos[5].jointtype = 1;
8719vinfos[5].foffset = j5;
8720vinfos[5].indices[0] = _ij5[0];
8721vinfos[5].indices[1] = _ij5[1];
8722vinfos[5].maxsolutions = _nj5;
8723std::vector<int> vfree(0);
8724solutions.AddSolution(vinfos,vfree);
8725}
8726}
8727}
8728
8729}
8730
8731}
8732
8733} else
8734{
8735{
8736IkReal j0array[2], cj0array[2], sj0array[2];
8737bool j0valid[2]={false};
8738_nj0 = 2;
8739CheckValue<IkReal> x581=IKPowWithIntegerCheck(new_r11,-1);
8740if(!x581.valid){
8741continue;
8742}
8743cj0array[0]=((-1.0)*gconst20*(x581.value));
8744if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
8745{
8746 j0valid[0] = j0valid[1] = true;
8747 j0array[0] = IKacos(cj0array[0]);
8748 sj0array[0] = IKsin(j0array[0]);
8749 cj0array[1] = cj0array[0];
8750 j0array[1] = -j0array[0];
8751 sj0array[1] = -sj0array[0];
8752}
8753else if( isnan(cj0array[0]) )
8754{
8755 // probably any value will work
8756 j0valid[0] = true;
8757 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
8758}
8759for(int ij0 = 0; ij0 < 2; ++ij0)
8760{
8761if( !j0valid[ij0] )
8762{
8763 continue;
8764}
8765_ij0[0] = ij0; _ij0[1] = -1;
8766for(int iij0 = ij0+1; iij0 < 2; ++iij0)
8767{
8768if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8769{
8770 j0valid[iij0]=false; _ij0[1] = iij0; break;
8771}
8772}
8773j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8774{
8775IkReal evalcond[6];
8776IkReal x582=IKsin(j0);
8777IkReal x583=IKcos(j0);
8778IkReal x584=(gconst20*x583);
8779evalcond[0]=(new_r00*x582);
8780evalcond[1]=(new_r11*x582);
8781evalcond[2]=((-1.0)*gconst20*x582);
8782evalcond[3]=(gconst20+((new_r00*x583)));
8783evalcond[4]=(x584+new_r00);
8784evalcond[5]=(x584+new_r11);
8785if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
8786{
8787continue;
8788}
8789}
8790
8791{
8792std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8793vinfos[0].jointtype = 1;
8794vinfos[0].foffset = j0;
8795vinfos[0].indices[0] = _ij0[0];
8796vinfos[0].indices[1] = _ij0[1];
8797vinfos[0].maxsolutions = _nj0;
8798vinfos[1].jointtype = 1;
8799vinfos[1].foffset = j1;
8800vinfos[1].indices[0] = _ij1[0];
8801vinfos[1].indices[1] = _ij1[1];
8802vinfos[1].maxsolutions = _nj1;
8803vinfos[2].jointtype = 1;
8804vinfos[2].foffset = j2;
8805vinfos[2].indices[0] = _ij2[0];
8806vinfos[2].indices[1] = _ij2[1];
8807vinfos[2].maxsolutions = _nj2;
8808vinfos[3].jointtype = 1;
8809vinfos[3].foffset = j3;
8810vinfos[3].indices[0] = _ij3[0];
8811vinfos[3].indices[1] = _ij3[1];
8812vinfos[3].maxsolutions = _nj3;
8813vinfos[4].jointtype = 1;
8814vinfos[4].foffset = j4;
8815vinfos[4].indices[0] = _ij4[0];
8816vinfos[4].indices[1] = _ij4[1];
8817vinfos[4].maxsolutions = _nj4;
8818vinfos[5].jointtype = 1;
8819vinfos[5].foffset = j5;
8820vinfos[5].indices[0] = _ij5[0];
8821vinfos[5].indices[1] = _ij5[1];
8822vinfos[5].maxsolutions = _nj5;
8823std::vector<int> vfree(0);
8824solutions.AddSolution(vinfos,vfree);
8825}
8826}
8827}
8828
8829}
8830
8831}
8832
8833}
8834} while(0);
8835if( bgotonextstatement )
8836{
8837bool bgotonextstatement = true;
8838do
8839{
8840evalcond[0]=IKabs(new_r00);
8841if( IKabs(evalcond[0]) < 0.0000050000000000 )
8842{
8843bgotonextstatement=false;
8844{
8845IkReal j0eval[1];
8846CheckValue<IkReal> x586 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8847if(!x586.valid){
8848continue;
8849}
8850IkReal x585=((1.0)*(x586.value));
8851sj1=1.0;
8852cj1=0;
8853j1=1.5707963267949;
8854sj2=gconst20;
8855cj2=gconst21;
8856j2=((3.14159265)+(((-1.0)*x585)));
8857new_r00=0;
8858IkReal gconst19=((3.14159265358979)+(((-1.0)*x585)));
8859IkReal gconst20=0;
8860IkReal x587 = new_r10*new_r10;
8861if(IKabs(x587)==0){
8862continue;
8863}
8864IkReal gconst21=((1.0)*new_r10*(pow(x587,-0.5)));
8865j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
8866if( IKabs(j0eval[0]) < 0.0000010000000000 )
8867{
8868{
8869IkReal j0eval[1];
8870CheckValue<IkReal> x589 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8871if(!x589.valid){
8872continue;
8873}
8874IkReal x588=((1.0)*(x589.value));
8875sj1=1.0;
8876cj1=0;
8877j1=1.5707963267949;
8878sj2=gconst20;
8879cj2=gconst21;
8880j2=((3.14159265)+(((-1.0)*x588)));
8881new_r00=0;
8882IkReal gconst19=((3.14159265358979)+(((-1.0)*x588)));
8883IkReal gconst20=0;
8884IkReal x590 = new_r10*new_r10;
8885if(IKabs(x590)==0){
8886continue;
8887}
8888IkReal gconst21=((1.0)*new_r10*(pow(x590,-0.5)));
8889j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
8890if( IKabs(j0eval[0]) < 0.0000010000000000 )
8891{
8892{
8893IkReal j0eval[1];
8894CheckValue<IkReal> x592 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH);
8895if(!x592.valid){
8896continue;
8897}
8898IkReal x591=((1.0)*(x592.value));
8899sj1=1.0;
8900cj1=0;
8901j1=1.5707963267949;
8902sj2=gconst20;
8903cj2=gconst21;
8904j2=((3.14159265)+(((-1.0)*x591)));
8905new_r00=0;
8906IkReal gconst19=((3.14159265358979)+(((-1.0)*x591)));
8907IkReal gconst20=0;
8908IkReal x593 = new_r10*new_r10;
8909if(IKabs(x593)==0){
8910continue;
8911}
8912IkReal gconst21=((1.0)*new_r10*(pow(x593,-0.5)));
8913j0eval[0]=new_r10;
8914if( IKabs(j0eval[0]) < 0.0000010000000000 )
8915{
8916continue; // 3 cases reached
8917
8918} else
8919{
8920{
8921IkReal j0array[1], cj0array[1], sj0array[1];
8922bool j0valid[1]={false};
8923_nj0 = 1;
8924CheckValue<IkReal> x594=IKPowWithIntegerCheck(gconst21,-1);
8925if(!x594.valid){
8926continue;
8927}
8928CheckValue<IkReal> x595=IKPowWithIntegerCheck(new_r10,-1);
8929if(!x595.valid){
8930continue;
8931}
8932if( IKabs(((-1.0)*new_r11*(x594.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst21*(x595.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x594.value)))+IKsqr((gconst21*(x595.value)))-1) <= IKFAST_SINCOS_THRESH )
8933 continue;
8934j0array[0]=IKatan2(((-1.0)*new_r11*(x594.value)), (gconst21*(x595.value)));
8935sj0array[0]=IKsin(j0array[0]);
8936cj0array[0]=IKcos(j0array[0]);
8937if( j0array[0] > IKPI )
8938{
8939 j0array[0]-=IK2PI;
8940}
8941else if( j0array[0] < -IKPI )
8942{ j0array[0]+=IK2PI;
8943}
8944j0valid[0] = true;
8945for(int ij0 = 0; ij0 < 1; ++ij0)
8946{
8947if( !j0valid[ij0] )
8948{
8949 continue;
8950}
8951_ij0[0] = ij0; _ij0[1] = -1;
8952for(int iij0 = ij0+1; iij0 < 1; ++iij0)
8953{
8954if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
8955{
8956 j0valid[iij0]=false; _ij0[1] = iij0; break;
8957}
8958}
8959j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
8960{
8961IkReal evalcond[8];
8962IkReal x596=IKsin(j0);
8963IkReal x597=IKcos(j0);
8964IkReal x598=(gconst21*x596);
8965IkReal x599=((1.0)*x597);
8966evalcond[0]=(new_r10*x596);
8967evalcond[1]=x598;
8968evalcond[2]=(x598+new_r11);
8969evalcond[3]=(((gconst21*x597))+new_r01);
8970evalcond[4]=((((-1.0)*new_r10*x599))+gconst21);
8971evalcond[5]=((((-1.0)*gconst21*x599))+new_r10);
8972evalcond[6]=(((new_r11*x597))+(((-1.0)*new_r01*x596)));
8973evalcond[7]=(((new_r11*x596))+gconst21+((new_r01*x597)));
8974if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
8975{
8976continue;
8977}
8978}
8979
8980{
8981std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
8982vinfos[0].jointtype = 1;
8983vinfos[0].foffset = j0;
8984vinfos[0].indices[0] = _ij0[0];
8985vinfos[0].indices[1] = _ij0[1];
8986vinfos[0].maxsolutions = _nj0;
8987vinfos[1].jointtype = 1;
8988vinfos[1].foffset = j1;
8989vinfos[1].indices[0] = _ij1[0];
8990vinfos[1].indices[1] = _ij1[1];
8991vinfos[1].maxsolutions = _nj1;
8992vinfos[2].jointtype = 1;
8993vinfos[2].foffset = j2;
8994vinfos[2].indices[0] = _ij2[0];
8995vinfos[2].indices[1] = _ij2[1];
8996vinfos[2].maxsolutions = _nj2;
8997vinfos[3].jointtype = 1;
8998vinfos[3].foffset = j3;
8999vinfos[3].indices[0] = _ij3[0];
9000vinfos[3].indices[1] = _ij3[1];
9001vinfos[3].maxsolutions = _nj3;
9002vinfos[4].jointtype = 1;
9003vinfos[4].foffset = j4;
9004vinfos[4].indices[0] = _ij4[0];
9005vinfos[4].indices[1] = _ij4[1];
9006vinfos[4].maxsolutions = _nj4;
9007vinfos[5].jointtype = 1;
9008vinfos[5].foffset = j5;
9009vinfos[5].indices[0] = _ij5[0];
9010vinfos[5].indices[1] = _ij5[1];
9011vinfos[5].maxsolutions = _nj5;
9012std::vector<int> vfree(0);
9013solutions.AddSolution(vinfos,vfree);
9014}
9015}
9016}
9017
9018}
9019
9020}
9021
9022} else
9023{
9024{
9025IkReal j0array[1], cj0array[1], sj0array[1];
9026bool j0valid[1]={false};
9027_nj0 = 1;
9028CheckValue<IkReal> x600=IKPowWithIntegerCheck(IKsign(gconst21),-1);
9029if(!x600.valid){
9030continue;
9031}
9032CheckValue<IkReal> x601 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
9033if(!x601.valid){
9034continue;
9035}
9036j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x600.value)))+(x601.value));
9037sj0array[0]=IKsin(j0array[0]);
9038cj0array[0]=IKcos(j0array[0]);
9039if( j0array[0] > IKPI )
9040{
9041 j0array[0]-=IK2PI;
9042}
9043else if( j0array[0] < -IKPI )
9044{ j0array[0]+=IK2PI;
9045}
9046j0valid[0] = true;
9047for(int ij0 = 0; ij0 < 1; ++ij0)
9048{
9049if( !j0valid[ij0] )
9050{
9051 continue;
9052}
9053_ij0[0] = ij0; _ij0[1] = -1;
9054for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9055{
9056if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9057{
9058 j0valid[iij0]=false; _ij0[1] = iij0; break;
9059}
9060}
9061j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9062{
9063IkReal evalcond[8];
9064IkReal x602=IKsin(j0);
9065IkReal x603=IKcos(j0);
9066IkReal x604=(gconst21*x602);
9067IkReal x605=((1.0)*x603);
9068evalcond[0]=(new_r10*x602);
9069evalcond[1]=x604;
9070evalcond[2]=(x604+new_r11);
9071evalcond[3]=(((gconst21*x603))+new_r01);
9072evalcond[4]=((((-1.0)*new_r10*x605))+gconst21);
9073evalcond[5]=(new_r10+(((-1.0)*gconst21*x605)));
9074evalcond[6]=(((new_r11*x603))+(((-1.0)*new_r01*x602)));
9075evalcond[7]=(gconst21+((new_r11*x602))+((new_r01*x603)));
9076if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9077{
9078continue;
9079}
9080}
9081
9082{
9083std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9084vinfos[0].jointtype = 1;
9085vinfos[0].foffset = j0;
9086vinfos[0].indices[0] = _ij0[0];
9087vinfos[0].indices[1] = _ij0[1];
9088vinfos[0].maxsolutions = _nj0;
9089vinfos[1].jointtype = 1;
9090vinfos[1].foffset = j1;
9091vinfos[1].indices[0] = _ij1[0];
9092vinfos[1].indices[1] = _ij1[1];
9093vinfos[1].maxsolutions = _nj1;
9094vinfos[2].jointtype = 1;
9095vinfos[2].foffset = j2;
9096vinfos[2].indices[0] = _ij2[0];
9097vinfos[2].indices[1] = _ij2[1];
9098vinfos[2].maxsolutions = _nj2;
9099vinfos[3].jointtype = 1;
9100vinfos[3].foffset = j3;
9101vinfos[3].indices[0] = _ij3[0];
9102vinfos[3].indices[1] = _ij3[1];
9103vinfos[3].maxsolutions = _nj3;
9104vinfos[4].jointtype = 1;
9105vinfos[4].foffset = j4;
9106vinfos[4].indices[0] = _ij4[0];
9107vinfos[4].indices[1] = _ij4[1];
9108vinfos[4].maxsolutions = _nj4;
9109vinfos[5].jointtype = 1;
9110vinfos[5].foffset = j5;
9111vinfos[5].indices[0] = _ij5[0];
9112vinfos[5].indices[1] = _ij5[1];
9113vinfos[5].maxsolutions = _nj5;
9114std::vector<int> vfree(0);
9115solutions.AddSolution(vinfos,vfree);
9116}
9117}
9118}
9119
9120}
9121
9122}
9123
9124} else
9125{
9126{
9127IkReal j0array[1], cj0array[1], sj0array[1];
9128bool j0valid[1]={false};
9129_nj0 = 1;
9130CheckValue<IkReal> x606=IKPowWithIntegerCheck(IKsign(gconst21),-1);
9131if(!x606.valid){
9132continue;
9133}
9134CheckValue<IkReal> x607 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
9135if(!x607.valid){
9136continue;
9137}
9138j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x606.value)))+(x607.value));
9139sj0array[0]=IKsin(j0array[0]);
9140cj0array[0]=IKcos(j0array[0]);
9141if( j0array[0] > IKPI )
9142{
9143 j0array[0]-=IK2PI;
9144}
9145else if( j0array[0] < -IKPI )
9146{ j0array[0]+=IK2PI;
9147}
9148j0valid[0] = true;
9149for(int ij0 = 0; ij0 < 1; ++ij0)
9150{
9151if( !j0valid[ij0] )
9152{
9153 continue;
9154}
9155_ij0[0] = ij0; _ij0[1] = -1;
9156for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9157{
9158if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9159{
9160 j0valid[iij0]=false; _ij0[1] = iij0; break;
9161}
9162}
9163j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9164{
9165IkReal evalcond[8];
9166IkReal x608=IKsin(j0);
9167IkReal x609=IKcos(j0);
9168IkReal x610=(gconst21*x608);
9169IkReal x611=((1.0)*x609);
9170evalcond[0]=(new_r10*x608);
9171evalcond[1]=x610;
9172evalcond[2]=(x610+new_r11);
9173evalcond[3]=(((gconst21*x609))+new_r01);
9174evalcond[4]=(gconst21+(((-1.0)*new_r10*x611)));
9175evalcond[5]=((((-1.0)*gconst21*x611))+new_r10);
9176evalcond[6]=(((new_r11*x609))+(((-1.0)*new_r01*x608)));
9177evalcond[7]=(gconst21+((new_r11*x608))+((new_r01*x609)));
9178if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9179{
9180continue;
9181}
9182}
9183
9184{
9185std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9186vinfos[0].jointtype = 1;
9187vinfos[0].foffset = j0;
9188vinfos[0].indices[0] = _ij0[0];
9189vinfos[0].indices[1] = _ij0[1];
9190vinfos[0].maxsolutions = _nj0;
9191vinfos[1].jointtype = 1;
9192vinfos[1].foffset = j1;
9193vinfos[1].indices[0] = _ij1[0];
9194vinfos[1].indices[1] = _ij1[1];
9195vinfos[1].maxsolutions = _nj1;
9196vinfos[2].jointtype = 1;
9197vinfos[2].foffset = j2;
9198vinfos[2].indices[0] = _ij2[0];
9199vinfos[2].indices[1] = _ij2[1];
9200vinfos[2].maxsolutions = _nj2;
9201vinfos[3].jointtype = 1;
9202vinfos[3].foffset = j3;
9203vinfos[3].indices[0] = _ij3[0];
9204vinfos[3].indices[1] = _ij3[1];
9205vinfos[3].maxsolutions = _nj3;
9206vinfos[4].jointtype = 1;
9207vinfos[4].foffset = j4;
9208vinfos[4].indices[0] = _ij4[0];
9209vinfos[4].indices[1] = _ij4[1];
9210vinfos[4].maxsolutions = _nj4;
9211vinfos[5].jointtype = 1;
9212vinfos[5].foffset = j5;
9213vinfos[5].indices[0] = _ij5[0];
9214vinfos[5].indices[1] = _ij5[1];
9215vinfos[5].maxsolutions = _nj5;
9216std::vector<int> vfree(0);
9217solutions.AddSolution(vinfos,vfree);
9218}
9219}
9220}
9221
9222}
9223
9224}
9225
9226}
9227} while(0);
9228if( bgotonextstatement )
9229{
9230bool bgotonextstatement = true;
9231do
9232{
9233evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
9234if( IKabs(evalcond[0]) < 0.0000050000000000 )
9235{
9236bgotonextstatement=false;
9237{
9238IkReal j0eval[1];
9239CheckValue<IkReal> x613 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
9240if(!x613.valid){
9241continue;
9242}
9243IkReal x612=((1.0)*(x613.value));
9244sj1=1.0;
9245cj1=0;
9246j1=1.5707963267949;
9247sj2=gconst20;
9248cj2=gconst21;
9249j2=((3.14159265)+(((-1.0)*x612)));
9250new_r11=0;
9251new_r10=0;
9252new_r22=0;
9253new_r02=0;
9254IkReal gconst19=((3.14159265358979)+(((-1.0)*x612)));
9255IkReal x614 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
9256if(IKabs(x614)==0){
9257continue;
9258}
9259IkReal gconst20=((1.0)*new_r00*(pow(x614,-0.5)));
9260IkReal gconst21=0;
9261j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
9262if( IKabs(j0eval[0]) < 0.0000010000000000 )
9263{
9264{
9265IkReal j0eval[2];
9266CheckValue<IkReal> x616 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
9267if(!x616.valid){
9268continue;
9269}
9270IkReal x615=((1.0)*(x616.value));
9271sj1=1.0;
9272cj1=0;
9273j1=1.5707963267949;
9274sj2=gconst20;
9275cj2=gconst21;
9276j2=((3.14159265)+(((-1.0)*x615)));
9277new_r11=0;
9278new_r10=0;
9279new_r22=0;
9280new_r02=0;
9281IkReal gconst19=((3.14159265358979)+(((-1.0)*x615)));
9282IkReal x617 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
9283if(IKabs(x617)==0){
9284continue;
9285}
9286IkReal gconst20=((1.0)*new_r00*(pow(x617,-0.5)));
9287IkReal gconst21=0;
9288j0eval[0]=new_r01;
9289j0eval[1]=new_r00;
9290if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
9291{
9292{
9293IkReal j0eval[1];
9294CheckValue<IkReal> x619 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
9295if(!x619.valid){
9296continue;
9297}
9298IkReal x618=((1.0)*(x619.value));
9299sj1=1.0;
9300cj1=0;
9301j1=1.5707963267949;
9302sj2=gconst20;
9303cj2=gconst21;
9304j2=((3.14159265)+(((-1.0)*x618)));
9305new_r11=0;
9306new_r10=0;
9307new_r22=0;
9308new_r02=0;
9309IkReal gconst19=((3.14159265358979)+(((-1.0)*x618)));
9310IkReal x620 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
9311if(IKabs(x620)==0){
9312continue;
9313}
9314IkReal gconst20=((1.0)*new_r00*(pow(x620,-0.5)));
9315IkReal gconst21=0;
9316j0eval[0]=new_r00;
9317if( IKabs(j0eval[0]) < 0.0000010000000000 )
9318{
9319continue; // 3 cases reached
9320
9321} else
9322{
9323{
9324IkReal j0array[1], cj0array[1], sj0array[1];
9325bool j0valid[1]={false};
9326_nj0 = 1;
9327CheckValue<IkReal> x621=IKPowWithIntegerCheck(gconst20,-1);
9328if(!x621.valid){
9329continue;
9330}
9331CheckValue<IkReal> x622=IKPowWithIntegerCheck(new_r00,-1);
9332if(!x622.valid){
9333continue;
9334}
9335if( IKabs((new_r01*(x621.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst20*(x622.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x621.value)))+IKsqr(((-1.0)*gconst20*(x622.value)))-1) <= IKFAST_SINCOS_THRESH )
9336 continue;
9337j0array[0]=IKatan2((new_r01*(x621.value)), ((-1.0)*gconst20*(x622.value)));
9338sj0array[0]=IKsin(j0array[0]);
9339cj0array[0]=IKcos(j0array[0]);
9340if( j0array[0] > IKPI )
9341{
9342 j0array[0]-=IK2PI;
9343}
9344else if( j0array[0] < -IKPI )
9345{ j0array[0]+=IK2PI;
9346}
9347j0valid[0] = true;
9348for(int ij0 = 0; ij0 < 1; ++ij0)
9349{
9350if( !j0valid[ij0] )
9351{
9352 continue;
9353}
9354_ij0[0] = ij0; _ij0[1] = -1;
9355for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9356{
9357if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9358{
9359 j0valid[iij0]=false; _ij0[1] = iij0; break;
9360}
9361}
9362j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9363{
9364IkReal evalcond[8];
9365IkReal x623=IKcos(j0);
9366IkReal x624=IKsin(j0);
9367IkReal x625=(gconst20*x623);
9368IkReal x626=((1.0)*x624);
9369evalcond[0]=(new_r00*x624);
9370evalcond[1]=(new_r01*x623);
9371evalcond[2]=x625;
9372evalcond[3]=(gconst20*x624);
9373evalcond[4]=(gconst20+((new_r00*x623)));
9374evalcond[5]=(x625+new_r00);
9375evalcond[6]=((((-1.0)*new_r01*x626))+gconst20);
9376evalcond[7]=(new_r01+(((-1.0)*gconst20*x626)));
9377if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9378{
9379continue;
9380}
9381}
9382
9383{
9384std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9385vinfos[0].jointtype = 1;
9386vinfos[0].foffset = j0;
9387vinfos[0].indices[0] = _ij0[0];
9388vinfos[0].indices[1] = _ij0[1];
9389vinfos[0].maxsolutions = _nj0;
9390vinfos[1].jointtype = 1;
9391vinfos[1].foffset = j1;
9392vinfos[1].indices[0] = _ij1[0];
9393vinfos[1].indices[1] = _ij1[1];
9394vinfos[1].maxsolutions = _nj1;
9395vinfos[2].jointtype = 1;
9396vinfos[2].foffset = j2;
9397vinfos[2].indices[0] = _ij2[0];
9398vinfos[2].indices[1] = _ij2[1];
9399vinfos[2].maxsolutions = _nj2;
9400vinfos[3].jointtype = 1;
9401vinfos[3].foffset = j3;
9402vinfos[3].indices[0] = _ij3[0];
9403vinfos[3].indices[1] = _ij3[1];
9404vinfos[3].maxsolutions = _nj3;
9405vinfos[4].jointtype = 1;
9406vinfos[4].foffset = j4;
9407vinfos[4].indices[0] = _ij4[0];
9408vinfos[4].indices[1] = _ij4[1];
9409vinfos[4].maxsolutions = _nj4;
9410vinfos[5].jointtype = 1;
9411vinfos[5].foffset = j5;
9412vinfos[5].indices[0] = _ij5[0];
9413vinfos[5].indices[1] = _ij5[1];
9414vinfos[5].maxsolutions = _nj5;
9415std::vector<int> vfree(0);
9416solutions.AddSolution(vinfos,vfree);
9417}
9418}
9419}
9420
9421}
9422
9423}
9424
9425} else
9426{
9427{
9428IkReal j0array[1], cj0array[1], sj0array[1];
9429bool j0valid[1]={false};
9430_nj0 = 1;
9431CheckValue<IkReal> x627=IKPowWithIntegerCheck(new_r01,-1);
9432if(!x627.valid){
9433continue;
9434}
9435CheckValue<IkReal> x628=IKPowWithIntegerCheck(new_r00,-1);
9436if(!x628.valid){
9437continue;
9438}
9439if( IKabs((gconst20*(x627.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst20*(x628.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst20*(x627.value)))+IKsqr(((-1.0)*gconst20*(x628.value)))-1) <= IKFAST_SINCOS_THRESH )
9440 continue;
9441j0array[0]=IKatan2((gconst20*(x627.value)), ((-1.0)*gconst20*(x628.value)));
9442sj0array[0]=IKsin(j0array[0]);
9443cj0array[0]=IKcos(j0array[0]);
9444if( j0array[0] > IKPI )
9445{
9446 j0array[0]-=IK2PI;
9447}
9448else if( j0array[0] < -IKPI )
9449{ j0array[0]+=IK2PI;
9450}
9451j0valid[0] = true;
9452for(int ij0 = 0; ij0 < 1; ++ij0)
9453{
9454if( !j0valid[ij0] )
9455{
9456 continue;
9457}
9458_ij0[0] = ij0; _ij0[1] = -1;
9459for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9460{
9461if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9462{
9463 j0valid[iij0]=false; _ij0[1] = iij0; break;
9464}
9465}
9466j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9467{
9468IkReal evalcond[8];
9469IkReal x629=IKcos(j0);
9470IkReal x630=IKsin(j0);
9471IkReal x631=(gconst20*x629);
9472IkReal x632=((1.0)*x630);
9473evalcond[0]=(new_r00*x630);
9474evalcond[1]=(new_r01*x629);
9475evalcond[2]=x631;
9476evalcond[3]=(gconst20*x630);
9477evalcond[4]=(gconst20+((new_r00*x629)));
9478evalcond[5]=(x631+new_r00);
9479evalcond[6]=((((-1.0)*new_r01*x632))+gconst20);
9480evalcond[7]=((((-1.0)*gconst20*x632))+new_r01);
9481if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9482{
9483continue;
9484}
9485}
9486
9487{
9488std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9489vinfos[0].jointtype = 1;
9490vinfos[0].foffset = j0;
9491vinfos[0].indices[0] = _ij0[0];
9492vinfos[0].indices[1] = _ij0[1];
9493vinfos[0].maxsolutions = _nj0;
9494vinfos[1].jointtype = 1;
9495vinfos[1].foffset = j1;
9496vinfos[1].indices[0] = _ij1[0];
9497vinfos[1].indices[1] = _ij1[1];
9498vinfos[1].maxsolutions = _nj1;
9499vinfos[2].jointtype = 1;
9500vinfos[2].foffset = j2;
9501vinfos[2].indices[0] = _ij2[0];
9502vinfos[2].indices[1] = _ij2[1];
9503vinfos[2].maxsolutions = _nj2;
9504vinfos[3].jointtype = 1;
9505vinfos[3].foffset = j3;
9506vinfos[3].indices[0] = _ij3[0];
9507vinfos[3].indices[1] = _ij3[1];
9508vinfos[3].maxsolutions = _nj3;
9509vinfos[4].jointtype = 1;
9510vinfos[4].foffset = j4;
9511vinfos[4].indices[0] = _ij4[0];
9512vinfos[4].indices[1] = _ij4[1];
9513vinfos[4].maxsolutions = _nj4;
9514vinfos[5].jointtype = 1;
9515vinfos[5].foffset = j5;
9516vinfos[5].indices[0] = _ij5[0];
9517vinfos[5].indices[1] = _ij5[1];
9518vinfos[5].maxsolutions = _nj5;
9519std::vector<int> vfree(0);
9520solutions.AddSolution(vinfos,vfree);
9521}
9522}
9523}
9524
9525}
9526
9527}
9528
9529} else
9530{
9531{
9532IkReal j0array[1], cj0array[1], sj0array[1];
9533bool j0valid[1]={false};
9534_nj0 = 1;
9535CheckValue<IkReal> x633 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
9536if(!x633.valid){
9537continue;
9538}
9539CheckValue<IkReal> x634=IKPowWithIntegerCheck(IKsign(gconst20),-1);
9540if(!x634.valid){
9541continue;
9542}
9543j0array[0]=((-1.5707963267949)+(x633.value)+(((1.5707963267949)*(x634.value))));
9544sj0array[0]=IKsin(j0array[0]);
9545cj0array[0]=IKcos(j0array[0]);
9546if( j0array[0] > IKPI )
9547{
9548 j0array[0]-=IK2PI;
9549}
9550else if( j0array[0] < -IKPI )
9551{ j0array[0]+=IK2PI;
9552}
9553j0valid[0] = true;
9554for(int ij0 = 0; ij0 < 1; ++ij0)
9555{
9556if( !j0valid[ij0] )
9557{
9558 continue;
9559}
9560_ij0[0] = ij0; _ij0[1] = -1;
9561for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9562{
9563if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9564{
9565 j0valid[iij0]=false; _ij0[1] = iij0; break;
9566}
9567}
9568j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9569{
9570IkReal evalcond[8];
9571IkReal x635=IKcos(j0);
9572IkReal x636=IKsin(j0);
9573IkReal x637=(gconst20*x635);
9574IkReal x638=((1.0)*x636);
9575evalcond[0]=(new_r00*x636);
9576evalcond[1]=(new_r01*x635);
9577evalcond[2]=x637;
9578evalcond[3]=(gconst20*x636);
9579evalcond[4]=(gconst20+((new_r00*x635)));
9580evalcond[5]=(x637+new_r00);
9581evalcond[6]=((((-1.0)*new_r01*x638))+gconst20);
9582evalcond[7]=((((-1.0)*gconst20*x638))+new_r01);
9583if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9584{
9585continue;
9586}
9587}
9588
9589{
9590std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9591vinfos[0].jointtype = 1;
9592vinfos[0].foffset = j0;
9593vinfos[0].indices[0] = _ij0[0];
9594vinfos[0].indices[1] = _ij0[1];
9595vinfos[0].maxsolutions = _nj0;
9596vinfos[1].jointtype = 1;
9597vinfos[1].foffset = j1;
9598vinfos[1].indices[0] = _ij1[0];
9599vinfos[1].indices[1] = _ij1[1];
9600vinfos[1].maxsolutions = _nj1;
9601vinfos[2].jointtype = 1;
9602vinfos[2].foffset = j2;
9603vinfos[2].indices[0] = _ij2[0];
9604vinfos[2].indices[1] = _ij2[1];
9605vinfos[2].maxsolutions = _nj2;
9606vinfos[3].jointtype = 1;
9607vinfos[3].foffset = j3;
9608vinfos[3].indices[0] = _ij3[0];
9609vinfos[3].indices[1] = _ij3[1];
9610vinfos[3].maxsolutions = _nj3;
9611vinfos[4].jointtype = 1;
9612vinfos[4].foffset = j4;
9613vinfos[4].indices[0] = _ij4[0];
9614vinfos[4].indices[1] = _ij4[1];
9615vinfos[4].maxsolutions = _nj4;
9616vinfos[5].jointtype = 1;
9617vinfos[5].foffset = j5;
9618vinfos[5].indices[0] = _ij5[0];
9619vinfos[5].indices[1] = _ij5[1];
9620vinfos[5].maxsolutions = _nj5;
9621std::vector<int> vfree(0);
9622solutions.AddSolution(vinfos,vfree);
9623}
9624}
9625}
9626
9627}
9628
9629}
9630
9631}
9632} while(0);
9633if( bgotonextstatement )
9634{
9635bool bgotonextstatement = true;
9636do
9637{
9638if( 1 )
9639{
9640bgotonextstatement=false;
9641continue; // branch miss [j0]
9642
9643}
9644} while(0);
9645if( bgotonextstatement )
9646{
9647}
9648}
9649}
9650}
9651}
9652}
9653}
9654
9655} else
9656{
9657{
9658IkReal j0array[1], cj0array[1], sj0array[1];
9659bool j0valid[1]={false};
9660_nj0 = 1;
9661IkReal x639=((1.0)*gconst20);
9662CheckValue<IkReal> x640=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
9663if(!x640.valid){
9664continue;
9665}
9666CheckValue<IkReal> x641 = IKatan2WithCheck(IkReal((((gconst20*new_r00))+(((-1.0)*new_r11*x639)))),IkReal(((((-1.0)*new_r01*x639))+(((-1.0)*new_r10*x639)))),IKFAST_ATAN2_MAGTHRESH);
9667if(!x641.valid){
9668continue;
9669}
9670j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x640.value)))+(x641.value));
9671sj0array[0]=IKsin(j0array[0]);
9672cj0array[0]=IKcos(j0array[0]);
9673if( j0array[0] > IKPI )
9674{
9675 j0array[0]-=IK2PI;
9676}
9677else if( j0array[0] < -IKPI )
9678{ j0array[0]+=IK2PI;
9679}
9680j0valid[0] = true;
9681for(int ij0 = 0; ij0 < 1; ++ij0)
9682{
9683if( !j0valid[ij0] )
9684{
9685 continue;
9686}
9687_ij0[0] = ij0; _ij0[1] = -1;
9688for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9689{
9690if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9691{
9692 j0valid[iij0]=false; _ij0[1] = iij0; break;
9693}
9694}
9695j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9696{
9697IkReal evalcond[8];
9698IkReal x642=IKsin(j0);
9699IkReal x643=IKcos(j0);
9700IkReal x644=(gconst21*x642);
9701IkReal x645=(gconst20*x643);
9702IkReal x646=((1.0)*x643);
9703IkReal x647=(gconst20*x642);
9704IkReal x648=(x645+x644);
9705evalcond[0]=(gconst20+((new_r10*x642))+((new_r00*x643)));
9706evalcond[1]=(gconst21+((new_r11*x642))+((new_r01*x643)));
9707evalcond[2]=(x648+new_r00);
9708evalcond[3]=(x648+new_r11);
9709evalcond[4]=((((-1.0)*new_r01*x642))+gconst20+((new_r11*x643)));
9710evalcond[5]=(gconst21+(((-1.0)*new_r10*x646))+((new_r00*x642)));
9711evalcond[6]=((((-1.0)*x647))+((gconst21*x643))+new_r01);
9712evalcond[7]=((((-1.0)*gconst21*x646))+x647+new_r10);
9713if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9714{
9715continue;
9716}
9717}
9718
9719{
9720std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9721vinfos[0].jointtype = 1;
9722vinfos[0].foffset = j0;
9723vinfos[0].indices[0] = _ij0[0];
9724vinfos[0].indices[1] = _ij0[1];
9725vinfos[0].maxsolutions = _nj0;
9726vinfos[1].jointtype = 1;
9727vinfos[1].foffset = j1;
9728vinfos[1].indices[0] = _ij1[0];
9729vinfos[1].indices[1] = _ij1[1];
9730vinfos[1].maxsolutions = _nj1;
9731vinfos[2].jointtype = 1;
9732vinfos[2].foffset = j2;
9733vinfos[2].indices[0] = _ij2[0];
9734vinfos[2].indices[1] = _ij2[1];
9735vinfos[2].maxsolutions = _nj2;
9736vinfos[3].jointtype = 1;
9737vinfos[3].foffset = j3;
9738vinfos[3].indices[0] = _ij3[0];
9739vinfos[3].indices[1] = _ij3[1];
9740vinfos[3].maxsolutions = _nj3;
9741vinfos[4].jointtype = 1;
9742vinfos[4].foffset = j4;
9743vinfos[4].indices[0] = _ij4[0];
9744vinfos[4].indices[1] = _ij4[1];
9745vinfos[4].maxsolutions = _nj4;
9746vinfos[5].jointtype = 1;
9747vinfos[5].foffset = j5;
9748vinfos[5].indices[0] = _ij5[0];
9749vinfos[5].indices[1] = _ij5[1];
9750vinfos[5].maxsolutions = _nj5;
9751std::vector<int> vfree(0);
9752solutions.AddSolution(vinfos,vfree);
9753}
9754}
9755}
9756
9757}
9758
9759}
9760
9761} else
9762{
9763{
9764IkReal j0array[1], cj0array[1], sj0array[1];
9765bool j0valid[1]={false};
9766_nj0 = 1;
9767IkReal x649=((1.0)*gconst21);
9768CheckValue<IkReal> x650 = IKatan2WithCheck(IkReal(((((-1.0)*gconst20*x649))+((new_r00*new_r01)))),IkReal(((gconst21*gconst21)+(((-1.0)*new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
9769if(!x650.valid){
9770continue;
9771}
9772CheckValue<IkReal> x651=IKPowWithIntegerCheck(IKsign((((gconst20*new_r11))+(((-1.0)*new_r01*x649)))),-1);
9773if(!x651.valid){
9774continue;
9775}
9776j0array[0]=((-1.5707963267949)+(x650.value)+(((1.5707963267949)*(x651.value))));
9777sj0array[0]=IKsin(j0array[0]);
9778cj0array[0]=IKcos(j0array[0]);
9779if( j0array[0] > IKPI )
9780{
9781 j0array[0]-=IK2PI;
9782}
9783else if( j0array[0] < -IKPI )
9784{ j0array[0]+=IK2PI;
9785}
9786j0valid[0] = true;
9787for(int ij0 = 0; ij0 < 1; ++ij0)
9788{
9789if( !j0valid[ij0] )
9790{
9791 continue;
9792}
9793_ij0[0] = ij0; _ij0[1] = -1;
9794for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9795{
9796if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9797{
9798 j0valid[iij0]=false; _ij0[1] = iij0; break;
9799}
9800}
9801j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9802{
9803IkReal evalcond[8];
9804IkReal x652=IKsin(j0);
9805IkReal x653=IKcos(j0);
9806IkReal x654=(gconst21*x652);
9807IkReal x655=(gconst20*x653);
9808IkReal x656=((1.0)*x653);
9809IkReal x657=(gconst20*x652);
9810IkReal x658=(x654+x655);
9811evalcond[0]=(gconst20+((new_r10*x652))+((new_r00*x653)));
9812evalcond[1]=(gconst21+((new_r01*x653))+((new_r11*x652)));
9813evalcond[2]=(x658+new_r00);
9814evalcond[3]=(x658+new_r11);
9815evalcond[4]=(gconst20+(((-1.0)*new_r01*x652))+((new_r11*x653)));
9816evalcond[5]=(gconst21+(((-1.0)*new_r10*x656))+((new_r00*x652)));
9817evalcond[6]=((((-1.0)*x657))+((gconst21*x653))+new_r01);
9818evalcond[7]=((((-1.0)*gconst21*x656))+x657+new_r10);
9819if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9820{
9821continue;
9822}
9823}
9824
9825{
9826std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9827vinfos[0].jointtype = 1;
9828vinfos[0].foffset = j0;
9829vinfos[0].indices[0] = _ij0[0];
9830vinfos[0].indices[1] = _ij0[1];
9831vinfos[0].maxsolutions = _nj0;
9832vinfos[1].jointtype = 1;
9833vinfos[1].foffset = j1;
9834vinfos[1].indices[0] = _ij1[0];
9835vinfos[1].indices[1] = _ij1[1];
9836vinfos[1].maxsolutions = _nj1;
9837vinfos[2].jointtype = 1;
9838vinfos[2].foffset = j2;
9839vinfos[2].indices[0] = _ij2[0];
9840vinfos[2].indices[1] = _ij2[1];
9841vinfos[2].maxsolutions = _nj2;
9842vinfos[3].jointtype = 1;
9843vinfos[3].foffset = j3;
9844vinfos[3].indices[0] = _ij3[0];
9845vinfos[3].indices[1] = _ij3[1];
9846vinfos[3].maxsolutions = _nj3;
9847vinfos[4].jointtype = 1;
9848vinfos[4].foffset = j4;
9849vinfos[4].indices[0] = _ij4[0];
9850vinfos[4].indices[1] = _ij4[1];
9851vinfos[4].maxsolutions = _nj4;
9852vinfos[5].jointtype = 1;
9853vinfos[5].foffset = j5;
9854vinfos[5].indices[0] = _ij5[0];
9855vinfos[5].indices[1] = _ij5[1];
9856vinfos[5].maxsolutions = _nj5;
9857std::vector<int> vfree(0);
9858solutions.AddSolution(vinfos,vfree);
9859}
9860}
9861}
9862
9863}
9864
9865}
9866
9867} else
9868{
9869{
9870IkReal j0array[1], cj0array[1], sj0array[1];
9871bool j0valid[1]={false};
9872_nj0 = 1;
9873CheckValue<IkReal> x659 = IKatan2WithCheck(IkReal(((((-1.0)*gconst21*new_r00))+((gconst20*new_r01)))),IkReal((((gconst21*new_r10))+(((-1.0)*gconst20*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
9874if(!x659.valid){
9875continue;
9876}
9877CheckValue<IkReal> x660=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1);
9878if(!x660.valid){
9879continue;
9880}
9881j0array[0]=((-1.5707963267949)+(x659.value)+(((1.5707963267949)*(x660.value))));
9882sj0array[0]=IKsin(j0array[0]);
9883cj0array[0]=IKcos(j0array[0]);
9884if( j0array[0] > IKPI )
9885{
9886 j0array[0]-=IK2PI;
9887}
9888else if( j0array[0] < -IKPI )
9889{ j0array[0]+=IK2PI;
9890}
9891j0valid[0] = true;
9892for(int ij0 = 0; ij0 < 1; ++ij0)
9893{
9894if( !j0valid[ij0] )
9895{
9896 continue;
9897}
9898_ij0[0] = ij0; _ij0[1] = -1;
9899for(int iij0 = ij0+1; iij0 < 1; ++iij0)
9900{
9901if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
9902{
9903 j0valid[iij0]=false; _ij0[1] = iij0; break;
9904}
9905}
9906j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
9907{
9908IkReal evalcond[8];
9909IkReal x661=IKsin(j0);
9910IkReal x662=IKcos(j0);
9911IkReal x663=(gconst21*x661);
9912IkReal x664=(gconst20*x662);
9913IkReal x665=((1.0)*x662);
9914IkReal x666=(gconst20*x661);
9915IkReal x667=(x663+x664);
9916evalcond[0]=(gconst20+((new_r10*x661))+((new_r00*x662)));
9917evalcond[1]=(gconst21+((new_r11*x661))+((new_r01*x662)));
9918evalcond[2]=(x667+new_r00);
9919evalcond[3]=(x667+new_r11);
9920evalcond[4]=(gconst20+((new_r11*x662))+(((-1.0)*new_r01*x661)));
9921evalcond[5]=(gconst21+(((-1.0)*new_r10*x665))+((new_r00*x661)));
9922evalcond[6]=((((-1.0)*x666))+((gconst21*x662))+new_r01);
9923evalcond[7]=((((-1.0)*gconst21*x665))+x666+new_r10);
9924if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
9925{
9926continue;
9927}
9928}
9929
9930{
9931std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
9932vinfos[0].jointtype = 1;
9933vinfos[0].foffset = j0;
9934vinfos[0].indices[0] = _ij0[0];
9935vinfos[0].indices[1] = _ij0[1];
9936vinfos[0].maxsolutions = _nj0;
9937vinfos[1].jointtype = 1;
9938vinfos[1].foffset = j1;
9939vinfos[1].indices[0] = _ij1[0];
9940vinfos[1].indices[1] = _ij1[1];
9941vinfos[1].maxsolutions = _nj1;
9942vinfos[2].jointtype = 1;
9943vinfos[2].foffset = j2;
9944vinfos[2].indices[0] = _ij2[0];
9945vinfos[2].indices[1] = _ij2[1];
9946vinfos[2].maxsolutions = _nj2;
9947vinfos[3].jointtype = 1;
9948vinfos[3].foffset = j3;
9949vinfos[3].indices[0] = _ij3[0];
9950vinfos[3].indices[1] = _ij3[1];
9951vinfos[3].maxsolutions = _nj3;
9952vinfos[4].jointtype = 1;
9953vinfos[4].foffset = j4;
9954vinfos[4].indices[0] = _ij4[0];
9955vinfos[4].indices[1] = _ij4[1];
9956vinfos[4].maxsolutions = _nj4;
9957vinfos[5].jointtype = 1;
9958vinfos[5].foffset = j5;
9959vinfos[5].indices[0] = _ij5[0];
9960vinfos[5].indices[1] = _ij5[1];
9961vinfos[5].maxsolutions = _nj5;
9962std::vector<int> vfree(0);
9963solutions.AddSolution(vinfos,vfree);
9964}
9965}
9966}
9967
9968}
9969
9970}
9971
9972}
9973} while(0);
9974if( bgotonextstatement )
9975{
9976bool bgotonextstatement = true;
9977do
9978{
9979IkReal x668=((-1.0)*new_r11);
9980IkReal x670 = ((new_r01*new_r01)+(new_r11*new_r11));
9981if(IKabs(x670)==0){
9982continue;
9983}
9984IkReal x669=pow(x670,-0.5);
9985CheckValue<IkReal> x671 = IKatan2WithCheck(IkReal(new_r01),IkReal(x668),IKFAST_ATAN2_MAGTHRESH);
9986if(!x671.valid){
9987continue;
9988}
9989IkReal gconst22=((-1.0)*(x671.value));
9990IkReal gconst23=((-1.0)*new_r01*x669);
9991IkReal gconst24=(x668*x669);
9992CheckValue<IkReal> x672 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
9993if(!x672.valid){
9994continue;
9995}
9996evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x672.value)+j2)))), 6.28318530717959)));
9997if( IKabs(evalcond[0]) < 0.0000050000000000 )
9998{
9999bgotonextstatement=false;
10000{
10001IkReal j0eval[3];
10002IkReal x673=((-1.0)*new_r11);
10003CheckValue<IkReal> x676 = IKatan2WithCheck(IkReal(new_r01),IkReal(x673),IKFAST_ATAN2_MAGTHRESH);
10004if(!x676.valid){
10005continue;
10006}
10007IkReal x674=((-1.0)*(x676.value));
10008IkReal x675=x669;
10009sj1=1.0;
10010cj1=0;
10011j1=1.5707963267949;
10012sj2=gconst23;
10013cj2=gconst24;
10014j2=x674;
10015IkReal gconst22=x674;
10016IkReal gconst23=((-1.0)*new_r01*x675);
10017IkReal gconst24=(x673*x675);
10018IkReal x677=new_r01*new_r01;
10019IkReal x678=((1.0)*new_r10);
10020IkReal x679=((((-1.0)*new_r01*x678))+((new_r00*new_r11)));
10021IkReal x680=x669;
10022IkReal x681=(new_r11*x680);
10023j0eval[0]=x679;
10024j0eval[1]=IKsign(x679);
10025j0eval[2]=((IKabs(((((-1.0)*x678*x681))+((new_r01*x681)))))+(IKabs((((new_r00*x681))+(((-1.0)*x677*x680))))));
10026if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
10027{
10028{
10029IkReal j0eval[3];
10030IkReal x682=((-1.0)*new_r11);
10031CheckValue<IkReal> x685 = IKatan2WithCheck(IkReal(new_r01),IkReal(x682),IKFAST_ATAN2_MAGTHRESH);
10032if(!x685.valid){
10033continue;
10034}
10035IkReal x683=((-1.0)*(x685.value));
10036IkReal x684=x669;
10037sj1=1.0;
10038cj1=0;
10039j1=1.5707963267949;
10040sj2=gconst23;
10041cj2=gconst24;
10042j2=x683;
10043IkReal gconst22=x683;
10044IkReal gconst23=((-1.0)*new_r01*x684);
10045IkReal gconst24=(x682*x684);
10046IkReal x686=new_r01*new_r01;
10047IkReal x687=(((new_r10*new_r11))+((new_r00*new_r01)));
10048IkReal x688=x669;
10049IkReal x689=(new_r01*x688);
10050j0eval[0]=x687;
10051j0eval[1]=((IKabs(((((-1.0)*new_r00*x689))+((new_r11*x689)))))+(IKabs((((x686*x688))+((new_r10*x689))))));
10052j0eval[2]=IKsign(x687);
10053if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
10054{
10055{
10056IkReal j0eval[1];
10057IkReal x690=((-1.0)*new_r11);
10058CheckValue<IkReal> x693 = IKatan2WithCheck(IkReal(new_r01),IkReal(x690),IKFAST_ATAN2_MAGTHRESH);
10059if(!x693.valid){
10060continue;
10061}
10062IkReal x691=((-1.0)*(x693.value));
10063IkReal x692=x669;
10064sj1=1.0;
10065cj1=0;
10066j1=1.5707963267949;
10067sj2=gconst23;
10068cj2=gconst24;
10069j2=x691;
10070IkReal gconst22=x691;
10071IkReal gconst23=((-1.0)*new_r01*x692);
10072IkReal gconst24=(x690*x692);
10073IkReal x694=new_r01*new_r01;
10074CheckValue<IkReal> x696=IKPowWithIntegerCheck(((new_r11*new_r11)+x694),-1);
10075if(!x696.valid){
10076continue;
10077}
10078IkReal x695=x696.value;
10079j0eval[0]=((IKabs(((((-1.0)*x694*x695))+(new_r00*new_r00))))+(IKabs((((new_r01*new_r11*x695))+(((-1.0)*new_r00*new_r10))))));
10080if( IKabs(j0eval[0]) < 0.0000010000000000 )
10081{
10082{
10083IkReal evalcond[3];
10084bool bgotonextstatement = true;
10085do
10086{
10087evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
10088evalcond[1]=gconst24;
10089evalcond[2]=gconst23;
10090if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 )
10091{
10092bgotonextstatement=false;
10093{
10094IkReal j0eval[3];
10095IkReal x697=((-1.0)*new_r11);
10096CheckValue<IkReal> x699 = IKatan2WithCheck(IkReal(new_r01),IkReal(x697),IKFAST_ATAN2_MAGTHRESH);
10097if(!x699.valid){
10098continue;
10099}
10100IkReal x698=((-1.0)*(x699.value));
10101sj1=1.0;
10102cj1=0;
10103j1=1.5707963267949;
10104sj2=gconst23;
10105cj2=gconst24;
10106j2=x698;
10107new_r00=0;
10108new_r10=0;
10109new_r21=0;
10110new_r22=0;
10111IkReal gconst22=x698;
10112IkReal gconst23=((-1.0)*new_r01);
10113IkReal gconst24=x697;
10114j0eval[0]=-1.0;
10115j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11))));
10116j0eval[2]=-1.0;
10117if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
10118{
10119{
10120IkReal j0eval[3];
10121IkReal x700=((-1.0)*new_r11);
10122CheckValue<IkReal> x702 = IKatan2WithCheck(IkReal(new_r01),IkReal(x700),IKFAST_ATAN2_MAGTHRESH);
10123if(!x702.valid){
10124continue;
10125}
10126IkReal x701=((-1.0)*(x702.value));
10127sj1=1.0;
10128cj1=0;
10129j1=1.5707963267949;
10130sj2=gconst23;
10131cj2=gconst24;
10132j2=x701;
10133new_r00=0;
10134new_r10=0;
10135new_r21=0;
10136new_r22=0;
10137IkReal gconst22=x701;
10138IkReal gconst23=((-1.0)*new_r01);
10139IkReal gconst24=x700;
10140j0eval[0]=1.0;
10141j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11))));
10142j0eval[2]=1.0;
10143if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
10144{
10145{
10146IkReal j0eval[3];
10147IkReal x703=((-1.0)*new_r11);
10148CheckValue<IkReal> x705 = IKatan2WithCheck(IkReal(new_r01),IkReal(x703),IKFAST_ATAN2_MAGTHRESH);
10149if(!x705.valid){
10150continue;
10151}
10152IkReal x704=((-1.0)*(x705.value));
10153sj1=1.0;
10154cj1=0;
10155j1=1.5707963267949;
10156sj2=gconst23;
10157cj2=gconst24;
10158j2=x704;
10159new_r00=0;
10160new_r10=0;
10161new_r21=0;
10162new_r22=0;
10163IkReal gconst22=x704;
10164IkReal gconst23=((-1.0)*new_r01);
10165IkReal gconst24=x703;
10166j0eval[0]=1.0;
10167j0eval[1]=1.0;
10168j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01)))))));
10169if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
10170{
10171continue; // 3 cases reached
10172
10173} else
10174{
10175{
10176IkReal j0array[1], cj0array[1], sj0array[1];
10177bool j0valid[1]={false};
10178_nj0 = 1;
10179CheckValue<IkReal> x706 = IKatan2WithCheck(IkReal(gconst24*gconst24),IkReal((gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH);
10180if(!x706.valid){
10181continue;
10182}
10183CheckValue<IkReal> x707=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst24*new_r11))+(((-1.0)*gconst23*new_r01)))),-1);
10184if(!x707.valid){
10185continue;
10186}
10187j0array[0]=((-1.5707963267949)+(x706.value)+(((1.5707963267949)*(x707.value))));
10188sj0array[0]=IKsin(j0array[0]);
10189cj0array[0]=IKcos(j0array[0]);
10190if( j0array[0] > IKPI )
10191{
10192 j0array[0]-=IK2PI;
10193}
10194else if( j0array[0] < -IKPI )
10195{ j0array[0]+=IK2PI;
10196}
10197j0valid[0] = true;
10198for(int ij0 = 0; ij0 < 1; ++ij0)
10199{
10200if( !j0valid[ij0] )
10201{
10202 continue;
10203}
10204_ij0[0] = ij0; _ij0[1] = -1;
10205for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10206{
10207if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10208{
10209 j0valid[iij0]=false; _ij0[1] = iij0; break;
10210}
10211}
10212j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10213{
10214IkReal evalcond[6];
10215IkReal x708=IKsin(j0);
10216IkReal x709=IKcos(j0);
10217IkReal x710=(gconst23*x709);
10218IkReal x711=(gconst24*x708);
10219IkReal x712=(gconst24*x709);
10220IkReal x713=((1.0)*x708);
10221IkReal x714=(x711+x710);
10222evalcond[0]=x714;
10223evalcond[1]=(((new_r01*x709))+gconst24+((new_r11*x708)));
10224evalcond[2]=(x714+new_r11);
10225evalcond[3]=((((-1.0)*x712))+((gconst23*x708)));
10226evalcond[4]=(gconst23+((new_r11*x709))+(((-1.0)*new_r01*x713)));
10227evalcond[5]=((((-1.0)*gconst23*x713))+x712+new_r01);
10228if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10229{
10230continue;
10231}
10232}
10233
10234{
10235std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10236vinfos[0].jointtype = 1;
10237vinfos[0].foffset = j0;
10238vinfos[0].indices[0] = _ij0[0];
10239vinfos[0].indices[1] = _ij0[1];
10240vinfos[0].maxsolutions = _nj0;
10241vinfos[1].jointtype = 1;
10242vinfos[1].foffset = j1;
10243vinfos[1].indices[0] = _ij1[0];
10244vinfos[1].indices[1] = _ij1[1];
10245vinfos[1].maxsolutions = _nj1;
10246vinfos[2].jointtype = 1;
10247vinfos[2].foffset = j2;
10248vinfos[2].indices[0] = _ij2[0];
10249vinfos[2].indices[1] = _ij2[1];
10250vinfos[2].maxsolutions = _nj2;
10251vinfos[3].jointtype = 1;
10252vinfos[3].foffset = j3;
10253vinfos[3].indices[0] = _ij3[0];
10254vinfos[3].indices[1] = _ij3[1];
10255vinfos[3].maxsolutions = _nj3;
10256vinfos[4].jointtype = 1;
10257vinfos[4].foffset = j4;
10258vinfos[4].indices[0] = _ij4[0];
10259vinfos[4].indices[1] = _ij4[1];
10260vinfos[4].maxsolutions = _nj4;
10261vinfos[5].jointtype = 1;
10262vinfos[5].foffset = j5;
10263vinfos[5].indices[0] = _ij5[0];
10264vinfos[5].indices[1] = _ij5[1];
10265vinfos[5].maxsolutions = _nj5;
10266std::vector<int> vfree(0);
10267solutions.AddSolution(vinfos,vfree);
10268}
10269}
10270}
10271
10272}
10273
10274}
10275
10276} else
10277{
10278{
10279IkReal j0array[1], cj0array[1], sj0array[1];
10280bool j0valid[1]={false};
10281_nj0 = 1;
10282CheckValue<IkReal> x715=IKPowWithIntegerCheck(IKsign(((gconst23*gconst23)+(gconst24*gconst24))),-1);
10283if(!x715.valid){
10284continue;
10285}
10286CheckValue<IkReal> x716 = IKatan2WithCheck(IkReal((gconst23*new_r01)),IkReal(((-1.0)*gconst24*new_r01)),IKFAST_ATAN2_MAGTHRESH);
10287if(!x716.valid){
10288continue;
10289}
10290j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x715.value)))+(x716.value));
10291sj0array[0]=IKsin(j0array[0]);
10292cj0array[0]=IKcos(j0array[0]);
10293if( j0array[0] > IKPI )
10294{
10295 j0array[0]-=IK2PI;
10296}
10297else if( j0array[0] < -IKPI )
10298{ j0array[0]+=IK2PI;
10299}
10300j0valid[0] = true;
10301for(int ij0 = 0; ij0 < 1; ++ij0)
10302{
10303if( !j0valid[ij0] )
10304{
10305 continue;
10306}
10307_ij0[0] = ij0; _ij0[1] = -1;
10308for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10309{
10310if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10311{
10312 j0valid[iij0]=false; _ij0[1] = iij0; break;
10313}
10314}
10315j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10316{
10317IkReal evalcond[6];
10318IkReal x717=IKsin(j0);
10319IkReal x718=IKcos(j0);
10320IkReal x719=(gconst23*x718);
10321IkReal x720=(gconst24*x717);
10322IkReal x721=(gconst24*x718);
10323IkReal x722=((1.0)*x717);
10324IkReal x723=(x719+x720);
10325evalcond[0]=x723;
10326evalcond[1]=(((new_r01*x718))+gconst24+((new_r11*x717)));
10327evalcond[2]=(x723+new_r11);
10328evalcond[3]=((((-1.0)*x721))+((gconst23*x717)));
10329evalcond[4]=(gconst23+((new_r11*x718))+(((-1.0)*new_r01*x722)));
10330evalcond[5]=((((-1.0)*gconst23*x722))+x721+new_r01);
10331if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10332{
10333continue;
10334}
10335}
10336
10337{
10338std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10339vinfos[0].jointtype = 1;
10340vinfos[0].foffset = j0;
10341vinfos[0].indices[0] = _ij0[0];
10342vinfos[0].indices[1] = _ij0[1];
10343vinfos[0].maxsolutions = _nj0;
10344vinfos[1].jointtype = 1;
10345vinfos[1].foffset = j1;
10346vinfos[1].indices[0] = _ij1[0];
10347vinfos[1].indices[1] = _ij1[1];
10348vinfos[1].maxsolutions = _nj1;
10349vinfos[2].jointtype = 1;
10350vinfos[2].foffset = j2;
10351vinfos[2].indices[0] = _ij2[0];
10352vinfos[2].indices[1] = _ij2[1];
10353vinfos[2].maxsolutions = _nj2;
10354vinfos[3].jointtype = 1;
10355vinfos[3].foffset = j3;
10356vinfos[3].indices[0] = _ij3[0];
10357vinfos[3].indices[1] = _ij3[1];
10358vinfos[3].maxsolutions = _nj3;
10359vinfos[4].jointtype = 1;
10360vinfos[4].foffset = j4;
10361vinfos[4].indices[0] = _ij4[0];
10362vinfos[4].indices[1] = _ij4[1];
10363vinfos[4].maxsolutions = _nj4;
10364vinfos[5].jointtype = 1;
10365vinfos[5].foffset = j5;
10366vinfos[5].indices[0] = _ij5[0];
10367vinfos[5].indices[1] = _ij5[1];
10368vinfos[5].maxsolutions = _nj5;
10369std::vector<int> vfree(0);
10370solutions.AddSolution(vinfos,vfree);
10371}
10372}
10373}
10374
10375}
10376
10377}
10378
10379} else
10380{
10381{
10382IkReal j0array[1], cj0array[1], sj0array[1];
10383bool j0valid[1]={false};
10384_nj0 = 1;
10385CheckValue<IkReal> x724 = IKatan2WithCheck(IkReal(gconst23*gconst23),IkReal(((-1.0)*gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH);
10386if(!x724.valid){
10387continue;
10388}
10389CheckValue<IkReal> x725=IKPowWithIntegerCheck(IKsign((((gconst23*new_r01))+((gconst24*new_r11)))),-1);
10390if(!x725.valid){
10391continue;
10392}
10393j0array[0]=((-1.5707963267949)+(x724.value)+(((1.5707963267949)*(x725.value))));
10394sj0array[0]=IKsin(j0array[0]);
10395cj0array[0]=IKcos(j0array[0]);
10396if( j0array[0] > IKPI )
10397{
10398 j0array[0]-=IK2PI;
10399}
10400else if( j0array[0] < -IKPI )
10401{ j0array[0]+=IK2PI;
10402}
10403j0valid[0] = true;
10404for(int ij0 = 0; ij0 < 1; ++ij0)
10405{
10406if( !j0valid[ij0] )
10407{
10408 continue;
10409}
10410_ij0[0] = ij0; _ij0[1] = -1;
10411for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10412{
10413if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10414{
10415 j0valid[iij0]=false; _ij0[1] = iij0; break;
10416}
10417}
10418j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10419{
10420IkReal evalcond[6];
10421IkReal x726=IKsin(j0);
10422IkReal x727=IKcos(j0);
10423IkReal x728=(gconst23*x727);
10424IkReal x729=(gconst24*x726);
10425IkReal x730=(gconst24*x727);
10426IkReal x731=((1.0)*x726);
10427IkReal x732=(x728+x729);
10428evalcond[0]=x732;
10429evalcond[1]=(gconst24+((new_r01*x727))+((new_r11*x726)));
10430evalcond[2]=(x732+new_r11);
10431evalcond[3]=((((-1.0)*x730))+((gconst23*x726)));
10432evalcond[4]=(gconst23+(((-1.0)*new_r01*x731))+((new_r11*x727)));
10433evalcond[5]=((((-1.0)*gconst23*x731))+x730+new_r01);
10434if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
10435{
10436continue;
10437}
10438}
10439
10440{
10441std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10442vinfos[0].jointtype = 1;
10443vinfos[0].foffset = j0;
10444vinfos[0].indices[0] = _ij0[0];
10445vinfos[0].indices[1] = _ij0[1];
10446vinfos[0].maxsolutions = _nj0;
10447vinfos[1].jointtype = 1;
10448vinfos[1].foffset = j1;
10449vinfos[1].indices[0] = _ij1[0];
10450vinfos[1].indices[1] = _ij1[1];
10451vinfos[1].maxsolutions = _nj1;
10452vinfos[2].jointtype = 1;
10453vinfos[2].foffset = j2;
10454vinfos[2].indices[0] = _ij2[0];
10455vinfos[2].indices[1] = _ij2[1];
10456vinfos[2].maxsolutions = _nj2;
10457vinfos[3].jointtype = 1;
10458vinfos[3].foffset = j3;
10459vinfos[3].indices[0] = _ij3[0];
10460vinfos[3].indices[1] = _ij3[1];
10461vinfos[3].maxsolutions = _nj3;
10462vinfos[4].jointtype = 1;
10463vinfos[4].foffset = j4;
10464vinfos[4].indices[0] = _ij4[0];
10465vinfos[4].indices[1] = _ij4[1];
10466vinfos[4].maxsolutions = _nj4;
10467vinfos[5].jointtype = 1;
10468vinfos[5].foffset = j5;
10469vinfos[5].indices[0] = _ij5[0];
10470vinfos[5].indices[1] = _ij5[1];
10471vinfos[5].maxsolutions = _nj5;
10472std::vector<int> vfree(0);
10473solutions.AddSolution(vinfos,vfree);
10474}
10475}
10476}
10477
10478}
10479
10480}
10481
10482}
10483} while(0);
10484if( bgotonextstatement )
10485{
10486bool bgotonextstatement = true;
10487do
10488{
10489evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
10490if( IKabs(evalcond[0]) < 0.0000050000000000 )
10491{
10492bgotonextstatement=false;
10493{
10494IkReal j0eval[1];
10495IkReal x733=((-1.0)*new_r11);
10496CheckValue<IkReal> x735 = IKatan2WithCheck(IkReal(0),IkReal(x733),IKFAST_ATAN2_MAGTHRESH);
10497if(!x735.valid){
10498continue;
10499}
10500IkReal x734=((-1.0)*(x735.value));
10501sj1=1.0;
10502cj1=0;
10503j1=1.5707963267949;
10504sj2=gconst23;
10505cj2=gconst24;
10506j2=x734;
10507new_r00=0;
10508new_r01=0;
10509new_r12=0;
10510new_r22=0;
10511IkReal gconst22=x734;
10512IkReal gconst23=0;
10513IkReal x736 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
10514if(IKabs(x736)==0){
10515continue;
10516}
10517IkReal gconst24=(x733*(pow(x736,-0.5)));
10518j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
10519if( IKabs(j0eval[0]) < 0.0000010000000000 )
10520{
10521{
10522IkReal j0eval[2];
10523IkReal x737=((-1.0)*new_r11);
10524CheckValue<IkReal> x739 = IKatan2WithCheck(IkReal(0),IkReal(x737),IKFAST_ATAN2_MAGTHRESH);
10525if(!x739.valid){
10526continue;
10527}
10528IkReal x738=((-1.0)*(x739.value));
10529sj1=1.0;
10530cj1=0;
10531j1=1.5707963267949;
10532sj2=gconst23;
10533cj2=gconst24;
10534j2=x738;
10535new_r00=0;
10536new_r01=0;
10537new_r12=0;
10538new_r22=0;
10539IkReal gconst22=x738;
10540IkReal gconst23=0;
10541IkReal x740 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
10542if(IKabs(x740)==0){
10543continue;
10544}
10545IkReal gconst24=(x737*(pow(x740,-0.5)));
10546j0eval[0]=new_r11;
10547j0eval[1]=new_r10;
10548if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
10549{
10550{
10551IkReal j0eval[1];
10552IkReal x741=((-1.0)*new_r11);
10553CheckValue<IkReal> x743 = IKatan2WithCheck(IkReal(0),IkReal(x741),IKFAST_ATAN2_MAGTHRESH);
10554if(!x743.valid){
10555continue;
10556}
10557IkReal x742=((-1.0)*(x743.value));
10558sj1=1.0;
10559cj1=0;
10560j1=1.5707963267949;
10561sj2=gconst23;
10562cj2=gconst24;
10563j2=x742;
10564new_r00=0;
10565new_r01=0;
10566new_r12=0;
10567new_r22=0;
10568IkReal gconst22=x742;
10569IkReal gconst23=0;
10570IkReal x744 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
10571if(IKabs(x744)==0){
10572continue;
10573}
10574IkReal gconst24=(x741*(pow(x744,-0.5)));
10575j0eval[0]=new_r11;
10576if( IKabs(j0eval[0]) < 0.0000010000000000 )
10577{
10578continue; // 3 cases reached
10579
10580} else
10581{
10582{
10583IkReal j0array[1], cj0array[1], sj0array[1];
10584bool j0valid[1]={false};
10585_nj0 = 1;
10586CheckValue<IkReal> x745=IKPowWithIntegerCheck(new_r11,-1);
10587if(!x745.valid){
10588continue;
10589}
10590CheckValue<IkReal> x746=IKPowWithIntegerCheck(gconst24,-1);
10591if(!x746.valid){
10592continue;
10593}
10594if( IKabs(((-1.0)*gconst24*(x745.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x746.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst24*(x745.value)))+IKsqr((new_r10*(x746.value)))-1) <= IKFAST_SINCOS_THRESH )
10595 continue;
10596j0array[0]=IKatan2(((-1.0)*gconst24*(x745.value)), (new_r10*(x746.value)));
10597sj0array[0]=IKsin(j0array[0]);
10598cj0array[0]=IKcos(j0array[0]);
10599if( j0array[0] > IKPI )
10600{
10601 j0array[0]-=IK2PI;
10602}
10603else if( j0array[0] < -IKPI )
10604{ j0array[0]+=IK2PI;
10605}
10606j0valid[0] = true;
10607for(int ij0 = 0; ij0 < 1; ++ij0)
10608{
10609if( !j0valid[ij0] )
10610{
10611 continue;
10612}
10613_ij0[0] = ij0; _ij0[1] = -1;
10614for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10615{
10616if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10617{
10618 j0valid[iij0]=false; _ij0[1] = iij0; break;
10619}
10620}
10621j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10622{
10623IkReal evalcond[8];
10624IkReal x747=IKsin(j0);
10625IkReal x748=IKcos(j0);
10626IkReal x749=(gconst24*x747);
10627IkReal x750=((1.0)*x748);
10628evalcond[0]=(new_r11*x748);
10629evalcond[1]=(new_r10*x747);
10630evalcond[2]=x749;
10631evalcond[3]=(gconst24*x748);
10632evalcond[4]=(gconst24+((new_r11*x747)));
10633evalcond[5]=(x749+new_r11);
10634evalcond[6]=(gconst24+(((-1.0)*new_r10*x750)));
10635evalcond[7]=((((-1.0)*gconst24*x750))+new_r10);
10636if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
10637{
10638continue;
10639}
10640}
10641
10642{
10643std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10644vinfos[0].jointtype = 1;
10645vinfos[0].foffset = j0;
10646vinfos[0].indices[0] = _ij0[0];
10647vinfos[0].indices[1] = _ij0[1];
10648vinfos[0].maxsolutions = _nj0;
10649vinfos[1].jointtype = 1;
10650vinfos[1].foffset = j1;
10651vinfos[1].indices[0] = _ij1[0];
10652vinfos[1].indices[1] = _ij1[1];
10653vinfos[1].maxsolutions = _nj1;
10654vinfos[2].jointtype = 1;
10655vinfos[2].foffset = j2;
10656vinfos[2].indices[0] = _ij2[0];
10657vinfos[2].indices[1] = _ij2[1];
10658vinfos[2].maxsolutions = _nj2;
10659vinfos[3].jointtype = 1;
10660vinfos[3].foffset = j3;
10661vinfos[3].indices[0] = _ij3[0];
10662vinfos[3].indices[1] = _ij3[1];
10663vinfos[3].maxsolutions = _nj3;
10664vinfos[4].jointtype = 1;
10665vinfos[4].foffset = j4;
10666vinfos[4].indices[0] = _ij4[0];
10667vinfos[4].indices[1] = _ij4[1];
10668vinfos[4].maxsolutions = _nj4;
10669vinfos[5].jointtype = 1;
10670vinfos[5].foffset = j5;
10671vinfos[5].indices[0] = _ij5[0];
10672vinfos[5].indices[1] = _ij5[1];
10673vinfos[5].maxsolutions = _nj5;
10674std::vector<int> vfree(0);
10675solutions.AddSolution(vinfos,vfree);
10676}
10677}
10678}
10679
10680}
10681
10682}
10683
10684} else
10685{
10686{
10687IkReal j0array[1], cj0array[1], sj0array[1];
10688bool j0valid[1]={false};
10689_nj0 = 1;
10690CheckValue<IkReal> x751=IKPowWithIntegerCheck(new_r11,-1);
10691if(!x751.valid){
10692continue;
10693}
10694CheckValue<IkReal> x752=IKPowWithIntegerCheck(new_r10,-1);
10695if(!x752.valid){
10696continue;
10697}
10698if( IKabs(((-1.0)*gconst24*(x751.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst24*(x752.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst24*(x751.value)))+IKsqr((gconst24*(x752.value)))-1) <= IKFAST_SINCOS_THRESH )
10699 continue;
10700j0array[0]=IKatan2(((-1.0)*gconst24*(x751.value)), (gconst24*(x752.value)));
10701sj0array[0]=IKsin(j0array[0]);
10702cj0array[0]=IKcos(j0array[0]);
10703if( j0array[0] > IKPI )
10704{
10705 j0array[0]-=IK2PI;
10706}
10707else if( j0array[0] < -IKPI )
10708{ j0array[0]+=IK2PI;
10709}
10710j0valid[0] = true;
10711for(int ij0 = 0; ij0 < 1; ++ij0)
10712{
10713if( !j0valid[ij0] )
10714{
10715 continue;
10716}
10717_ij0[0] = ij0; _ij0[1] = -1;
10718for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10719{
10720if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10721{
10722 j0valid[iij0]=false; _ij0[1] = iij0; break;
10723}
10724}
10725j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10726{
10727IkReal evalcond[8];
10728IkReal x753=IKsin(j0);
10729IkReal x754=IKcos(j0);
10730IkReal x755=(gconst24*x753);
10731IkReal x756=((1.0)*x754);
10732evalcond[0]=(new_r11*x754);
10733evalcond[1]=(new_r10*x753);
10734evalcond[2]=x755;
10735evalcond[3]=(gconst24*x754);
10736evalcond[4]=(gconst24+((new_r11*x753)));
10737evalcond[5]=(x755+new_r11);
10738evalcond[6]=(gconst24+(((-1.0)*new_r10*x756)));
10739evalcond[7]=((((-1.0)*gconst24*x756))+new_r10);
10740if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
10741{
10742continue;
10743}
10744}
10745
10746{
10747std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10748vinfos[0].jointtype = 1;
10749vinfos[0].foffset = j0;
10750vinfos[0].indices[0] = _ij0[0];
10751vinfos[0].indices[1] = _ij0[1];
10752vinfos[0].maxsolutions = _nj0;
10753vinfos[1].jointtype = 1;
10754vinfos[1].foffset = j1;
10755vinfos[1].indices[0] = _ij1[0];
10756vinfos[1].indices[1] = _ij1[1];
10757vinfos[1].maxsolutions = _nj1;
10758vinfos[2].jointtype = 1;
10759vinfos[2].foffset = j2;
10760vinfos[2].indices[0] = _ij2[0];
10761vinfos[2].indices[1] = _ij2[1];
10762vinfos[2].maxsolutions = _nj2;
10763vinfos[3].jointtype = 1;
10764vinfos[3].foffset = j3;
10765vinfos[3].indices[0] = _ij3[0];
10766vinfos[3].indices[1] = _ij3[1];
10767vinfos[3].maxsolutions = _nj3;
10768vinfos[4].jointtype = 1;
10769vinfos[4].foffset = j4;
10770vinfos[4].indices[0] = _ij4[0];
10771vinfos[4].indices[1] = _ij4[1];
10772vinfos[4].maxsolutions = _nj4;
10773vinfos[5].jointtype = 1;
10774vinfos[5].foffset = j5;
10775vinfos[5].indices[0] = _ij5[0];
10776vinfos[5].indices[1] = _ij5[1];
10777vinfos[5].maxsolutions = _nj5;
10778std::vector<int> vfree(0);
10779solutions.AddSolution(vinfos,vfree);
10780}
10781}
10782}
10783
10784}
10785
10786}
10787
10788} else
10789{
10790{
10791IkReal j0array[1], cj0array[1], sj0array[1];
10792bool j0valid[1]={false};
10793_nj0 = 1;
10794CheckValue<IkReal> x757=IKPowWithIntegerCheck(IKsign(gconst24),-1);
10795if(!x757.valid){
10796continue;
10797}
10798CheckValue<IkReal> x758 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
10799if(!x758.valid){
10800continue;
10801}
10802j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x757.value)))+(x758.value));
10803sj0array[0]=IKsin(j0array[0]);
10804cj0array[0]=IKcos(j0array[0]);
10805if( j0array[0] > IKPI )
10806{
10807 j0array[0]-=IK2PI;
10808}
10809else if( j0array[0] < -IKPI )
10810{ j0array[0]+=IK2PI;
10811}
10812j0valid[0] = true;
10813for(int ij0 = 0; ij0 < 1; ++ij0)
10814{
10815if( !j0valid[ij0] )
10816{
10817 continue;
10818}
10819_ij0[0] = ij0; _ij0[1] = -1;
10820for(int iij0 = ij0+1; iij0 < 1; ++iij0)
10821{
10822if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
10823{
10824 j0valid[iij0]=false; _ij0[1] = iij0; break;
10825}
10826}
10827j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
10828{
10829IkReal evalcond[8];
10830IkReal x759=IKsin(j0);
10831IkReal x760=IKcos(j0);
10832IkReal x761=(gconst24*x759);
10833IkReal x762=((1.0)*x760);
10834evalcond[0]=(new_r11*x760);
10835evalcond[1]=(new_r10*x759);
10836evalcond[2]=x761;
10837evalcond[3]=(gconst24*x760);
10838evalcond[4]=(gconst24+((new_r11*x759)));
10839evalcond[5]=(x761+new_r11);
10840evalcond[6]=(gconst24+(((-1.0)*new_r10*x762)));
10841evalcond[7]=((((-1.0)*gconst24*x762))+new_r10);
10842if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
10843{
10844continue;
10845}
10846}
10847
10848{
10849std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10850vinfos[0].jointtype = 1;
10851vinfos[0].foffset = j0;
10852vinfos[0].indices[0] = _ij0[0];
10853vinfos[0].indices[1] = _ij0[1];
10854vinfos[0].maxsolutions = _nj0;
10855vinfos[1].jointtype = 1;
10856vinfos[1].foffset = j1;
10857vinfos[1].indices[0] = _ij1[0];
10858vinfos[1].indices[1] = _ij1[1];
10859vinfos[1].maxsolutions = _nj1;
10860vinfos[2].jointtype = 1;
10861vinfos[2].foffset = j2;
10862vinfos[2].indices[0] = _ij2[0];
10863vinfos[2].indices[1] = _ij2[1];
10864vinfos[2].maxsolutions = _nj2;
10865vinfos[3].jointtype = 1;
10866vinfos[3].foffset = j3;
10867vinfos[3].indices[0] = _ij3[0];
10868vinfos[3].indices[1] = _ij3[1];
10869vinfos[3].maxsolutions = _nj3;
10870vinfos[4].jointtype = 1;
10871vinfos[4].foffset = j4;
10872vinfos[4].indices[0] = _ij4[0];
10873vinfos[4].indices[1] = _ij4[1];
10874vinfos[4].maxsolutions = _nj4;
10875vinfos[5].jointtype = 1;
10876vinfos[5].foffset = j5;
10877vinfos[5].indices[0] = _ij5[0];
10878vinfos[5].indices[1] = _ij5[1];
10879vinfos[5].maxsolutions = _nj5;
10880std::vector<int> vfree(0);
10881solutions.AddSolution(vinfos,vfree);
10882}
10883}
10884}
10885
10886}
10887
10888}
10889
10890}
10891} while(0);
10892if( bgotonextstatement )
10893{
10894bool bgotonextstatement = true;
10895do
10896{
10897evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
10898if( IKabs(evalcond[0]) < 0.0000050000000000 )
10899{
10900bgotonextstatement=false;
10901{
10902IkReal j0eval[1];
10903CheckValue<IkReal> x764 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
10904if(!x764.valid){
10905continue;
10906}
10907IkReal x763=((-1.0)*(x764.value));
10908sj1=1.0;
10909cj1=0;
10910j1=1.5707963267949;
10911sj2=gconst23;
10912cj2=gconst24;
10913j2=x763;
10914new_r11=0;
10915new_r10=0;
10916new_r22=0;
10917new_r02=0;
10918IkReal gconst22=x763;
10919IkReal x765 = new_r01*new_r01;
10920if(IKabs(x765)==0){
10921continue;
10922}
10923IkReal gconst23=((-1.0)*new_r01*(pow(x765,-0.5)));
10924IkReal gconst24=0;
10925j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
10926if( IKabs(j0eval[0]) < 0.0000010000000000 )
10927{
10928{
10929IkReal j0eval[2];
10930CheckValue<IkReal> x767 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
10931if(!x767.valid){
10932continue;
10933}
10934IkReal x766=((-1.0)*(x767.value));
10935sj1=1.0;
10936cj1=0;
10937j1=1.5707963267949;
10938sj2=gconst23;
10939cj2=gconst24;
10940j2=x766;
10941new_r11=0;
10942new_r10=0;
10943new_r22=0;
10944new_r02=0;
10945IkReal gconst22=x766;
10946IkReal x768 = new_r01*new_r01;
10947if(IKabs(x768)==0){
10948continue;
10949}
10950IkReal gconst23=((-1.0)*new_r01*(pow(x768,-0.5)));
10951IkReal gconst24=0;
10952j0eval[0]=new_r01;
10953j0eval[1]=new_r00;
10954if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
10955{
10956{
10957IkReal j0eval[1];
10958CheckValue<IkReal> x770 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
10959if(!x770.valid){
10960continue;
10961}
10962IkReal x769=((-1.0)*(x770.value));
10963sj1=1.0;
10964cj1=0;
10965j1=1.5707963267949;
10966sj2=gconst23;
10967cj2=gconst24;
10968j2=x769;
10969new_r11=0;
10970new_r10=0;
10971new_r22=0;
10972new_r02=0;
10973IkReal gconst22=x769;
10974IkReal x771 = new_r01*new_r01;
10975if(IKabs(x771)==0){
10976continue;
10977}
10978IkReal gconst23=((-1.0)*new_r01*(pow(x771,-0.5)));
10979IkReal gconst24=0;
10980j0eval[0]=new_r00;
10981if( IKabs(j0eval[0]) < 0.0000010000000000 )
10982{
10983continue; // 3 cases reached
10984
10985} else
10986{
10987{
10988IkReal j0array[1], cj0array[1], sj0array[1];
10989bool j0valid[1]={false};
10990_nj0 = 1;
10991CheckValue<IkReal> x772=IKPowWithIntegerCheck(gconst23,-1);
10992if(!x772.valid){
10993continue;
10994}
10995CheckValue<IkReal> x773=IKPowWithIntegerCheck(new_r00,-1);
10996if(!x773.valid){
10997continue;
10998}
10999if( IKabs((new_r01*(x772.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst23*(x773.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x772.value)))+IKsqr(((-1.0)*gconst23*(x773.value)))-1) <= IKFAST_SINCOS_THRESH )
11000 continue;
11001j0array[0]=IKatan2((new_r01*(x772.value)), ((-1.0)*gconst23*(x773.value)));
11002sj0array[0]=IKsin(j0array[0]);
11003cj0array[0]=IKcos(j0array[0]);
11004if( j0array[0] > IKPI )
11005{
11006 j0array[0]-=IK2PI;
11007}
11008else if( j0array[0] < -IKPI )
11009{ j0array[0]+=IK2PI;
11010}
11011j0valid[0] = true;
11012for(int ij0 = 0; ij0 < 1; ++ij0)
11013{
11014if( !j0valid[ij0] )
11015{
11016 continue;
11017}
11018_ij0[0] = ij0; _ij0[1] = -1;
11019for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11020{
11021if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11022{
11023 j0valid[iij0]=false; _ij0[1] = iij0; break;
11024}
11025}
11026j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11027{
11028IkReal evalcond[8];
11029IkReal x774=IKcos(j0);
11030IkReal x775=IKsin(j0);
11031IkReal x776=(gconst23*x774);
11032IkReal x777=(gconst23*x775);
11033evalcond[0]=(new_r00*x775);
11034evalcond[1]=(new_r01*x774);
11035evalcond[2]=x776;
11036evalcond[3]=x777;
11037evalcond[4]=(gconst23+((new_r00*x774)));
11038evalcond[5]=(x776+new_r00);
11039evalcond[6]=(gconst23+(((-1.0)*new_r01*x775)));
11040evalcond[7]=(new_r01+(((-1.0)*x777)));
11041if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11042{
11043continue;
11044}
11045}
11046
11047{
11048std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11049vinfos[0].jointtype = 1;
11050vinfos[0].foffset = j0;
11051vinfos[0].indices[0] = _ij0[0];
11052vinfos[0].indices[1] = _ij0[1];
11053vinfos[0].maxsolutions = _nj0;
11054vinfos[1].jointtype = 1;
11055vinfos[1].foffset = j1;
11056vinfos[1].indices[0] = _ij1[0];
11057vinfos[1].indices[1] = _ij1[1];
11058vinfos[1].maxsolutions = _nj1;
11059vinfos[2].jointtype = 1;
11060vinfos[2].foffset = j2;
11061vinfos[2].indices[0] = _ij2[0];
11062vinfos[2].indices[1] = _ij2[1];
11063vinfos[2].maxsolutions = _nj2;
11064vinfos[3].jointtype = 1;
11065vinfos[3].foffset = j3;
11066vinfos[3].indices[0] = _ij3[0];
11067vinfos[3].indices[1] = _ij3[1];
11068vinfos[3].maxsolutions = _nj3;
11069vinfos[4].jointtype = 1;
11070vinfos[4].foffset = j4;
11071vinfos[4].indices[0] = _ij4[0];
11072vinfos[4].indices[1] = _ij4[1];
11073vinfos[4].maxsolutions = _nj4;
11074vinfos[5].jointtype = 1;
11075vinfos[5].foffset = j5;
11076vinfos[5].indices[0] = _ij5[0];
11077vinfos[5].indices[1] = _ij5[1];
11078vinfos[5].maxsolutions = _nj5;
11079std::vector<int> vfree(0);
11080solutions.AddSolution(vinfos,vfree);
11081}
11082}
11083}
11084
11085}
11086
11087}
11088
11089} else
11090{
11091{
11092IkReal j0array[1], cj0array[1], sj0array[1];
11093bool j0valid[1]={false};
11094_nj0 = 1;
11095CheckValue<IkReal> x778=IKPowWithIntegerCheck(new_r01,-1);
11096if(!x778.valid){
11097continue;
11098}
11099CheckValue<IkReal> x779=IKPowWithIntegerCheck(new_r00,-1);
11100if(!x779.valid){
11101continue;
11102}
11103if( IKabs((gconst23*(x778.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst23*(x779.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst23*(x778.value)))+IKsqr(((-1.0)*gconst23*(x779.value)))-1) <= IKFAST_SINCOS_THRESH )
11104 continue;
11105j0array[0]=IKatan2((gconst23*(x778.value)), ((-1.0)*gconst23*(x779.value)));
11106sj0array[0]=IKsin(j0array[0]);
11107cj0array[0]=IKcos(j0array[0]);
11108if( j0array[0] > IKPI )
11109{
11110 j0array[0]-=IK2PI;
11111}
11112else if( j0array[0] < -IKPI )
11113{ j0array[0]+=IK2PI;
11114}
11115j0valid[0] = true;
11116for(int ij0 = 0; ij0 < 1; ++ij0)
11117{
11118if( !j0valid[ij0] )
11119{
11120 continue;
11121}
11122_ij0[0] = ij0; _ij0[1] = -1;
11123for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11124{
11125if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11126{
11127 j0valid[iij0]=false; _ij0[1] = iij0; break;
11128}
11129}
11130j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11131{
11132IkReal evalcond[8];
11133IkReal x780=IKcos(j0);
11134IkReal x781=IKsin(j0);
11135IkReal x782=(gconst23*x780);
11136IkReal x783=(gconst23*x781);
11137evalcond[0]=(new_r00*x781);
11138evalcond[1]=(new_r01*x780);
11139evalcond[2]=x782;
11140evalcond[3]=x783;
11141evalcond[4]=(gconst23+((new_r00*x780)));
11142evalcond[5]=(x782+new_r00);
11143evalcond[6]=(gconst23+(((-1.0)*new_r01*x781)));
11144evalcond[7]=((((-1.0)*x783))+new_r01);
11145if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11146{
11147continue;
11148}
11149}
11150
11151{
11152std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11153vinfos[0].jointtype = 1;
11154vinfos[0].foffset = j0;
11155vinfos[0].indices[0] = _ij0[0];
11156vinfos[0].indices[1] = _ij0[1];
11157vinfos[0].maxsolutions = _nj0;
11158vinfos[1].jointtype = 1;
11159vinfos[1].foffset = j1;
11160vinfos[1].indices[0] = _ij1[0];
11161vinfos[1].indices[1] = _ij1[1];
11162vinfos[1].maxsolutions = _nj1;
11163vinfos[2].jointtype = 1;
11164vinfos[2].foffset = j2;
11165vinfos[2].indices[0] = _ij2[0];
11166vinfos[2].indices[1] = _ij2[1];
11167vinfos[2].maxsolutions = _nj2;
11168vinfos[3].jointtype = 1;
11169vinfos[3].foffset = j3;
11170vinfos[3].indices[0] = _ij3[0];
11171vinfos[3].indices[1] = _ij3[1];
11172vinfos[3].maxsolutions = _nj3;
11173vinfos[4].jointtype = 1;
11174vinfos[4].foffset = j4;
11175vinfos[4].indices[0] = _ij4[0];
11176vinfos[4].indices[1] = _ij4[1];
11177vinfos[4].maxsolutions = _nj4;
11178vinfos[5].jointtype = 1;
11179vinfos[5].foffset = j5;
11180vinfos[5].indices[0] = _ij5[0];
11181vinfos[5].indices[1] = _ij5[1];
11182vinfos[5].maxsolutions = _nj5;
11183std::vector<int> vfree(0);
11184solutions.AddSolution(vinfos,vfree);
11185}
11186}
11187}
11188
11189}
11190
11191}
11192
11193} else
11194{
11195{
11196IkReal j0array[1], cj0array[1], sj0array[1];
11197bool j0valid[1]={false};
11198_nj0 = 1;
11199CheckValue<IkReal> x784 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
11200if(!x784.valid){
11201continue;
11202}
11203CheckValue<IkReal> x785=IKPowWithIntegerCheck(IKsign(gconst23),-1);
11204if(!x785.valid){
11205continue;
11206}
11207j0array[0]=((-1.5707963267949)+(x784.value)+(((1.5707963267949)*(x785.value))));
11208sj0array[0]=IKsin(j0array[0]);
11209cj0array[0]=IKcos(j0array[0]);
11210if( j0array[0] > IKPI )
11211{
11212 j0array[0]-=IK2PI;
11213}
11214else if( j0array[0] < -IKPI )
11215{ j0array[0]+=IK2PI;
11216}
11217j0valid[0] = true;
11218for(int ij0 = 0; ij0 < 1; ++ij0)
11219{
11220if( !j0valid[ij0] )
11221{
11222 continue;
11223}
11224_ij0[0] = ij0; _ij0[1] = -1;
11225for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11226{
11227if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11228{
11229 j0valid[iij0]=false; _ij0[1] = iij0; break;
11230}
11231}
11232j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11233{
11234IkReal evalcond[8];
11235IkReal x786=IKcos(j0);
11236IkReal x787=IKsin(j0);
11237IkReal x788=(gconst23*x786);
11238IkReal x789=(gconst23*x787);
11239evalcond[0]=(new_r00*x787);
11240evalcond[1]=(new_r01*x786);
11241evalcond[2]=x788;
11242evalcond[3]=x789;
11243evalcond[4]=(gconst23+((new_r00*x786)));
11244evalcond[5]=(x788+new_r00);
11245evalcond[6]=(gconst23+(((-1.0)*new_r01*x787)));
11246evalcond[7]=((((-1.0)*x789))+new_r01);
11247if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11248{
11249continue;
11250}
11251}
11252
11253{
11254std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11255vinfos[0].jointtype = 1;
11256vinfos[0].foffset = j0;
11257vinfos[0].indices[0] = _ij0[0];
11258vinfos[0].indices[1] = _ij0[1];
11259vinfos[0].maxsolutions = _nj0;
11260vinfos[1].jointtype = 1;
11261vinfos[1].foffset = j1;
11262vinfos[1].indices[0] = _ij1[0];
11263vinfos[1].indices[1] = _ij1[1];
11264vinfos[1].maxsolutions = _nj1;
11265vinfos[2].jointtype = 1;
11266vinfos[2].foffset = j2;
11267vinfos[2].indices[0] = _ij2[0];
11268vinfos[2].indices[1] = _ij2[1];
11269vinfos[2].maxsolutions = _nj2;
11270vinfos[3].jointtype = 1;
11271vinfos[3].foffset = j3;
11272vinfos[3].indices[0] = _ij3[0];
11273vinfos[3].indices[1] = _ij3[1];
11274vinfos[3].maxsolutions = _nj3;
11275vinfos[4].jointtype = 1;
11276vinfos[4].foffset = j4;
11277vinfos[4].indices[0] = _ij4[0];
11278vinfos[4].indices[1] = _ij4[1];
11279vinfos[4].maxsolutions = _nj4;
11280vinfos[5].jointtype = 1;
11281vinfos[5].foffset = j5;
11282vinfos[5].indices[0] = _ij5[0];
11283vinfos[5].indices[1] = _ij5[1];
11284vinfos[5].maxsolutions = _nj5;
11285std::vector<int> vfree(0);
11286solutions.AddSolution(vinfos,vfree);
11287}
11288}
11289}
11290
11291}
11292
11293}
11294
11295}
11296} while(0);
11297if( bgotonextstatement )
11298{
11299bool bgotonextstatement = true;
11300do
11301{
11302if( 1 )
11303{
11304bgotonextstatement=false;
11305continue; // branch miss [j0]
11306
11307}
11308} while(0);
11309if( bgotonextstatement )
11310{
11311}
11312}
11313}
11314}
11315}
11316
11317} else
11318{
11319{
11320IkReal j0array[1], cj0array[1], sj0array[1];
11321bool j0valid[1]={false};
11322_nj0 = 1;
11323IkReal x790=((1.0)*new_r00);
11324CheckValue<IkReal> x791=IKPowWithIntegerCheck(IKsign((((gconst23*new_r10))+(((-1.0)*gconst24*x790)))),-1);
11325if(!x791.valid){
11326continue;
11327}
11328CheckValue<IkReal> x792 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst23*gconst23)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x790))+((gconst23*gconst24)))),IKFAST_ATAN2_MAGTHRESH);
11329if(!x792.valid){
11330continue;
11331}
11332j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x791.value)))+(x792.value));
11333sj0array[0]=IKsin(j0array[0]);
11334cj0array[0]=IKcos(j0array[0]);
11335if( j0array[0] > IKPI )
11336{
11337 j0array[0]-=IK2PI;
11338}
11339else if( j0array[0] < -IKPI )
11340{ j0array[0]+=IK2PI;
11341}
11342j0valid[0] = true;
11343for(int ij0 = 0; ij0 < 1; ++ij0)
11344{
11345if( !j0valid[ij0] )
11346{
11347 continue;
11348}
11349_ij0[0] = ij0; _ij0[1] = -1;
11350for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11351{
11352if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11353{
11354 j0valid[iij0]=false; _ij0[1] = iij0; break;
11355}
11356}
11357j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11358{
11359IkReal evalcond[8];
11360IkReal x793=IKsin(j0);
11361IkReal x794=IKcos(j0);
11362IkReal x795=(gconst23*x794);
11363IkReal x796=(gconst24*x793);
11364IkReal x797=((1.0)*x794);
11365IkReal x798=((1.0)*x793);
11366IkReal x799=(x795+x796);
11367evalcond[0]=(((new_r10*x793))+gconst23+((new_r00*x794)));
11368evalcond[1]=(((new_r11*x793))+gconst24+((new_r01*x794)));
11369evalcond[2]=(x799+new_r00);
11370evalcond[3]=(x799+new_r11);
11371evalcond[4]=((((-1.0)*new_r01*x798))+((new_r11*x794))+gconst23);
11372evalcond[5]=(gconst24+(((-1.0)*new_r10*x797))+((new_r00*x793)));
11373evalcond[6]=((((-1.0)*gconst23*x798))+((gconst24*x794))+new_r01);
11374evalcond[7]=((((-1.0)*gconst24*x797))+((gconst23*x793))+new_r10);
11375if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11376{
11377continue;
11378}
11379}
11380
11381{
11382std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11383vinfos[0].jointtype = 1;
11384vinfos[0].foffset = j0;
11385vinfos[0].indices[0] = _ij0[0];
11386vinfos[0].indices[1] = _ij0[1];
11387vinfos[0].maxsolutions = _nj0;
11388vinfos[1].jointtype = 1;
11389vinfos[1].foffset = j1;
11390vinfos[1].indices[0] = _ij1[0];
11391vinfos[1].indices[1] = _ij1[1];
11392vinfos[1].maxsolutions = _nj1;
11393vinfos[2].jointtype = 1;
11394vinfos[2].foffset = j2;
11395vinfos[2].indices[0] = _ij2[0];
11396vinfos[2].indices[1] = _ij2[1];
11397vinfos[2].maxsolutions = _nj2;
11398vinfos[3].jointtype = 1;
11399vinfos[3].foffset = j3;
11400vinfos[3].indices[0] = _ij3[0];
11401vinfos[3].indices[1] = _ij3[1];
11402vinfos[3].maxsolutions = _nj3;
11403vinfos[4].jointtype = 1;
11404vinfos[4].foffset = j4;
11405vinfos[4].indices[0] = _ij4[0];
11406vinfos[4].indices[1] = _ij4[1];
11407vinfos[4].maxsolutions = _nj4;
11408vinfos[5].jointtype = 1;
11409vinfos[5].foffset = j5;
11410vinfos[5].indices[0] = _ij5[0];
11411vinfos[5].indices[1] = _ij5[1];
11412vinfos[5].maxsolutions = _nj5;
11413std::vector<int> vfree(0);
11414solutions.AddSolution(vinfos,vfree);
11415}
11416}
11417}
11418
11419}
11420
11421}
11422
11423} else
11424{
11425{
11426IkReal j0array[1], cj0array[1], sj0array[1];
11427bool j0valid[1]={false};
11428_nj0 = 1;
11429IkReal x800=((1.0)*gconst23);
11430CheckValue<IkReal> x801 = IKatan2WithCheck(IkReal((((gconst23*new_r00))+(((-1.0)*new_r11*x800)))),IkReal(((((-1.0)*new_r01*x800))+(((-1.0)*new_r10*x800)))),IKFAST_ATAN2_MAGTHRESH);
11431if(!x801.valid){
11432continue;
11433}
11434CheckValue<IkReal> x802=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
11435if(!x802.valid){
11436continue;
11437}
11438j0array[0]=((-1.5707963267949)+(x801.value)+(((1.5707963267949)*(x802.value))));
11439sj0array[0]=IKsin(j0array[0]);
11440cj0array[0]=IKcos(j0array[0]);
11441if( j0array[0] > IKPI )
11442{
11443 j0array[0]-=IK2PI;
11444}
11445else if( j0array[0] < -IKPI )
11446{ j0array[0]+=IK2PI;
11447}
11448j0valid[0] = true;
11449for(int ij0 = 0; ij0 < 1; ++ij0)
11450{
11451if( !j0valid[ij0] )
11452{
11453 continue;
11454}
11455_ij0[0] = ij0; _ij0[1] = -1;
11456for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11457{
11458if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11459{
11460 j0valid[iij0]=false; _ij0[1] = iij0; break;
11461}
11462}
11463j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11464{
11465IkReal evalcond[8];
11466IkReal x803=IKsin(j0);
11467IkReal x804=IKcos(j0);
11468IkReal x805=(gconst23*x804);
11469IkReal x806=(gconst24*x803);
11470IkReal x807=((1.0)*x804);
11471IkReal x808=((1.0)*x803);
11472IkReal x809=(x805+x806);
11473evalcond[0]=(gconst23+((new_r00*x804))+((new_r10*x803)));
11474evalcond[1]=(gconst24+((new_r11*x803))+((new_r01*x804)));
11475evalcond[2]=(new_r00+x809);
11476evalcond[3]=(new_r11+x809);
11477evalcond[4]=((((-1.0)*new_r01*x808))+gconst23+((new_r11*x804)));
11478evalcond[5]=(gconst24+((new_r00*x803))+(((-1.0)*new_r10*x807)));
11479evalcond[6]=(new_r01+(((-1.0)*gconst23*x808))+((gconst24*x804)));
11480evalcond[7]=((((-1.0)*gconst24*x807))+((gconst23*x803))+new_r10);
11481if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11482{
11483continue;
11484}
11485}
11486
11487{
11488std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11489vinfos[0].jointtype = 1;
11490vinfos[0].foffset = j0;
11491vinfos[0].indices[0] = _ij0[0];
11492vinfos[0].indices[1] = _ij0[1];
11493vinfos[0].maxsolutions = _nj0;
11494vinfos[1].jointtype = 1;
11495vinfos[1].foffset = j1;
11496vinfos[1].indices[0] = _ij1[0];
11497vinfos[1].indices[1] = _ij1[1];
11498vinfos[1].maxsolutions = _nj1;
11499vinfos[2].jointtype = 1;
11500vinfos[2].foffset = j2;
11501vinfos[2].indices[0] = _ij2[0];
11502vinfos[2].indices[1] = _ij2[1];
11503vinfos[2].maxsolutions = _nj2;
11504vinfos[3].jointtype = 1;
11505vinfos[3].foffset = j3;
11506vinfos[3].indices[0] = _ij3[0];
11507vinfos[3].indices[1] = _ij3[1];
11508vinfos[3].maxsolutions = _nj3;
11509vinfos[4].jointtype = 1;
11510vinfos[4].foffset = j4;
11511vinfos[4].indices[0] = _ij4[0];
11512vinfos[4].indices[1] = _ij4[1];
11513vinfos[4].maxsolutions = _nj4;
11514vinfos[5].jointtype = 1;
11515vinfos[5].foffset = j5;
11516vinfos[5].indices[0] = _ij5[0];
11517vinfos[5].indices[1] = _ij5[1];
11518vinfos[5].maxsolutions = _nj5;
11519std::vector<int> vfree(0);
11520solutions.AddSolution(vinfos,vfree);
11521}
11522}
11523}
11524
11525}
11526
11527}
11528
11529} else
11530{
11531{
11532IkReal j0array[1], cj0array[1], sj0array[1];
11533bool j0valid[1]={false};
11534_nj0 = 1;
11535CheckValue<IkReal> x810 = IKatan2WithCheck(IkReal((((gconst23*new_r01))+(((-1.0)*gconst24*new_r00)))),IkReal(((((-1.0)*gconst23*new_r11))+((gconst24*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
11536if(!x810.valid){
11537continue;
11538}
11539CheckValue<IkReal> x811=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1);
11540if(!x811.valid){
11541continue;
11542}
11543j0array[0]=((-1.5707963267949)+(x810.value)+(((1.5707963267949)*(x811.value))));
11544sj0array[0]=IKsin(j0array[0]);
11545cj0array[0]=IKcos(j0array[0]);
11546if( j0array[0] > IKPI )
11547{
11548 j0array[0]-=IK2PI;
11549}
11550else if( j0array[0] < -IKPI )
11551{ j0array[0]+=IK2PI;
11552}
11553j0valid[0] = true;
11554for(int ij0 = 0; ij0 < 1; ++ij0)
11555{
11556if( !j0valid[ij0] )
11557{
11558 continue;
11559}
11560_ij0[0] = ij0; _ij0[1] = -1;
11561for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11562{
11563if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11564{
11565 j0valid[iij0]=false; _ij0[1] = iij0; break;
11566}
11567}
11568j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11569{
11570IkReal evalcond[8];
11571IkReal x812=IKsin(j0);
11572IkReal x813=IKcos(j0);
11573IkReal x814=(gconst23*x813);
11574IkReal x815=(gconst24*x812);
11575IkReal x816=((1.0)*x813);
11576IkReal x817=((1.0)*x812);
11577IkReal x818=(x814+x815);
11578evalcond[0]=(((new_r00*x813))+((new_r10*x812))+gconst23);
11579evalcond[1]=(((new_r11*x812))+((new_r01*x813))+gconst24);
11580evalcond[2]=(new_r00+x818);
11581evalcond[3]=(new_r11+x818);
11582evalcond[4]=(((new_r11*x813))+gconst23+(((-1.0)*new_r01*x817)));
11583evalcond[5]=(((new_r00*x812))+gconst24+(((-1.0)*new_r10*x816)));
11584evalcond[6]=((((-1.0)*gconst23*x817))+((gconst24*x813))+new_r01);
11585evalcond[7]=(((gconst23*x812))+(((-1.0)*gconst24*x816))+new_r10);
11586if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11587{
11588continue;
11589}
11590}
11591
11592{
11593std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11594vinfos[0].jointtype = 1;
11595vinfos[0].foffset = j0;
11596vinfos[0].indices[0] = _ij0[0];
11597vinfos[0].indices[1] = _ij0[1];
11598vinfos[0].maxsolutions = _nj0;
11599vinfos[1].jointtype = 1;
11600vinfos[1].foffset = j1;
11601vinfos[1].indices[0] = _ij1[0];
11602vinfos[1].indices[1] = _ij1[1];
11603vinfos[1].maxsolutions = _nj1;
11604vinfos[2].jointtype = 1;
11605vinfos[2].foffset = j2;
11606vinfos[2].indices[0] = _ij2[0];
11607vinfos[2].indices[1] = _ij2[1];
11608vinfos[2].maxsolutions = _nj2;
11609vinfos[3].jointtype = 1;
11610vinfos[3].foffset = j3;
11611vinfos[3].indices[0] = _ij3[0];
11612vinfos[3].indices[1] = _ij3[1];
11613vinfos[3].maxsolutions = _nj3;
11614vinfos[4].jointtype = 1;
11615vinfos[4].foffset = j4;
11616vinfos[4].indices[0] = _ij4[0];
11617vinfos[4].indices[1] = _ij4[1];
11618vinfos[4].maxsolutions = _nj4;
11619vinfos[5].jointtype = 1;
11620vinfos[5].foffset = j5;
11621vinfos[5].indices[0] = _ij5[0];
11622vinfos[5].indices[1] = _ij5[1];
11623vinfos[5].maxsolutions = _nj5;
11624std::vector<int> vfree(0);
11625solutions.AddSolution(vinfos,vfree);
11626}
11627}
11628}
11629
11630}
11631
11632}
11633
11634}
11635} while(0);
11636if( bgotonextstatement )
11637{
11638bool bgotonextstatement = true;
11639do
11640{
11641IkReal x821 = ((new_r01*new_r01)+(new_r11*new_r11));
11642if(IKabs(x821)==0){
11643continue;
11644}
11645IkReal x819=pow(x821,-0.5);
11646IkReal x820=((1.0)*x819);
11647CheckValue<IkReal> x822 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
11648if(!x822.valid){
11649continue;
11650}
11651IkReal gconst25=((3.14159265358979)+(((-1.0)*(x822.value))));
11652IkReal gconst26=(new_r01*x820);
11653IkReal gconst27=(new_r11*x820);
11654CheckValue<IkReal> x823 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
11655if(!x823.valid){
11656continue;
11657}
11658evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x823.value)+j2)))), 6.28318530717959)));
11659if( IKabs(evalcond[0]) < 0.0000050000000000 )
11660{
11661bgotonextstatement=false;
11662{
11663IkReal j0eval[3];
11664CheckValue<IkReal> x827 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
11665if(!x827.valid){
11666continue;
11667}
11668IkReal x824=((1.0)*(x827.value));
11669IkReal x825=x819;
11670IkReal x826=((1.0)*x825);
11671sj1=1.0;
11672cj1=0;
11673j1=1.5707963267949;
11674sj2=gconst26;
11675cj2=gconst27;
11676j2=((3.14159265)+(((-1.0)*x824)));
11677IkReal gconst25=((3.14159265358979)+(((-1.0)*x824)));
11678IkReal gconst26=(new_r01*x826);
11679IkReal gconst27=(new_r11*x826);
11680IkReal x828=new_r01*new_r01;
11681IkReal x829=((1.0)*new_r01);
11682IkReal x830=((((-1.0)*new_r10*x829))+((new_r00*new_r11)));
11683IkReal x831=x819;
11684IkReal x832=(new_r11*x831);
11685j0eval[0]=x830;
11686j0eval[1]=((IKabs(((((-1.0)*new_r00*x832))+((x828*x831)))))+(IKabs(((((-1.0)*x829*x832))+((new_r10*x832))))));
11687j0eval[2]=IKsign(x830);
11688if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
11689{
11690{
11691IkReal j0eval[3];
11692CheckValue<IkReal> x836 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
11693if(!x836.valid){
11694continue;
11695}
11696IkReal x833=((1.0)*(x836.value));
11697IkReal x834=x819;
11698IkReal x835=((1.0)*x834);
11699sj1=1.0;
11700cj1=0;
11701j1=1.5707963267949;
11702sj2=gconst26;
11703cj2=gconst27;
11704j2=((3.14159265)+(((-1.0)*x833)));
11705IkReal gconst25=((3.14159265358979)+(((-1.0)*x833)));
11706IkReal gconst26=(new_r01*x835);
11707IkReal gconst27=(new_r11*x835);
11708IkReal x837=new_r01*new_r01;
11709IkReal x838=(new_r00*new_r01);
11710IkReal x839=(((new_r10*new_r11))+x838);
11711IkReal x840=x819;
11712IkReal x841=((1.0)*new_r01*x840);
11713j0eval[0]=x839;
11714j0eval[1]=((IKabs((((x838*x840))+(((-1.0)*new_r11*x841)))))+(IKabs(((((-1.0)*new_r10*x841))+(((-1.0)*x837*x840))))));
11715j0eval[2]=IKsign(x839);
11716if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
11717{
11718{
11719IkReal j0array[1], cj0array[1], sj0array[1];
11720bool j0valid[1]={false};
11721_nj0 = 1;
11722IkReal x842=((1.0)*new_r00);
11723CheckValue<IkReal> x843 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst26*gconst26)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x842))+((gconst26*gconst27)))),IKFAST_ATAN2_MAGTHRESH);
11724if(!x843.valid){
11725continue;
11726}
11727CheckValue<IkReal> x844=IKPowWithIntegerCheck(IKsign((((gconst26*new_r10))+(((-1.0)*gconst27*x842)))),-1);
11728if(!x844.valid){
11729continue;
11730}
11731j0array[0]=((-1.5707963267949)+(x843.value)+(((1.5707963267949)*(x844.value))));
11732sj0array[0]=IKsin(j0array[0]);
11733cj0array[0]=IKcos(j0array[0]);
11734if( j0array[0] > IKPI )
11735{
11736 j0array[0]-=IK2PI;
11737}
11738else if( j0array[0] < -IKPI )
11739{ j0array[0]+=IK2PI;
11740}
11741j0valid[0] = true;
11742for(int ij0 = 0; ij0 < 1; ++ij0)
11743{
11744if( !j0valid[ij0] )
11745{
11746 continue;
11747}
11748_ij0[0] = ij0; _ij0[1] = -1;
11749for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11750{
11751if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11752{
11753 j0valid[iij0]=false; _ij0[1] = iij0; break;
11754}
11755}
11756j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11757{
11758IkReal evalcond[8];
11759IkReal x845=IKsin(j0);
11760IkReal x846=IKcos(j0);
11761IkReal x847=(gconst26*x846);
11762IkReal x848=(gconst27*x845);
11763IkReal x849=(gconst27*x846);
11764IkReal x850=(gconst26*x845);
11765IkReal x851=(x847+x848);
11766evalcond[0]=(((new_r10*x845))+((new_r00*x846))+gconst26);
11767evalcond[1]=(gconst27+((new_r01*x846))+((new_r11*x845)));
11768evalcond[2]=(new_r00+x851);
11769evalcond[3]=(new_r11+x851);
11770evalcond[4]=((((-1.0)*new_r01*x845))+gconst26+((new_r11*x846)));
11771evalcond[5]=(((new_r00*x845))+gconst27+(((-1.0)*new_r10*x846)));
11772evalcond[6]=((((-1.0)*x850))+new_r01+x849);
11773evalcond[7]=((((-1.0)*x849))+new_r10+x850);
11774if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11775{
11776continue;
11777}
11778}
11779
11780{
11781std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11782vinfos[0].jointtype = 1;
11783vinfos[0].foffset = j0;
11784vinfos[0].indices[0] = _ij0[0];
11785vinfos[0].indices[1] = _ij0[1];
11786vinfos[0].maxsolutions = _nj0;
11787vinfos[1].jointtype = 1;
11788vinfos[1].foffset = j1;
11789vinfos[1].indices[0] = _ij1[0];
11790vinfos[1].indices[1] = _ij1[1];
11791vinfos[1].maxsolutions = _nj1;
11792vinfos[2].jointtype = 1;
11793vinfos[2].foffset = j2;
11794vinfos[2].indices[0] = _ij2[0];
11795vinfos[2].indices[1] = _ij2[1];
11796vinfos[2].maxsolutions = _nj2;
11797vinfos[3].jointtype = 1;
11798vinfos[3].foffset = j3;
11799vinfos[3].indices[0] = _ij3[0];
11800vinfos[3].indices[1] = _ij3[1];
11801vinfos[3].maxsolutions = _nj3;
11802vinfos[4].jointtype = 1;
11803vinfos[4].foffset = j4;
11804vinfos[4].indices[0] = _ij4[0];
11805vinfos[4].indices[1] = _ij4[1];
11806vinfos[4].maxsolutions = _nj4;
11807vinfos[5].jointtype = 1;
11808vinfos[5].foffset = j5;
11809vinfos[5].indices[0] = _ij5[0];
11810vinfos[5].indices[1] = _ij5[1];
11811vinfos[5].maxsolutions = _nj5;
11812std::vector<int> vfree(0);
11813solutions.AddSolution(vinfos,vfree);
11814}
11815}
11816}
11817
11818} else
11819{
11820{
11821IkReal j0array[1], cj0array[1], sj0array[1];
11822bool j0valid[1]={false};
11823_nj0 = 1;
11824IkReal x852=((1.0)*gconst26);
11825CheckValue<IkReal> x853 = IKatan2WithCheck(IkReal((((gconst26*new_r00))+(((-1.0)*new_r11*x852)))),IkReal(((((-1.0)*new_r01*x852))+(((-1.0)*new_r10*x852)))),IKFAST_ATAN2_MAGTHRESH);
11826if(!x853.valid){
11827continue;
11828}
11829CheckValue<IkReal> x854=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
11830if(!x854.valid){
11831continue;
11832}
11833j0array[0]=((-1.5707963267949)+(x853.value)+(((1.5707963267949)*(x854.value))));
11834sj0array[0]=IKsin(j0array[0]);
11835cj0array[0]=IKcos(j0array[0]);
11836if( j0array[0] > IKPI )
11837{
11838 j0array[0]-=IK2PI;
11839}
11840else if( j0array[0] < -IKPI )
11841{ j0array[0]+=IK2PI;
11842}
11843j0valid[0] = true;
11844for(int ij0 = 0; ij0 < 1; ++ij0)
11845{
11846if( !j0valid[ij0] )
11847{
11848 continue;
11849}
11850_ij0[0] = ij0; _ij0[1] = -1;
11851for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11852{
11853if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11854{
11855 j0valid[iij0]=false; _ij0[1] = iij0; break;
11856}
11857}
11858j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11859{
11860IkReal evalcond[8];
11861IkReal x855=IKsin(j0);
11862IkReal x856=IKcos(j0);
11863IkReal x857=(gconst26*x856);
11864IkReal x858=(gconst27*x855);
11865IkReal x859=(gconst27*x856);
11866IkReal x860=(gconst26*x855);
11867IkReal x861=(x857+x858);
11868evalcond[0]=(gconst26+((new_r10*x855))+((new_r00*x856)));
11869evalcond[1]=(gconst27+((new_r11*x855))+((new_r01*x856)));
11870evalcond[2]=(new_r00+x861);
11871evalcond[3]=(new_r11+x861);
11872evalcond[4]=(gconst26+((new_r11*x856))+(((-1.0)*new_r01*x855)));
11873evalcond[5]=(gconst27+(((-1.0)*new_r10*x856))+((new_r00*x855)));
11874evalcond[6]=((((-1.0)*x860))+new_r01+x859);
11875evalcond[7]=((((-1.0)*x859))+new_r10+x860);
11876if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11877{
11878continue;
11879}
11880}
11881
11882{
11883std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11884vinfos[0].jointtype = 1;
11885vinfos[0].foffset = j0;
11886vinfos[0].indices[0] = _ij0[0];
11887vinfos[0].indices[1] = _ij0[1];
11888vinfos[0].maxsolutions = _nj0;
11889vinfos[1].jointtype = 1;
11890vinfos[1].foffset = j1;
11891vinfos[1].indices[0] = _ij1[0];
11892vinfos[1].indices[1] = _ij1[1];
11893vinfos[1].maxsolutions = _nj1;
11894vinfos[2].jointtype = 1;
11895vinfos[2].foffset = j2;
11896vinfos[2].indices[0] = _ij2[0];
11897vinfos[2].indices[1] = _ij2[1];
11898vinfos[2].maxsolutions = _nj2;
11899vinfos[3].jointtype = 1;
11900vinfos[3].foffset = j3;
11901vinfos[3].indices[0] = _ij3[0];
11902vinfos[3].indices[1] = _ij3[1];
11903vinfos[3].maxsolutions = _nj3;
11904vinfos[4].jointtype = 1;
11905vinfos[4].foffset = j4;
11906vinfos[4].indices[0] = _ij4[0];
11907vinfos[4].indices[1] = _ij4[1];
11908vinfos[4].maxsolutions = _nj4;
11909vinfos[5].jointtype = 1;
11910vinfos[5].foffset = j5;
11911vinfos[5].indices[0] = _ij5[0];
11912vinfos[5].indices[1] = _ij5[1];
11913vinfos[5].maxsolutions = _nj5;
11914std::vector<int> vfree(0);
11915solutions.AddSolution(vinfos,vfree);
11916}
11917}
11918}
11919
11920}
11921
11922}
11923
11924} else
11925{
11926{
11927IkReal j0array[1], cj0array[1], sj0array[1];
11928bool j0valid[1]={false};
11929_nj0 = 1;
11930CheckValue<IkReal> x862=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1);
11931if(!x862.valid){
11932continue;
11933}
11934CheckValue<IkReal> x863 = IKatan2WithCheck(IkReal((((gconst26*new_r01))+(((-1.0)*gconst27*new_r00)))),IkReal(((((-1.0)*gconst26*new_r11))+((gconst27*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
11935if(!x863.valid){
11936continue;
11937}
11938j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x862.value)))+(x863.value));
11939sj0array[0]=IKsin(j0array[0]);
11940cj0array[0]=IKcos(j0array[0]);
11941if( j0array[0] > IKPI )
11942{
11943 j0array[0]-=IK2PI;
11944}
11945else if( j0array[0] < -IKPI )
11946{ j0array[0]+=IK2PI;
11947}
11948j0valid[0] = true;
11949for(int ij0 = 0; ij0 < 1; ++ij0)
11950{
11951if( !j0valid[ij0] )
11952{
11953 continue;
11954}
11955_ij0[0] = ij0; _ij0[1] = -1;
11956for(int iij0 = ij0+1; iij0 < 1; ++iij0)
11957{
11958if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
11959{
11960 j0valid[iij0]=false; _ij0[1] = iij0; break;
11961}
11962}
11963j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
11964{
11965IkReal evalcond[8];
11966IkReal x864=IKsin(j0);
11967IkReal x865=IKcos(j0);
11968IkReal x866=(gconst26*x865);
11969IkReal x867=(gconst27*x864);
11970IkReal x868=(gconst27*x865);
11971IkReal x869=(gconst26*x864);
11972IkReal x870=(x867+x866);
11973evalcond[0]=(((new_r00*x865))+gconst26+((new_r10*x864)));
11974evalcond[1]=(((new_r01*x865))+gconst27+((new_r11*x864)));
11975evalcond[2]=(new_r00+x870);
11976evalcond[3]=(new_r11+x870);
11977evalcond[4]=(gconst26+((new_r11*x865))+(((-1.0)*new_r01*x864)));
11978evalcond[5]=(((new_r00*x864))+(((-1.0)*new_r10*x865))+gconst27);
11979evalcond[6]=((((-1.0)*x869))+new_r01+x868);
11980evalcond[7]=((((-1.0)*x868))+new_r10+x869);
11981if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
11982{
11983continue;
11984}
11985}
11986
11987{
11988std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11989vinfos[0].jointtype = 1;
11990vinfos[0].foffset = j0;
11991vinfos[0].indices[0] = _ij0[0];
11992vinfos[0].indices[1] = _ij0[1];
11993vinfos[0].maxsolutions = _nj0;
11994vinfos[1].jointtype = 1;
11995vinfos[1].foffset = j1;
11996vinfos[1].indices[0] = _ij1[0];
11997vinfos[1].indices[1] = _ij1[1];
11998vinfos[1].maxsolutions = _nj1;
11999vinfos[2].jointtype = 1;
12000vinfos[2].foffset = j2;
12001vinfos[2].indices[0] = _ij2[0];
12002vinfos[2].indices[1] = _ij2[1];
12003vinfos[2].maxsolutions = _nj2;
12004vinfos[3].jointtype = 1;
12005vinfos[3].foffset = j3;
12006vinfos[3].indices[0] = _ij3[0];
12007vinfos[3].indices[1] = _ij3[1];
12008vinfos[3].maxsolutions = _nj3;
12009vinfos[4].jointtype = 1;
12010vinfos[4].foffset = j4;
12011vinfos[4].indices[0] = _ij4[0];
12012vinfos[4].indices[1] = _ij4[1];
12013vinfos[4].maxsolutions = _nj4;
12014vinfos[5].jointtype = 1;
12015vinfos[5].foffset = j5;
12016vinfos[5].indices[0] = _ij5[0];
12017vinfos[5].indices[1] = _ij5[1];
12018vinfos[5].maxsolutions = _nj5;
12019std::vector<int> vfree(0);
12020solutions.AddSolution(vinfos,vfree);
12021}
12022}
12023}
12024
12025}
12026
12027}
12028
12029}
12030} while(0);
12031if( bgotonextstatement )
12032{
12033bool bgotonextstatement = true;
12034do
12035{
12036evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
12037if( IKabs(evalcond[0]) < 0.0000050000000000 )
12038{
12039bgotonextstatement=false;
12040{
12041IkReal j0eval[1];
12042sj1=1.0;
12043cj1=0;
12044j1=1.5707963267949;
12045new_r11=0;
12046new_r01=0;
12047new_r22=0;
12048new_r20=0;
12049j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
12050if( IKabs(j0eval[0]) < 0.0000010000000000 )
12051{
12052continue; // no branches [j0]
12053
12054} else
12055{
12056{
12057IkReal j0array[2], cj0array[2], sj0array[2];
12058bool j0valid[2]={false};
12059_nj0 = 2;
12060CheckValue<IkReal> x872 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
12061if(!x872.valid){
12062continue;
12063}
12064IkReal x871=x872.value;
12065j0array[0]=((-1.0)*x871);
12066sj0array[0]=IKsin(j0array[0]);
12067cj0array[0]=IKcos(j0array[0]);
12068j0array[1]=((3.14159265358979)+(((-1.0)*x871)));
12069sj0array[1]=IKsin(j0array[1]);
12070cj0array[1]=IKcos(j0array[1]);
12071if( j0array[0] > IKPI )
12072{
12073 j0array[0]-=IK2PI;
12074}
12075else if( j0array[0] < -IKPI )
12076{ j0array[0]+=IK2PI;
12077}
12078j0valid[0] = true;
12079if( j0array[1] > IKPI )
12080{
12081 j0array[1]-=IK2PI;
12082}
12083else if( j0array[1] < -IKPI )
12084{ j0array[1]+=IK2PI;
12085}
12086j0valid[1] = true;
12087for(int ij0 = 0; ij0 < 2; ++ij0)
12088{
12089if( !j0valid[ij0] )
12090{
12091 continue;
12092}
12093_ij0[0] = ij0; _ij0[1] = -1;
12094for(int iij0 = ij0+1; iij0 < 2; ++iij0)
12095{
12096if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12097{
12098 j0valid[iij0]=false; _ij0[1] = iij0; break;
12099}
12100}
12101j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12102{
12103IkReal evalcond[1];
12104evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0)))));
12105if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
12106{
12107continue;
12108}
12109}
12110
12111{
12112std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12113vinfos[0].jointtype = 1;
12114vinfos[0].foffset = j0;
12115vinfos[0].indices[0] = _ij0[0];
12116vinfos[0].indices[1] = _ij0[1];
12117vinfos[0].maxsolutions = _nj0;
12118vinfos[1].jointtype = 1;
12119vinfos[1].foffset = j1;
12120vinfos[1].indices[0] = _ij1[0];
12121vinfos[1].indices[1] = _ij1[1];
12122vinfos[1].maxsolutions = _nj1;
12123vinfos[2].jointtype = 1;
12124vinfos[2].foffset = j2;
12125vinfos[2].indices[0] = _ij2[0];
12126vinfos[2].indices[1] = _ij2[1];
12127vinfos[2].maxsolutions = _nj2;
12128vinfos[3].jointtype = 1;
12129vinfos[3].foffset = j3;
12130vinfos[3].indices[0] = _ij3[0];
12131vinfos[3].indices[1] = _ij3[1];
12132vinfos[3].maxsolutions = _nj3;
12133vinfos[4].jointtype = 1;
12134vinfos[4].foffset = j4;
12135vinfos[4].indices[0] = _ij4[0];
12136vinfos[4].indices[1] = _ij4[1];
12137vinfos[4].maxsolutions = _nj4;
12138vinfos[5].jointtype = 1;
12139vinfos[5].foffset = j5;
12140vinfos[5].indices[0] = _ij5[0];
12141vinfos[5].indices[1] = _ij5[1];
12142vinfos[5].maxsolutions = _nj5;
12143std::vector<int> vfree(0);
12144solutions.AddSolution(vinfos,vfree);
12145}
12146}
12147}
12148
12149}
12150
12151}
12152
12153}
12154} while(0);
12155if( bgotonextstatement )
12156{
12157bool bgotonextstatement = true;
12158do
12159{
12160evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
12161if( IKabs(evalcond[0]) < 0.0000050000000000 )
12162{
12163bgotonextstatement=false;
12164{
12165IkReal j0eval[3];
12166sj1=1.0;
12167cj1=0;
12168j1=1.5707963267949;
12169new_r11=0;
12170new_r10=0;
12171new_r22=0;
12172new_r02=0;
12173j0eval[0]=new_r01;
12174j0eval[1]=((IKabs(cj2))+(IKabs(sj2)));
12175j0eval[2]=IKsign(new_r01);
12176if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
12177{
12178{
12179IkReal j0eval[3];
12180sj1=1.0;
12181cj1=0;
12182j1=1.5707963267949;
12183new_r11=0;
12184new_r10=0;
12185new_r22=0;
12186new_r02=0;
12187j0eval[0]=new_r00;
12188j0eval[1]=((IKabs(cj2))+(IKabs(sj2)));
12189j0eval[2]=IKsign(new_r00);
12190if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
12191{
12192{
12193IkReal j0eval[2];
12194sj1=1.0;
12195cj1=0;
12196j1=1.5707963267949;
12197new_r11=0;
12198new_r10=0;
12199new_r22=0;
12200new_r02=0;
12201j0eval[0]=new_r01;
12202j0eval[1]=new_r00;
12203if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
12204{
12205continue; // no branches [j0]
12206
12207} else
12208{
12209{
12210IkReal j0array[1], cj0array[1], sj0array[1];
12211bool j0valid[1]={false};
12212_nj0 = 1;
12213CheckValue<IkReal> x873=IKPowWithIntegerCheck(new_r01,-1);
12214if(!x873.valid){
12215continue;
12216}
12217CheckValue<IkReal> x874=IKPowWithIntegerCheck(new_r00,-1);
12218if(!x874.valid){
12219continue;
12220}
12221if( IKabs((sj2*(x873.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj2*(x874.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x873.value)))+IKsqr(((-1.0)*sj2*(x874.value)))-1) <= IKFAST_SINCOS_THRESH )
12222 continue;
12223j0array[0]=IKatan2((sj2*(x873.value)), ((-1.0)*sj2*(x874.value)));
12224sj0array[0]=IKsin(j0array[0]);
12225cj0array[0]=IKcos(j0array[0]);
12226if( j0array[0] > IKPI )
12227{
12228 j0array[0]-=IK2PI;
12229}
12230else if( j0array[0] < -IKPI )
12231{ j0array[0]+=IK2PI;
12232}
12233j0valid[0] = true;
12234for(int ij0 = 0; ij0 < 1; ++ij0)
12235{
12236if( !j0valid[ij0] )
12237{
12238 continue;
12239}
12240_ij0[0] = ij0; _ij0[1] = -1;
12241for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12242{
12243if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12244{
12245 j0valid[iij0]=false; _ij0[1] = iij0; break;
12246}
12247}
12248j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12249{
12250IkReal evalcond[8];
12251IkReal x875=IKcos(j0);
12252IkReal x876=IKsin(j0);
12253IkReal x877=(sj2*x875);
12254IkReal x878=(cj2*x876);
12255IkReal x879=(sj2*x876);
12256IkReal x880=(cj2*x875);
12257IkReal x881=(x878+x877);
12258evalcond[0]=(((new_r00*x876))+cj2);
12259evalcond[1]=(((new_r00*x875))+sj2);
12260evalcond[2]=(((new_r01*x875))+cj2);
12261evalcond[3]=(sj2+(((-1.0)*new_r01*x876)));
12262evalcond[4]=x881;
12263evalcond[5]=(new_r00+x881);
12264evalcond[6]=((((-1.0)*x880))+x879);
12265evalcond[7]=((((-1.0)*x879))+new_r01+x880);
12266if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12267{
12268continue;
12269}
12270}
12271
12272{
12273std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12274vinfos[0].jointtype = 1;
12275vinfos[0].foffset = j0;
12276vinfos[0].indices[0] = _ij0[0];
12277vinfos[0].indices[1] = _ij0[1];
12278vinfos[0].maxsolutions = _nj0;
12279vinfos[1].jointtype = 1;
12280vinfos[1].foffset = j1;
12281vinfos[1].indices[0] = _ij1[0];
12282vinfos[1].indices[1] = _ij1[1];
12283vinfos[1].maxsolutions = _nj1;
12284vinfos[2].jointtype = 1;
12285vinfos[2].foffset = j2;
12286vinfos[2].indices[0] = _ij2[0];
12287vinfos[2].indices[1] = _ij2[1];
12288vinfos[2].maxsolutions = _nj2;
12289vinfos[3].jointtype = 1;
12290vinfos[3].foffset = j3;
12291vinfos[3].indices[0] = _ij3[0];
12292vinfos[3].indices[1] = _ij3[1];
12293vinfos[3].maxsolutions = _nj3;
12294vinfos[4].jointtype = 1;
12295vinfos[4].foffset = j4;
12296vinfos[4].indices[0] = _ij4[0];
12297vinfos[4].indices[1] = _ij4[1];
12298vinfos[4].maxsolutions = _nj4;
12299vinfos[5].jointtype = 1;
12300vinfos[5].foffset = j5;
12301vinfos[5].indices[0] = _ij5[0];
12302vinfos[5].indices[1] = _ij5[1];
12303vinfos[5].maxsolutions = _nj5;
12304std::vector<int> vfree(0);
12305solutions.AddSolution(vinfos,vfree);
12306}
12307}
12308}
12309
12310}
12311
12312}
12313
12314} else
12315{
12316{
12317IkReal j0array[1], cj0array[1], sj0array[1];
12318bool j0valid[1]={false};
12319_nj0 = 1;
12320CheckValue<IkReal> x882 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH);
12321if(!x882.valid){
12322continue;
12323}
12324CheckValue<IkReal> x883=IKPowWithIntegerCheck(IKsign(new_r00),-1);
12325if(!x883.valid){
12326continue;
12327}
12328j0array[0]=((-1.5707963267949)+(x882.value)+(((1.5707963267949)*(x883.value))));
12329sj0array[0]=IKsin(j0array[0]);
12330cj0array[0]=IKcos(j0array[0]);
12331if( j0array[0] > IKPI )
12332{
12333 j0array[0]-=IK2PI;
12334}
12335else if( j0array[0] < -IKPI )
12336{ j0array[0]+=IK2PI;
12337}
12338j0valid[0] = true;
12339for(int ij0 = 0; ij0 < 1; ++ij0)
12340{
12341if( !j0valid[ij0] )
12342{
12343 continue;
12344}
12345_ij0[0] = ij0; _ij0[1] = -1;
12346for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12347{
12348if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12349{
12350 j0valid[iij0]=false; _ij0[1] = iij0; break;
12351}
12352}
12353j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12354{
12355IkReal evalcond[8];
12356IkReal x884=IKcos(j0);
12357IkReal x885=IKsin(j0);
12358IkReal x886=(sj2*x884);
12359IkReal x887=(cj2*x885);
12360IkReal x888=(sj2*x885);
12361IkReal x889=(cj2*x884);
12362IkReal x890=(x887+x886);
12363evalcond[0]=(cj2+((new_r00*x885)));
12364evalcond[1]=(sj2+((new_r00*x884)));
12365evalcond[2]=(cj2+((new_r01*x884)));
12366evalcond[3]=(sj2+(((-1.0)*new_r01*x885)));
12367evalcond[4]=x890;
12368evalcond[5]=(new_r00+x890);
12369evalcond[6]=((((-1.0)*x889))+x888);
12370evalcond[7]=((((-1.0)*x888))+new_r01+x889);
12371if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12372{
12373continue;
12374}
12375}
12376
12377{
12378std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12379vinfos[0].jointtype = 1;
12380vinfos[0].foffset = j0;
12381vinfos[0].indices[0] = _ij0[0];
12382vinfos[0].indices[1] = _ij0[1];
12383vinfos[0].maxsolutions = _nj0;
12384vinfos[1].jointtype = 1;
12385vinfos[1].foffset = j1;
12386vinfos[1].indices[0] = _ij1[0];
12387vinfos[1].indices[1] = _ij1[1];
12388vinfos[1].maxsolutions = _nj1;
12389vinfos[2].jointtype = 1;
12390vinfos[2].foffset = j2;
12391vinfos[2].indices[0] = _ij2[0];
12392vinfos[2].indices[1] = _ij2[1];
12393vinfos[2].maxsolutions = _nj2;
12394vinfos[3].jointtype = 1;
12395vinfos[3].foffset = j3;
12396vinfos[3].indices[0] = _ij3[0];
12397vinfos[3].indices[1] = _ij3[1];
12398vinfos[3].maxsolutions = _nj3;
12399vinfos[4].jointtype = 1;
12400vinfos[4].foffset = j4;
12401vinfos[4].indices[0] = _ij4[0];
12402vinfos[4].indices[1] = _ij4[1];
12403vinfos[4].maxsolutions = _nj4;
12404vinfos[5].jointtype = 1;
12405vinfos[5].foffset = j5;
12406vinfos[5].indices[0] = _ij5[0];
12407vinfos[5].indices[1] = _ij5[1];
12408vinfos[5].maxsolutions = _nj5;
12409std::vector<int> vfree(0);
12410solutions.AddSolution(vinfos,vfree);
12411}
12412}
12413}
12414
12415}
12416
12417}
12418
12419} else
12420{
12421{
12422IkReal j0array[1], cj0array[1], sj0array[1];
12423bool j0valid[1]={false};
12424_nj0 = 1;
12425CheckValue<IkReal> x891=IKPowWithIntegerCheck(IKsign(new_r01),-1);
12426if(!x891.valid){
12427continue;
12428}
12429CheckValue<IkReal> x892 = IKatan2WithCheck(IkReal(sj2),IkReal(((-1.0)*cj2)),IKFAST_ATAN2_MAGTHRESH);
12430if(!x892.valid){
12431continue;
12432}
12433j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x891.value)))+(x892.value));
12434sj0array[0]=IKsin(j0array[0]);
12435cj0array[0]=IKcos(j0array[0]);
12436if( j0array[0] > IKPI )
12437{
12438 j0array[0]-=IK2PI;
12439}
12440else if( j0array[0] < -IKPI )
12441{ j0array[0]+=IK2PI;
12442}
12443j0valid[0] = true;
12444for(int ij0 = 0; ij0 < 1; ++ij0)
12445{
12446if( !j0valid[ij0] )
12447{
12448 continue;
12449}
12450_ij0[0] = ij0; _ij0[1] = -1;
12451for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12452{
12453if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12454{
12455 j0valid[iij0]=false; _ij0[1] = iij0; break;
12456}
12457}
12458j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12459{
12460IkReal evalcond[8];
12461IkReal x893=IKcos(j0);
12462IkReal x894=IKsin(j0);
12463IkReal x895=(sj2*x893);
12464IkReal x896=(cj2*x894);
12465IkReal x897=(sj2*x894);
12466IkReal x898=(cj2*x893);
12467IkReal x899=(x896+x895);
12468evalcond[0]=(cj2+((new_r00*x894)));
12469evalcond[1]=(sj2+((new_r00*x893)));
12470evalcond[2]=(cj2+((new_r01*x893)));
12471evalcond[3]=(sj2+(((-1.0)*new_r01*x894)));
12472evalcond[4]=x899;
12473evalcond[5]=(new_r00+x899);
12474evalcond[6]=((((-1.0)*x898))+x897);
12475evalcond[7]=((((-1.0)*x897))+new_r01+x898);
12476if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12477{
12478continue;
12479}
12480}
12481
12482{
12483std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12484vinfos[0].jointtype = 1;
12485vinfos[0].foffset = j0;
12486vinfos[0].indices[0] = _ij0[0];
12487vinfos[0].indices[1] = _ij0[1];
12488vinfos[0].maxsolutions = _nj0;
12489vinfos[1].jointtype = 1;
12490vinfos[1].foffset = j1;
12491vinfos[1].indices[0] = _ij1[0];
12492vinfos[1].indices[1] = _ij1[1];
12493vinfos[1].maxsolutions = _nj1;
12494vinfos[2].jointtype = 1;
12495vinfos[2].foffset = j2;
12496vinfos[2].indices[0] = _ij2[0];
12497vinfos[2].indices[1] = _ij2[1];
12498vinfos[2].maxsolutions = _nj2;
12499vinfos[3].jointtype = 1;
12500vinfos[3].foffset = j3;
12501vinfos[3].indices[0] = _ij3[0];
12502vinfos[3].indices[1] = _ij3[1];
12503vinfos[3].maxsolutions = _nj3;
12504vinfos[4].jointtype = 1;
12505vinfos[4].foffset = j4;
12506vinfos[4].indices[0] = _ij4[0];
12507vinfos[4].indices[1] = _ij4[1];
12508vinfos[4].maxsolutions = _nj4;
12509vinfos[5].jointtype = 1;
12510vinfos[5].foffset = j5;
12511vinfos[5].indices[0] = _ij5[0];
12512vinfos[5].indices[1] = _ij5[1];
12513vinfos[5].maxsolutions = _nj5;
12514std::vector<int> vfree(0);
12515solutions.AddSolution(vinfos,vfree);
12516}
12517}
12518}
12519
12520}
12521
12522}
12523
12524}
12525} while(0);
12526if( bgotonextstatement )
12527{
12528bool bgotonextstatement = true;
12529do
12530{
12531evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
12532if( IKabs(evalcond[0]) < 0.0000050000000000 )
12533{
12534bgotonextstatement=false;
12535{
12536IkReal j0eval[3];
12537sj1=1.0;
12538cj1=0;
12539j1=1.5707963267949;
12540new_r00=0;
12541new_r01=0;
12542new_r12=0;
12543new_r22=0;
12544j0eval[0]=new_r10;
12545j0eval[1]=((IKabs(cj2))+(IKabs(sj2)));
12546j0eval[2]=IKsign(new_r10);
12547if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
12548{
12549{
12550IkReal j0eval[3];
12551sj1=1.0;
12552cj1=0;
12553j1=1.5707963267949;
12554new_r00=0;
12555new_r01=0;
12556new_r12=0;
12557new_r22=0;
12558j0eval[0]=new_r11;
12559j0eval[1]=((IKabs(cj2))+(IKabs(sj2)));
12560j0eval[2]=IKsign(new_r11);
12561if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
12562{
12563{
12564IkReal j0eval[2];
12565sj1=1.0;
12566cj1=0;
12567j1=1.5707963267949;
12568new_r00=0;
12569new_r01=0;
12570new_r12=0;
12571new_r22=0;
12572j0eval[0]=new_r11;
12573j0eval[1]=new_r10;
12574if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
12575{
12576continue; // no branches [j0]
12577
12578} else
12579{
12580{
12581IkReal j0array[1], cj0array[1], sj0array[1];
12582bool j0valid[1]={false};
12583_nj0 = 1;
12584CheckValue<IkReal> x900=IKPowWithIntegerCheck(new_r11,-1);
12585if(!x900.valid){
12586continue;
12587}
12588CheckValue<IkReal> x901=IKPowWithIntegerCheck(new_r10,-1);
12589if(!x901.valid){
12590continue;
12591}
12592if( IKabs(((-1.0)*cj2*(x900.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((cj2*(x901.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*cj2*(x900.value)))+IKsqr((cj2*(x901.value)))-1) <= IKFAST_SINCOS_THRESH )
12593 continue;
12594j0array[0]=IKatan2(((-1.0)*cj2*(x900.value)), (cj2*(x901.value)));
12595sj0array[0]=IKsin(j0array[0]);
12596cj0array[0]=IKcos(j0array[0]);
12597if( j0array[0] > IKPI )
12598{
12599 j0array[0]-=IK2PI;
12600}
12601else if( j0array[0] < -IKPI )
12602{ j0array[0]+=IK2PI;
12603}
12604j0valid[0] = true;
12605for(int ij0 = 0; ij0 < 1; ++ij0)
12606{
12607if( !j0valid[ij0] )
12608{
12609 continue;
12610}
12611_ij0[0] = ij0; _ij0[1] = -1;
12612for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12613{
12614if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12615{
12616 j0valid[iij0]=false; _ij0[1] = iij0; break;
12617}
12618}
12619j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12620{
12621IkReal evalcond[8];
12622IkReal x902=IKsin(j0);
12623IkReal x903=IKcos(j0);
12624IkReal x904=(sj2*x903);
12625IkReal x905=(cj2*x902);
12626IkReal x906=(sj2*x902);
12627IkReal x907=((1.0)*x903);
12628IkReal x908=(x904+x905);
12629evalcond[0]=(sj2+((new_r11*x903)));
12630evalcond[1]=(sj2+((new_r10*x902)));
12631evalcond[2]=(cj2+((new_r11*x902)));
12632evalcond[3]=(cj2+(((-1.0)*new_r10*x907)));
12633evalcond[4]=x908;
12634evalcond[5]=(new_r11+x908);
12635evalcond[6]=(((cj2*x903))+(((-1.0)*x906)));
12636evalcond[7]=(new_r10+x906+(((-1.0)*cj2*x907)));
12637if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12638{
12639continue;
12640}
12641}
12642
12643{
12644std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12645vinfos[0].jointtype = 1;
12646vinfos[0].foffset = j0;
12647vinfos[0].indices[0] = _ij0[0];
12648vinfos[0].indices[1] = _ij0[1];
12649vinfos[0].maxsolutions = _nj0;
12650vinfos[1].jointtype = 1;
12651vinfos[1].foffset = j1;
12652vinfos[1].indices[0] = _ij1[0];
12653vinfos[1].indices[1] = _ij1[1];
12654vinfos[1].maxsolutions = _nj1;
12655vinfos[2].jointtype = 1;
12656vinfos[2].foffset = j2;
12657vinfos[2].indices[0] = _ij2[0];
12658vinfos[2].indices[1] = _ij2[1];
12659vinfos[2].maxsolutions = _nj2;
12660vinfos[3].jointtype = 1;
12661vinfos[3].foffset = j3;
12662vinfos[3].indices[0] = _ij3[0];
12663vinfos[3].indices[1] = _ij3[1];
12664vinfos[3].maxsolutions = _nj3;
12665vinfos[4].jointtype = 1;
12666vinfos[4].foffset = j4;
12667vinfos[4].indices[0] = _ij4[0];
12668vinfos[4].indices[1] = _ij4[1];
12669vinfos[4].maxsolutions = _nj4;
12670vinfos[5].jointtype = 1;
12671vinfos[5].foffset = j5;
12672vinfos[5].indices[0] = _ij5[0];
12673vinfos[5].indices[1] = _ij5[1];
12674vinfos[5].maxsolutions = _nj5;
12675std::vector<int> vfree(0);
12676solutions.AddSolution(vinfos,vfree);
12677}
12678}
12679}
12680
12681}
12682
12683}
12684
12685} else
12686{
12687{
12688IkReal j0array[1], cj0array[1], sj0array[1];
12689bool j0valid[1]={false};
12690_nj0 = 1;
12691CheckValue<IkReal> x909=IKPowWithIntegerCheck(IKsign(new_r11),-1);
12692if(!x909.valid){
12693continue;
12694}
12695CheckValue<IkReal> x910 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH);
12696if(!x910.valid){
12697continue;
12698}
12699j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x909.value)))+(x910.value));
12700sj0array[0]=IKsin(j0array[0]);
12701cj0array[0]=IKcos(j0array[0]);
12702if( j0array[0] > IKPI )
12703{
12704 j0array[0]-=IK2PI;
12705}
12706else if( j0array[0] < -IKPI )
12707{ j0array[0]+=IK2PI;
12708}
12709j0valid[0] = true;
12710for(int ij0 = 0; ij0 < 1; ++ij0)
12711{
12712if( !j0valid[ij0] )
12713{
12714 continue;
12715}
12716_ij0[0] = ij0; _ij0[1] = -1;
12717for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12718{
12719if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12720{
12721 j0valid[iij0]=false; _ij0[1] = iij0; break;
12722}
12723}
12724j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12725{
12726IkReal evalcond[8];
12727IkReal x911=IKsin(j0);
12728IkReal x912=IKcos(j0);
12729IkReal x913=(sj2*x912);
12730IkReal x914=(cj2*x911);
12731IkReal x915=(sj2*x911);
12732IkReal x916=((1.0)*x912);
12733IkReal x917=(x913+x914);
12734evalcond[0]=(sj2+((new_r11*x912)));
12735evalcond[1]=(sj2+((new_r10*x911)));
12736evalcond[2]=(cj2+((new_r11*x911)));
12737evalcond[3]=(cj2+(((-1.0)*new_r10*x916)));
12738evalcond[4]=x917;
12739evalcond[5]=(new_r11+x917);
12740evalcond[6]=(((cj2*x912))+(((-1.0)*x915)));
12741evalcond[7]=(new_r10+x915+(((-1.0)*cj2*x916)));
12742if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12743{
12744continue;
12745}
12746}
12747
12748{
12749std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12750vinfos[0].jointtype = 1;
12751vinfos[0].foffset = j0;
12752vinfos[0].indices[0] = _ij0[0];
12753vinfos[0].indices[1] = _ij0[1];
12754vinfos[0].maxsolutions = _nj0;
12755vinfos[1].jointtype = 1;
12756vinfos[1].foffset = j1;
12757vinfos[1].indices[0] = _ij1[0];
12758vinfos[1].indices[1] = _ij1[1];
12759vinfos[1].maxsolutions = _nj1;
12760vinfos[2].jointtype = 1;
12761vinfos[2].foffset = j2;
12762vinfos[2].indices[0] = _ij2[0];
12763vinfos[2].indices[1] = _ij2[1];
12764vinfos[2].maxsolutions = _nj2;
12765vinfos[3].jointtype = 1;
12766vinfos[3].foffset = j3;
12767vinfos[3].indices[0] = _ij3[0];
12768vinfos[3].indices[1] = _ij3[1];
12769vinfos[3].maxsolutions = _nj3;
12770vinfos[4].jointtype = 1;
12771vinfos[4].foffset = j4;
12772vinfos[4].indices[0] = _ij4[0];
12773vinfos[4].indices[1] = _ij4[1];
12774vinfos[4].maxsolutions = _nj4;
12775vinfos[5].jointtype = 1;
12776vinfos[5].foffset = j5;
12777vinfos[5].indices[0] = _ij5[0];
12778vinfos[5].indices[1] = _ij5[1];
12779vinfos[5].maxsolutions = _nj5;
12780std::vector<int> vfree(0);
12781solutions.AddSolution(vinfos,vfree);
12782}
12783}
12784}
12785
12786}
12787
12788}
12789
12790} else
12791{
12792{
12793IkReal j0array[1], cj0array[1], sj0array[1];
12794bool j0valid[1]={false};
12795_nj0 = 1;
12796CheckValue<IkReal> x918=IKPowWithIntegerCheck(IKsign(new_r10),-1);
12797if(!x918.valid){
12798continue;
12799}
12800CheckValue<IkReal> x919 = IKatan2WithCheck(IkReal(((-1.0)*sj2)),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH);
12801if(!x919.valid){
12802continue;
12803}
12804j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x918.value)))+(x919.value));
12805sj0array[0]=IKsin(j0array[0]);
12806cj0array[0]=IKcos(j0array[0]);
12807if( j0array[0] > IKPI )
12808{
12809 j0array[0]-=IK2PI;
12810}
12811else if( j0array[0] < -IKPI )
12812{ j0array[0]+=IK2PI;
12813}
12814j0valid[0] = true;
12815for(int ij0 = 0; ij0 < 1; ++ij0)
12816{
12817if( !j0valid[ij0] )
12818{
12819 continue;
12820}
12821_ij0[0] = ij0; _ij0[1] = -1;
12822for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12823{
12824if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12825{
12826 j0valid[iij0]=false; _ij0[1] = iij0; break;
12827}
12828}
12829j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12830{
12831IkReal evalcond[8];
12832IkReal x920=IKsin(j0);
12833IkReal x921=IKcos(j0);
12834IkReal x922=(sj2*x921);
12835IkReal x923=(cj2*x920);
12836IkReal x924=(sj2*x920);
12837IkReal x925=((1.0)*x921);
12838IkReal x926=(x922+x923);
12839evalcond[0]=(sj2+((new_r11*x921)));
12840evalcond[1]=(sj2+((new_r10*x920)));
12841evalcond[2]=(cj2+((new_r11*x920)));
12842evalcond[3]=(cj2+(((-1.0)*new_r10*x925)));
12843evalcond[4]=x926;
12844evalcond[5]=(new_r11+x926);
12845evalcond[6]=((((-1.0)*x924))+((cj2*x921)));
12846evalcond[7]=((((-1.0)*cj2*x925))+new_r10+x924);
12847if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
12848{
12849continue;
12850}
12851}
12852
12853{
12854std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12855vinfos[0].jointtype = 1;
12856vinfos[0].foffset = j0;
12857vinfos[0].indices[0] = _ij0[0];
12858vinfos[0].indices[1] = _ij0[1];
12859vinfos[0].maxsolutions = _nj0;
12860vinfos[1].jointtype = 1;
12861vinfos[1].foffset = j1;
12862vinfos[1].indices[0] = _ij1[0];
12863vinfos[1].indices[1] = _ij1[1];
12864vinfos[1].maxsolutions = _nj1;
12865vinfos[2].jointtype = 1;
12866vinfos[2].foffset = j2;
12867vinfos[2].indices[0] = _ij2[0];
12868vinfos[2].indices[1] = _ij2[1];
12869vinfos[2].maxsolutions = _nj2;
12870vinfos[3].jointtype = 1;
12871vinfos[3].foffset = j3;
12872vinfos[3].indices[0] = _ij3[0];
12873vinfos[3].indices[1] = _ij3[1];
12874vinfos[3].maxsolutions = _nj3;
12875vinfos[4].jointtype = 1;
12876vinfos[4].foffset = j4;
12877vinfos[4].indices[0] = _ij4[0];
12878vinfos[4].indices[1] = _ij4[1];
12879vinfos[4].maxsolutions = _nj4;
12880vinfos[5].jointtype = 1;
12881vinfos[5].foffset = j5;
12882vinfos[5].indices[0] = _ij5[0];
12883vinfos[5].indices[1] = _ij5[1];
12884vinfos[5].maxsolutions = _nj5;
12885std::vector<int> vfree(0);
12886solutions.AddSolution(vinfos,vfree);
12887}
12888}
12889}
12890
12891}
12892
12893}
12894
12895}
12896} while(0);
12897if( bgotonextstatement )
12898{
12899bool bgotonextstatement = true;
12900do
12901{
12902evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
12903if( IKabs(evalcond[0]) < 0.0000050000000000 )
12904{
12905bgotonextstatement=false;
12906{
12907IkReal j0eval[1];
12908sj1=1.0;
12909cj1=0;
12910j1=1.5707963267949;
12911new_r00=0;
12912new_r10=0;
12913new_r21=0;
12914new_r22=0;
12915j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
12916if( IKabs(j0eval[0]) < 0.0000010000000000 )
12917{
12918continue; // no branches [j0]
12919
12920} else
12921{
12922{
12923IkReal j0array[2], cj0array[2], sj0array[2];
12924bool j0valid[2]={false};
12925_nj0 = 2;
12926CheckValue<IkReal> x928 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
12927if(!x928.valid){
12928continue;
12929}
12930IkReal x927=x928.value;
12931j0array[0]=((-1.0)*x927);
12932sj0array[0]=IKsin(j0array[0]);
12933cj0array[0]=IKcos(j0array[0]);
12934j0array[1]=((3.14159265358979)+(((-1.0)*x927)));
12935sj0array[1]=IKsin(j0array[1]);
12936cj0array[1]=IKcos(j0array[1]);
12937if( j0array[0] > IKPI )
12938{
12939 j0array[0]-=IK2PI;
12940}
12941else if( j0array[0] < -IKPI )
12942{ j0array[0]+=IK2PI;
12943}
12944j0valid[0] = true;
12945if( j0array[1] > IKPI )
12946{
12947 j0array[1]-=IK2PI;
12948}
12949else if( j0array[1] < -IKPI )
12950{ j0array[1]+=IK2PI;
12951}
12952j0valid[1] = true;
12953for(int ij0 = 0; ij0 < 2; ++ij0)
12954{
12955if( !j0valid[ij0] )
12956{
12957 continue;
12958}
12959_ij0[0] = ij0; _ij0[1] = -1;
12960for(int iij0 = ij0+1; iij0 < 2; ++iij0)
12961{
12962if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12963{
12964 j0valid[iij0]=false; _ij0[1] = iij0; break;
12965}
12966}
12967j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12968{
12969IkReal evalcond[1];
12970evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0)))));
12971if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
12972{
12973continue;
12974}
12975}
12976
12977{
12978std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12979vinfos[0].jointtype = 1;
12980vinfos[0].foffset = j0;
12981vinfos[0].indices[0] = _ij0[0];
12982vinfos[0].indices[1] = _ij0[1];
12983vinfos[0].maxsolutions = _nj0;
12984vinfos[1].jointtype = 1;
12985vinfos[1].foffset = j1;
12986vinfos[1].indices[0] = _ij1[0];
12987vinfos[1].indices[1] = _ij1[1];
12988vinfos[1].maxsolutions = _nj1;
12989vinfos[2].jointtype = 1;
12990vinfos[2].foffset = j2;
12991vinfos[2].indices[0] = _ij2[0];
12992vinfos[2].indices[1] = _ij2[1];
12993vinfos[2].maxsolutions = _nj2;
12994vinfos[3].jointtype = 1;
12995vinfos[3].foffset = j3;
12996vinfos[3].indices[0] = _ij3[0];
12997vinfos[3].indices[1] = _ij3[1];
12998vinfos[3].maxsolutions = _nj3;
12999vinfos[4].jointtype = 1;
13000vinfos[4].foffset = j4;
13001vinfos[4].indices[0] = _ij4[0];
13002vinfos[4].indices[1] = _ij4[1];
13003vinfos[4].maxsolutions = _nj4;
13004vinfos[5].jointtype = 1;
13005vinfos[5].foffset = j5;
13006vinfos[5].indices[0] = _ij5[0];
13007vinfos[5].indices[1] = _ij5[1];
13008vinfos[5].maxsolutions = _nj5;
13009std::vector<int> vfree(0);
13010solutions.AddSolution(vinfos,vfree);
13011}
13012}
13013}
13014
13015}
13016
13017}
13018
13019}
13020} while(0);
13021if( bgotonextstatement )
13022{
13023bool bgotonextstatement = true;
13024do
13025{
13026if( 1 )
13027{
13028bgotonextstatement=false;
13029continue; // branch miss [j0]
13030
13031}
13032} while(0);
13033if( bgotonextstatement )
13034{
13035}
13036}
13037}
13038}
13039}
13040}
13041}
13042}
13043}
13044}
13045
13046} else
13047{
13048{
13049IkReal j0array[1], cj0array[1], sj0array[1];
13050bool j0valid[1]={false};
13051_nj0 = 1;
13052IkReal x929=((1.0)*sj2);
13053CheckValue<IkReal> x930=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x929))+((cj2*new_r00)))),-1);
13054if(!x930.valid){
13055continue;
13056}
13057CheckValue<IkReal> x931 = IKatan2WithCheck(IkReal(((1.0)+(((-1.0)*(cj2*cj2)))+(((-1.0)*new_r00*new_r11)))),IkReal(((((-1.0)*cj2*x929))+((new_r10*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
13058if(!x931.valid){
13059continue;
13060}
13061j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x930.value)))+(x931.value));
13062sj0array[0]=IKsin(j0array[0]);
13063cj0array[0]=IKcos(j0array[0]);
13064if( j0array[0] > IKPI )
13065{
13066 j0array[0]-=IK2PI;
13067}
13068else if( j0array[0] < -IKPI )
13069{ j0array[0]+=IK2PI;
13070}
13071j0valid[0] = true;
13072for(int ij0 = 0; ij0 < 1; ++ij0)
13073{
13074if( !j0valid[ij0] )
13075{
13076 continue;
13077}
13078_ij0[0] = ij0; _ij0[1] = -1;
13079for(int iij0 = ij0+1; iij0 < 1; ++iij0)
13080{
13081if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13082{
13083 j0valid[iij0]=false; _ij0[1] = iij0; break;
13084}
13085}
13086j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13087{
13088IkReal evalcond[8];
13089IkReal x932=IKsin(j0);
13090IkReal x933=IKcos(j0);
13091IkReal x934=(sj2*x933);
13092IkReal x935=(cj2*x932);
13093IkReal x936=(sj2*x932);
13094IkReal x937=((1.0)*x933);
13095IkReal x938=(x935+x934);
13096evalcond[0]=(sj2+((new_r00*x933))+((new_r10*x932)));
13097evalcond[1]=(cj2+((new_r01*x933))+((new_r11*x932)));
13098evalcond[2]=(new_r00+x938);
13099evalcond[3]=(new_r11+x938);
13100evalcond[4]=(sj2+(((-1.0)*new_r01*x932))+((new_r11*x933)));
13101evalcond[5]=(cj2+(((-1.0)*new_r10*x937))+((new_r00*x932)));
13102evalcond[6]=(((cj2*x933))+(((-1.0)*x936))+new_r01);
13103evalcond[7]=((((-1.0)*cj2*x937))+new_r10+x936);
13104if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
13105{
13106continue;
13107}
13108}
13109
13110{
13111std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13112vinfos[0].jointtype = 1;
13113vinfos[0].foffset = j0;
13114vinfos[0].indices[0] = _ij0[0];
13115vinfos[0].indices[1] = _ij0[1];
13116vinfos[0].maxsolutions = _nj0;
13117vinfos[1].jointtype = 1;
13118vinfos[1].foffset = j1;
13119vinfos[1].indices[0] = _ij1[0];
13120vinfos[1].indices[1] = _ij1[1];
13121vinfos[1].maxsolutions = _nj1;
13122vinfos[2].jointtype = 1;
13123vinfos[2].foffset = j2;
13124vinfos[2].indices[0] = _ij2[0];
13125vinfos[2].indices[1] = _ij2[1];
13126vinfos[2].maxsolutions = _nj2;
13127vinfos[3].jointtype = 1;
13128vinfos[3].foffset = j3;
13129vinfos[3].indices[0] = _ij3[0];
13130vinfos[3].indices[1] = _ij3[1];
13131vinfos[3].maxsolutions = _nj3;
13132vinfos[4].jointtype = 1;
13133vinfos[4].foffset = j4;
13134vinfos[4].indices[0] = _ij4[0];
13135vinfos[4].indices[1] = _ij4[1];
13136vinfos[4].maxsolutions = _nj4;
13137vinfos[5].jointtype = 1;
13138vinfos[5].foffset = j5;
13139vinfos[5].indices[0] = _ij5[0];
13140vinfos[5].indices[1] = _ij5[1];
13141vinfos[5].maxsolutions = _nj5;
13142std::vector<int> vfree(0);
13143solutions.AddSolution(vinfos,vfree);
13144}
13145}
13146}
13147
13148}
13149
13150}
13151
13152} else
13153{
13154{
13155IkReal j0array[1], cj0array[1], sj0array[1];
13156bool j0valid[1]={false};
13157_nj0 = 1;
13158CheckValue<IkReal> x939=IKPowWithIntegerCheck(IKsign((((cj2*new_r01))+(((-1.0)*new_r11*sj2)))),-1);
13159if(!x939.valid){
13160continue;
13161}
13162CheckValue<IkReal> x940 = IKatan2WithCheck(IkReal((((cj2*sj2))+(((-1.0)*new_r00*new_r01)))),IkReal(((((-1.0)*(cj2*cj2)))+((new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH);
13163if(!x940.valid){
13164continue;
13165}
13166j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x939.value)))+(x940.value));
13167sj0array[0]=IKsin(j0array[0]);
13168cj0array[0]=IKcos(j0array[0]);
13169if( j0array[0] > IKPI )
13170{
13171 j0array[0]-=IK2PI;
13172}
13173else if( j0array[0] < -IKPI )
13174{ j0array[0]+=IK2PI;
13175}
13176j0valid[0] = true;
13177for(int ij0 = 0; ij0 < 1; ++ij0)
13178{
13179if( !j0valid[ij0] )
13180{
13181 continue;
13182}
13183_ij0[0] = ij0; _ij0[1] = -1;
13184for(int iij0 = ij0+1; iij0 < 1; ++iij0)
13185{
13186if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13187{
13188 j0valid[iij0]=false; _ij0[1] = iij0; break;
13189}
13190}
13191j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13192{
13193IkReal evalcond[8];
13194IkReal x941=IKsin(j0);
13195IkReal x942=IKcos(j0);
13196IkReal x943=(sj2*x942);
13197IkReal x944=(cj2*x941);
13198IkReal x945=(sj2*x941);
13199IkReal x946=((1.0)*x942);
13200IkReal x947=(x943+x944);
13201evalcond[0]=(sj2+((new_r00*x942))+((new_r10*x941)));
13202evalcond[1]=(cj2+((new_r01*x942))+((new_r11*x941)));
13203evalcond[2]=(new_r00+x947);
13204evalcond[3]=(new_r11+x947);
13205evalcond[4]=((((-1.0)*new_r01*x941))+sj2+((new_r11*x942)));
13206evalcond[5]=(((new_r00*x941))+cj2+(((-1.0)*new_r10*x946)));
13207evalcond[6]=(((cj2*x942))+(((-1.0)*x945))+new_r01);
13208evalcond[7]=((((-1.0)*cj2*x946))+new_r10+x945);
13209if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
13210{
13211continue;
13212}
13213}
13214
13215{
13216std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13217vinfos[0].jointtype = 1;
13218vinfos[0].foffset = j0;
13219vinfos[0].indices[0] = _ij0[0];
13220vinfos[0].indices[1] = _ij0[1];
13221vinfos[0].maxsolutions = _nj0;
13222vinfos[1].jointtype = 1;
13223vinfos[1].foffset = j1;
13224vinfos[1].indices[0] = _ij1[0];
13225vinfos[1].indices[1] = _ij1[1];
13226vinfos[1].maxsolutions = _nj1;
13227vinfos[2].jointtype = 1;
13228vinfos[2].foffset = j2;
13229vinfos[2].indices[0] = _ij2[0];
13230vinfos[2].indices[1] = _ij2[1];
13231vinfos[2].maxsolutions = _nj2;
13232vinfos[3].jointtype = 1;
13233vinfos[3].foffset = j3;
13234vinfos[3].indices[0] = _ij3[0];
13235vinfos[3].indices[1] = _ij3[1];
13236vinfos[3].maxsolutions = _nj3;
13237vinfos[4].jointtype = 1;
13238vinfos[4].foffset = j4;
13239vinfos[4].indices[0] = _ij4[0];
13240vinfos[4].indices[1] = _ij4[1];
13241vinfos[4].maxsolutions = _nj4;
13242vinfos[5].jointtype = 1;
13243vinfos[5].foffset = j5;
13244vinfos[5].indices[0] = _ij5[0];
13245vinfos[5].indices[1] = _ij5[1];
13246vinfos[5].maxsolutions = _nj5;
13247std::vector<int> vfree(0);
13248solutions.AddSolution(vinfos,vfree);
13249}
13250}
13251}
13252
13253}
13254
13255}
13256
13257} else
13258{
13259{
13260IkReal j0array[1], cj0array[1], sj0array[1];
13261bool j0valid[1]={false};
13262_nj0 = 1;
13263CheckValue<IkReal> x948 = IKatan2WithCheck(IkReal((((new_r01*sj2))+(((-1.0)*cj2*new_r00)))),IkReal((((cj2*new_r10))+(((-1.0)*new_r11*sj2)))),IKFAST_ATAN2_MAGTHRESH);
13264if(!x948.valid){
13265continue;
13266}
13267CheckValue<IkReal> x949=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1);
13268if(!x949.valid){
13269continue;
13270}
13271j0array[0]=((-1.5707963267949)+(x948.value)+(((1.5707963267949)*(x949.value))));
13272sj0array[0]=IKsin(j0array[0]);
13273cj0array[0]=IKcos(j0array[0]);
13274if( j0array[0] > IKPI )
13275{
13276 j0array[0]-=IK2PI;
13277}
13278else if( j0array[0] < -IKPI )
13279{ j0array[0]+=IK2PI;
13280}
13281j0valid[0] = true;
13282for(int ij0 = 0; ij0 < 1; ++ij0)
13283{
13284if( !j0valid[ij0] )
13285{
13286 continue;
13287}
13288_ij0[0] = ij0; _ij0[1] = -1;
13289for(int iij0 = ij0+1; iij0 < 1; ++iij0)
13290{
13291if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13292{
13293 j0valid[iij0]=false; _ij0[1] = iij0; break;
13294}
13295}
13296j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13297{
13298IkReal evalcond[8];
13299IkReal x950=IKsin(j0);
13300IkReal x951=IKcos(j0);
13301IkReal x952=(sj2*x951);
13302IkReal x953=(cj2*x950);
13303IkReal x954=(sj2*x950);
13304IkReal x955=((1.0)*x951);
13305IkReal x956=(x953+x952);
13306evalcond[0]=(((new_r10*x950))+((new_r00*x951))+sj2);
13307evalcond[1]=(((new_r01*x951))+cj2+((new_r11*x950)));
13308evalcond[2]=(new_r00+x956);
13309evalcond[3]=(new_r11+x956);
13310evalcond[4]=(sj2+(((-1.0)*new_r01*x950))+((new_r11*x951)));
13311evalcond[5]=(((new_r00*x950))+cj2+(((-1.0)*new_r10*x955)));
13312evalcond[6]=((((-1.0)*x954))+((cj2*x951))+new_r01);
13313evalcond[7]=((((-1.0)*cj2*x955))+new_r10+x954);
13314if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
13315{
13316continue;
13317}
13318}
13319
13320{
13321std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13322vinfos[0].jointtype = 1;
13323vinfos[0].foffset = j0;
13324vinfos[0].indices[0] = _ij0[0];
13325vinfos[0].indices[1] = _ij0[1];
13326vinfos[0].maxsolutions = _nj0;
13327vinfos[1].jointtype = 1;
13328vinfos[1].foffset = j1;
13329vinfos[1].indices[0] = _ij1[0];
13330vinfos[1].indices[1] = _ij1[1];
13331vinfos[1].maxsolutions = _nj1;
13332vinfos[2].jointtype = 1;
13333vinfos[2].foffset = j2;
13334vinfos[2].indices[0] = _ij2[0];
13335vinfos[2].indices[1] = _ij2[1];
13336vinfos[2].maxsolutions = _nj2;
13337vinfos[3].jointtype = 1;
13338vinfos[3].foffset = j3;
13339vinfos[3].indices[0] = _ij3[0];
13340vinfos[3].indices[1] = _ij3[1];
13341vinfos[3].maxsolutions = _nj3;
13342vinfos[4].jointtype = 1;
13343vinfos[4].foffset = j4;
13344vinfos[4].indices[0] = _ij4[0];
13345vinfos[4].indices[1] = _ij4[1];
13346vinfos[4].maxsolutions = _nj4;
13347vinfos[5].jointtype = 1;
13348vinfos[5].foffset = j5;
13349vinfos[5].indices[0] = _ij5[0];
13350vinfos[5].indices[1] = _ij5[1];
13351vinfos[5].maxsolutions = _nj5;
13352std::vector<int> vfree(0);
13353solutions.AddSolution(vinfos,vfree);
13354}
13355}
13356}
13357
13358}
13359
13360}
13361
13362}
13363} while(0);
13364if( bgotonextstatement )
13365{
13366bool bgotonextstatement = true;
13367do
13368{
13369evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959)));
13370evalcond[1]=new_r02;
13371evalcond[2]=new_r12;
13372evalcond[3]=new_r20;
13373evalcond[4]=new_r21;
13374if( 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 )
13375{
13376bgotonextstatement=false;
13377{
13378IkReal j0eval[3];
13379sj1=-1.0;
13380cj1=0;
13381j1=-1.5707963267949;
13382IkReal x957=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
13383j0eval[0]=x957;
13384j0eval[1]=IKsign(x957);
13385j0eval[2]=((IKabs((((new_r10*sj2))+((cj2*new_r11)))))+(IKabs((((new_r00*sj2))+((cj2*new_r01))))));
13386if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13387{
13388{
13389IkReal j0eval[3];
13390sj1=-1.0;
13391cj1=0;
13392j1=-1.5707963267949;
13393IkReal x958=((1.0)*sj2);
13394IkReal x959=((((-1.0)*new_r01*x958))+((cj2*new_r11)));
13395j0eval[0]=x959;
13396j0eval[1]=((IKabs(((-1.0)+(cj2*cj2)+(new_r11*new_r11))))+(IKabs(((((-1.0)*cj2*x958))+((new_r01*new_r11))))));
13397j0eval[2]=IKsign(x959);
13398if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13399{
13400{
13401IkReal j0eval[3];
13402sj1=-1.0;
13403cj1=0;
13404j1=-1.5707963267949;
13405IkReal x960=((1.0)*new_r00);
13406IkReal x961=((((-1.0)*sj2*x960))+((cj2*new_r10)));
13407j0eval[0]=x961;
13408j0eval[1]=IKsign(x961);
13409j0eval[2]=((IKabs(((cj2*cj2)+(((-1.0)*new_r00*x960)))))+(IKabs((((cj2*sj2))+(((-1.0)*new_r10*x960))))));
13410if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13411{
13412{
13413IkReal evalcond[1];
13414bool bgotonextstatement = true;
13415do
13416{
13417IkReal x962=((-1.0)*new_r00);
13418IkReal x964 = ((new_r10*new_r10)+(new_r00*new_r00));
13419if(IKabs(x964)==0){
13420continue;
13421}
13422IkReal x963=pow(x964,-0.5);
13423CheckValue<IkReal> x965 = IKatan2WithCheck(IkReal(new_r10),IkReal(x962),IKFAST_ATAN2_MAGTHRESH);
13424if(!x965.valid){
13425continue;
13426}
13427IkReal gconst28=((-1.0)*(x965.value));
13428IkReal gconst29=((-1.0)*new_r10*x963);
13429IkReal gconst30=(x962*x963);
13430CheckValue<IkReal> x966 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
13431if(!x966.valid){
13432continue;
13433}
13434evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((j2+(x966.value))))), 6.28318530717959)));
13435if( IKabs(evalcond[0]) < 0.0000050000000000 )
13436{
13437bgotonextstatement=false;
13438{
13439IkReal j0eval[3];
13440IkReal x967=((-1.0)*new_r00);
13441CheckValue<IkReal> x970 = IKatan2WithCheck(IkReal(new_r10),IkReal(x967),IKFAST_ATAN2_MAGTHRESH);
13442if(!x970.valid){
13443continue;
13444}
13445IkReal x968=((-1.0)*(x970.value));
13446IkReal x969=x963;
13447sj1=-1.0;
13448cj1=0;
13449j1=-1.5707963267949;
13450sj2=gconst29;
13451cj2=gconst30;
13452j2=x968;
13453IkReal gconst28=x968;
13454IkReal gconst29=((-1.0)*new_r10*x969);
13455IkReal gconst30=(x967*x969);
13456IkReal x971=new_r10*new_r10;
13457IkReal x972=(new_r00*new_r11);
13458IkReal x973=((((-1.0)*x972))+((new_r01*new_r10)));
13459IkReal x974=x963;
13460IkReal x975=((1.0)*new_r00*x974);
13461j0eval[0]=x973;
13462j0eval[1]=IKsign(x973);
13463j0eval[2]=((IKabs(((((-1.0)*new_r01*x975))+(((-1.0)*new_r10*x975)))))+(IKabs((((x971*x974))+((x972*x974))))));
13464if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13465{
13466{
13467IkReal j0eval[1];
13468IkReal x976=((-1.0)*new_r00);
13469CheckValue<IkReal> x979 = IKatan2WithCheck(IkReal(new_r10),IkReal(x976),IKFAST_ATAN2_MAGTHRESH);
13470if(!x979.valid){
13471continue;
13472}
13473IkReal x977=((-1.0)*(x979.value));
13474IkReal x978=x963;
13475sj1=-1.0;
13476cj1=0;
13477j1=-1.5707963267949;
13478sj2=gconst29;
13479cj2=gconst30;
13480j2=x977;
13481IkReal gconst28=x977;
13482IkReal gconst29=((-1.0)*new_r10*x978);
13483IkReal gconst30=(x976*x978);
13484IkReal x980=new_r10*new_r10;
13485CheckValue<IkReal> x983=IKPowWithIntegerCheck((x980+(new_r00*new_r00)),-1);
13486if(!x983.valid){
13487continue;
13488}
13489IkReal x981=x983.value;
13490IkReal x982=(new_r00*x981);
13491j0eval[0]=((IKabs((((new_r00*new_r11))+((x980*x981)))))+(IKabs((((new_r01*x982*(new_r00*new_r00)))+((new_r10*x982))+((new_r01*x980*x982))))));
13492if( IKabs(j0eval[0]) < 0.0000010000000000 )
13493{
13494{
13495IkReal j0eval[3];
13496IkReal x984=((-1.0)*new_r00);
13497CheckValue<IkReal> x987 = IKatan2WithCheck(IkReal(new_r10),IkReal(x984),IKFAST_ATAN2_MAGTHRESH);
13498if(!x987.valid){
13499continue;
13500}
13501IkReal x985=((-1.0)*(x987.value));
13502IkReal x986=x963;
13503sj1=-1.0;
13504cj1=0;
13505j1=-1.5707963267949;
13506sj2=gconst29;
13507cj2=gconst30;
13508j2=x985;
13509IkReal gconst28=x985;
13510IkReal gconst29=((-1.0)*new_r10*x986);
13511IkReal gconst30=(x984*x986);
13512IkReal x988=new_r10*new_r10;
13513IkReal x989=(((new_r10*new_r11))+((new_r00*new_r01)));
13514IkReal x990=x963;
13515IkReal x991=((1.0)*new_r10*x990);
13516j0eval[0]=x989;
13517j0eval[1]=IKsign(x989);
13518j0eval[2]=((IKabs(((((-1.0)*new_r11*x991))+(((-1.0)*new_r00*x991)))))+(IKabs((((x988*x990))+(((-1.0)*new_r01*x991))))));
13519if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13520{
13521{
13522IkReal evalcond[2];
13523bool bgotonextstatement = true;
13524do
13525{
13526evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
13527if( IKabs(evalcond[0]) < 0.0000050000000000 )
13528{
13529bgotonextstatement=false;
13530{
13531IkReal j0eval[1];
13532CheckValue<IkReal> x993 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
13533if(!x993.valid){
13534continue;
13535}
13536IkReal x992=((-1.0)*(x993.value));
13537sj1=-1.0;
13538cj1=0;
13539j1=-1.5707963267949;
13540sj2=gconst29;
13541cj2=gconst30;
13542j2=x992;
13543new_r11=0;
13544new_r00=0;
13545IkReal gconst28=x992;
13546IkReal x994 = new_r10*new_r10;
13547if(IKabs(x994)==0){
13548continue;
13549}
13550IkReal gconst29=((-1.0)*new_r10*(pow(x994,-0.5)));
13551IkReal gconst30=0;
13552j0eval[0]=new_r01;
13553if( IKabs(j0eval[0]) < 0.0000010000000000 )
13554{
13555{
13556IkReal j0array[2], cj0array[2], sj0array[2];
13557bool j0valid[2]={false};
13558_nj0 = 2;
13559CheckValue<IkReal> x995=IKPowWithIntegerCheck(gconst29,-1);
13560if(!x995.valid){
13561continue;
13562}
13563sj0array[0]=(new_r01*(x995.value));
13564if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
13565{
13566 j0valid[0] = j0valid[1] = true;
13567 j0array[0] = IKasin(sj0array[0]);
13568 cj0array[0] = IKcos(j0array[0]);
13569 sj0array[1] = sj0array[0];
13570 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
13571 cj0array[1] = -cj0array[0];
13572}
13573else if( isnan(sj0array[0]) )
13574{
13575 // probably any value will work
13576 j0valid[0] = true;
13577 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
13578}
13579for(int ij0 = 0; ij0 < 2; ++ij0)
13580{
13581if( !j0valid[ij0] )
13582{
13583 continue;
13584}
13585_ij0[0] = ij0; _ij0[1] = -1;
13586for(int iij0 = ij0+1; iij0 < 2; ++iij0)
13587{
13588if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13589{
13590 j0valid[iij0]=false; _ij0[1] = iij0; break;
13591}
13592}
13593j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13594{
13595IkReal evalcond[6];
13596IkReal x996=IKcos(j0);
13597IkReal x997=IKsin(j0);
13598IkReal x998=((1.0)*gconst29);
13599IkReal x999=((-1.0)*x996);
13600evalcond[0]=(new_r01*x996);
13601evalcond[1]=(new_r10*x999);
13602evalcond[2]=(gconst29*x999);
13603evalcond[3]=(gconst29+(((-1.0)*new_r01*x997)));
13604evalcond[4]=((((-1.0)*x997*x998))+new_r10);
13605evalcond[5]=(((new_r10*x997))+(((-1.0)*x998)));
13606if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
13607{
13608continue;
13609}
13610}
13611
13612{
13613std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13614vinfos[0].jointtype = 1;
13615vinfos[0].foffset = j0;
13616vinfos[0].indices[0] = _ij0[0];
13617vinfos[0].indices[1] = _ij0[1];
13618vinfos[0].maxsolutions = _nj0;
13619vinfos[1].jointtype = 1;
13620vinfos[1].foffset = j1;
13621vinfos[1].indices[0] = _ij1[0];
13622vinfos[1].indices[1] = _ij1[1];
13623vinfos[1].maxsolutions = _nj1;
13624vinfos[2].jointtype = 1;
13625vinfos[2].foffset = j2;
13626vinfos[2].indices[0] = _ij2[0];
13627vinfos[2].indices[1] = _ij2[1];
13628vinfos[2].maxsolutions = _nj2;
13629vinfos[3].jointtype = 1;
13630vinfos[3].foffset = j3;
13631vinfos[3].indices[0] = _ij3[0];
13632vinfos[3].indices[1] = _ij3[1];
13633vinfos[3].maxsolutions = _nj3;
13634vinfos[4].jointtype = 1;
13635vinfos[4].foffset = j4;
13636vinfos[4].indices[0] = _ij4[0];
13637vinfos[4].indices[1] = _ij4[1];
13638vinfos[4].maxsolutions = _nj4;
13639vinfos[5].jointtype = 1;
13640vinfos[5].foffset = j5;
13641vinfos[5].indices[0] = _ij5[0];
13642vinfos[5].indices[1] = _ij5[1];
13643vinfos[5].maxsolutions = _nj5;
13644std::vector<int> vfree(0);
13645solutions.AddSolution(vinfos,vfree);
13646}
13647}
13648}
13649
13650} else
13651{
13652{
13653IkReal j0array[2], cj0array[2], sj0array[2];
13654bool j0valid[2]={false};
13655_nj0 = 2;
13656CheckValue<IkReal> x1000=IKPowWithIntegerCheck(new_r01,-1);
13657if(!x1000.valid){
13658continue;
13659}
13660sj0array[0]=(gconst29*(x1000.value));
13661if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
13662{
13663 j0valid[0] = j0valid[1] = true;
13664 j0array[0] = IKasin(sj0array[0]);
13665 cj0array[0] = IKcos(j0array[0]);
13666 sj0array[1] = sj0array[0];
13667 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
13668 cj0array[1] = -cj0array[0];
13669}
13670else if( isnan(sj0array[0]) )
13671{
13672 // probably any value will work
13673 j0valid[0] = true;
13674 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
13675}
13676for(int ij0 = 0; ij0 < 2; ++ij0)
13677{
13678if( !j0valid[ij0] )
13679{
13680 continue;
13681}
13682_ij0[0] = ij0; _ij0[1] = -1;
13683for(int iij0 = ij0+1; iij0 < 2; ++iij0)
13684{
13685if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13686{
13687 j0valid[iij0]=false; _ij0[1] = iij0; break;
13688}
13689}
13690j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13691{
13692IkReal evalcond[6];
13693IkReal x1001=IKcos(j0);
13694IkReal x1002=IKsin(j0);
13695IkReal x1003=((1.0)*gconst29);
13696IkReal x1004=(x1002*x1003);
13697IkReal x1005=((-1.0)*x1001);
13698evalcond[0]=(new_r01*x1001);
13699evalcond[1]=(new_r10*x1005);
13700evalcond[2]=(gconst29*x1005);
13701evalcond[3]=((((-1.0)*x1004))+new_r01);
13702evalcond[4]=((((-1.0)*x1004))+new_r10);
13703evalcond[5]=((((-1.0)*x1003))+((new_r10*x1002)));
13704if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
13705{
13706continue;
13707}
13708}
13709
13710{
13711std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13712vinfos[0].jointtype = 1;
13713vinfos[0].foffset = j0;
13714vinfos[0].indices[0] = _ij0[0];
13715vinfos[0].indices[1] = _ij0[1];
13716vinfos[0].maxsolutions = _nj0;
13717vinfos[1].jointtype = 1;
13718vinfos[1].foffset = j1;
13719vinfos[1].indices[0] = _ij1[0];
13720vinfos[1].indices[1] = _ij1[1];
13721vinfos[1].maxsolutions = _nj1;
13722vinfos[2].jointtype = 1;
13723vinfos[2].foffset = j2;
13724vinfos[2].indices[0] = _ij2[0];
13725vinfos[2].indices[1] = _ij2[1];
13726vinfos[2].maxsolutions = _nj2;
13727vinfos[3].jointtype = 1;
13728vinfos[3].foffset = j3;
13729vinfos[3].indices[0] = _ij3[0];
13730vinfos[3].indices[1] = _ij3[1];
13731vinfos[3].maxsolutions = _nj3;
13732vinfos[4].jointtype = 1;
13733vinfos[4].foffset = j4;
13734vinfos[4].indices[0] = _ij4[0];
13735vinfos[4].indices[1] = _ij4[1];
13736vinfos[4].maxsolutions = _nj4;
13737vinfos[5].jointtype = 1;
13738vinfos[5].foffset = j5;
13739vinfos[5].indices[0] = _ij5[0];
13740vinfos[5].indices[1] = _ij5[1];
13741vinfos[5].maxsolutions = _nj5;
13742std::vector<int> vfree(0);
13743solutions.AddSolution(vinfos,vfree);
13744}
13745}
13746}
13747
13748}
13749
13750}
13751
13752}
13753} while(0);
13754if( bgotonextstatement )
13755{
13756bool bgotonextstatement = true;
13757do
13758{
13759evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
13760evalcond[1]=gconst29;
13761if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
13762{
13763bgotonextstatement=false;
13764{
13765IkReal j0eval[3];
13766IkReal x1006=((-1.0)*new_r00);
13767CheckValue<IkReal> x1008 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1006),IKFAST_ATAN2_MAGTHRESH);
13768if(!x1008.valid){
13769continue;
13770}
13771IkReal x1007=((-1.0)*(x1008.value));
13772sj1=-1.0;
13773cj1=0;
13774j1=-1.5707963267949;
13775sj2=gconst29;
13776cj2=gconst30;
13777j2=x1007;
13778new_r11=0;
13779new_r01=0;
13780new_r22=0;
13781new_r20=0;
13782IkReal gconst28=x1007;
13783IkReal gconst29=((-1.0)*new_r10);
13784IkReal gconst30=x1006;
13785j0eval[0]=-1.0;
13786j0eval[1]=-1.0;
13787j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10))));
13788if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13789{
13790{
13791IkReal j0eval[3];
13792IkReal x1009=((-1.0)*new_r00);
13793CheckValue<IkReal> x1011 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1009),IKFAST_ATAN2_MAGTHRESH);
13794if(!x1011.valid){
13795continue;
13796}
13797IkReal x1010=((-1.0)*(x1011.value));
13798sj1=-1.0;
13799cj1=0;
13800j1=-1.5707963267949;
13801sj2=gconst29;
13802cj2=gconst30;
13803j2=x1010;
13804new_r11=0;
13805new_r01=0;
13806new_r22=0;
13807new_r20=0;
13808IkReal gconst28=x1010;
13809IkReal gconst29=((-1.0)*new_r10);
13810IkReal gconst30=x1009;
13811j0eval[0]=1.0;
13812j0eval[1]=1.0;
13813j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10))));
13814if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13815{
13816{
13817IkReal j0eval[3];
13818IkReal x1012=((-1.0)*new_r00);
13819CheckValue<IkReal> x1014 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1012),IKFAST_ATAN2_MAGTHRESH);
13820if(!x1014.valid){
13821continue;
13822}
13823IkReal x1013=((-1.0)*(x1014.value));
13824sj1=-1.0;
13825cj1=0;
13826j1=-1.5707963267949;
13827sj2=gconst29;
13828cj2=gconst30;
13829j2=x1013;
13830new_r11=0;
13831new_r01=0;
13832new_r22=0;
13833new_r20=0;
13834IkReal gconst28=x1013;
13835IkReal gconst29=((-1.0)*new_r10);
13836IkReal gconst30=x1012;
13837j0eval[0]=1.0;
13838j0eval[1]=1.0;
13839j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10))));
13840if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
13841{
13842continue; // 3 cases reached
13843
13844} else
13845{
13846{
13847IkReal j0array[1], cj0array[1], sj0array[1];
13848bool j0valid[1]={false};
13849_nj0 = 1;
13850CheckValue<IkReal> x1015=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst29*new_r10))+(((-1.0)*gconst30*new_r00)))),-1);
13851if(!x1015.valid){
13852continue;
13853}
13854CheckValue<IkReal> x1016 = IKatan2WithCheck(IkReal(gconst30*gconst30),IkReal(((-1.0)*gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH);
13855if(!x1016.valid){
13856continue;
13857}
13858j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1015.value)))+(x1016.value));
13859sj0array[0]=IKsin(j0array[0]);
13860cj0array[0]=IKcos(j0array[0]);
13861if( j0array[0] > IKPI )
13862{
13863 j0array[0]-=IK2PI;
13864}
13865else if( j0array[0] < -IKPI )
13866{ j0array[0]+=IK2PI;
13867}
13868j0valid[0] = true;
13869for(int ij0 = 0; ij0 < 1; ++ij0)
13870{
13871if( !j0valid[ij0] )
13872{
13873 continue;
13874}
13875_ij0[0] = ij0; _ij0[1] = -1;
13876for(int iij0 = ij0+1; iij0 < 1; ++iij0)
13877{
13878if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13879{
13880 j0valid[iij0]=false; _ij0[1] = iij0; break;
13881}
13882}
13883j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13884{
13885IkReal evalcond[6];
13886IkReal x1017=IKsin(j0);
13887IkReal x1018=IKcos(j0);
13888IkReal x1019=((1.0)*x1017);
13889IkReal x1020=(gconst29*x1018);
13890IkReal x1021=((1.0)*x1018);
13891IkReal x1022=(((gconst30*x1021))+((gconst29*x1019)));
13892evalcond[0]=(x1020+(((-1.0)*gconst30*x1019)));
13893evalcond[1]=(gconst30+(((-1.0)*new_r10*x1021))+((new_r00*x1017)));
13894evalcond[2]=((((-1.0)*x1020))+((gconst30*x1017))+new_r00);
13895evalcond[3]=((-1.0)*x1022);
13896evalcond[4]=(((new_r10*x1017))+((new_r00*x1018))+(((-1.0)*gconst29)));
13897evalcond[5]=((((-1.0)*x1022))+new_r10);
13898if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
13899{
13900continue;
13901}
13902}
13903
13904{
13905std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13906vinfos[0].jointtype = 1;
13907vinfos[0].foffset = j0;
13908vinfos[0].indices[0] = _ij0[0];
13909vinfos[0].indices[1] = _ij0[1];
13910vinfos[0].maxsolutions = _nj0;
13911vinfos[1].jointtype = 1;
13912vinfos[1].foffset = j1;
13913vinfos[1].indices[0] = _ij1[0];
13914vinfos[1].indices[1] = _ij1[1];
13915vinfos[1].maxsolutions = _nj1;
13916vinfos[2].jointtype = 1;
13917vinfos[2].foffset = j2;
13918vinfos[2].indices[0] = _ij2[0];
13919vinfos[2].indices[1] = _ij2[1];
13920vinfos[2].maxsolutions = _nj2;
13921vinfos[3].jointtype = 1;
13922vinfos[3].foffset = j3;
13923vinfos[3].indices[0] = _ij3[0];
13924vinfos[3].indices[1] = _ij3[1];
13925vinfos[3].maxsolutions = _nj3;
13926vinfos[4].jointtype = 1;
13927vinfos[4].foffset = j4;
13928vinfos[4].indices[0] = _ij4[0];
13929vinfos[4].indices[1] = _ij4[1];
13930vinfos[4].maxsolutions = _nj4;
13931vinfos[5].jointtype = 1;
13932vinfos[5].foffset = j5;
13933vinfos[5].indices[0] = _ij5[0];
13934vinfos[5].indices[1] = _ij5[1];
13935vinfos[5].maxsolutions = _nj5;
13936std::vector<int> vfree(0);
13937solutions.AddSolution(vinfos,vfree);
13938}
13939}
13940}
13941
13942}
13943
13944}
13945
13946} else
13947{
13948{
13949IkReal j0array[1], cj0array[1], sj0array[1];
13950bool j0valid[1]={false};
13951_nj0 = 1;
13952CheckValue<IkReal> x1023=IKPowWithIntegerCheck(IKsign(((gconst29*gconst29)+(gconst30*gconst30))),-1);
13953if(!x1023.valid){
13954continue;
13955}
13956CheckValue<IkReal> x1024 = IKatan2WithCheck(IkReal((gconst29*new_r10)),IkReal((gconst30*new_r10)),IKFAST_ATAN2_MAGTHRESH);
13957if(!x1024.valid){
13958continue;
13959}
13960j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1023.value)))+(x1024.value));
13961sj0array[0]=IKsin(j0array[0]);
13962cj0array[0]=IKcos(j0array[0]);
13963if( j0array[0] > IKPI )
13964{
13965 j0array[0]-=IK2PI;
13966}
13967else if( j0array[0] < -IKPI )
13968{ j0array[0]+=IK2PI;
13969}
13970j0valid[0] = true;
13971for(int ij0 = 0; ij0 < 1; ++ij0)
13972{
13973if( !j0valid[ij0] )
13974{
13975 continue;
13976}
13977_ij0[0] = ij0; _ij0[1] = -1;
13978for(int iij0 = ij0+1; iij0 < 1; ++iij0)
13979{
13980if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
13981{
13982 j0valid[iij0]=false; _ij0[1] = iij0; break;
13983}
13984}
13985j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
13986{
13987IkReal evalcond[6];
13988IkReal x1025=IKsin(j0);
13989IkReal x1026=IKcos(j0);
13990IkReal x1027=((1.0)*x1025);
13991IkReal x1028=(gconst29*x1026);
13992IkReal x1029=((1.0)*x1026);
13993IkReal x1030=(((gconst30*x1029))+((gconst29*x1027)));
13994evalcond[0]=(x1028+(((-1.0)*gconst30*x1027)));
13995evalcond[1]=(gconst30+(((-1.0)*new_r10*x1029))+((new_r00*x1025)));
13996evalcond[2]=((((-1.0)*x1028))+((gconst30*x1025))+new_r00);
13997evalcond[3]=((-1.0)*x1030);
13998evalcond[4]=(((new_r10*x1025))+(((-1.0)*gconst29))+((new_r00*x1026)));
13999evalcond[5]=((((-1.0)*x1030))+new_r10);
14000if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14001{
14002continue;
14003}
14004}
14005
14006{
14007std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14008vinfos[0].jointtype = 1;
14009vinfos[0].foffset = j0;
14010vinfos[0].indices[0] = _ij0[0];
14011vinfos[0].indices[1] = _ij0[1];
14012vinfos[0].maxsolutions = _nj0;
14013vinfos[1].jointtype = 1;
14014vinfos[1].foffset = j1;
14015vinfos[1].indices[0] = _ij1[0];
14016vinfos[1].indices[1] = _ij1[1];
14017vinfos[1].maxsolutions = _nj1;
14018vinfos[2].jointtype = 1;
14019vinfos[2].foffset = j2;
14020vinfos[2].indices[0] = _ij2[0];
14021vinfos[2].indices[1] = _ij2[1];
14022vinfos[2].maxsolutions = _nj2;
14023vinfos[3].jointtype = 1;
14024vinfos[3].foffset = j3;
14025vinfos[3].indices[0] = _ij3[0];
14026vinfos[3].indices[1] = _ij3[1];
14027vinfos[3].maxsolutions = _nj3;
14028vinfos[4].jointtype = 1;
14029vinfos[4].foffset = j4;
14030vinfos[4].indices[0] = _ij4[0];
14031vinfos[4].indices[1] = _ij4[1];
14032vinfos[4].maxsolutions = _nj4;
14033vinfos[5].jointtype = 1;
14034vinfos[5].foffset = j5;
14035vinfos[5].indices[0] = _ij5[0];
14036vinfos[5].indices[1] = _ij5[1];
14037vinfos[5].maxsolutions = _nj5;
14038std::vector<int> vfree(0);
14039solutions.AddSolution(vinfos,vfree);
14040}
14041}
14042}
14043
14044}
14045
14046}
14047
14048} else
14049{
14050{
14051IkReal j0array[1], cj0array[1], sj0array[1];
14052bool j0valid[1]={false};
14053_nj0 = 1;
14054CheckValue<IkReal> x1031=IKPowWithIntegerCheck(IKsign((((gconst29*new_r10))+((gconst30*new_r00)))),-1);
14055if(!x1031.valid){
14056continue;
14057}
14058CheckValue<IkReal> x1032 = IKatan2WithCheck(IkReal(gconst29*gconst29),IkReal((gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH);
14059if(!x1032.valid){
14060continue;
14061}
14062j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1031.value)))+(x1032.value));
14063sj0array[0]=IKsin(j0array[0]);
14064cj0array[0]=IKcos(j0array[0]);
14065if( j0array[0] > IKPI )
14066{
14067 j0array[0]-=IK2PI;
14068}
14069else if( j0array[0] < -IKPI )
14070{ j0array[0]+=IK2PI;
14071}
14072j0valid[0] = true;
14073for(int ij0 = 0; ij0 < 1; ++ij0)
14074{
14075if( !j0valid[ij0] )
14076{
14077 continue;
14078}
14079_ij0[0] = ij0; _ij0[1] = -1;
14080for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14081{
14082if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14083{
14084 j0valid[iij0]=false; _ij0[1] = iij0; break;
14085}
14086}
14087j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14088{
14089IkReal evalcond[6];
14090IkReal x1033=IKsin(j0);
14091IkReal x1034=IKcos(j0);
14092IkReal x1035=((1.0)*x1033);
14093IkReal x1036=(gconst29*x1034);
14094IkReal x1037=((1.0)*x1034);
14095IkReal x1038=(((gconst30*x1037))+((gconst29*x1035)));
14096evalcond[0]=(x1036+(((-1.0)*gconst30*x1035)));
14097evalcond[1]=(gconst30+(((-1.0)*new_r10*x1037))+((new_r00*x1033)));
14098evalcond[2]=((((-1.0)*x1036))+((gconst30*x1033))+new_r00);
14099evalcond[3]=((-1.0)*x1038);
14100evalcond[4]=(((new_r10*x1033))+(((-1.0)*gconst29))+((new_r00*x1034)));
14101evalcond[5]=((((-1.0)*x1038))+new_r10);
14102if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14103{
14104continue;
14105}
14106}
14107
14108{
14109std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14110vinfos[0].jointtype = 1;
14111vinfos[0].foffset = j0;
14112vinfos[0].indices[0] = _ij0[0];
14113vinfos[0].indices[1] = _ij0[1];
14114vinfos[0].maxsolutions = _nj0;
14115vinfos[1].jointtype = 1;
14116vinfos[1].foffset = j1;
14117vinfos[1].indices[0] = _ij1[0];
14118vinfos[1].indices[1] = _ij1[1];
14119vinfos[1].maxsolutions = _nj1;
14120vinfos[2].jointtype = 1;
14121vinfos[2].foffset = j2;
14122vinfos[2].indices[0] = _ij2[0];
14123vinfos[2].indices[1] = _ij2[1];
14124vinfos[2].maxsolutions = _nj2;
14125vinfos[3].jointtype = 1;
14126vinfos[3].foffset = j3;
14127vinfos[3].indices[0] = _ij3[0];
14128vinfos[3].indices[1] = _ij3[1];
14129vinfos[3].maxsolutions = _nj3;
14130vinfos[4].jointtype = 1;
14131vinfos[4].foffset = j4;
14132vinfos[4].indices[0] = _ij4[0];
14133vinfos[4].indices[1] = _ij4[1];
14134vinfos[4].maxsolutions = _nj4;
14135vinfos[5].jointtype = 1;
14136vinfos[5].foffset = j5;
14137vinfos[5].indices[0] = _ij5[0];
14138vinfos[5].indices[1] = _ij5[1];
14139vinfos[5].maxsolutions = _nj5;
14140std::vector<int> vfree(0);
14141solutions.AddSolution(vinfos,vfree);
14142}
14143}
14144}
14145
14146}
14147
14148}
14149
14150}
14151} while(0);
14152if( bgotonextstatement )
14153{
14154bool bgotonextstatement = true;
14155do
14156{
14157evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
14158if( IKabs(evalcond[0]) < 0.0000050000000000 )
14159{
14160bgotonextstatement=false;
14161{
14162IkReal j0array[2], cj0array[2], sj0array[2];
14163bool j0valid[2]={false};
14164_nj0 = 2;
14165CheckValue<IkReal> x1039=IKPowWithIntegerCheck(gconst30,-1);
14166if(!x1039.valid){
14167continue;
14168}
14169sj0array[0]=(new_r11*(x1039.value));
14170if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
14171{
14172 j0valid[0] = j0valid[1] = true;
14173 j0array[0] = IKasin(sj0array[0]);
14174 cj0array[0] = IKcos(j0array[0]);
14175 sj0array[1] = sj0array[0];
14176 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
14177 cj0array[1] = -cj0array[0];
14178}
14179else if( isnan(sj0array[0]) )
14180{
14181 // probably any value will work
14182 j0valid[0] = true;
14183 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
14184}
14185for(int ij0 = 0; ij0 < 2; ++ij0)
14186{
14187if( !j0valid[ij0] )
14188{
14189 continue;
14190}
14191_ij0[0] = ij0; _ij0[1] = -1;
14192for(int iij0 = ij0+1; iij0 < 2; ++iij0)
14193{
14194if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14195{
14196 j0valid[iij0]=false; _ij0[1] = iij0; break;
14197}
14198}
14199j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14200{
14201IkReal evalcond[6];
14202IkReal x1040=IKcos(j0);
14203IkReal x1041=IKsin(j0);
14204evalcond[0]=(new_r11*x1040);
14205evalcond[1]=(new_r00*x1040);
14206evalcond[2]=((-1.0)*gconst30*x1040);
14207evalcond[3]=(gconst30+((new_r00*x1041)));
14208evalcond[4]=(new_r00+((gconst30*x1041)));
14209evalcond[5]=(((new_r11*x1041))+(((-1.0)*gconst30)));
14210if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
14211{
14212continue;
14213}
14214}
14215
14216{
14217std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14218vinfos[0].jointtype = 1;
14219vinfos[0].foffset = j0;
14220vinfos[0].indices[0] = _ij0[0];
14221vinfos[0].indices[1] = _ij0[1];
14222vinfos[0].maxsolutions = _nj0;
14223vinfos[1].jointtype = 1;
14224vinfos[1].foffset = j1;
14225vinfos[1].indices[0] = _ij1[0];
14226vinfos[1].indices[1] = _ij1[1];
14227vinfos[1].maxsolutions = _nj1;
14228vinfos[2].jointtype = 1;
14229vinfos[2].foffset = j2;
14230vinfos[2].indices[0] = _ij2[0];
14231vinfos[2].indices[1] = _ij2[1];
14232vinfos[2].maxsolutions = _nj2;
14233vinfos[3].jointtype = 1;
14234vinfos[3].foffset = j3;
14235vinfos[3].indices[0] = _ij3[0];
14236vinfos[3].indices[1] = _ij3[1];
14237vinfos[3].maxsolutions = _nj3;
14238vinfos[4].jointtype = 1;
14239vinfos[4].foffset = j4;
14240vinfos[4].indices[0] = _ij4[0];
14241vinfos[4].indices[1] = _ij4[1];
14242vinfos[4].maxsolutions = _nj4;
14243vinfos[5].jointtype = 1;
14244vinfos[5].foffset = j5;
14245vinfos[5].indices[0] = _ij5[0];
14246vinfos[5].indices[1] = _ij5[1];
14247vinfos[5].maxsolutions = _nj5;
14248std::vector<int> vfree(0);
14249solutions.AddSolution(vinfos,vfree);
14250}
14251}
14252}
14253
14254}
14255} while(0);
14256if( bgotonextstatement )
14257{
14258bool bgotonextstatement = true;
14259do
14260{
14261evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
14262if( IKabs(evalcond[0]) < 0.0000050000000000 )
14263{
14264bgotonextstatement=false;
14265{
14266IkReal j0eval[1];
14267IkReal x1042=((-1.0)*new_r00);
14268CheckValue<IkReal> x1044 = IKatan2WithCheck(IkReal(0),IkReal(x1042),IKFAST_ATAN2_MAGTHRESH);
14269if(!x1044.valid){
14270continue;
14271}
14272IkReal x1043=((-1.0)*(x1044.value));
14273sj1=-1.0;
14274cj1=0;
14275j1=-1.5707963267949;
14276sj2=gconst29;
14277cj2=gconst30;
14278j2=x1043;
14279new_r11=0;
14280new_r10=0;
14281new_r22=0;
14282new_r02=0;
14283IkReal gconst28=x1043;
14284IkReal gconst29=0;
14285IkReal x1045 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14286if(IKabs(x1045)==0){
14287continue;
14288}
14289IkReal gconst30=(x1042*(pow(x1045,-0.5)));
14290j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
14291if( IKabs(j0eval[0]) < 0.0000010000000000 )
14292{
14293{
14294IkReal j0eval[1];
14295IkReal x1046=((-1.0)*new_r00);
14296CheckValue<IkReal> x1048 = IKatan2WithCheck(IkReal(0),IkReal(x1046),IKFAST_ATAN2_MAGTHRESH);
14297if(!x1048.valid){
14298continue;
14299}
14300IkReal x1047=((-1.0)*(x1048.value));
14301sj1=-1.0;
14302cj1=0;
14303j1=-1.5707963267949;
14304sj2=gconst29;
14305cj2=gconst30;
14306j2=x1047;
14307new_r11=0;
14308new_r10=0;
14309new_r22=0;
14310new_r02=0;
14311IkReal gconst28=x1047;
14312IkReal gconst29=0;
14313IkReal x1049 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14314if(IKabs(x1049)==0){
14315continue;
14316}
14317IkReal gconst30=(x1046*(pow(x1049,-0.5)));
14318j0eval[0]=new_r00;
14319if( IKabs(j0eval[0]) < 0.0000010000000000 )
14320{
14321{
14322IkReal j0eval[2];
14323IkReal x1050=((-1.0)*new_r00);
14324CheckValue<IkReal> x1052 = IKatan2WithCheck(IkReal(0),IkReal(x1050),IKFAST_ATAN2_MAGTHRESH);
14325if(!x1052.valid){
14326continue;
14327}
14328IkReal x1051=((-1.0)*(x1052.value));
14329sj1=-1.0;
14330cj1=0;
14331j1=-1.5707963267949;
14332sj2=gconst29;
14333cj2=gconst30;
14334j2=x1051;
14335new_r11=0;
14336new_r10=0;
14337new_r22=0;
14338new_r02=0;
14339IkReal gconst28=x1051;
14340IkReal gconst29=0;
14341IkReal x1053 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
14342if(IKabs(x1053)==0){
14343continue;
14344}
14345IkReal gconst30=(x1050*(pow(x1053,-0.5)));
14346j0eval[0]=new_r00;
14347j0eval[1]=new_r01;
14348if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
14349{
14350continue; // 3 cases reached
14351
14352} else
14353{
14354{
14355IkReal j0array[1], cj0array[1], sj0array[1];
14356bool j0valid[1]={false};
14357_nj0 = 1;
14358CheckValue<IkReal> x1054=IKPowWithIntegerCheck(new_r00,-1);
14359if(!x1054.valid){
14360continue;
14361}
14362CheckValue<IkReal> x1055=IKPowWithIntegerCheck(new_r01,-1);
14363if(!x1055.valid){
14364continue;
14365}
14366if( IKabs(((-1.0)*gconst30*(x1054.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst30*(x1055.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1054.value)))+IKsqr((gconst30*(x1055.value)))-1) <= IKFAST_SINCOS_THRESH )
14367 continue;
14368j0array[0]=IKatan2(((-1.0)*gconst30*(x1054.value)), (gconst30*(x1055.value)));
14369sj0array[0]=IKsin(j0array[0]);
14370cj0array[0]=IKcos(j0array[0]);
14371if( j0array[0] > IKPI )
14372{
14373 j0array[0]-=IK2PI;
14374}
14375else if( j0array[0] < -IKPI )
14376{ j0array[0]+=IK2PI;
14377}
14378j0valid[0] = true;
14379for(int ij0 = 0; ij0 < 1; ++ij0)
14380{
14381if( !j0valid[ij0] )
14382{
14383 continue;
14384}
14385_ij0[0] = ij0; _ij0[1] = -1;
14386for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14387{
14388if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14389{
14390 j0valid[iij0]=false; _ij0[1] = iij0; break;
14391}
14392}
14393j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14394{
14395IkReal evalcond[8];
14396IkReal x1056=IKsin(j0);
14397IkReal x1057=IKcos(j0);
14398IkReal x1058=((1.0)*gconst30);
14399IkReal x1059=((-1.0)*gconst30);
14400evalcond[0]=(new_r00*x1057);
14401evalcond[1]=((-1.0)*new_r01*x1056);
14402evalcond[2]=(x1056*x1059);
14403evalcond[3]=(x1057*x1059);
14404evalcond[4]=(gconst30+((new_r00*x1056)));
14405evalcond[5]=(((gconst30*x1056))+new_r00);
14406evalcond[6]=((((-1.0)*x1057*x1058))+new_r01);
14407evalcond[7]=((((-1.0)*x1058))+((new_r01*x1057)));
14408if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
14409{
14410continue;
14411}
14412}
14413
14414{
14415std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14416vinfos[0].jointtype = 1;
14417vinfos[0].foffset = j0;
14418vinfos[0].indices[0] = _ij0[0];
14419vinfos[0].indices[1] = _ij0[1];
14420vinfos[0].maxsolutions = _nj0;
14421vinfos[1].jointtype = 1;
14422vinfos[1].foffset = j1;
14423vinfos[1].indices[0] = _ij1[0];
14424vinfos[1].indices[1] = _ij1[1];
14425vinfos[1].maxsolutions = _nj1;
14426vinfos[2].jointtype = 1;
14427vinfos[2].foffset = j2;
14428vinfos[2].indices[0] = _ij2[0];
14429vinfos[2].indices[1] = _ij2[1];
14430vinfos[2].maxsolutions = _nj2;
14431vinfos[3].jointtype = 1;
14432vinfos[3].foffset = j3;
14433vinfos[3].indices[0] = _ij3[0];
14434vinfos[3].indices[1] = _ij3[1];
14435vinfos[3].maxsolutions = _nj3;
14436vinfos[4].jointtype = 1;
14437vinfos[4].foffset = j4;
14438vinfos[4].indices[0] = _ij4[0];
14439vinfos[4].indices[1] = _ij4[1];
14440vinfos[4].maxsolutions = _nj4;
14441vinfos[5].jointtype = 1;
14442vinfos[5].foffset = j5;
14443vinfos[5].indices[0] = _ij5[0];
14444vinfos[5].indices[1] = _ij5[1];
14445vinfos[5].maxsolutions = _nj5;
14446std::vector<int> vfree(0);
14447solutions.AddSolution(vinfos,vfree);
14448}
14449}
14450}
14451
14452}
14453
14454}
14455
14456} else
14457{
14458{
14459IkReal j0array[1], cj0array[1], sj0array[1];
14460bool j0valid[1]={false};
14461_nj0 = 1;
14462CheckValue<IkReal> x1060=IKPowWithIntegerCheck(new_r00,-1);
14463if(!x1060.valid){
14464continue;
14465}
14466CheckValue<IkReal> x1061=IKPowWithIntegerCheck(gconst30,-1);
14467if(!x1061.valid){
14468continue;
14469}
14470if( IKabs(((-1.0)*gconst30*(x1060.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1061.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1060.value)))+IKsqr((new_r01*(x1061.value)))-1) <= IKFAST_SINCOS_THRESH )
14471 continue;
14472j0array[0]=IKatan2(((-1.0)*gconst30*(x1060.value)), (new_r01*(x1061.value)));
14473sj0array[0]=IKsin(j0array[0]);
14474cj0array[0]=IKcos(j0array[0]);
14475if( j0array[0] > IKPI )
14476{
14477 j0array[0]-=IK2PI;
14478}
14479else if( j0array[0] < -IKPI )
14480{ j0array[0]+=IK2PI;
14481}
14482j0valid[0] = true;
14483for(int ij0 = 0; ij0 < 1; ++ij0)
14484{
14485if( !j0valid[ij0] )
14486{
14487 continue;
14488}
14489_ij0[0] = ij0; _ij0[1] = -1;
14490for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14491{
14492if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14493{
14494 j0valid[iij0]=false; _ij0[1] = iij0; break;
14495}
14496}
14497j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14498{
14499IkReal evalcond[8];
14500IkReal x1062=IKsin(j0);
14501IkReal x1063=IKcos(j0);
14502IkReal x1064=((1.0)*gconst30);
14503IkReal x1065=((-1.0)*gconst30);
14504evalcond[0]=(new_r00*x1063);
14505evalcond[1]=((-1.0)*new_r01*x1062);
14506evalcond[2]=(x1062*x1065);
14507evalcond[3]=(x1063*x1065);
14508evalcond[4]=(gconst30+((new_r00*x1062)));
14509evalcond[5]=(((gconst30*x1062))+new_r00);
14510evalcond[6]=((((-1.0)*x1063*x1064))+new_r01);
14511evalcond[7]=(((new_r01*x1063))+(((-1.0)*x1064)));
14512if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
14513{
14514continue;
14515}
14516}
14517
14518{
14519std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14520vinfos[0].jointtype = 1;
14521vinfos[0].foffset = j0;
14522vinfos[0].indices[0] = _ij0[0];
14523vinfos[0].indices[1] = _ij0[1];
14524vinfos[0].maxsolutions = _nj0;
14525vinfos[1].jointtype = 1;
14526vinfos[1].foffset = j1;
14527vinfos[1].indices[0] = _ij1[0];
14528vinfos[1].indices[1] = _ij1[1];
14529vinfos[1].maxsolutions = _nj1;
14530vinfos[2].jointtype = 1;
14531vinfos[2].foffset = j2;
14532vinfos[2].indices[0] = _ij2[0];
14533vinfos[2].indices[1] = _ij2[1];
14534vinfos[2].maxsolutions = _nj2;
14535vinfos[3].jointtype = 1;
14536vinfos[3].foffset = j3;
14537vinfos[3].indices[0] = _ij3[0];
14538vinfos[3].indices[1] = _ij3[1];
14539vinfos[3].maxsolutions = _nj3;
14540vinfos[4].jointtype = 1;
14541vinfos[4].foffset = j4;
14542vinfos[4].indices[0] = _ij4[0];
14543vinfos[4].indices[1] = _ij4[1];
14544vinfos[4].maxsolutions = _nj4;
14545vinfos[5].jointtype = 1;
14546vinfos[5].foffset = j5;
14547vinfos[5].indices[0] = _ij5[0];
14548vinfos[5].indices[1] = _ij5[1];
14549vinfos[5].maxsolutions = _nj5;
14550std::vector<int> vfree(0);
14551solutions.AddSolution(vinfos,vfree);
14552}
14553}
14554}
14555
14556}
14557
14558}
14559
14560} else
14561{
14562{
14563IkReal j0array[1], cj0array[1], sj0array[1];
14564bool j0valid[1]={false};
14565_nj0 = 1;
14566CheckValue<IkReal> x1066=IKPowWithIntegerCheck(IKsign(gconst30),-1);
14567if(!x1066.valid){
14568continue;
14569}
14570CheckValue<IkReal> x1067 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
14571if(!x1067.valid){
14572continue;
14573}
14574j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1066.value)))+(x1067.value));
14575sj0array[0]=IKsin(j0array[0]);
14576cj0array[0]=IKcos(j0array[0]);
14577if( j0array[0] > IKPI )
14578{
14579 j0array[0]-=IK2PI;
14580}
14581else if( j0array[0] < -IKPI )
14582{ j0array[0]+=IK2PI;
14583}
14584j0valid[0] = true;
14585for(int ij0 = 0; ij0 < 1; ++ij0)
14586{
14587if( !j0valid[ij0] )
14588{
14589 continue;
14590}
14591_ij0[0] = ij0; _ij0[1] = -1;
14592for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14593{
14594if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14595{
14596 j0valid[iij0]=false; _ij0[1] = iij0; break;
14597}
14598}
14599j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14600{
14601IkReal evalcond[8];
14602IkReal x1068=IKsin(j0);
14603IkReal x1069=IKcos(j0);
14604IkReal x1070=((1.0)*gconst30);
14605IkReal x1071=((-1.0)*gconst30);
14606evalcond[0]=(new_r00*x1069);
14607evalcond[1]=((-1.0)*new_r01*x1068);
14608evalcond[2]=(x1068*x1071);
14609evalcond[3]=(x1069*x1071);
14610evalcond[4]=(gconst30+((new_r00*x1068)));
14611evalcond[5]=(((gconst30*x1068))+new_r00);
14612evalcond[6]=(new_r01+(((-1.0)*x1069*x1070)));
14613evalcond[7]=(((new_r01*x1069))+(((-1.0)*x1070)));
14614if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
14615{
14616continue;
14617}
14618}
14619
14620{
14621std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14622vinfos[0].jointtype = 1;
14623vinfos[0].foffset = j0;
14624vinfos[0].indices[0] = _ij0[0];
14625vinfos[0].indices[1] = _ij0[1];
14626vinfos[0].maxsolutions = _nj0;
14627vinfos[1].jointtype = 1;
14628vinfos[1].foffset = j1;
14629vinfos[1].indices[0] = _ij1[0];
14630vinfos[1].indices[1] = _ij1[1];
14631vinfos[1].maxsolutions = _nj1;
14632vinfos[2].jointtype = 1;
14633vinfos[2].foffset = j2;
14634vinfos[2].indices[0] = _ij2[0];
14635vinfos[2].indices[1] = _ij2[1];
14636vinfos[2].maxsolutions = _nj2;
14637vinfos[3].jointtype = 1;
14638vinfos[3].foffset = j3;
14639vinfos[3].indices[0] = _ij3[0];
14640vinfos[3].indices[1] = _ij3[1];
14641vinfos[3].maxsolutions = _nj3;
14642vinfos[4].jointtype = 1;
14643vinfos[4].foffset = j4;
14644vinfos[4].indices[0] = _ij4[0];
14645vinfos[4].indices[1] = _ij4[1];
14646vinfos[4].maxsolutions = _nj4;
14647vinfos[5].jointtype = 1;
14648vinfos[5].foffset = j5;
14649vinfos[5].indices[0] = _ij5[0];
14650vinfos[5].indices[1] = _ij5[1];
14651vinfos[5].maxsolutions = _nj5;
14652std::vector<int> vfree(0);
14653solutions.AddSolution(vinfos,vfree);
14654}
14655}
14656}
14657
14658}
14659
14660}
14661
14662}
14663} while(0);
14664if( bgotonextstatement )
14665{
14666bool bgotonextstatement = true;
14667do
14668{
14669evalcond[0]=IKabs(new_r10);
14670if( IKabs(evalcond[0]) < 0.0000050000000000 )
14671{
14672bgotonextstatement=false;
14673{
14674IkReal j0eval[1];
14675IkReal x1072=((-1.0)*new_r00);
14676CheckValue<IkReal> x1074 = IKatan2WithCheck(IkReal(0),IkReal(x1072),IKFAST_ATAN2_MAGTHRESH);
14677if(!x1074.valid){
14678continue;
14679}
14680IkReal x1073=((-1.0)*(x1074.value));
14681sj1=-1.0;
14682cj1=0;
14683j1=-1.5707963267949;
14684sj2=gconst29;
14685cj2=gconst30;
14686j2=x1073;
14687new_r10=0;
14688IkReal gconst28=x1073;
14689IkReal gconst29=0;
14690IkReal x1075 = new_r00*new_r00;
14691if(IKabs(x1075)==0){
14692continue;
14693}
14694IkReal gconst30=(x1072*(pow(x1075,-0.5)));
14695j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
14696if( IKabs(j0eval[0]) < 0.0000010000000000 )
14697{
14698{
14699IkReal j0eval[1];
14700IkReal x1076=((-1.0)*new_r00);
14701CheckValue<IkReal> x1078 = IKatan2WithCheck(IkReal(0),IkReal(x1076),IKFAST_ATAN2_MAGTHRESH);
14702if(!x1078.valid){
14703continue;
14704}
14705IkReal x1077=((-1.0)*(x1078.value));
14706sj1=-1.0;
14707cj1=0;
14708j1=-1.5707963267949;
14709sj2=gconst29;
14710cj2=gconst30;
14711j2=x1077;
14712new_r10=0;
14713IkReal gconst28=x1077;
14714IkReal gconst29=0;
14715IkReal x1079 = new_r00*new_r00;
14716if(IKabs(x1079)==0){
14717continue;
14718}
14719IkReal gconst30=(x1076*(pow(x1079,-0.5)));
14720j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
14721if( IKabs(j0eval[0]) < 0.0000010000000000 )
14722{
14723{
14724IkReal j0eval[1];
14725IkReal x1080=((-1.0)*new_r00);
14726CheckValue<IkReal> x1082 = IKatan2WithCheck(IkReal(0),IkReal(x1080),IKFAST_ATAN2_MAGTHRESH);
14727if(!x1082.valid){
14728continue;
14729}
14730IkReal x1081=((-1.0)*(x1082.value));
14731sj1=-1.0;
14732cj1=0;
14733j1=-1.5707963267949;
14734sj2=gconst29;
14735cj2=gconst30;
14736j2=x1081;
14737new_r10=0;
14738IkReal gconst28=x1081;
14739IkReal gconst29=0;
14740IkReal x1083 = new_r00*new_r00;
14741if(IKabs(x1083)==0){
14742continue;
14743}
14744IkReal gconst30=(x1080*(pow(x1083,-0.5)));
14745j0eval[0]=new_r00;
14746if( IKabs(j0eval[0]) < 0.0000010000000000 )
14747{
14748continue; // 3 cases reached
14749
14750} else
14751{
14752{
14753IkReal j0array[1], cj0array[1], sj0array[1];
14754bool j0valid[1]={false};
14755_nj0 = 1;
14756CheckValue<IkReal> x1084=IKPowWithIntegerCheck(new_r00,-1);
14757if(!x1084.valid){
14758continue;
14759}
14760CheckValue<IkReal> x1085=IKPowWithIntegerCheck(gconst30,-1);
14761if(!x1085.valid){
14762continue;
14763}
14764if( IKabs(((-1.0)*gconst30*(x1084.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1085.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1084.value)))+IKsqr((new_r01*(x1085.value)))-1) <= IKFAST_SINCOS_THRESH )
14765 continue;
14766j0array[0]=IKatan2(((-1.0)*gconst30*(x1084.value)), (new_r01*(x1085.value)));
14767sj0array[0]=IKsin(j0array[0]);
14768cj0array[0]=IKcos(j0array[0]);
14769if( j0array[0] > IKPI )
14770{
14771 j0array[0]-=IK2PI;
14772}
14773else if( j0array[0] < -IKPI )
14774{ j0array[0]+=IK2PI;
14775}
14776j0valid[0] = true;
14777for(int ij0 = 0; ij0 < 1; ++ij0)
14778{
14779if( !j0valid[ij0] )
14780{
14781 continue;
14782}
14783_ij0[0] = ij0; _ij0[1] = -1;
14784for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14785{
14786if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14787{
14788 j0valid[iij0]=false; _ij0[1] = iij0; break;
14789}
14790}
14791j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14792{
14793IkReal evalcond[8];
14794IkReal x1086=IKcos(j0);
14795IkReal x1087=IKsin(j0);
14796IkReal x1088=((1.0)*gconst30);
14797evalcond[0]=(new_r00*x1086);
14798evalcond[1]=((-1.0)*gconst30*x1086);
14799evalcond[2]=(((new_r00*x1087))+gconst30);
14800evalcond[3]=(((gconst30*x1087))+new_r00);
14801evalcond[4]=((((-1.0)*x1087*x1088))+new_r11);
14802evalcond[5]=(new_r01+(((-1.0)*x1086*x1088)));
14803evalcond[6]=((((-1.0)*new_r01*x1087))+((new_r11*x1086)));
14804evalcond[7]=(((new_r01*x1086))+((new_r11*x1087))+(((-1.0)*x1088)));
14805if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
14806{
14807continue;
14808}
14809}
14810
14811{
14812std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14813vinfos[0].jointtype = 1;
14814vinfos[0].foffset = j0;
14815vinfos[0].indices[0] = _ij0[0];
14816vinfos[0].indices[1] = _ij0[1];
14817vinfos[0].maxsolutions = _nj0;
14818vinfos[1].jointtype = 1;
14819vinfos[1].foffset = j1;
14820vinfos[1].indices[0] = _ij1[0];
14821vinfos[1].indices[1] = _ij1[1];
14822vinfos[1].maxsolutions = _nj1;
14823vinfos[2].jointtype = 1;
14824vinfos[2].foffset = j2;
14825vinfos[2].indices[0] = _ij2[0];
14826vinfos[2].indices[1] = _ij2[1];
14827vinfos[2].maxsolutions = _nj2;
14828vinfos[3].jointtype = 1;
14829vinfos[3].foffset = j3;
14830vinfos[3].indices[0] = _ij3[0];
14831vinfos[3].indices[1] = _ij3[1];
14832vinfos[3].maxsolutions = _nj3;
14833vinfos[4].jointtype = 1;
14834vinfos[4].foffset = j4;
14835vinfos[4].indices[0] = _ij4[0];
14836vinfos[4].indices[1] = _ij4[1];
14837vinfos[4].maxsolutions = _nj4;
14838vinfos[5].jointtype = 1;
14839vinfos[5].foffset = j5;
14840vinfos[5].indices[0] = _ij5[0];
14841vinfos[5].indices[1] = _ij5[1];
14842vinfos[5].maxsolutions = _nj5;
14843std::vector<int> vfree(0);
14844solutions.AddSolution(vinfos,vfree);
14845}
14846}
14847}
14848
14849}
14850
14851}
14852
14853} else
14854{
14855{
14856IkReal j0array[1], cj0array[1], sj0array[1];
14857bool j0valid[1]={false};
14858_nj0 = 1;
14859CheckValue<IkReal> x1089=IKPowWithIntegerCheck(IKsign(gconst30),-1);
14860if(!x1089.valid){
14861continue;
14862}
14863CheckValue<IkReal> x1090 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
14864if(!x1090.valid){
14865continue;
14866}
14867j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1089.value)))+(x1090.value));
14868sj0array[0]=IKsin(j0array[0]);
14869cj0array[0]=IKcos(j0array[0]);
14870if( j0array[0] > IKPI )
14871{
14872 j0array[0]-=IK2PI;
14873}
14874else if( j0array[0] < -IKPI )
14875{ j0array[0]+=IK2PI;
14876}
14877j0valid[0] = true;
14878for(int ij0 = 0; ij0 < 1; ++ij0)
14879{
14880if( !j0valid[ij0] )
14881{
14882 continue;
14883}
14884_ij0[0] = ij0; _ij0[1] = -1;
14885for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14886{
14887if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14888{
14889 j0valid[iij0]=false; _ij0[1] = iij0; break;
14890}
14891}
14892j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14893{
14894IkReal evalcond[8];
14895IkReal x1091=IKcos(j0);
14896IkReal x1092=IKsin(j0);
14897IkReal x1093=((1.0)*gconst30);
14898evalcond[0]=(new_r00*x1091);
14899evalcond[1]=((-1.0)*gconst30*x1091);
14900evalcond[2]=(((new_r00*x1092))+gconst30);
14901evalcond[3]=(((gconst30*x1092))+new_r00);
14902evalcond[4]=((((-1.0)*x1092*x1093))+new_r11);
14903evalcond[5]=((((-1.0)*x1091*x1093))+new_r01);
14904evalcond[6]=(((new_r11*x1091))+(((-1.0)*new_r01*x1092)));
14905evalcond[7]=(((new_r11*x1092))+((new_r01*x1091))+(((-1.0)*x1093)));
14906if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
14907{
14908continue;
14909}
14910}
14911
14912{
14913std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14914vinfos[0].jointtype = 1;
14915vinfos[0].foffset = j0;
14916vinfos[0].indices[0] = _ij0[0];
14917vinfos[0].indices[1] = _ij0[1];
14918vinfos[0].maxsolutions = _nj0;
14919vinfos[1].jointtype = 1;
14920vinfos[1].foffset = j1;
14921vinfos[1].indices[0] = _ij1[0];
14922vinfos[1].indices[1] = _ij1[1];
14923vinfos[1].maxsolutions = _nj1;
14924vinfos[2].jointtype = 1;
14925vinfos[2].foffset = j2;
14926vinfos[2].indices[0] = _ij2[0];
14927vinfos[2].indices[1] = _ij2[1];
14928vinfos[2].maxsolutions = _nj2;
14929vinfos[3].jointtype = 1;
14930vinfos[3].foffset = j3;
14931vinfos[3].indices[0] = _ij3[0];
14932vinfos[3].indices[1] = _ij3[1];
14933vinfos[3].maxsolutions = _nj3;
14934vinfos[4].jointtype = 1;
14935vinfos[4].foffset = j4;
14936vinfos[4].indices[0] = _ij4[0];
14937vinfos[4].indices[1] = _ij4[1];
14938vinfos[4].maxsolutions = _nj4;
14939vinfos[5].jointtype = 1;
14940vinfos[5].foffset = j5;
14941vinfos[5].indices[0] = _ij5[0];
14942vinfos[5].indices[1] = _ij5[1];
14943vinfos[5].maxsolutions = _nj5;
14944std::vector<int> vfree(0);
14945solutions.AddSolution(vinfos,vfree);
14946}
14947}
14948}
14949
14950}
14951
14952}
14953
14954} else
14955{
14956{
14957IkReal j0array[1], cj0array[1], sj0array[1];
14958bool j0valid[1]={false};
14959_nj0 = 1;
14960CheckValue<IkReal> x1094=IKPowWithIntegerCheck(IKsign(gconst30),-1);
14961if(!x1094.valid){
14962continue;
14963}
14964CheckValue<IkReal> x1095 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
14965if(!x1095.valid){
14966continue;
14967}
14968j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1094.value)))+(x1095.value));
14969sj0array[0]=IKsin(j0array[0]);
14970cj0array[0]=IKcos(j0array[0]);
14971if( j0array[0] > IKPI )
14972{
14973 j0array[0]-=IK2PI;
14974}
14975else if( j0array[0] < -IKPI )
14976{ j0array[0]+=IK2PI;
14977}
14978j0valid[0] = true;
14979for(int ij0 = 0; ij0 < 1; ++ij0)
14980{
14981if( !j0valid[ij0] )
14982{
14983 continue;
14984}
14985_ij0[0] = ij0; _ij0[1] = -1;
14986for(int iij0 = ij0+1; iij0 < 1; ++iij0)
14987{
14988if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
14989{
14990 j0valid[iij0]=false; _ij0[1] = iij0; break;
14991}
14992}
14993j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
14994{
14995IkReal evalcond[8];
14996IkReal x1096=IKcos(j0);
14997IkReal x1097=IKsin(j0);
14998IkReal x1098=((1.0)*gconst30);
14999evalcond[0]=(new_r00*x1096);
15000evalcond[1]=((-1.0)*gconst30*x1096);
15001evalcond[2]=(((new_r00*x1097))+gconst30);
15002evalcond[3]=(((gconst30*x1097))+new_r00);
15003evalcond[4]=((((-1.0)*x1097*x1098))+new_r11);
15004evalcond[5]=((((-1.0)*x1096*x1098))+new_r01);
15005evalcond[6]=(((new_r11*x1096))+(((-1.0)*new_r01*x1097)));
15006evalcond[7]=(((new_r11*x1097))+((new_r01*x1096))+(((-1.0)*x1098)));
15007if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15008{
15009continue;
15010}
15011}
15012
15013{
15014std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15015vinfos[0].jointtype = 1;
15016vinfos[0].foffset = j0;
15017vinfos[0].indices[0] = _ij0[0];
15018vinfos[0].indices[1] = _ij0[1];
15019vinfos[0].maxsolutions = _nj0;
15020vinfos[1].jointtype = 1;
15021vinfos[1].foffset = j1;
15022vinfos[1].indices[0] = _ij1[0];
15023vinfos[1].indices[1] = _ij1[1];
15024vinfos[1].maxsolutions = _nj1;
15025vinfos[2].jointtype = 1;
15026vinfos[2].foffset = j2;
15027vinfos[2].indices[0] = _ij2[0];
15028vinfos[2].indices[1] = _ij2[1];
15029vinfos[2].maxsolutions = _nj2;
15030vinfos[3].jointtype = 1;
15031vinfos[3].foffset = j3;
15032vinfos[3].indices[0] = _ij3[0];
15033vinfos[3].indices[1] = _ij3[1];
15034vinfos[3].maxsolutions = _nj3;
15035vinfos[4].jointtype = 1;
15036vinfos[4].foffset = j4;
15037vinfos[4].indices[0] = _ij4[0];
15038vinfos[4].indices[1] = _ij4[1];
15039vinfos[4].maxsolutions = _nj4;
15040vinfos[5].jointtype = 1;
15041vinfos[5].foffset = j5;
15042vinfos[5].indices[0] = _ij5[0];
15043vinfos[5].indices[1] = _ij5[1];
15044vinfos[5].maxsolutions = _nj5;
15045std::vector<int> vfree(0);
15046solutions.AddSolution(vinfos,vfree);
15047}
15048}
15049}
15050
15051}
15052
15053}
15054
15055}
15056} while(0);
15057if( bgotonextstatement )
15058{
15059bool bgotonextstatement = true;
15060do
15061{
15062evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
15063if( IKabs(evalcond[0]) < 0.0000050000000000 )
15064{
15065bgotonextstatement=false;
15066{
15067IkReal j0eval[1];
15068CheckValue<IkReal> x1100 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15069if(!x1100.valid){
15070continue;
15071}
15072IkReal x1099=((-1.0)*(x1100.value));
15073sj1=-1.0;
15074cj1=0;
15075j1=-1.5707963267949;
15076sj2=gconst29;
15077cj2=gconst30;
15078j2=x1099;
15079new_r00=0;
15080new_r01=0;
15081new_r12=0;
15082new_r22=0;
15083IkReal gconst28=x1099;
15084IkReal x1101 = new_r10*new_r10;
15085if(IKabs(x1101)==0){
15086continue;
15087}
15088IkReal gconst29=((-1.0)*new_r10*(pow(x1101,-0.5)));
15089IkReal gconst30=0;
15090j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
15091if( IKabs(j0eval[0]) < 0.0000010000000000 )
15092{
15093{
15094IkReal j0eval[1];
15095CheckValue<IkReal> x1103 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15096if(!x1103.valid){
15097continue;
15098}
15099IkReal x1102=((-1.0)*(x1103.value));
15100sj1=-1.0;
15101cj1=0;
15102j1=-1.5707963267949;
15103sj2=gconst29;
15104cj2=gconst30;
15105j2=x1102;
15106new_r00=0;
15107new_r01=0;
15108new_r12=0;
15109new_r22=0;
15110IkReal gconst28=x1102;
15111IkReal x1104 = new_r10*new_r10;
15112if(IKabs(x1104)==0){
15113continue;
15114}
15115IkReal gconst29=((-1.0)*new_r10*(pow(x1104,-0.5)));
15116IkReal gconst30=0;
15117j0eval[0]=new_r11;
15118if( IKabs(j0eval[0]) < 0.0000010000000000 )
15119{
15120{
15121IkReal j0eval[2];
15122CheckValue<IkReal> x1106 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15123if(!x1106.valid){
15124continue;
15125}
15126IkReal x1105=((-1.0)*(x1106.value));
15127sj1=-1.0;
15128cj1=0;
15129j1=-1.5707963267949;
15130sj2=gconst29;
15131cj2=gconst30;
15132j2=x1105;
15133new_r00=0;
15134new_r01=0;
15135new_r12=0;
15136new_r22=0;
15137IkReal gconst28=x1105;
15138IkReal x1107 = new_r10*new_r10;
15139if(IKabs(x1107)==0){
15140continue;
15141}
15142IkReal gconst29=((-1.0)*new_r10*(pow(x1107,-0.5)));
15143IkReal gconst30=0;
15144j0eval[0]=new_r10;
15145j0eval[1]=new_r11;
15146if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
15147{
15148continue; // 3 cases reached
15149
15150} else
15151{
15152{
15153IkReal j0array[1], cj0array[1], sj0array[1];
15154bool j0valid[1]={false};
15155_nj0 = 1;
15156CheckValue<IkReal> x1108=IKPowWithIntegerCheck(new_r10,-1);
15157if(!x1108.valid){
15158continue;
15159}
15160CheckValue<IkReal> x1109=IKPowWithIntegerCheck(new_r11,-1);
15161if(!x1109.valid){
15162continue;
15163}
15164if( IKabs((gconst29*(x1108.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst29*(x1109.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst29*(x1108.value)))+IKsqr(((-1.0)*gconst29*(x1109.value)))-1) <= IKFAST_SINCOS_THRESH )
15165 continue;
15166j0array[0]=IKatan2((gconst29*(x1108.value)), ((-1.0)*gconst29*(x1109.value)));
15167sj0array[0]=IKsin(j0array[0]);
15168cj0array[0]=IKcos(j0array[0]);
15169if( j0array[0] > IKPI )
15170{
15171 j0array[0]-=IK2PI;
15172}
15173else if( j0array[0] < -IKPI )
15174{ j0array[0]+=IK2PI;
15175}
15176j0valid[0] = true;
15177for(int ij0 = 0; ij0 < 1; ++ij0)
15178{
15179if( !j0valid[ij0] )
15180{
15181 continue;
15182}
15183_ij0[0] = ij0; _ij0[1] = -1;
15184for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15185{
15186if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15187{
15188 j0valid[iij0]=false; _ij0[1] = iij0; break;
15189}
15190}
15191j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15192{
15193IkReal evalcond[8];
15194IkReal x1110=IKcos(j0);
15195IkReal x1111=IKsin(j0);
15196IkReal x1112=((1.0)*gconst29);
15197IkReal x1113=(gconst29*x1110);
15198evalcond[0]=(new_r11*x1111);
15199evalcond[1]=((-1.0)*new_r10*x1110);
15200evalcond[2]=((-1.0)*x1113);
15201evalcond[3]=((-1.0)*gconst29*x1111);
15202evalcond[4]=(gconst29+((new_r11*x1110)));
15203evalcond[5]=(x1113+new_r11);
15204evalcond[6]=(new_r10+(((-1.0)*x1111*x1112)));
15205evalcond[7]=(((new_r10*x1111))+(((-1.0)*x1112)));
15206if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15207{
15208continue;
15209}
15210}
15211
15212{
15213std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15214vinfos[0].jointtype = 1;
15215vinfos[0].foffset = j0;
15216vinfos[0].indices[0] = _ij0[0];
15217vinfos[0].indices[1] = _ij0[1];
15218vinfos[0].maxsolutions = _nj0;
15219vinfos[1].jointtype = 1;
15220vinfos[1].foffset = j1;
15221vinfos[1].indices[0] = _ij1[0];
15222vinfos[1].indices[1] = _ij1[1];
15223vinfos[1].maxsolutions = _nj1;
15224vinfos[2].jointtype = 1;
15225vinfos[2].foffset = j2;
15226vinfos[2].indices[0] = _ij2[0];
15227vinfos[2].indices[1] = _ij2[1];
15228vinfos[2].maxsolutions = _nj2;
15229vinfos[3].jointtype = 1;
15230vinfos[3].foffset = j3;
15231vinfos[3].indices[0] = _ij3[0];
15232vinfos[3].indices[1] = _ij3[1];
15233vinfos[3].maxsolutions = _nj3;
15234vinfos[4].jointtype = 1;
15235vinfos[4].foffset = j4;
15236vinfos[4].indices[0] = _ij4[0];
15237vinfos[4].indices[1] = _ij4[1];
15238vinfos[4].maxsolutions = _nj4;
15239vinfos[5].jointtype = 1;
15240vinfos[5].foffset = j5;
15241vinfos[5].indices[0] = _ij5[0];
15242vinfos[5].indices[1] = _ij5[1];
15243vinfos[5].maxsolutions = _nj5;
15244std::vector<int> vfree(0);
15245solutions.AddSolution(vinfos,vfree);
15246}
15247}
15248}
15249
15250}
15251
15252}
15253
15254} else
15255{
15256{
15257IkReal j0array[1], cj0array[1], sj0array[1];
15258bool j0valid[1]={false};
15259_nj0 = 1;
15260CheckValue<IkReal> x1114=IKPowWithIntegerCheck(gconst29,-1);
15261if(!x1114.valid){
15262continue;
15263}
15264CheckValue<IkReal> x1115=IKPowWithIntegerCheck(new_r11,-1);
15265if(!x1115.valid){
15266continue;
15267}
15268if( IKabs((new_r10*(x1114.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst29*(x1115.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1114.value)))+IKsqr(((-1.0)*gconst29*(x1115.value)))-1) <= IKFAST_SINCOS_THRESH )
15269 continue;
15270j0array[0]=IKatan2((new_r10*(x1114.value)), ((-1.0)*gconst29*(x1115.value)));
15271sj0array[0]=IKsin(j0array[0]);
15272cj0array[0]=IKcos(j0array[0]);
15273if( j0array[0] > IKPI )
15274{
15275 j0array[0]-=IK2PI;
15276}
15277else if( j0array[0] < -IKPI )
15278{ j0array[0]+=IK2PI;
15279}
15280j0valid[0] = true;
15281for(int ij0 = 0; ij0 < 1; ++ij0)
15282{
15283if( !j0valid[ij0] )
15284{
15285 continue;
15286}
15287_ij0[0] = ij0; _ij0[1] = -1;
15288for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15289{
15290if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15291{
15292 j0valid[iij0]=false; _ij0[1] = iij0; break;
15293}
15294}
15295j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15296{
15297IkReal evalcond[8];
15298IkReal x1116=IKcos(j0);
15299IkReal x1117=IKsin(j0);
15300IkReal x1118=((1.0)*gconst29);
15301IkReal x1119=(gconst29*x1116);
15302evalcond[0]=(new_r11*x1117);
15303evalcond[1]=((-1.0)*new_r10*x1116);
15304evalcond[2]=((-1.0)*x1119);
15305evalcond[3]=((-1.0)*gconst29*x1117);
15306evalcond[4]=(gconst29+((new_r11*x1116)));
15307evalcond[5]=(x1119+new_r11);
15308evalcond[6]=(new_r10+(((-1.0)*x1117*x1118)));
15309evalcond[7]=(((new_r10*x1117))+(((-1.0)*x1118)));
15310if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15311{
15312continue;
15313}
15314}
15315
15316{
15317std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15318vinfos[0].jointtype = 1;
15319vinfos[0].foffset = j0;
15320vinfos[0].indices[0] = _ij0[0];
15321vinfos[0].indices[1] = _ij0[1];
15322vinfos[0].maxsolutions = _nj0;
15323vinfos[1].jointtype = 1;
15324vinfos[1].foffset = j1;
15325vinfos[1].indices[0] = _ij1[0];
15326vinfos[1].indices[1] = _ij1[1];
15327vinfos[1].maxsolutions = _nj1;
15328vinfos[2].jointtype = 1;
15329vinfos[2].foffset = j2;
15330vinfos[2].indices[0] = _ij2[0];
15331vinfos[2].indices[1] = _ij2[1];
15332vinfos[2].maxsolutions = _nj2;
15333vinfos[3].jointtype = 1;
15334vinfos[3].foffset = j3;
15335vinfos[3].indices[0] = _ij3[0];
15336vinfos[3].indices[1] = _ij3[1];
15337vinfos[3].maxsolutions = _nj3;
15338vinfos[4].jointtype = 1;
15339vinfos[4].foffset = j4;
15340vinfos[4].indices[0] = _ij4[0];
15341vinfos[4].indices[1] = _ij4[1];
15342vinfos[4].maxsolutions = _nj4;
15343vinfos[5].jointtype = 1;
15344vinfos[5].foffset = j5;
15345vinfos[5].indices[0] = _ij5[0];
15346vinfos[5].indices[1] = _ij5[1];
15347vinfos[5].maxsolutions = _nj5;
15348std::vector<int> vfree(0);
15349solutions.AddSolution(vinfos,vfree);
15350}
15351}
15352}
15353
15354}
15355
15356}
15357
15358} else
15359{
15360{
15361IkReal j0array[1], cj0array[1], sj0array[1];
15362bool j0valid[1]={false};
15363_nj0 = 1;
15364CheckValue<IkReal> x1120 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
15365if(!x1120.valid){
15366continue;
15367}
15368CheckValue<IkReal> x1121=IKPowWithIntegerCheck(IKsign(gconst29),-1);
15369if(!x1121.valid){
15370continue;
15371}
15372j0array[0]=((-1.5707963267949)+(x1120.value)+(((1.5707963267949)*(x1121.value))));
15373sj0array[0]=IKsin(j0array[0]);
15374cj0array[0]=IKcos(j0array[0]);
15375if( j0array[0] > IKPI )
15376{
15377 j0array[0]-=IK2PI;
15378}
15379else if( j0array[0] < -IKPI )
15380{ j0array[0]+=IK2PI;
15381}
15382j0valid[0] = true;
15383for(int ij0 = 0; ij0 < 1; ++ij0)
15384{
15385if( !j0valid[ij0] )
15386{
15387 continue;
15388}
15389_ij0[0] = ij0; _ij0[1] = -1;
15390for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15391{
15392if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15393{
15394 j0valid[iij0]=false; _ij0[1] = iij0; break;
15395}
15396}
15397j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15398{
15399IkReal evalcond[8];
15400IkReal x1122=IKcos(j0);
15401IkReal x1123=IKsin(j0);
15402IkReal x1124=((1.0)*gconst29);
15403IkReal x1125=(gconst29*x1122);
15404evalcond[0]=(new_r11*x1123);
15405evalcond[1]=((-1.0)*new_r10*x1122);
15406evalcond[2]=((-1.0)*x1125);
15407evalcond[3]=((-1.0)*gconst29*x1123);
15408evalcond[4]=(gconst29+((new_r11*x1122)));
15409evalcond[5]=(x1125+new_r11);
15410evalcond[6]=((((-1.0)*x1123*x1124))+new_r10);
15411evalcond[7]=(((new_r10*x1123))+(((-1.0)*x1124)));
15412if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15413{
15414continue;
15415}
15416}
15417
15418{
15419std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15420vinfos[0].jointtype = 1;
15421vinfos[0].foffset = j0;
15422vinfos[0].indices[0] = _ij0[0];
15423vinfos[0].indices[1] = _ij0[1];
15424vinfos[0].maxsolutions = _nj0;
15425vinfos[1].jointtype = 1;
15426vinfos[1].foffset = j1;
15427vinfos[1].indices[0] = _ij1[0];
15428vinfos[1].indices[1] = _ij1[1];
15429vinfos[1].maxsolutions = _nj1;
15430vinfos[2].jointtype = 1;
15431vinfos[2].foffset = j2;
15432vinfos[2].indices[0] = _ij2[0];
15433vinfos[2].indices[1] = _ij2[1];
15434vinfos[2].maxsolutions = _nj2;
15435vinfos[3].jointtype = 1;
15436vinfos[3].foffset = j3;
15437vinfos[3].indices[0] = _ij3[0];
15438vinfos[3].indices[1] = _ij3[1];
15439vinfos[3].maxsolutions = _nj3;
15440vinfos[4].jointtype = 1;
15441vinfos[4].foffset = j4;
15442vinfos[4].indices[0] = _ij4[0];
15443vinfos[4].indices[1] = _ij4[1];
15444vinfos[4].maxsolutions = _nj4;
15445vinfos[5].jointtype = 1;
15446vinfos[5].foffset = j5;
15447vinfos[5].indices[0] = _ij5[0];
15448vinfos[5].indices[1] = _ij5[1];
15449vinfos[5].maxsolutions = _nj5;
15450std::vector<int> vfree(0);
15451solutions.AddSolution(vinfos,vfree);
15452}
15453}
15454}
15455
15456}
15457
15458}
15459
15460}
15461} while(0);
15462if( bgotonextstatement )
15463{
15464bool bgotonextstatement = true;
15465do
15466{
15467if( 1 )
15468{
15469bgotonextstatement=false;
15470continue; // branch miss [j0]
15471
15472}
15473} while(0);
15474if( bgotonextstatement )
15475{
15476}
15477}
15478}
15479}
15480}
15481}
15482}
15483}
15484
15485} else
15486{
15487{
15488IkReal j0array[1], cj0array[1], sj0array[1];
15489bool j0valid[1]={false};
15490_nj0 = 1;
15491CheckValue<IkReal> x1126 = IKatan2WithCheck(IkReal((((gconst29*new_r11))+((gconst29*new_r00)))),IkReal((((gconst29*new_r01))+(((-1.0)*gconst29*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
15492if(!x1126.valid){
15493continue;
15494}
15495CheckValue<IkReal> x1127=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
15496if(!x1127.valid){
15497continue;
15498}
15499j0array[0]=((-1.5707963267949)+(x1126.value)+(((1.5707963267949)*(x1127.value))));
15500sj0array[0]=IKsin(j0array[0]);
15501cj0array[0]=IKcos(j0array[0]);
15502if( j0array[0] > IKPI )
15503{
15504 j0array[0]-=IK2PI;
15505}
15506else if( j0array[0] < -IKPI )
15507{ j0array[0]+=IK2PI;
15508}
15509j0valid[0] = true;
15510for(int ij0 = 0; ij0 < 1; ++ij0)
15511{
15512if( !j0valid[ij0] )
15513{
15514 continue;
15515}
15516_ij0[0] = ij0; _ij0[1] = -1;
15517for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15518{
15519if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15520{
15521 j0valid[iij0]=false; _ij0[1] = iij0; break;
15522}
15523}
15524j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15525{
15526IkReal evalcond[8];
15527IkReal x1128=IKsin(j0);
15528IkReal x1129=IKcos(j0);
15529IkReal x1130=((1.0)*gconst30);
15530IkReal x1131=((1.0)*gconst29);
15531IkReal x1132=(gconst29*x1129);
15532IkReal x1133=(((x1129*x1130))+((x1128*x1131)));
15533evalcond[0]=((((-1.0)*new_r01*x1128))+gconst29+((new_r11*x1129)));
15534evalcond[1]=(gconst30+((new_r00*x1128))+(((-1.0)*new_r10*x1129)));
15535evalcond[2]=(((gconst30*x1128))+new_r00+(((-1.0)*x1129*x1131)));
15536evalcond[3]=(x1132+(((-1.0)*x1128*x1130))+new_r11);
15537evalcond[4]=(((new_r10*x1128))+(((-1.0)*x1131))+((new_r00*x1129)));
15538evalcond[5]=((((-1.0)*x1130))+((new_r01*x1129))+((new_r11*x1128)));
15539evalcond[6]=((((-1.0)*x1133))+new_r01);
15540evalcond[7]=((((-1.0)*x1133))+new_r10);
15541if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15542{
15543continue;
15544}
15545}
15546
15547{
15548std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15549vinfos[0].jointtype = 1;
15550vinfos[0].foffset = j0;
15551vinfos[0].indices[0] = _ij0[0];
15552vinfos[0].indices[1] = _ij0[1];
15553vinfos[0].maxsolutions = _nj0;
15554vinfos[1].jointtype = 1;
15555vinfos[1].foffset = j1;
15556vinfos[1].indices[0] = _ij1[0];
15557vinfos[1].indices[1] = _ij1[1];
15558vinfos[1].maxsolutions = _nj1;
15559vinfos[2].jointtype = 1;
15560vinfos[2].foffset = j2;
15561vinfos[2].indices[0] = _ij2[0];
15562vinfos[2].indices[1] = _ij2[1];
15563vinfos[2].maxsolutions = _nj2;
15564vinfos[3].jointtype = 1;
15565vinfos[3].foffset = j3;
15566vinfos[3].indices[0] = _ij3[0];
15567vinfos[3].indices[1] = _ij3[1];
15568vinfos[3].maxsolutions = _nj3;
15569vinfos[4].jointtype = 1;
15570vinfos[4].foffset = j4;
15571vinfos[4].indices[0] = _ij4[0];
15572vinfos[4].indices[1] = _ij4[1];
15573vinfos[4].maxsolutions = _nj4;
15574vinfos[5].jointtype = 1;
15575vinfos[5].foffset = j5;
15576vinfos[5].indices[0] = _ij5[0];
15577vinfos[5].indices[1] = _ij5[1];
15578vinfos[5].maxsolutions = _nj5;
15579std::vector<int> vfree(0);
15580solutions.AddSolution(vinfos,vfree);
15581}
15582}
15583}
15584
15585}
15586
15587}
15588
15589} else
15590{
15591{
15592IkReal j0array[1], cj0array[1], sj0array[1];
15593bool j0valid[1]={false};
15594_nj0 = 1;
15595CheckValue<IkReal> x1134 = IKatan2WithCheck(IkReal(((gconst29*gconst29)+((new_r00*new_r11)))),IkReal((((new_r00*new_r01))+((gconst29*gconst30)))),IKFAST_ATAN2_MAGTHRESH);
15596if(!x1134.valid){
15597continue;
15598}
15599CheckValue<IkReal> x1135=IKPowWithIntegerCheck(IKsign((((gconst29*new_r01))+(((-1.0)*gconst30*new_r11)))),-1);
15600if(!x1135.valid){
15601continue;
15602}
15603j0array[0]=((-1.5707963267949)+(x1134.value)+(((1.5707963267949)*(x1135.value))));
15604sj0array[0]=IKsin(j0array[0]);
15605cj0array[0]=IKcos(j0array[0]);
15606if( j0array[0] > IKPI )
15607{
15608 j0array[0]-=IK2PI;
15609}
15610else if( j0array[0] < -IKPI )
15611{ j0array[0]+=IK2PI;
15612}
15613j0valid[0] = true;
15614for(int ij0 = 0; ij0 < 1; ++ij0)
15615{
15616if( !j0valid[ij0] )
15617{
15618 continue;
15619}
15620_ij0[0] = ij0; _ij0[1] = -1;
15621for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15622{
15623if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15624{
15625 j0valid[iij0]=false; _ij0[1] = iij0; break;
15626}
15627}
15628j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15629{
15630IkReal evalcond[8];
15631IkReal x1136=IKsin(j0);
15632IkReal x1137=IKcos(j0);
15633IkReal x1138=((1.0)*gconst30);
15634IkReal x1139=((1.0)*gconst29);
15635IkReal x1140=(gconst29*x1137);
15636IkReal x1141=(((x1136*x1139))+((x1137*x1138)));
15637evalcond[0]=((((-1.0)*new_r01*x1136))+gconst29+((new_r11*x1137)));
15638evalcond[1]=(gconst30+((new_r00*x1136))+(((-1.0)*new_r10*x1137)));
15639evalcond[2]=(((gconst30*x1136))+new_r00+(((-1.0)*x1137*x1139)));
15640evalcond[3]=(x1140+(((-1.0)*x1136*x1138))+new_r11);
15641evalcond[4]=((((-1.0)*x1139))+((new_r00*x1137))+((new_r10*x1136)));
15642evalcond[5]=((((-1.0)*x1138))+((new_r11*x1136))+((new_r01*x1137)));
15643evalcond[6]=((((-1.0)*x1141))+new_r01);
15644evalcond[7]=((((-1.0)*x1141))+new_r10);
15645if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15646{
15647continue;
15648}
15649}
15650
15651{
15652std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15653vinfos[0].jointtype = 1;
15654vinfos[0].foffset = j0;
15655vinfos[0].indices[0] = _ij0[0];
15656vinfos[0].indices[1] = _ij0[1];
15657vinfos[0].maxsolutions = _nj0;
15658vinfos[1].jointtype = 1;
15659vinfos[1].foffset = j1;
15660vinfos[1].indices[0] = _ij1[0];
15661vinfos[1].indices[1] = _ij1[1];
15662vinfos[1].maxsolutions = _nj1;
15663vinfos[2].jointtype = 1;
15664vinfos[2].foffset = j2;
15665vinfos[2].indices[0] = _ij2[0];
15666vinfos[2].indices[1] = _ij2[1];
15667vinfos[2].maxsolutions = _nj2;
15668vinfos[3].jointtype = 1;
15669vinfos[3].foffset = j3;
15670vinfos[3].indices[0] = _ij3[0];
15671vinfos[3].indices[1] = _ij3[1];
15672vinfos[3].maxsolutions = _nj3;
15673vinfos[4].jointtype = 1;
15674vinfos[4].foffset = j4;
15675vinfos[4].indices[0] = _ij4[0];
15676vinfos[4].indices[1] = _ij4[1];
15677vinfos[4].maxsolutions = _nj4;
15678vinfos[5].jointtype = 1;
15679vinfos[5].foffset = j5;
15680vinfos[5].indices[0] = _ij5[0];
15681vinfos[5].indices[1] = _ij5[1];
15682vinfos[5].maxsolutions = _nj5;
15683std::vector<int> vfree(0);
15684solutions.AddSolution(vinfos,vfree);
15685}
15686}
15687}
15688
15689}
15690
15691}
15692
15693} else
15694{
15695{
15696IkReal j0array[1], cj0array[1], sj0array[1];
15697bool j0valid[1]={false};
15698_nj0 = 1;
15699CheckValue<IkReal> x1142 = IKatan2WithCheck(IkReal((((gconst29*new_r10))+((gconst30*new_r11)))),IkReal((((gconst29*new_r00))+((gconst30*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
15700if(!x1142.valid){
15701continue;
15702}
15703CheckValue<IkReal> x1143=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
15704if(!x1143.valid){
15705continue;
15706}
15707j0array[0]=((-1.5707963267949)+(x1142.value)+(((1.5707963267949)*(x1143.value))));
15708sj0array[0]=IKsin(j0array[0]);
15709cj0array[0]=IKcos(j0array[0]);
15710if( j0array[0] > IKPI )
15711{
15712 j0array[0]-=IK2PI;
15713}
15714else if( j0array[0] < -IKPI )
15715{ j0array[0]+=IK2PI;
15716}
15717j0valid[0] = true;
15718for(int ij0 = 0; ij0 < 1; ++ij0)
15719{
15720if( !j0valid[ij0] )
15721{
15722 continue;
15723}
15724_ij0[0] = ij0; _ij0[1] = -1;
15725for(int iij0 = ij0+1; iij0 < 1; ++iij0)
15726{
15727if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15728{
15729 j0valid[iij0]=false; _ij0[1] = iij0; break;
15730}
15731}
15732j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15733{
15734IkReal evalcond[8];
15735IkReal x1144=IKsin(j0);
15736IkReal x1145=IKcos(j0);
15737IkReal x1146=((1.0)*gconst30);
15738IkReal x1147=((1.0)*gconst29);
15739IkReal x1148=(gconst29*x1145);
15740IkReal x1149=(((x1145*x1146))+((x1144*x1147)));
15741evalcond[0]=(gconst29+(((-1.0)*new_r01*x1144))+((new_r11*x1145)));
15742evalcond[1]=((((-1.0)*new_r10*x1145))+((new_r00*x1144))+gconst30);
15743evalcond[2]=((((-1.0)*x1145*x1147))+((gconst30*x1144))+new_r00);
15744evalcond[3]=(x1148+new_r11+(((-1.0)*x1144*x1146)));
15745evalcond[4]=(((new_r00*x1145))+(((-1.0)*x1147))+((new_r10*x1144)));
15746evalcond[5]=((((-1.0)*x1146))+((new_r01*x1145))+((new_r11*x1144)));
15747evalcond[6]=((((-1.0)*x1149))+new_r01);
15748evalcond[7]=((((-1.0)*x1149))+new_r10);
15749if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
15750{
15751continue;
15752}
15753}
15754
15755{
15756std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15757vinfos[0].jointtype = 1;
15758vinfos[0].foffset = j0;
15759vinfos[0].indices[0] = _ij0[0];
15760vinfos[0].indices[1] = _ij0[1];
15761vinfos[0].maxsolutions = _nj0;
15762vinfos[1].jointtype = 1;
15763vinfos[1].foffset = j1;
15764vinfos[1].indices[0] = _ij1[0];
15765vinfos[1].indices[1] = _ij1[1];
15766vinfos[1].maxsolutions = _nj1;
15767vinfos[2].jointtype = 1;
15768vinfos[2].foffset = j2;
15769vinfos[2].indices[0] = _ij2[0];
15770vinfos[2].indices[1] = _ij2[1];
15771vinfos[2].maxsolutions = _nj2;
15772vinfos[3].jointtype = 1;
15773vinfos[3].foffset = j3;
15774vinfos[3].indices[0] = _ij3[0];
15775vinfos[3].indices[1] = _ij3[1];
15776vinfos[3].maxsolutions = _nj3;
15777vinfos[4].jointtype = 1;
15778vinfos[4].foffset = j4;
15779vinfos[4].indices[0] = _ij4[0];
15780vinfos[4].indices[1] = _ij4[1];
15781vinfos[4].maxsolutions = _nj4;
15782vinfos[5].jointtype = 1;
15783vinfos[5].foffset = j5;
15784vinfos[5].indices[0] = _ij5[0];
15785vinfos[5].indices[1] = _ij5[1];
15786vinfos[5].maxsolutions = _nj5;
15787std::vector<int> vfree(0);
15788solutions.AddSolution(vinfos,vfree);
15789}
15790}
15791}
15792
15793}
15794
15795}
15796
15797}
15798} while(0);
15799if( bgotonextstatement )
15800{
15801bool bgotonextstatement = true;
15802do
15803{
15804IkReal x1152 = ((new_r10*new_r10)+(new_r00*new_r00));
15805if(IKabs(x1152)==0){
15806continue;
15807}
15808IkReal x1150=pow(x1152,-0.5);
15809IkReal x1151=((1.0)*x1150);
15810CheckValue<IkReal> x1153 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
15811if(!x1153.valid){
15812continue;
15813}
15814IkReal gconst31=((3.14159265358979)+(((-1.0)*(x1153.value))));
15815IkReal gconst32=(new_r10*x1151);
15816IkReal gconst33=(new_r00*x1151);
15817CheckValue<IkReal> x1154 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
15818if(!x1154.valid){
15819continue;
15820}
15821evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2+(x1154.value))))), 6.28318530717959)));
15822if( IKabs(evalcond[0]) < 0.0000050000000000 )
15823{
15824bgotonextstatement=false;
15825{
15826IkReal j0eval[3];
15827CheckValue<IkReal> x1158 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
15828if(!x1158.valid){
15829continue;
15830}
15831IkReal x1155=((1.0)*(x1158.value));
15832IkReal x1156=x1150;
15833IkReal x1157=((1.0)*x1156);
15834sj1=-1.0;
15835cj1=0;
15836j1=-1.5707963267949;
15837sj2=gconst32;
15838cj2=gconst33;
15839j2=((3.14159265)+(((-1.0)*x1155)));
15840IkReal gconst31=((3.14159265358979)+(((-1.0)*x1155)));
15841IkReal gconst32=(new_r10*x1157);
15842IkReal gconst33=(new_r00*x1157);
15843IkReal x1159=new_r10*new_r10;
15844IkReal x1160=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
15845IkReal x1161=x1150;
15846IkReal x1162=(new_r00*x1161);
15847j0eval[0]=x1160;
15848j0eval[1]=IKsign(x1160);
15849j0eval[2]=((IKabs((((new_r10*x1162))+((new_r01*x1162)))))+(IKabs((((x1159*x1161))+((new_r11*x1162))))));
15850if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
15851{
15852{
15853IkReal j0eval[1];
15854CheckValue<IkReal> x1166 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
15855if(!x1166.valid){
15856continue;
15857}
15858IkReal x1163=((1.0)*(x1166.value));
15859IkReal x1164=x1150;
15860IkReal x1165=((1.0)*x1164);
15861sj1=-1.0;
15862cj1=0;
15863j1=-1.5707963267949;
15864sj2=gconst32;
15865cj2=gconst33;
15866j2=((3.14159265)+(((-1.0)*x1163)));
15867IkReal gconst31=((3.14159265358979)+(((-1.0)*x1163)));
15868IkReal gconst32=(new_r10*x1165);
15869IkReal gconst33=(new_r00*x1165);
15870IkReal x1167=new_r10*new_r10;
15871IkReal x1168=new_r00*new_r00*new_r00;
15872CheckValue<IkReal> x1172=IKPowWithIntegerCheck((x1167+(new_r00*new_r00)),-1);
15873if(!x1172.valid){
15874continue;
15875}
15876IkReal x1169=x1172.value;
15877IkReal x1170=(x1167*x1169);
15878IkReal x1171=(x1168*x1169);
15879j0eval[0]=((IKabs((((new_r00*new_r11*x1170))+x1170+((new_r11*x1171)))))+(IKabs((((new_r00*new_r10*x1169))+((new_r00*new_r01*x1170))+((new_r01*x1171))))));
15880if( IKabs(j0eval[0]) < 0.0000010000000000 )
15881{
15882{
15883IkReal j0eval[3];
15884CheckValue<IkReal> x1176 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
15885if(!x1176.valid){
15886continue;
15887}
15888IkReal x1173=((1.0)*(x1176.value));
15889IkReal x1174=x1150;
15890IkReal x1175=((1.0)*x1174);
15891sj1=-1.0;
15892cj1=0;
15893j1=-1.5707963267949;
15894sj2=gconst32;
15895cj2=gconst33;
15896j2=((3.14159265)+(((-1.0)*x1173)));
15897IkReal gconst31=((3.14159265358979)+(((-1.0)*x1173)));
15898IkReal gconst32=(new_r10*x1175);
15899IkReal gconst33=(new_r00*x1175);
15900IkReal x1177=new_r10*new_r10;
15901IkReal x1178=(((new_r10*new_r11))+((new_r00*new_r01)));
15902IkReal x1179=x1150;
15903IkReal x1180=(new_r10*x1179);
15904j0eval[0]=x1178;
15905j0eval[1]=IKsign(x1178);
15906j0eval[2]=((IKabs((((new_r11*x1180))+((new_r00*x1180)))))+(IKabs(((((-1.0)*x1177*x1179))+((new_r01*x1180))))));
15907if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
15908{
15909{
15910IkReal evalcond[2];
15911bool bgotonextstatement = true;
15912do
15913{
15914evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
15915if( IKabs(evalcond[0]) < 0.0000050000000000 )
15916{
15917bgotonextstatement=false;
15918{
15919IkReal j0eval[1];
15920CheckValue<IkReal> x1182 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
15921if(!x1182.valid){
15922continue;
15923}
15924IkReal x1181=((1.0)*(x1182.value));
15925sj1=-1.0;
15926cj1=0;
15927j1=-1.5707963267949;
15928sj2=gconst32;
15929cj2=gconst33;
15930j2=((3.14159265)+(((-1.0)*x1181)));
15931new_r11=0;
15932new_r00=0;
15933IkReal gconst31=((3.14159265358979)+(((-1.0)*x1181)));
15934IkReal x1183 = new_r10*new_r10;
15935if(IKabs(x1183)==0){
15936continue;
15937}
15938IkReal gconst32=((1.0)*new_r10*(pow(x1183,-0.5)));
15939IkReal gconst33=0;
15940j0eval[0]=new_r01;
15941if( IKabs(j0eval[0]) < 0.0000010000000000 )
15942{
15943{
15944IkReal j0array[2], cj0array[2], sj0array[2];
15945bool j0valid[2]={false};
15946_nj0 = 2;
15947CheckValue<IkReal> x1184=IKPowWithIntegerCheck(gconst32,-1);
15948if(!x1184.valid){
15949continue;
15950}
15951sj0array[0]=(new_r01*(x1184.value));
15952if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
15953{
15954 j0valid[0] = j0valid[1] = true;
15955 j0array[0] = IKasin(sj0array[0]);
15956 cj0array[0] = IKcos(j0array[0]);
15957 sj0array[1] = sj0array[0];
15958 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
15959 cj0array[1] = -cj0array[0];
15960}
15961else if( isnan(sj0array[0]) )
15962{
15963 // probably any value will work
15964 j0valid[0] = true;
15965 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
15966}
15967for(int ij0 = 0; ij0 < 2; ++ij0)
15968{
15969if( !j0valid[ij0] )
15970{
15971 continue;
15972}
15973_ij0[0] = ij0; _ij0[1] = -1;
15974for(int iij0 = ij0+1; iij0 < 2; ++iij0)
15975{
15976if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
15977{
15978 j0valid[iij0]=false; _ij0[1] = iij0; break;
15979}
15980}
15981j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
15982{
15983IkReal evalcond[6];
15984IkReal x1185=IKcos(j0);
15985IkReal x1186=IKsin(j0);
15986IkReal x1187=((1.0)*gconst32);
15987IkReal x1188=((-1.0)*x1185);
15988evalcond[0]=(new_r01*x1185);
15989evalcond[1]=(new_r10*x1188);
15990evalcond[2]=(gconst32*x1188);
15991evalcond[3]=((((-1.0)*new_r01*x1186))+gconst32);
15992evalcond[4]=((((-1.0)*x1186*x1187))+new_r10);
15993evalcond[5]=((((-1.0)*x1187))+((new_r10*x1186)));
15994if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
15995{
15996continue;
15997}
15998}
15999
16000{
16001std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16002vinfos[0].jointtype = 1;
16003vinfos[0].foffset = j0;
16004vinfos[0].indices[0] = _ij0[0];
16005vinfos[0].indices[1] = _ij0[1];
16006vinfos[0].maxsolutions = _nj0;
16007vinfos[1].jointtype = 1;
16008vinfos[1].foffset = j1;
16009vinfos[1].indices[0] = _ij1[0];
16010vinfos[1].indices[1] = _ij1[1];
16011vinfos[1].maxsolutions = _nj1;
16012vinfos[2].jointtype = 1;
16013vinfos[2].foffset = j2;
16014vinfos[2].indices[0] = _ij2[0];
16015vinfos[2].indices[1] = _ij2[1];
16016vinfos[2].maxsolutions = _nj2;
16017vinfos[3].jointtype = 1;
16018vinfos[3].foffset = j3;
16019vinfos[3].indices[0] = _ij3[0];
16020vinfos[3].indices[1] = _ij3[1];
16021vinfos[3].maxsolutions = _nj3;
16022vinfos[4].jointtype = 1;
16023vinfos[4].foffset = j4;
16024vinfos[4].indices[0] = _ij4[0];
16025vinfos[4].indices[1] = _ij4[1];
16026vinfos[4].maxsolutions = _nj4;
16027vinfos[5].jointtype = 1;
16028vinfos[5].foffset = j5;
16029vinfos[5].indices[0] = _ij5[0];
16030vinfos[5].indices[1] = _ij5[1];
16031vinfos[5].maxsolutions = _nj5;
16032std::vector<int> vfree(0);
16033solutions.AddSolution(vinfos,vfree);
16034}
16035}
16036}
16037
16038} else
16039{
16040{
16041IkReal j0array[2], cj0array[2], sj0array[2];
16042bool j0valid[2]={false};
16043_nj0 = 2;
16044CheckValue<IkReal> x1189=IKPowWithIntegerCheck(new_r01,-1);
16045if(!x1189.valid){
16046continue;
16047}
16048sj0array[0]=(gconst32*(x1189.value));
16049if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
16050{
16051 j0valid[0] = j0valid[1] = true;
16052 j0array[0] = IKasin(sj0array[0]);
16053 cj0array[0] = IKcos(j0array[0]);
16054 sj0array[1] = sj0array[0];
16055 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
16056 cj0array[1] = -cj0array[0];
16057}
16058else if( isnan(sj0array[0]) )
16059{
16060 // probably any value will work
16061 j0valid[0] = true;
16062 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
16063}
16064for(int ij0 = 0; ij0 < 2; ++ij0)
16065{
16066if( !j0valid[ij0] )
16067{
16068 continue;
16069}
16070_ij0[0] = ij0; _ij0[1] = -1;
16071for(int iij0 = ij0+1; iij0 < 2; ++iij0)
16072{
16073if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16074{
16075 j0valid[iij0]=false; _ij0[1] = iij0; break;
16076}
16077}
16078j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16079{
16080IkReal evalcond[6];
16081IkReal x1190=IKcos(j0);
16082IkReal x1191=IKsin(j0);
16083IkReal x1192=((1.0)*gconst32);
16084IkReal x1193=(x1191*x1192);
16085IkReal x1194=((-1.0)*x1190);
16086evalcond[0]=(new_r01*x1190);
16087evalcond[1]=(new_r10*x1194);
16088evalcond[2]=(gconst32*x1194);
16089evalcond[3]=((((-1.0)*x1193))+new_r01);
16090evalcond[4]=((((-1.0)*x1193))+new_r10);
16091evalcond[5]=((((-1.0)*x1192))+((new_r10*x1191)));
16092if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16093{
16094continue;
16095}
16096}
16097
16098{
16099std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16100vinfos[0].jointtype = 1;
16101vinfos[0].foffset = j0;
16102vinfos[0].indices[0] = _ij0[0];
16103vinfos[0].indices[1] = _ij0[1];
16104vinfos[0].maxsolutions = _nj0;
16105vinfos[1].jointtype = 1;
16106vinfos[1].foffset = j1;
16107vinfos[1].indices[0] = _ij1[0];
16108vinfos[1].indices[1] = _ij1[1];
16109vinfos[1].maxsolutions = _nj1;
16110vinfos[2].jointtype = 1;
16111vinfos[2].foffset = j2;
16112vinfos[2].indices[0] = _ij2[0];
16113vinfos[2].indices[1] = _ij2[1];
16114vinfos[2].maxsolutions = _nj2;
16115vinfos[3].jointtype = 1;
16116vinfos[3].foffset = j3;
16117vinfos[3].indices[0] = _ij3[0];
16118vinfos[3].indices[1] = _ij3[1];
16119vinfos[3].maxsolutions = _nj3;
16120vinfos[4].jointtype = 1;
16121vinfos[4].foffset = j4;
16122vinfos[4].indices[0] = _ij4[0];
16123vinfos[4].indices[1] = _ij4[1];
16124vinfos[4].maxsolutions = _nj4;
16125vinfos[5].jointtype = 1;
16126vinfos[5].foffset = j5;
16127vinfos[5].indices[0] = _ij5[0];
16128vinfos[5].indices[1] = _ij5[1];
16129vinfos[5].maxsolutions = _nj5;
16130std::vector<int> vfree(0);
16131solutions.AddSolution(vinfos,vfree);
16132}
16133}
16134}
16135
16136}
16137
16138}
16139
16140}
16141} while(0);
16142if( bgotonextstatement )
16143{
16144bool bgotonextstatement = true;
16145do
16146{
16147evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
16148evalcond[1]=gconst32;
16149if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
16150{
16151bgotonextstatement=false;
16152{
16153IkReal j0eval[4];
16154CheckValue<IkReal> x1196 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16155if(!x1196.valid){
16156continue;
16157}
16158IkReal x1195=((1.0)*(x1196.value));
16159sj1=-1.0;
16160cj1=0;
16161j1=-1.5707963267949;
16162sj2=gconst32;
16163cj2=gconst33;
16164j2=((3.14159265)+(((-1.0)*x1195)));
16165new_r11=0;
16166new_r01=0;
16167new_r22=0;
16168new_r20=0;
16169IkReal gconst31=((3.14159265358979)+(((-1.0)*x1195)));
16170IkReal gconst32=((1.0)*new_r10);
16171IkReal gconst33=((1.0)*new_r00);
16172j0eval[0]=1.0;
16173j0eval[1]=new_r10;
16174j0eval[2]=1.0;
16175j0eval[3]=1.0;
16176if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 )
16177{
16178{
16179IkReal j0eval[4];
16180CheckValue<IkReal> x1198 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16181if(!x1198.valid){
16182continue;
16183}
16184IkReal x1197=((1.0)*(x1198.value));
16185sj1=-1.0;
16186cj1=0;
16187j1=-1.5707963267949;
16188sj2=gconst32;
16189cj2=gconst33;
16190j2=((3.14159265)+(((-1.0)*x1197)));
16191new_r11=0;
16192new_r01=0;
16193new_r22=0;
16194new_r20=0;
16195IkReal gconst31=((3.14159265358979)+(((-1.0)*x1197)));
16196IkReal gconst32=((1.0)*new_r10);
16197IkReal gconst33=((1.0)*new_r00);
16198j0eval[0]=1.0;
16199j0eval[1]=new_r10;
16200j0eval[2]=1.0;
16201j0eval[3]=1.0;
16202if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 )
16203{
16204{
16205IkReal j0eval[3];
16206CheckValue<IkReal> x1200 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16207if(!x1200.valid){
16208continue;
16209}
16210IkReal x1199=((1.0)*(x1200.value));
16211sj1=-1.0;
16212cj1=0;
16213j1=-1.5707963267949;
16214sj2=gconst32;
16215cj2=gconst33;
16216j2=((3.14159265)+(((-1.0)*x1199)));
16217new_r11=0;
16218new_r01=0;
16219new_r22=0;
16220new_r20=0;
16221IkReal gconst31=((3.14159265358979)+(((-1.0)*x1199)));
16222IkReal gconst32=((1.0)*new_r10);
16223IkReal gconst33=((1.0)*new_r00);
16224j0eval[0]=-1.0;
16225j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10))));
16226j0eval[2]=-1.0;
16227if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
16228{
16229continue; // 3 cases reached
16230
16231} else
16232{
16233{
16234IkReal j0array[1], cj0array[1], sj0array[1];
16235bool j0valid[1]={false};
16236_nj0 = 1;
16237CheckValue<IkReal> x1201=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r00))+(((-1.0)*gconst32*new_r10)))),-1);
16238if(!x1201.valid){
16239continue;
16240}
16241CheckValue<IkReal> x1202 = IKatan2WithCheck(IkReal(gconst33*gconst33),IkReal(((-1.0)*gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH);
16242if(!x1202.valid){
16243continue;
16244}
16245j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1201.value)))+(x1202.value));
16246sj0array[0]=IKsin(j0array[0]);
16247cj0array[0]=IKcos(j0array[0]);
16248if( j0array[0] > IKPI )
16249{
16250 j0array[0]-=IK2PI;
16251}
16252else if( j0array[0] < -IKPI )
16253{ j0array[0]+=IK2PI;
16254}
16255j0valid[0] = true;
16256for(int ij0 = 0; ij0 < 1; ++ij0)
16257{
16258if( !j0valid[ij0] )
16259{
16260 continue;
16261}
16262_ij0[0] = ij0; _ij0[1] = -1;
16263for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16264{
16265if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16266{
16267 j0valid[iij0]=false; _ij0[1] = iij0; break;
16268}
16269}
16270j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16271{
16272IkReal evalcond[6];
16273IkReal x1203=IKsin(j0);
16274IkReal x1204=IKcos(j0);
16275IkReal x1205=((1.0)*gconst32);
16276IkReal x1206=(gconst33*x1203);
16277IkReal x1207=((1.0)*x1204);
16278IkReal x1208=(((gconst33*x1207))+((x1203*x1205)));
16279evalcond[0]=((((-1.0)*x1206))+((gconst32*x1204)));
16280evalcond[1]=(((new_r00*x1203))+gconst33+(((-1.0)*new_r10*x1207)));
16281evalcond[2]=((((-1.0)*x1204*x1205))+x1206+new_r00);
16282evalcond[3]=((-1.0)*x1208);
16283evalcond[4]=(((new_r00*x1204))+((new_r10*x1203))+(((-1.0)*x1205)));
16284evalcond[5]=(new_r10+(((-1.0)*x1208)));
16285if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16286{
16287continue;
16288}
16289}
16290
16291{
16292std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16293vinfos[0].jointtype = 1;
16294vinfos[0].foffset = j0;
16295vinfos[0].indices[0] = _ij0[0];
16296vinfos[0].indices[1] = _ij0[1];
16297vinfos[0].maxsolutions = _nj0;
16298vinfos[1].jointtype = 1;
16299vinfos[1].foffset = j1;
16300vinfos[1].indices[0] = _ij1[0];
16301vinfos[1].indices[1] = _ij1[1];
16302vinfos[1].maxsolutions = _nj1;
16303vinfos[2].jointtype = 1;
16304vinfos[2].foffset = j2;
16305vinfos[2].indices[0] = _ij2[0];
16306vinfos[2].indices[1] = _ij2[1];
16307vinfos[2].maxsolutions = _nj2;
16308vinfos[3].jointtype = 1;
16309vinfos[3].foffset = j3;
16310vinfos[3].indices[0] = _ij3[0];
16311vinfos[3].indices[1] = _ij3[1];
16312vinfos[3].maxsolutions = _nj3;
16313vinfos[4].jointtype = 1;
16314vinfos[4].foffset = j4;
16315vinfos[4].indices[0] = _ij4[0];
16316vinfos[4].indices[1] = _ij4[1];
16317vinfos[4].maxsolutions = _nj4;
16318vinfos[5].jointtype = 1;
16319vinfos[5].foffset = j5;
16320vinfos[5].indices[0] = _ij5[0];
16321vinfos[5].indices[1] = _ij5[1];
16322vinfos[5].maxsolutions = _nj5;
16323std::vector<int> vfree(0);
16324solutions.AddSolution(vinfos,vfree);
16325}
16326}
16327}
16328
16329}
16330
16331}
16332
16333} else
16334{
16335{
16336IkReal j0array[1], cj0array[1], sj0array[1];
16337bool j0valid[1]={false};
16338_nj0 = 1;
16339CheckValue<IkReal> x1209=IKPowWithIntegerCheck(IKsign(((gconst32*gconst32)+(gconst33*gconst33))),-1);
16340if(!x1209.valid){
16341continue;
16342}
16343CheckValue<IkReal> x1210 = IKatan2WithCheck(IkReal((gconst32*new_r10)),IkReal((gconst33*new_r10)),IKFAST_ATAN2_MAGTHRESH);
16344if(!x1210.valid){
16345continue;
16346}
16347j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1209.value)))+(x1210.value));
16348sj0array[0]=IKsin(j0array[0]);
16349cj0array[0]=IKcos(j0array[0]);
16350if( j0array[0] > IKPI )
16351{
16352 j0array[0]-=IK2PI;
16353}
16354else if( j0array[0] < -IKPI )
16355{ j0array[0]+=IK2PI;
16356}
16357j0valid[0] = true;
16358for(int ij0 = 0; ij0 < 1; ++ij0)
16359{
16360if( !j0valid[ij0] )
16361{
16362 continue;
16363}
16364_ij0[0] = ij0; _ij0[1] = -1;
16365for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16366{
16367if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16368{
16369 j0valid[iij0]=false; _ij0[1] = iij0; break;
16370}
16371}
16372j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16373{
16374IkReal evalcond[6];
16375IkReal x1211=IKsin(j0);
16376IkReal x1212=IKcos(j0);
16377IkReal x1213=((1.0)*gconst32);
16378IkReal x1214=(gconst33*x1211);
16379IkReal x1215=((1.0)*x1212);
16380IkReal x1216=(((gconst33*x1215))+((x1211*x1213)));
16381evalcond[0]=(((gconst32*x1212))+(((-1.0)*x1214)));
16382evalcond[1]=(gconst33+((new_r00*x1211))+(((-1.0)*new_r10*x1215)));
16383evalcond[2]=(x1214+(((-1.0)*x1212*x1213))+new_r00);
16384evalcond[3]=((-1.0)*x1216);
16385evalcond[4]=(((new_r10*x1211))+((new_r00*x1212))+(((-1.0)*x1213)));
16386evalcond[5]=(new_r10+(((-1.0)*x1216)));
16387if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16388{
16389continue;
16390}
16391}
16392
16393{
16394std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16395vinfos[0].jointtype = 1;
16396vinfos[0].foffset = j0;
16397vinfos[0].indices[0] = _ij0[0];
16398vinfos[0].indices[1] = _ij0[1];
16399vinfos[0].maxsolutions = _nj0;
16400vinfos[1].jointtype = 1;
16401vinfos[1].foffset = j1;
16402vinfos[1].indices[0] = _ij1[0];
16403vinfos[1].indices[1] = _ij1[1];
16404vinfos[1].maxsolutions = _nj1;
16405vinfos[2].jointtype = 1;
16406vinfos[2].foffset = j2;
16407vinfos[2].indices[0] = _ij2[0];
16408vinfos[2].indices[1] = _ij2[1];
16409vinfos[2].maxsolutions = _nj2;
16410vinfos[3].jointtype = 1;
16411vinfos[3].foffset = j3;
16412vinfos[3].indices[0] = _ij3[0];
16413vinfos[3].indices[1] = _ij3[1];
16414vinfos[3].maxsolutions = _nj3;
16415vinfos[4].jointtype = 1;
16416vinfos[4].foffset = j4;
16417vinfos[4].indices[0] = _ij4[0];
16418vinfos[4].indices[1] = _ij4[1];
16419vinfos[4].maxsolutions = _nj4;
16420vinfos[5].jointtype = 1;
16421vinfos[5].foffset = j5;
16422vinfos[5].indices[0] = _ij5[0];
16423vinfos[5].indices[1] = _ij5[1];
16424vinfos[5].maxsolutions = _nj5;
16425std::vector<int> vfree(0);
16426solutions.AddSolution(vinfos,vfree);
16427}
16428}
16429}
16430
16431}
16432
16433}
16434
16435} else
16436{
16437{
16438IkReal j0array[1], cj0array[1], sj0array[1];
16439bool j0valid[1]={false};
16440_nj0 = 1;
16441CheckValue<IkReal> x1217=IKPowWithIntegerCheck(IKsign((((gconst33*new_r00))+((gconst32*new_r10)))),-1);
16442if(!x1217.valid){
16443continue;
16444}
16445CheckValue<IkReal> x1218 = IKatan2WithCheck(IkReal(gconst32*gconst32),IkReal((gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH);
16446if(!x1218.valid){
16447continue;
16448}
16449j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1217.value)))+(x1218.value));
16450sj0array[0]=IKsin(j0array[0]);
16451cj0array[0]=IKcos(j0array[0]);
16452if( j0array[0] > IKPI )
16453{
16454 j0array[0]-=IK2PI;
16455}
16456else if( j0array[0] < -IKPI )
16457{ j0array[0]+=IK2PI;
16458}
16459j0valid[0] = true;
16460for(int ij0 = 0; ij0 < 1; ++ij0)
16461{
16462if( !j0valid[ij0] )
16463{
16464 continue;
16465}
16466_ij0[0] = ij0; _ij0[1] = -1;
16467for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16468{
16469if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16470{
16471 j0valid[iij0]=false; _ij0[1] = iij0; break;
16472}
16473}
16474j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16475{
16476IkReal evalcond[6];
16477IkReal x1219=IKsin(j0);
16478IkReal x1220=IKcos(j0);
16479IkReal x1221=((1.0)*gconst32);
16480IkReal x1222=(gconst33*x1219);
16481IkReal x1223=((1.0)*x1220);
16482IkReal x1224=(((x1219*x1221))+((gconst33*x1223)));
16483evalcond[0]=((((-1.0)*x1222))+((gconst32*x1220)));
16484evalcond[1]=(gconst33+((new_r00*x1219))+(((-1.0)*new_r10*x1223)));
16485evalcond[2]=(x1222+(((-1.0)*x1220*x1221))+new_r00);
16486evalcond[3]=((-1.0)*x1224);
16487evalcond[4]=(((new_r10*x1219))+(((-1.0)*x1221))+((new_r00*x1220)));
16488evalcond[5]=((((-1.0)*x1224))+new_r10);
16489if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16490{
16491continue;
16492}
16493}
16494
16495{
16496std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16497vinfos[0].jointtype = 1;
16498vinfos[0].foffset = j0;
16499vinfos[0].indices[0] = _ij0[0];
16500vinfos[0].indices[1] = _ij0[1];
16501vinfos[0].maxsolutions = _nj0;
16502vinfos[1].jointtype = 1;
16503vinfos[1].foffset = j1;
16504vinfos[1].indices[0] = _ij1[0];
16505vinfos[1].indices[1] = _ij1[1];
16506vinfos[1].maxsolutions = _nj1;
16507vinfos[2].jointtype = 1;
16508vinfos[2].foffset = j2;
16509vinfos[2].indices[0] = _ij2[0];
16510vinfos[2].indices[1] = _ij2[1];
16511vinfos[2].maxsolutions = _nj2;
16512vinfos[3].jointtype = 1;
16513vinfos[3].foffset = j3;
16514vinfos[3].indices[0] = _ij3[0];
16515vinfos[3].indices[1] = _ij3[1];
16516vinfos[3].maxsolutions = _nj3;
16517vinfos[4].jointtype = 1;
16518vinfos[4].foffset = j4;
16519vinfos[4].indices[0] = _ij4[0];
16520vinfos[4].indices[1] = _ij4[1];
16521vinfos[4].maxsolutions = _nj4;
16522vinfos[5].jointtype = 1;
16523vinfos[5].foffset = j5;
16524vinfos[5].indices[0] = _ij5[0];
16525vinfos[5].indices[1] = _ij5[1];
16526vinfos[5].maxsolutions = _nj5;
16527std::vector<int> vfree(0);
16528solutions.AddSolution(vinfos,vfree);
16529}
16530}
16531}
16532
16533}
16534
16535}
16536
16537}
16538} while(0);
16539if( bgotonextstatement )
16540{
16541bool bgotonextstatement = true;
16542do
16543{
16544evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
16545if( IKabs(evalcond[0]) < 0.0000050000000000 )
16546{
16547bgotonextstatement=false;
16548{
16549IkReal j0array[2], cj0array[2], sj0array[2];
16550bool j0valid[2]={false};
16551_nj0 = 2;
16552CheckValue<IkReal> x1225=IKPowWithIntegerCheck(gconst33,-1);
16553if(!x1225.valid){
16554continue;
16555}
16556sj0array[0]=(new_r11*(x1225.value));
16557if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH )
16558{
16559 j0valid[0] = j0valid[1] = true;
16560 j0array[0] = IKasin(sj0array[0]);
16561 cj0array[0] = IKcos(j0array[0]);
16562 sj0array[1] = sj0array[0];
16563 j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]);
16564 cj0array[1] = -cj0array[0];
16565}
16566else if( isnan(sj0array[0]) )
16567{
16568 // probably any value will work
16569 j0valid[0] = true;
16570 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
16571}
16572for(int ij0 = 0; ij0 < 2; ++ij0)
16573{
16574if( !j0valid[ij0] )
16575{
16576 continue;
16577}
16578_ij0[0] = ij0; _ij0[1] = -1;
16579for(int iij0 = ij0+1; iij0 < 2; ++iij0)
16580{
16581if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16582{
16583 j0valid[iij0]=false; _ij0[1] = iij0; break;
16584}
16585}
16586j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16587{
16588IkReal evalcond[6];
16589IkReal x1226=IKcos(j0);
16590IkReal x1227=IKsin(j0);
16591evalcond[0]=(new_r11*x1226);
16592evalcond[1]=(new_r00*x1226);
16593evalcond[2]=((-1.0)*gconst33*x1226);
16594evalcond[3]=(gconst33+((new_r00*x1227)));
16595evalcond[4]=(((gconst33*x1227))+new_r00);
16596evalcond[5]=(((new_r11*x1227))+(((-1.0)*gconst33)));
16597if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
16598{
16599continue;
16600}
16601}
16602
16603{
16604std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16605vinfos[0].jointtype = 1;
16606vinfos[0].foffset = j0;
16607vinfos[0].indices[0] = _ij0[0];
16608vinfos[0].indices[1] = _ij0[1];
16609vinfos[0].maxsolutions = _nj0;
16610vinfos[1].jointtype = 1;
16611vinfos[1].foffset = j1;
16612vinfos[1].indices[0] = _ij1[0];
16613vinfos[1].indices[1] = _ij1[1];
16614vinfos[1].maxsolutions = _nj1;
16615vinfos[2].jointtype = 1;
16616vinfos[2].foffset = j2;
16617vinfos[2].indices[0] = _ij2[0];
16618vinfos[2].indices[1] = _ij2[1];
16619vinfos[2].maxsolutions = _nj2;
16620vinfos[3].jointtype = 1;
16621vinfos[3].foffset = j3;
16622vinfos[3].indices[0] = _ij3[0];
16623vinfos[3].indices[1] = _ij3[1];
16624vinfos[3].maxsolutions = _nj3;
16625vinfos[4].jointtype = 1;
16626vinfos[4].foffset = j4;
16627vinfos[4].indices[0] = _ij4[0];
16628vinfos[4].indices[1] = _ij4[1];
16629vinfos[4].maxsolutions = _nj4;
16630vinfos[5].jointtype = 1;
16631vinfos[5].foffset = j5;
16632vinfos[5].indices[0] = _ij5[0];
16633vinfos[5].indices[1] = _ij5[1];
16634vinfos[5].maxsolutions = _nj5;
16635std::vector<int> vfree(0);
16636solutions.AddSolution(vinfos,vfree);
16637}
16638}
16639}
16640
16641}
16642} while(0);
16643if( bgotonextstatement )
16644{
16645bool bgotonextstatement = true;
16646do
16647{
16648evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
16649if( IKabs(evalcond[0]) < 0.0000050000000000 )
16650{
16651bgotonextstatement=false;
16652{
16653IkReal j0eval[1];
16654CheckValue<IkReal> x1229 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16655if(!x1229.valid){
16656continue;
16657}
16658IkReal x1228=((1.0)*(x1229.value));
16659sj1=-1.0;
16660cj1=0;
16661j1=-1.5707963267949;
16662sj2=gconst32;
16663cj2=gconst33;
16664j2=((3.14159265)+(((-1.0)*x1228)));
16665new_r11=0;
16666new_r10=0;
16667new_r22=0;
16668new_r02=0;
16669IkReal gconst31=((3.14159265358979)+(((-1.0)*x1228)));
16670IkReal gconst32=0;
16671IkReal x1230 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16672if(IKabs(x1230)==0){
16673continue;
16674}
16675IkReal gconst33=((1.0)*new_r00*(pow(x1230,-0.5)));
16676j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
16677if( IKabs(j0eval[0]) < 0.0000010000000000 )
16678{
16679{
16680IkReal j0eval[1];
16681CheckValue<IkReal> x1232 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16682if(!x1232.valid){
16683continue;
16684}
16685IkReal x1231=((1.0)*(x1232.value));
16686sj1=-1.0;
16687cj1=0;
16688j1=-1.5707963267949;
16689sj2=gconst32;
16690cj2=gconst33;
16691j2=((3.14159265)+(((-1.0)*x1231)));
16692new_r11=0;
16693new_r10=0;
16694new_r22=0;
16695new_r02=0;
16696IkReal gconst31=((3.14159265358979)+(((-1.0)*x1231)));
16697IkReal gconst32=0;
16698IkReal x1233 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16699if(IKabs(x1233)==0){
16700continue;
16701}
16702IkReal gconst33=((1.0)*new_r00*(pow(x1233,-0.5)));
16703j0eval[0]=new_r00;
16704if( IKabs(j0eval[0]) < 0.0000010000000000 )
16705{
16706{
16707IkReal j0eval[2];
16708CheckValue<IkReal> x1235 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
16709if(!x1235.valid){
16710continue;
16711}
16712IkReal x1234=((1.0)*(x1235.value));
16713sj1=-1.0;
16714cj1=0;
16715j1=-1.5707963267949;
16716sj2=gconst32;
16717cj2=gconst33;
16718j2=((3.14159265)+(((-1.0)*x1234)));
16719new_r11=0;
16720new_r10=0;
16721new_r22=0;
16722new_r02=0;
16723IkReal gconst31=((3.14159265358979)+(((-1.0)*x1234)));
16724IkReal gconst32=0;
16725IkReal x1236 = ((1.0)+(((-1.0)*(new_r01*new_r01))));
16726if(IKabs(x1236)==0){
16727continue;
16728}
16729IkReal gconst33=((1.0)*new_r00*(pow(x1236,-0.5)));
16730j0eval[0]=new_r00;
16731j0eval[1]=new_r01;
16732if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
16733{
16734continue; // 3 cases reached
16735
16736} else
16737{
16738{
16739IkReal j0array[1], cj0array[1], sj0array[1];
16740bool j0valid[1]={false};
16741_nj0 = 1;
16742CheckValue<IkReal> x1237=IKPowWithIntegerCheck(new_r00,-1);
16743if(!x1237.valid){
16744continue;
16745}
16746CheckValue<IkReal> x1238=IKPowWithIntegerCheck(new_r01,-1);
16747if(!x1238.valid){
16748continue;
16749}
16750if( IKabs(((-1.0)*gconst33*(x1237.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst33*(x1238.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1237.value)))+IKsqr((gconst33*(x1238.value)))-1) <= IKFAST_SINCOS_THRESH )
16751 continue;
16752j0array[0]=IKatan2(((-1.0)*gconst33*(x1237.value)), (gconst33*(x1238.value)));
16753sj0array[0]=IKsin(j0array[0]);
16754cj0array[0]=IKcos(j0array[0]);
16755if( j0array[0] > IKPI )
16756{
16757 j0array[0]-=IK2PI;
16758}
16759else if( j0array[0] < -IKPI )
16760{ j0array[0]+=IK2PI;
16761}
16762j0valid[0] = true;
16763for(int ij0 = 0; ij0 < 1; ++ij0)
16764{
16765if( !j0valid[ij0] )
16766{
16767 continue;
16768}
16769_ij0[0] = ij0; _ij0[1] = -1;
16770for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16771{
16772if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16773{
16774 j0valid[iij0]=false; _ij0[1] = iij0; break;
16775}
16776}
16777j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16778{
16779IkReal evalcond[8];
16780IkReal x1239=IKsin(j0);
16781IkReal x1240=IKcos(j0);
16782IkReal x1241=((1.0)*gconst33);
16783IkReal x1242=(gconst33*x1239);
16784evalcond[0]=(new_r00*x1240);
16785evalcond[1]=((-1.0)*new_r01*x1239);
16786evalcond[2]=((-1.0)*x1242);
16787evalcond[3]=((-1.0)*gconst33*x1240);
16788evalcond[4]=(gconst33+((new_r00*x1239)));
16789evalcond[5]=(x1242+new_r00);
16790evalcond[6]=((((-1.0)*x1240*x1241))+new_r01);
16791evalcond[7]=((((-1.0)*x1241))+((new_r01*x1240)));
16792if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
16793{
16794continue;
16795}
16796}
16797
16798{
16799std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16800vinfos[0].jointtype = 1;
16801vinfos[0].foffset = j0;
16802vinfos[0].indices[0] = _ij0[0];
16803vinfos[0].indices[1] = _ij0[1];
16804vinfos[0].maxsolutions = _nj0;
16805vinfos[1].jointtype = 1;
16806vinfos[1].foffset = j1;
16807vinfos[1].indices[0] = _ij1[0];
16808vinfos[1].indices[1] = _ij1[1];
16809vinfos[1].maxsolutions = _nj1;
16810vinfos[2].jointtype = 1;
16811vinfos[2].foffset = j2;
16812vinfos[2].indices[0] = _ij2[0];
16813vinfos[2].indices[1] = _ij2[1];
16814vinfos[2].maxsolutions = _nj2;
16815vinfos[3].jointtype = 1;
16816vinfos[3].foffset = j3;
16817vinfos[3].indices[0] = _ij3[0];
16818vinfos[3].indices[1] = _ij3[1];
16819vinfos[3].maxsolutions = _nj3;
16820vinfos[4].jointtype = 1;
16821vinfos[4].foffset = j4;
16822vinfos[4].indices[0] = _ij4[0];
16823vinfos[4].indices[1] = _ij4[1];
16824vinfos[4].maxsolutions = _nj4;
16825vinfos[5].jointtype = 1;
16826vinfos[5].foffset = j5;
16827vinfos[5].indices[0] = _ij5[0];
16828vinfos[5].indices[1] = _ij5[1];
16829vinfos[5].maxsolutions = _nj5;
16830std::vector<int> vfree(0);
16831solutions.AddSolution(vinfos,vfree);
16832}
16833}
16834}
16835
16836}
16837
16838}
16839
16840} else
16841{
16842{
16843IkReal j0array[1], cj0array[1], sj0array[1];
16844bool j0valid[1]={false};
16845_nj0 = 1;
16846CheckValue<IkReal> x1243=IKPowWithIntegerCheck(new_r00,-1);
16847if(!x1243.valid){
16848continue;
16849}
16850CheckValue<IkReal> x1244=IKPowWithIntegerCheck(gconst33,-1);
16851if(!x1244.valid){
16852continue;
16853}
16854if( IKabs(((-1.0)*gconst33*(x1243.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1244.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1243.value)))+IKsqr((new_r01*(x1244.value)))-1) <= IKFAST_SINCOS_THRESH )
16855 continue;
16856j0array[0]=IKatan2(((-1.0)*gconst33*(x1243.value)), (new_r01*(x1244.value)));
16857sj0array[0]=IKsin(j0array[0]);
16858cj0array[0]=IKcos(j0array[0]);
16859if( j0array[0] > IKPI )
16860{
16861 j0array[0]-=IK2PI;
16862}
16863else if( j0array[0] < -IKPI )
16864{ j0array[0]+=IK2PI;
16865}
16866j0valid[0] = true;
16867for(int ij0 = 0; ij0 < 1; ++ij0)
16868{
16869if( !j0valid[ij0] )
16870{
16871 continue;
16872}
16873_ij0[0] = ij0; _ij0[1] = -1;
16874for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16875{
16876if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16877{
16878 j0valid[iij0]=false; _ij0[1] = iij0; break;
16879}
16880}
16881j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16882{
16883IkReal evalcond[8];
16884IkReal x1245=IKsin(j0);
16885IkReal x1246=IKcos(j0);
16886IkReal x1247=((1.0)*gconst33);
16887IkReal x1248=(gconst33*x1245);
16888evalcond[0]=(new_r00*x1246);
16889evalcond[1]=((-1.0)*new_r01*x1245);
16890evalcond[2]=((-1.0)*x1248);
16891evalcond[3]=((-1.0)*gconst33*x1246);
16892evalcond[4]=(gconst33+((new_r00*x1245)));
16893evalcond[5]=(x1248+new_r00);
16894evalcond[6]=(new_r01+(((-1.0)*x1246*x1247)));
16895evalcond[7]=((((-1.0)*x1247))+((new_r01*x1246)));
16896if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
16897{
16898continue;
16899}
16900}
16901
16902{
16903std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16904vinfos[0].jointtype = 1;
16905vinfos[0].foffset = j0;
16906vinfos[0].indices[0] = _ij0[0];
16907vinfos[0].indices[1] = _ij0[1];
16908vinfos[0].maxsolutions = _nj0;
16909vinfos[1].jointtype = 1;
16910vinfos[1].foffset = j1;
16911vinfos[1].indices[0] = _ij1[0];
16912vinfos[1].indices[1] = _ij1[1];
16913vinfos[1].maxsolutions = _nj1;
16914vinfos[2].jointtype = 1;
16915vinfos[2].foffset = j2;
16916vinfos[2].indices[0] = _ij2[0];
16917vinfos[2].indices[1] = _ij2[1];
16918vinfos[2].maxsolutions = _nj2;
16919vinfos[3].jointtype = 1;
16920vinfos[3].foffset = j3;
16921vinfos[3].indices[0] = _ij3[0];
16922vinfos[3].indices[1] = _ij3[1];
16923vinfos[3].maxsolutions = _nj3;
16924vinfos[4].jointtype = 1;
16925vinfos[4].foffset = j4;
16926vinfos[4].indices[0] = _ij4[0];
16927vinfos[4].indices[1] = _ij4[1];
16928vinfos[4].maxsolutions = _nj4;
16929vinfos[5].jointtype = 1;
16930vinfos[5].foffset = j5;
16931vinfos[5].indices[0] = _ij5[0];
16932vinfos[5].indices[1] = _ij5[1];
16933vinfos[5].maxsolutions = _nj5;
16934std::vector<int> vfree(0);
16935solutions.AddSolution(vinfos,vfree);
16936}
16937}
16938}
16939
16940}
16941
16942}
16943
16944} else
16945{
16946{
16947IkReal j0array[1], cj0array[1], sj0array[1];
16948bool j0valid[1]={false};
16949_nj0 = 1;
16950CheckValue<IkReal> x1249 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
16951if(!x1249.valid){
16952continue;
16953}
16954CheckValue<IkReal> x1250=IKPowWithIntegerCheck(IKsign(gconst33),-1);
16955if(!x1250.valid){
16956continue;
16957}
16958j0array[0]=((-1.5707963267949)+(x1249.value)+(((1.5707963267949)*(x1250.value))));
16959sj0array[0]=IKsin(j0array[0]);
16960cj0array[0]=IKcos(j0array[0]);
16961if( j0array[0] > IKPI )
16962{
16963 j0array[0]-=IK2PI;
16964}
16965else if( j0array[0] < -IKPI )
16966{ j0array[0]+=IK2PI;
16967}
16968j0valid[0] = true;
16969for(int ij0 = 0; ij0 < 1; ++ij0)
16970{
16971if( !j0valid[ij0] )
16972{
16973 continue;
16974}
16975_ij0[0] = ij0; _ij0[1] = -1;
16976for(int iij0 = ij0+1; iij0 < 1; ++iij0)
16977{
16978if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
16979{
16980 j0valid[iij0]=false; _ij0[1] = iij0; break;
16981}
16982}
16983j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
16984{
16985IkReal evalcond[8];
16986IkReal x1251=IKsin(j0);
16987IkReal x1252=IKcos(j0);
16988IkReal x1253=((1.0)*gconst33);
16989IkReal x1254=(gconst33*x1251);
16990evalcond[0]=(new_r00*x1252);
16991evalcond[1]=((-1.0)*new_r01*x1251);
16992evalcond[2]=((-1.0)*x1254);
16993evalcond[3]=((-1.0)*gconst33*x1252);
16994evalcond[4]=(((new_r00*x1251))+gconst33);
16995evalcond[5]=(x1254+new_r00);
16996evalcond[6]=((((-1.0)*x1252*x1253))+new_r01);
16997evalcond[7]=((((-1.0)*x1253))+((new_r01*x1252)));
16998if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
16999{
17000continue;
17001}
17002}
17003
17004{
17005std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17006vinfos[0].jointtype = 1;
17007vinfos[0].foffset = j0;
17008vinfos[0].indices[0] = _ij0[0];
17009vinfos[0].indices[1] = _ij0[1];
17010vinfos[0].maxsolutions = _nj0;
17011vinfos[1].jointtype = 1;
17012vinfos[1].foffset = j1;
17013vinfos[1].indices[0] = _ij1[0];
17014vinfos[1].indices[1] = _ij1[1];
17015vinfos[1].maxsolutions = _nj1;
17016vinfos[2].jointtype = 1;
17017vinfos[2].foffset = j2;
17018vinfos[2].indices[0] = _ij2[0];
17019vinfos[2].indices[1] = _ij2[1];
17020vinfos[2].maxsolutions = _nj2;
17021vinfos[3].jointtype = 1;
17022vinfos[3].foffset = j3;
17023vinfos[3].indices[0] = _ij3[0];
17024vinfos[3].indices[1] = _ij3[1];
17025vinfos[3].maxsolutions = _nj3;
17026vinfos[4].jointtype = 1;
17027vinfos[4].foffset = j4;
17028vinfos[4].indices[0] = _ij4[0];
17029vinfos[4].indices[1] = _ij4[1];
17030vinfos[4].maxsolutions = _nj4;
17031vinfos[5].jointtype = 1;
17032vinfos[5].foffset = j5;
17033vinfos[5].indices[0] = _ij5[0];
17034vinfos[5].indices[1] = _ij5[1];
17035vinfos[5].maxsolutions = _nj5;
17036std::vector<int> vfree(0);
17037solutions.AddSolution(vinfos,vfree);
17038}
17039}
17040}
17041
17042}
17043
17044}
17045
17046}
17047} while(0);
17048if( bgotonextstatement )
17049{
17050bool bgotonextstatement = true;
17051do
17052{
17053evalcond[0]=IKabs(new_r10);
17054if( IKabs(evalcond[0]) < 0.0000050000000000 )
17055{
17056bgotonextstatement=false;
17057{
17058IkReal j0eval[1];
17059CheckValue<IkReal> x1256 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
17060if(!x1256.valid){
17061continue;
17062}
17063IkReal x1255=((1.0)*(x1256.value));
17064sj1=-1.0;
17065cj1=0;
17066j1=-1.5707963267949;
17067sj2=gconst32;
17068cj2=gconst33;
17069j2=((3.14159265)+(((-1.0)*x1255)));
17070new_r10=0;
17071IkReal gconst31=((3.14159265358979)+(((-1.0)*x1255)));
17072IkReal gconst32=0;
17073IkReal x1257 = new_r00*new_r00;
17074if(IKabs(x1257)==0){
17075continue;
17076}
17077IkReal gconst33=((1.0)*new_r00*(pow(x1257,-0.5)));
17078j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
17079if( IKabs(j0eval[0]) < 0.0000010000000000 )
17080{
17081{
17082IkReal j0eval[1];
17083CheckValue<IkReal> x1259 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
17084if(!x1259.valid){
17085continue;
17086}
17087IkReal x1258=((1.0)*(x1259.value));
17088sj1=-1.0;
17089cj1=0;
17090j1=-1.5707963267949;
17091sj2=gconst32;
17092cj2=gconst33;
17093j2=((3.14159265)+(((-1.0)*x1258)));
17094new_r10=0;
17095IkReal gconst31=((3.14159265358979)+(((-1.0)*x1258)));
17096IkReal gconst32=0;
17097IkReal x1260 = new_r00*new_r00;
17098if(IKabs(x1260)==0){
17099continue;
17100}
17101IkReal gconst33=((1.0)*new_r00*(pow(x1260,-0.5)));
17102j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
17103if( IKabs(j0eval[0]) < 0.0000010000000000 )
17104{
17105{
17106IkReal j0eval[1];
17107CheckValue<IkReal> x1262 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH);
17108if(!x1262.valid){
17109continue;
17110}
17111IkReal x1261=((1.0)*(x1262.value));
17112sj1=-1.0;
17113cj1=0;
17114j1=-1.5707963267949;
17115sj2=gconst32;
17116cj2=gconst33;
17117j2=((3.14159265)+(((-1.0)*x1261)));
17118new_r10=0;
17119IkReal gconst31=((3.14159265358979)+(((-1.0)*x1261)));
17120IkReal gconst32=0;
17121IkReal x1263 = new_r00*new_r00;
17122if(IKabs(x1263)==0){
17123continue;
17124}
17125IkReal gconst33=((1.0)*new_r00*(pow(x1263,-0.5)));
17126j0eval[0]=new_r00;
17127if( IKabs(j0eval[0]) < 0.0000010000000000 )
17128{
17129continue; // 3 cases reached
17130
17131} else
17132{
17133{
17134IkReal j0array[1], cj0array[1], sj0array[1];
17135bool j0valid[1]={false};
17136_nj0 = 1;
17137CheckValue<IkReal> x1264=IKPowWithIntegerCheck(new_r00,-1);
17138if(!x1264.valid){
17139continue;
17140}
17141CheckValue<IkReal> x1265=IKPowWithIntegerCheck(gconst33,-1);
17142if(!x1265.valid){
17143continue;
17144}
17145if( IKabs(((-1.0)*gconst33*(x1264.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1265.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1264.value)))+IKsqr((new_r01*(x1265.value)))-1) <= IKFAST_SINCOS_THRESH )
17146 continue;
17147j0array[0]=IKatan2(((-1.0)*gconst33*(x1264.value)), (new_r01*(x1265.value)));
17148sj0array[0]=IKsin(j0array[0]);
17149cj0array[0]=IKcos(j0array[0]);
17150if( j0array[0] > IKPI )
17151{
17152 j0array[0]-=IK2PI;
17153}
17154else if( j0array[0] < -IKPI )
17155{ j0array[0]+=IK2PI;
17156}
17157j0valid[0] = true;
17158for(int ij0 = 0; ij0 < 1; ++ij0)
17159{
17160if( !j0valid[ij0] )
17161{
17162 continue;
17163}
17164_ij0[0] = ij0; _ij0[1] = -1;
17165for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17166{
17167if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17168{
17169 j0valid[iij0]=false; _ij0[1] = iij0; break;
17170}
17171}
17172j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17173{
17174IkReal evalcond[8];
17175IkReal x1266=IKcos(j0);
17176IkReal x1267=IKsin(j0);
17177IkReal x1268=((1.0)*gconst33);
17178evalcond[0]=(new_r00*x1266);
17179evalcond[1]=((-1.0)*gconst33*x1266);
17180evalcond[2]=(gconst33+((new_r00*x1267)));
17181evalcond[3]=(((gconst33*x1267))+new_r00);
17182evalcond[4]=((((-1.0)*x1267*x1268))+new_r11);
17183evalcond[5]=((((-1.0)*x1266*x1268))+new_r01);
17184evalcond[6]=((((-1.0)*new_r01*x1267))+((new_r11*x1266)));
17185evalcond[7]=(((new_r01*x1266))+((new_r11*x1267))+(((-1.0)*x1268)));
17186if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17187{
17188continue;
17189}
17190}
17191
17192{
17193std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17194vinfos[0].jointtype = 1;
17195vinfos[0].foffset = j0;
17196vinfos[0].indices[0] = _ij0[0];
17197vinfos[0].indices[1] = _ij0[1];
17198vinfos[0].maxsolutions = _nj0;
17199vinfos[1].jointtype = 1;
17200vinfos[1].foffset = j1;
17201vinfos[1].indices[0] = _ij1[0];
17202vinfos[1].indices[1] = _ij1[1];
17203vinfos[1].maxsolutions = _nj1;
17204vinfos[2].jointtype = 1;
17205vinfos[2].foffset = j2;
17206vinfos[2].indices[0] = _ij2[0];
17207vinfos[2].indices[1] = _ij2[1];
17208vinfos[2].maxsolutions = _nj2;
17209vinfos[3].jointtype = 1;
17210vinfos[3].foffset = j3;
17211vinfos[3].indices[0] = _ij3[0];
17212vinfos[3].indices[1] = _ij3[1];
17213vinfos[3].maxsolutions = _nj3;
17214vinfos[4].jointtype = 1;
17215vinfos[4].foffset = j4;
17216vinfos[4].indices[0] = _ij4[0];
17217vinfos[4].indices[1] = _ij4[1];
17218vinfos[4].maxsolutions = _nj4;
17219vinfos[5].jointtype = 1;
17220vinfos[5].foffset = j5;
17221vinfos[5].indices[0] = _ij5[0];
17222vinfos[5].indices[1] = _ij5[1];
17223vinfos[5].maxsolutions = _nj5;
17224std::vector<int> vfree(0);
17225solutions.AddSolution(vinfos,vfree);
17226}
17227}
17228}
17229
17230}
17231
17232}
17233
17234} else
17235{
17236{
17237IkReal j0array[1], cj0array[1], sj0array[1];
17238bool j0valid[1]={false};
17239_nj0 = 1;
17240CheckValue<IkReal> x1269 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
17241if(!x1269.valid){
17242continue;
17243}
17244CheckValue<IkReal> x1270=IKPowWithIntegerCheck(IKsign(gconst33),-1);
17245if(!x1270.valid){
17246continue;
17247}
17248j0array[0]=((-1.5707963267949)+(x1269.value)+(((1.5707963267949)*(x1270.value))));
17249sj0array[0]=IKsin(j0array[0]);
17250cj0array[0]=IKcos(j0array[0]);
17251if( j0array[0] > IKPI )
17252{
17253 j0array[0]-=IK2PI;
17254}
17255else if( j0array[0] < -IKPI )
17256{ j0array[0]+=IK2PI;
17257}
17258j0valid[0] = true;
17259for(int ij0 = 0; ij0 < 1; ++ij0)
17260{
17261if( !j0valid[ij0] )
17262{
17263 continue;
17264}
17265_ij0[0] = ij0; _ij0[1] = -1;
17266for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17267{
17268if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17269{
17270 j0valid[iij0]=false; _ij0[1] = iij0; break;
17271}
17272}
17273j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17274{
17275IkReal evalcond[8];
17276IkReal x1271=IKcos(j0);
17277IkReal x1272=IKsin(j0);
17278IkReal x1273=((1.0)*gconst33);
17279evalcond[0]=(new_r00*x1271);
17280evalcond[1]=((-1.0)*gconst33*x1271);
17281evalcond[2]=(((new_r00*x1272))+gconst33);
17282evalcond[3]=(((gconst33*x1272))+new_r00);
17283evalcond[4]=((((-1.0)*x1272*x1273))+new_r11);
17284evalcond[5]=((((-1.0)*x1271*x1273))+new_r01);
17285evalcond[6]=((((-1.0)*new_r01*x1272))+((new_r11*x1271)));
17286evalcond[7]=(((new_r01*x1271))+(((-1.0)*x1273))+((new_r11*x1272)));
17287if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17288{
17289continue;
17290}
17291}
17292
17293{
17294std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17295vinfos[0].jointtype = 1;
17296vinfos[0].foffset = j0;
17297vinfos[0].indices[0] = _ij0[0];
17298vinfos[0].indices[1] = _ij0[1];
17299vinfos[0].maxsolutions = _nj0;
17300vinfos[1].jointtype = 1;
17301vinfos[1].foffset = j1;
17302vinfos[1].indices[0] = _ij1[0];
17303vinfos[1].indices[1] = _ij1[1];
17304vinfos[1].maxsolutions = _nj1;
17305vinfos[2].jointtype = 1;
17306vinfos[2].foffset = j2;
17307vinfos[2].indices[0] = _ij2[0];
17308vinfos[2].indices[1] = _ij2[1];
17309vinfos[2].maxsolutions = _nj2;
17310vinfos[3].jointtype = 1;
17311vinfos[3].foffset = j3;
17312vinfos[3].indices[0] = _ij3[0];
17313vinfos[3].indices[1] = _ij3[1];
17314vinfos[3].maxsolutions = _nj3;
17315vinfos[4].jointtype = 1;
17316vinfos[4].foffset = j4;
17317vinfos[4].indices[0] = _ij4[0];
17318vinfos[4].indices[1] = _ij4[1];
17319vinfos[4].maxsolutions = _nj4;
17320vinfos[5].jointtype = 1;
17321vinfos[5].foffset = j5;
17322vinfos[5].indices[0] = _ij5[0];
17323vinfos[5].indices[1] = _ij5[1];
17324vinfos[5].maxsolutions = _nj5;
17325std::vector<int> vfree(0);
17326solutions.AddSolution(vinfos,vfree);
17327}
17328}
17329}
17330
17331}
17332
17333}
17334
17335} else
17336{
17337{
17338IkReal j0array[1], cj0array[1], sj0array[1];
17339bool j0valid[1]={false};
17340_nj0 = 1;
17341CheckValue<IkReal> x1274 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
17342if(!x1274.valid){
17343continue;
17344}
17345CheckValue<IkReal> x1275=IKPowWithIntegerCheck(IKsign(gconst33),-1);
17346if(!x1275.valid){
17347continue;
17348}
17349j0array[0]=((-1.5707963267949)+(x1274.value)+(((1.5707963267949)*(x1275.value))));
17350sj0array[0]=IKsin(j0array[0]);
17351cj0array[0]=IKcos(j0array[0]);
17352if( j0array[0] > IKPI )
17353{
17354 j0array[0]-=IK2PI;
17355}
17356else if( j0array[0] < -IKPI )
17357{ j0array[0]+=IK2PI;
17358}
17359j0valid[0] = true;
17360for(int ij0 = 0; ij0 < 1; ++ij0)
17361{
17362if( !j0valid[ij0] )
17363{
17364 continue;
17365}
17366_ij0[0] = ij0; _ij0[1] = -1;
17367for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17368{
17369if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17370{
17371 j0valid[iij0]=false; _ij0[1] = iij0; break;
17372}
17373}
17374j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17375{
17376IkReal evalcond[8];
17377IkReal x1276=IKcos(j0);
17378IkReal x1277=IKsin(j0);
17379IkReal x1278=((1.0)*gconst33);
17380evalcond[0]=(new_r00*x1276);
17381evalcond[1]=((-1.0)*gconst33*x1276);
17382evalcond[2]=(((new_r00*x1277))+gconst33);
17383evalcond[3]=(((gconst33*x1277))+new_r00);
17384evalcond[4]=((((-1.0)*x1277*x1278))+new_r11);
17385evalcond[5]=((((-1.0)*x1276*x1278))+new_r01);
17386evalcond[6]=((((-1.0)*new_r01*x1277))+((new_r11*x1276)));
17387evalcond[7]=(((new_r01*x1276))+(((-1.0)*x1278))+((new_r11*x1277)));
17388if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17389{
17390continue;
17391}
17392}
17393
17394{
17395std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17396vinfos[0].jointtype = 1;
17397vinfos[0].foffset = j0;
17398vinfos[0].indices[0] = _ij0[0];
17399vinfos[0].indices[1] = _ij0[1];
17400vinfos[0].maxsolutions = _nj0;
17401vinfos[1].jointtype = 1;
17402vinfos[1].foffset = j1;
17403vinfos[1].indices[0] = _ij1[0];
17404vinfos[1].indices[1] = _ij1[1];
17405vinfos[1].maxsolutions = _nj1;
17406vinfos[2].jointtype = 1;
17407vinfos[2].foffset = j2;
17408vinfos[2].indices[0] = _ij2[0];
17409vinfos[2].indices[1] = _ij2[1];
17410vinfos[2].maxsolutions = _nj2;
17411vinfos[3].jointtype = 1;
17412vinfos[3].foffset = j3;
17413vinfos[3].indices[0] = _ij3[0];
17414vinfos[3].indices[1] = _ij3[1];
17415vinfos[3].maxsolutions = _nj3;
17416vinfos[4].jointtype = 1;
17417vinfos[4].foffset = j4;
17418vinfos[4].indices[0] = _ij4[0];
17419vinfos[4].indices[1] = _ij4[1];
17420vinfos[4].maxsolutions = _nj4;
17421vinfos[5].jointtype = 1;
17422vinfos[5].foffset = j5;
17423vinfos[5].indices[0] = _ij5[0];
17424vinfos[5].indices[1] = _ij5[1];
17425vinfos[5].maxsolutions = _nj5;
17426std::vector<int> vfree(0);
17427solutions.AddSolution(vinfos,vfree);
17428}
17429}
17430}
17431
17432}
17433
17434}
17435
17436}
17437} while(0);
17438if( bgotonextstatement )
17439{
17440bool bgotonextstatement = true;
17441do
17442{
17443evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
17444if( IKabs(evalcond[0]) < 0.0000050000000000 )
17445{
17446bgotonextstatement=false;
17447{
17448IkReal j0eval[1];
17449CheckValue<IkReal> x1280 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17450if(!x1280.valid){
17451continue;
17452}
17453IkReal x1279=((1.0)*(x1280.value));
17454sj1=-1.0;
17455cj1=0;
17456j1=-1.5707963267949;
17457sj2=gconst32;
17458cj2=gconst33;
17459j2=((3.14159265)+(((-1.0)*x1279)));
17460new_r00=0;
17461new_r01=0;
17462new_r12=0;
17463new_r22=0;
17464IkReal gconst31=((3.14159265358979)+(((-1.0)*x1279)));
17465IkReal x1281 = new_r10*new_r10;
17466if(IKabs(x1281)==0){
17467continue;
17468}
17469IkReal gconst32=((1.0)*new_r10*(pow(x1281,-0.5)));
17470IkReal gconst33=0;
17471j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
17472if( IKabs(j0eval[0]) < 0.0000010000000000 )
17473{
17474{
17475IkReal j0eval[1];
17476CheckValue<IkReal> x1283 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17477if(!x1283.valid){
17478continue;
17479}
17480IkReal x1282=((1.0)*(x1283.value));
17481sj1=-1.0;
17482cj1=0;
17483j1=-1.5707963267949;
17484sj2=gconst32;
17485cj2=gconst33;
17486j2=((3.14159265)+(((-1.0)*x1282)));
17487new_r00=0;
17488new_r01=0;
17489new_r12=0;
17490new_r22=0;
17491IkReal gconst31=((3.14159265358979)+(((-1.0)*x1282)));
17492IkReal x1284 = new_r10*new_r10;
17493if(IKabs(x1284)==0){
17494continue;
17495}
17496IkReal gconst32=((1.0)*new_r10*(pow(x1284,-0.5)));
17497IkReal gconst33=0;
17498j0eval[0]=new_r11;
17499if( IKabs(j0eval[0]) < 0.0000010000000000 )
17500{
17501{
17502IkReal j0eval[2];
17503CheckValue<IkReal> x1286 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
17504if(!x1286.valid){
17505continue;
17506}
17507IkReal x1285=((1.0)*(x1286.value));
17508sj1=-1.0;
17509cj1=0;
17510j1=-1.5707963267949;
17511sj2=gconst32;
17512cj2=gconst33;
17513j2=((3.14159265)+(((-1.0)*x1285)));
17514new_r00=0;
17515new_r01=0;
17516new_r12=0;
17517new_r22=0;
17518IkReal gconst31=((3.14159265358979)+(((-1.0)*x1285)));
17519IkReal x1287 = new_r10*new_r10;
17520if(IKabs(x1287)==0){
17521continue;
17522}
17523IkReal gconst32=((1.0)*new_r10*(pow(x1287,-0.5)));
17524IkReal gconst33=0;
17525j0eval[0]=new_r10;
17526j0eval[1]=new_r11;
17527if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
17528{
17529continue; // 3 cases reached
17530
17531} else
17532{
17533{
17534IkReal j0array[1], cj0array[1], sj0array[1];
17535bool j0valid[1]={false};
17536_nj0 = 1;
17537CheckValue<IkReal> x1288=IKPowWithIntegerCheck(new_r10,-1);
17538if(!x1288.valid){
17539continue;
17540}
17541CheckValue<IkReal> x1289=IKPowWithIntegerCheck(new_r11,-1);
17542if(!x1289.valid){
17543continue;
17544}
17545if( IKabs((gconst32*(x1288.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst32*(x1289.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst32*(x1288.value)))+IKsqr(((-1.0)*gconst32*(x1289.value)))-1) <= IKFAST_SINCOS_THRESH )
17546 continue;
17547j0array[0]=IKatan2((gconst32*(x1288.value)), ((-1.0)*gconst32*(x1289.value)));
17548sj0array[0]=IKsin(j0array[0]);
17549cj0array[0]=IKcos(j0array[0]);
17550if( j0array[0] > IKPI )
17551{
17552 j0array[0]-=IK2PI;
17553}
17554else if( j0array[0] < -IKPI )
17555{ j0array[0]+=IK2PI;
17556}
17557j0valid[0] = true;
17558for(int ij0 = 0; ij0 < 1; ++ij0)
17559{
17560if( !j0valid[ij0] )
17561{
17562 continue;
17563}
17564_ij0[0] = ij0; _ij0[1] = -1;
17565for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17566{
17567if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17568{
17569 j0valid[iij0]=false; _ij0[1] = iij0; break;
17570}
17571}
17572j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17573{
17574IkReal evalcond[8];
17575IkReal x1290=IKcos(j0);
17576IkReal x1291=IKsin(j0);
17577IkReal x1292=((1.0)*gconst32);
17578IkReal x1293=(gconst32*x1290);
17579evalcond[0]=(new_r11*x1291);
17580evalcond[1]=((-1.0)*new_r10*x1290);
17581evalcond[2]=((-1.0)*x1293);
17582evalcond[3]=((-1.0)*gconst32*x1291);
17583evalcond[4]=(gconst32+((new_r11*x1290)));
17584evalcond[5]=(x1293+new_r11);
17585evalcond[6]=(new_r10+(((-1.0)*x1291*x1292)));
17586evalcond[7]=((((-1.0)*x1292))+((new_r10*x1291)));
17587if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17588{
17589continue;
17590}
17591}
17592
17593{
17594std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17595vinfos[0].jointtype = 1;
17596vinfos[0].foffset = j0;
17597vinfos[0].indices[0] = _ij0[0];
17598vinfos[0].indices[1] = _ij0[1];
17599vinfos[0].maxsolutions = _nj0;
17600vinfos[1].jointtype = 1;
17601vinfos[1].foffset = j1;
17602vinfos[1].indices[0] = _ij1[0];
17603vinfos[1].indices[1] = _ij1[1];
17604vinfos[1].maxsolutions = _nj1;
17605vinfos[2].jointtype = 1;
17606vinfos[2].foffset = j2;
17607vinfos[2].indices[0] = _ij2[0];
17608vinfos[2].indices[1] = _ij2[1];
17609vinfos[2].maxsolutions = _nj2;
17610vinfos[3].jointtype = 1;
17611vinfos[3].foffset = j3;
17612vinfos[3].indices[0] = _ij3[0];
17613vinfos[3].indices[1] = _ij3[1];
17614vinfos[3].maxsolutions = _nj3;
17615vinfos[4].jointtype = 1;
17616vinfos[4].foffset = j4;
17617vinfos[4].indices[0] = _ij4[0];
17618vinfos[4].indices[1] = _ij4[1];
17619vinfos[4].maxsolutions = _nj4;
17620vinfos[5].jointtype = 1;
17621vinfos[5].foffset = j5;
17622vinfos[5].indices[0] = _ij5[0];
17623vinfos[5].indices[1] = _ij5[1];
17624vinfos[5].maxsolutions = _nj5;
17625std::vector<int> vfree(0);
17626solutions.AddSolution(vinfos,vfree);
17627}
17628}
17629}
17630
17631}
17632
17633}
17634
17635} else
17636{
17637{
17638IkReal j0array[1], cj0array[1], sj0array[1];
17639bool j0valid[1]={false};
17640_nj0 = 1;
17641CheckValue<IkReal> x1294=IKPowWithIntegerCheck(gconst32,-1);
17642if(!x1294.valid){
17643continue;
17644}
17645CheckValue<IkReal> x1295=IKPowWithIntegerCheck(new_r11,-1);
17646if(!x1295.valid){
17647continue;
17648}
17649if( IKabs((new_r10*(x1294.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst32*(x1295.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1294.value)))+IKsqr(((-1.0)*gconst32*(x1295.value)))-1) <= IKFAST_SINCOS_THRESH )
17650 continue;
17651j0array[0]=IKatan2((new_r10*(x1294.value)), ((-1.0)*gconst32*(x1295.value)));
17652sj0array[0]=IKsin(j0array[0]);
17653cj0array[0]=IKcos(j0array[0]);
17654if( j0array[0] > IKPI )
17655{
17656 j0array[0]-=IK2PI;
17657}
17658else if( j0array[0] < -IKPI )
17659{ j0array[0]+=IK2PI;
17660}
17661j0valid[0] = true;
17662for(int ij0 = 0; ij0 < 1; ++ij0)
17663{
17664if( !j0valid[ij0] )
17665{
17666 continue;
17667}
17668_ij0[0] = ij0; _ij0[1] = -1;
17669for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17670{
17671if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17672{
17673 j0valid[iij0]=false; _ij0[1] = iij0; break;
17674}
17675}
17676j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17677{
17678IkReal evalcond[8];
17679IkReal x1296=IKcos(j0);
17680IkReal x1297=IKsin(j0);
17681IkReal x1298=((1.0)*gconst32);
17682IkReal x1299=(gconst32*x1296);
17683evalcond[0]=(new_r11*x1297);
17684evalcond[1]=((-1.0)*new_r10*x1296);
17685evalcond[2]=((-1.0)*x1299);
17686evalcond[3]=((-1.0)*gconst32*x1297);
17687evalcond[4]=(gconst32+((new_r11*x1296)));
17688evalcond[5]=(x1299+new_r11);
17689evalcond[6]=((((-1.0)*x1297*x1298))+new_r10);
17690evalcond[7]=((((-1.0)*x1298))+((new_r10*x1297)));
17691if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17692{
17693continue;
17694}
17695}
17696
17697{
17698std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17699vinfos[0].jointtype = 1;
17700vinfos[0].foffset = j0;
17701vinfos[0].indices[0] = _ij0[0];
17702vinfos[0].indices[1] = _ij0[1];
17703vinfos[0].maxsolutions = _nj0;
17704vinfos[1].jointtype = 1;
17705vinfos[1].foffset = j1;
17706vinfos[1].indices[0] = _ij1[0];
17707vinfos[1].indices[1] = _ij1[1];
17708vinfos[1].maxsolutions = _nj1;
17709vinfos[2].jointtype = 1;
17710vinfos[2].foffset = j2;
17711vinfos[2].indices[0] = _ij2[0];
17712vinfos[2].indices[1] = _ij2[1];
17713vinfos[2].maxsolutions = _nj2;
17714vinfos[3].jointtype = 1;
17715vinfos[3].foffset = j3;
17716vinfos[3].indices[0] = _ij3[0];
17717vinfos[3].indices[1] = _ij3[1];
17718vinfos[3].maxsolutions = _nj3;
17719vinfos[4].jointtype = 1;
17720vinfos[4].foffset = j4;
17721vinfos[4].indices[0] = _ij4[0];
17722vinfos[4].indices[1] = _ij4[1];
17723vinfos[4].maxsolutions = _nj4;
17724vinfos[5].jointtype = 1;
17725vinfos[5].foffset = j5;
17726vinfos[5].indices[0] = _ij5[0];
17727vinfos[5].indices[1] = _ij5[1];
17728vinfos[5].maxsolutions = _nj5;
17729std::vector<int> vfree(0);
17730solutions.AddSolution(vinfos,vfree);
17731}
17732}
17733}
17734
17735}
17736
17737}
17738
17739} else
17740{
17741{
17742IkReal j0array[1], cj0array[1], sj0array[1];
17743bool j0valid[1]={false};
17744_nj0 = 1;
17745CheckValue<IkReal> x1300 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
17746if(!x1300.valid){
17747continue;
17748}
17749CheckValue<IkReal> x1301=IKPowWithIntegerCheck(IKsign(gconst32),-1);
17750if(!x1301.valid){
17751continue;
17752}
17753j0array[0]=((-1.5707963267949)+(x1300.value)+(((1.5707963267949)*(x1301.value))));
17754sj0array[0]=IKsin(j0array[0]);
17755cj0array[0]=IKcos(j0array[0]);
17756if( j0array[0] > IKPI )
17757{
17758 j0array[0]-=IK2PI;
17759}
17760else if( j0array[0] < -IKPI )
17761{ j0array[0]+=IK2PI;
17762}
17763j0valid[0] = true;
17764for(int ij0 = 0; ij0 < 1; ++ij0)
17765{
17766if( !j0valid[ij0] )
17767{
17768 continue;
17769}
17770_ij0[0] = ij0; _ij0[1] = -1;
17771for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17772{
17773if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17774{
17775 j0valid[iij0]=false; _ij0[1] = iij0; break;
17776}
17777}
17778j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17779{
17780IkReal evalcond[8];
17781IkReal x1302=IKcos(j0);
17782IkReal x1303=IKsin(j0);
17783IkReal x1304=((1.0)*gconst32);
17784IkReal x1305=(gconst32*x1302);
17785evalcond[0]=(new_r11*x1303);
17786evalcond[1]=((-1.0)*new_r10*x1302);
17787evalcond[2]=((-1.0)*x1305);
17788evalcond[3]=((-1.0)*gconst32*x1303);
17789evalcond[4]=(gconst32+((new_r11*x1302)));
17790evalcond[5]=(x1305+new_r11);
17791evalcond[6]=((((-1.0)*x1303*x1304))+new_r10);
17792evalcond[7]=((((-1.0)*x1304))+((new_r10*x1303)));
17793if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17794{
17795continue;
17796}
17797}
17798
17799{
17800std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17801vinfos[0].jointtype = 1;
17802vinfos[0].foffset = j0;
17803vinfos[0].indices[0] = _ij0[0];
17804vinfos[0].indices[1] = _ij0[1];
17805vinfos[0].maxsolutions = _nj0;
17806vinfos[1].jointtype = 1;
17807vinfos[1].foffset = j1;
17808vinfos[1].indices[0] = _ij1[0];
17809vinfos[1].indices[1] = _ij1[1];
17810vinfos[1].maxsolutions = _nj1;
17811vinfos[2].jointtype = 1;
17812vinfos[2].foffset = j2;
17813vinfos[2].indices[0] = _ij2[0];
17814vinfos[2].indices[1] = _ij2[1];
17815vinfos[2].maxsolutions = _nj2;
17816vinfos[3].jointtype = 1;
17817vinfos[3].foffset = j3;
17818vinfos[3].indices[0] = _ij3[0];
17819vinfos[3].indices[1] = _ij3[1];
17820vinfos[3].maxsolutions = _nj3;
17821vinfos[4].jointtype = 1;
17822vinfos[4].foffset = j4;
17823vinfos[4].indices[0] = _ij4[0];
17824vinfos[4].indices[1] = _ij4[1];
17825vinfos[4].maxsolutions = _nj4;
17826vinfos[5].jointtype = 1;
17827vinfos[5].foffset = j5;
17828vinfos[5].indices[0] = _ij5[0];
17829vinfos[5].indices[1] = _ij5[1];
17830vinfos[5].maxsolutions = _nj5;
17831std::vector<int> vfree(0);
17832solutions.AddSolution(vinfos,vfree);
17833}
17834}
17835}
17836
17837}
17838
17839}
17840
17841}
17842} while(0);
17843if( bgotonextstatement )
17844{
17845bool bgotonextstatement = true;
17846do
17847{
17848if( 1 )
17849{
17850bgotonextstatement=false;
17851continue; // branch miss [j0]
17852
17853}
17854} while(0);
17855if( bgotonextstatement )
17856{
17857}
17858}
17859}
17860}
17861}
17862}
17863}
17864}
17865
17866} else
17867{
17868{
17869IkReal j0array[1], cj0array[1], sj0array[1];
17870bool j0valid[1]={false};
17871_nj0 = 1;
17872CheckValue<IkReal> x1306 = IKatan2WithCheck(IkReal((((gconst32*new_r11))+((gconst32*new_r00)))),IkReal(((((-1.0)*gconst32*new_r10))+((gconst32*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
17873if(!x1306.valid){
17874continue;
17875}
17876CheckValue<IkReal> x1307=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
17877if(!x1307.valid){
17878continue;
17879}
17880j0array[0]=((-1.5707963267949)+(x1306.value)+(((1.5707963267949)*(x1307.value))));
17881sj0array[0]=IKsin(j0array[0]);
17882cj0array[0]=IKcos(j0array[0]);
17883if( j0array[0] > IKPI )
17884{
17885 j0array[0]-=IK2PI;
17886}
17887else if( j0array[0] < -IKPI )
17888{ j0array[0]+=IK2PI;
17889}
17890j0valid[0] = true;
17891for(int ij0 = 0; ij0 < 1; ++ij0)
17892{
17893if( !j0valid[ij0] )
17894{
17895 continue;
17896}
17897_ij0[0] = ij0; _ij0[1] = -1;
17898for(int iij0 = ij0+1; iij0 < 1; ++iij0)
17899{
17900if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
17901{
17902 j0valid[iij0]=false; _ij0[1] = iij0; break;
17903}
17904}
17905j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
17906{
17907IkReal evalcond[8];
17908IkReal x1308=IKsin(j0);
17909IkReal x1309=IKcos(j0);
17910IkReal x1310=((1.0)*gconst32);
17911IkReal x1311=(gconst33*x1308);
17912IkReal x1312=((1.0)*x1309);
17913IkReal x1313=(((gconst33*x1312))+((x1308*x1310)));
17914evalcond[0]=(gconst32+((new_r11*x1309))+(((-1.0)*new_r01*x1308)));
17915evalcond[1]=((((-1.0)*new_r10*x1312))+gconst33+((new_r00*x1308)));
17916evalcond[2]=(x1311+new_r00+(((-1.0)*x1309*x1310)));
17917evalcond[3]=((((-1.0)*x1311))+((gconst32*x1309))+new_r11);
17918evalcond[4]=((((-1.0)*x1310))+((new_r10*x1308))+((new_r00*x1309)));
17919evalcond[5]=(((new_r11*x1308))+(((-1.0)*gconst33))+((new_r01*x1309)));
17920evalcond[6]=((((-1.0)*x1313))+new_r01);
17921evalcond[7]=((((-1.0)*x1313))+new_r10);
17922if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
17923{
17924continue;
17925}
17926}
17927
17928{
17929std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17930vinfos[0].jointtype = 1;
17931vinfos[0].foffset = j0;
17932vinfos[0].indices[0] = _ij0[0];
17933vinfos[0].indices[1] = _ij0[1];
17934vinfos[0].maxsolutions = _nj0;
17935vinfos[1].jointtype = 1;
17936vinfos[1].foffset = j1;
17937vinfos[1].indices[0] = _ij1[0];
17938vinfos[1].indices[1] = _ij1[1];
17939vinfos[1].maxsolutions = _nj1;
17940vinfos[2].jointtype = 1;
17941vinfos[2].foffset = j2;
17942vinfos[2].indices[0] = _ij2[0];
17943vinfos[2].indices[1] = _ij2[1];
17944vinfos[2].maxsolutions = _nj2;
17945vinfos[3].jointtype = 1;
17946vinfos[3].foffset = j3;
17947vinfos[3].indices[0] = _ij3[0];
17948vinfos[3].indices[1] = _ij3[1];
17949vinfos[3].maxsolutions = _nj3;
17950vinfos[4].jointtype = 1;
17951vinfos[4].foffset = j4;
17952vinfos[4].indices[0] = _ij4[0];
17953vinfos[4].indices[1] = _ij4[1];
17954vinfos[4].maxsolutions = _nj4;
17955vinfos[5].jointtype = 1;
17956vinfos[5].foffset = j5;
17957vinfos[5].indices[0] = _ij5[0];
17958vinfos[5].indices[1] = _ij5[1];
17959vinfos[5].maxsolutions = _nj5;
17960std::vector<int> vfree(0);
17961solutions.AddSolution(vinfos,vfree);
17962}
17963}
17964}
17965
17966}
17967
17968}
17969
17970} else
17971{
17972{
17973IkReal j0array[1], cj0array[1], sj0array[1];
17974bool j0valid[1]={false};
17975_nj0 = 1;
17976CheckValue<IkReal> x1314=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r11))+((gconst32*new_r01)))),-1);
17977if(!x1314.valid){
17978continue;
17979}
17980CheckValue<IkReal> x1315 = IKatan2WithCheck(IkReal((((new_r00*new_r11))+(gconst32*gconst32))),IkReal((((gconst32*gconst33))+((new_r00*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
17981if(!x1315.valid){
17982continue;
17983}
17984j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1314.value)))+(x1315.value));
17985sj0array[0]=IKsin(j0array[0]);
17986cj0array[0]=IKcos(j0array[0]);
17987if( j0array[0] > IKPI )
17988{
17989 j0array[0]-=IK2PI;
17990}
17991else if( j0array[0] < -IKPI )
17992{ j0array[0]+=IK2PI;
17993}
17994j0valid[0] = true;
17995for(int ij0 = 0; ij0 < 1; ++ij0)
17996{
17997if( !j0valid[ij0] )
17998{
17999 continue;
18000}
18001_ij0[0] = ij0; _ij0[1] = -1;
18002for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18003{
18004if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18005{
18006 j0valid[iij0]=false; _ij0[1] = iij0; break;
18007}
18008}
18009j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18010{
18011IkReal evalcond[8];
18012IkReal x1316=IKsin(j0);
18013IkReal x1317=IKcos(j0);
18014IkReal x1318=((1.0)*gconst32);
18015IkReal x1319=(gconst33*x1316);
18016IkReal x1320=((1.0)*x1317);
18017IkReal x1321=(((gconst33*x1320))+((x1316*x1318)));
18018evalcond[0]=(gconst32+((new_r11*x1317))+(((-1.0)*new_r01*x1316)));
18019evalcond[1]=(((new_r00*x1316))+(((-1.0)*new_r10*x1320))+gconst33);
18020evalcond[2]=(x1319+(((-1.0)*x1317*x1318))+new_r00);
18021evalcond[3]=((((-1.0)*x1319))+((gconst32*x1317))+new_r11);
18022evalcond[4]=(((new_r00*x1317))+(((-1.0)*x1318))+((new_r10*x1316)));
18023evalcond[5]=(((new_r01*x1317))+((new_r11*x1316))+(((-1.0)*gconst33)));
18024evalcond[6]=((((-1.0)*x1321))+new_r01);
18025evalcond[7]=((((-1.0)*x1321))+new_r10);
18026if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
18027{
18028continue;
18029}
18030}
18031
18032{
18033std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18034vinfos[0].jointtype = 1;
18035vinfos[0].foffset = j0;
18036vinfos[0].indices[0] = _ij0[0];
18037vinfos[0].indices[1] = _ij0[1];
18038vinfos[0].maxsolutions = _nj0;
18039vinfos[1].jointtype = 1;
18040vinfos[1].foffset = j1;
18041vinfos[1].indices[0] = _ij1[0];
18042vinfos[1].indices[1] = _ij1[1];
18043vinfos[1].maxsolutions = _nj1;
18044vinfos[2].jointtype = 1;
18045vinfos[2].foffset = j2;
18046vinfos[2].indices[0] = _ij2[0];
18047vinfos[2].indices[1] = _ij2[1];
18048vinfos[2].maxsolutions = _nj2;
18049vinfos[3].jointtype = 1;
18050vinfos[3].foffset = j3;
18051vinfos[3].indices[0] = _ij3[0];
18052vinfos[3].indices[1] = _ij3[1];
18053vinfos[3].maxsolutions = _nj3;
18054vinfos[4].jointtype = 1;
18055vinfos[4].foffset = j4;
18056vinfos[4].indices[0] = _ij4[0];
18057vinfos[4].indices[1] = _ij4[1];
18058vinfos[4].maxsolutions = _nj4;
18059vinfos[5].jointtype = 1;
18060vinfos[5].foffset = j5;
18061vinfos[5].indices[0] = _ij5[0];
18062vinfos[5].indices[1] = _ij5[1];
18063vinfos[5].maxsolutions = _nj5;
18064std::vector<int> vfree(0);
18065solutions.AddSolution(vinfos,vfree);
18066}
18067}
18068}
18069
18070}
18071
18072}
18073
18074} else
18075{
18076{
18077IkReal j0array[1], cj0array[1], sj0array[1];
18078bool j0valid[1]={false};
18079_nj0 = 1;
18080CheckValue<IkReal> x1322=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
18081if(!x1322.valid){
18082continue;
18083}
18084CheckValue<IkReal> x1323 = IKatan2WithCheck(IkReal((((gconst33*new_r11))+((gconst32*new_r10)))),IkReal((((gconst33*new_r01))+((gconst32*new_r00)))),IKFAST_ATAN2_MAGTHRESH);
18085if(!x1323.valid){
18086continue;
18087}
18088j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1322.value)))+(x1323.value));
18089sj0array[0]=IKsin(j0array[0]);
18090cj0array[0]=IKcos(j0array[0]);
18091if( j0array[0] > IKPI )
18092{
18093 j0array[0]-=IK2PI;
18094}
18095else if( j0array[0] < -IKPI )
18096{ j0array[0]+=IK2PI;
18097}
18098j0valid[0] = true;
18099for(int ij0 = 0; ij0 < 1; ++ij0)
18100{
18101if( !j0valid[ij0] )
18102{
18103 continue;
18104}
18105_ij0[0] = ij0; _ij0[1] = -1;
18106for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18107{
18108if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18109{
18110 j0valid[iij0]=false; _ij0[1] = iij0; break;
18111}
18112}
18113j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18114{
18115IkReal evalcond[8];
18116IkReal x1324=IKsin(j0);
18117IkReal x1325=IKcos(j0);
18118IkReal x1326=((1.0)*gconst32);
18119IkReal x1327=(gconst33*x1324);
18120IkReal x1328=((1.0)*x1325);
18121IkReal x1329=(((gconst33*x1328))+((x1324*x1326)));
18122evalcond[0]=(gconst32+((new_r11*x1325))+(((-1.0)*new_r01*x1324)));
18123evalcond[1]=(((new_r00*x1324))+(((-1.0)*new_r10*x1328))+gconst33);
18124evalcond[2]=(x1327+(((-1.0)*x1325*x1326))+new_r00);
18125evalcond[3]=((((-1.0)*x1327))+((gconst32*x1325))+new_r11);
18126evalcond[4]=(((new_r00*x1325))+(((-1.0)*x1326))+((new_r10*x1324)));
18127evalcond[5]=(((new_r01*x1325))+((new_r11*x1324))+(((-1.0)*gconst33)));
18128evalcond[6]=((((-1.0)*x1329))+new_r01);
18129evalcond[7]=((((-1.0)*x1329))+new_r10);
18130if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
18131{
18132continue;
18133}
18134}
18135
18136{
18137std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18138vinfos[0].jointtype = 1;
18139vinfos[0].foffset = j0;
18140vinfos[0].indices[0] = _ij0[0];
18141vinfos[0].indices[1] = _ij0[1];
18142vinfos[0].maxsolutions = _nj0;
18143vinfos[1].jointtype = 1;
18144vinfos[1].foffset = j1;
18145vinfos[1].indices[0] = _ij1[0];
18146vinfos[1].indices[1] = _ij1[1];
18147vinfos[1].maxsolutions = _nj1;
18148vinfos[2].jointtype = 1;
18149vinfos[2].foffset = j2;
18150vinfos[2].indices[0] = _ij2[0];
18151vinfos[2].indices[1] = _ij2[1];
18152vinfos[2].maxsolutions = _nj2;
18153vinfos[3].jointtype = 1;
18154vinfos[3].foffset = j3;
18155vinfos[3].indices[0] = _ij3[0];
18156vinfos[3].indices[1] = _ij3[1];
18157vinfos[3].maxsolutions = _nj3;
18158vinfos[4].jointtype = 1;
18159vinfos[4].foffset = j4;
18160vinfos[4].indices[0] = _ij4[0];
18161vinfos[4].indices[1] = _ij4[1];
18162vinfos[4].maxsolutions = _nj4;
18163vinfos[5].jointtype = 1;
18164vinfos[5].foffset = j5;
18165vinfos[5].indices[0] = _ij5[0];
18166vinfos[5].indices[1] = _ij5[1];
18167vinfos[5].maxsolutions = _nj5;
18168std::vector<int> vfree(0);
18169solutions.AddSolution(vinfos,vfree);
18170}
18171}
18172}
18173
18174}
18175
18176}
18177
18178}
18179} while(0);
18180if( bgotonextstatement )
18181{
18182bool bgotonextstatement = true;
18183do
18184{
18185IkReal x1332 = ((new_r01*new_r01)+(new_r11*new_r11));
18186if(IKabs(x1332)==0){
18187continue;
18188}
18189IkReal x1330=pow(x1332,-0.5);
18190IkReal x1331=((-1.0)*x1330);
18191CheckValue<IkReal> x1333 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18192if(!x1333.valid){
18193continue;
18194}
18195IkReal gconst34=((-1.0)*(x1333.value));
18196IkReal gconst35=(new_r11*x1331);
18197IkReal gconst36=(new_r01*x1331);
18198CheckValue<IkReal> x1334 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18199if(!x1334.valid){
18200continue;
18201}
18202evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1334.value)+j2)))), 6.28318530717959)));
18203if( IKabs(evalcond[0]) < 0.0000050000000000 )
18204{
18205bgotonextstatement=false;
18206{
18207IkReal j0eval[3];
18208CheckValue<IkReal> x1338 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18209if(!x1338.valid){
18210continue;
18211}
18212IkReal x1335=((-1.0)*(x1338.value));
18213IkReal x1336=x1330;
18214IkReal x1337=((-1.0)*x1336);
18215sj1=-1.0;
18216cj1=0;
18217j1=-1.5707963267949;
18218sj2=gconst35;
18219cj2=gconst36;
18220j2=x1335;
18221IkReal gconst34=x1335;
18222IkReal gconst35=(new_r11*x1337);
18223IkReal gconst36=(new_r01*x1337);
18224IkReal x1339=new_r01*new_r01;
18225IkReal x1340=(new_r00*new_r11);
18226IkReal x1341=(((new_r01*new_r10))+(((-1.0)*x1340)));
18227IkReal x1342=x1330;
18228IkReal x1343=((1.0)*new_r11*x1342);
18229j0eval[0]=x1341;
18230j0eval[1]=IKsign(x1341);
18231j0eval[2]=((IKabs(((((-1.0)*new_r10*x1343))+(((-1.0)*new_r01*x1343)))))+(IKabs((((x1339*x1342))+((x1340*x1342))))));
18232if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
18233{
18234{
18235IkReal j0eval[3];
18236CheckValue<IkReal> x1347 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18237if(!x1347.valid){
18238continue;
18239}
18240IkReal x1344=((-1.0)*(x1347.value));
18241IkReal x1345=x1330;
18242IkReal x1346=((-1.0)*x1345);
18243sj1=-1.0;
18244cj1=0;
18245j1=-1.5707963267949;
18246sj2=gconst35;
18247cj2=gconst36;
18248j2=x1344;
18249IkReal gconst34=x1344;
18250IkReal gconst35=(new_r11*x1346);
18251IkReal gconst36=(new_r01*x1346);
18252IkReal x1348=new_r11*new_r11;
18253IkReal x1349=(((new_r10*new_r11))+((new_r00*new_r01)));
18254IkReal x1350=x1330;
18255IkReal x1351=(new_r11*x1350);
18256j0eval[0]=x1349;
18257j0eval[1]=IKsign(x1349);
18258j0eval[2]=((IKabs((((new_r10*x1351))+(((-1.0)*new_r01*x1351)))))+(IKabs(((((-1.0)*x1348*x1350))+(((-1.0)*new_r00*x1351))))));
18259if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
18260{
18261{
18262IkReal j0eval[1];
18263CheckValue<IkReal> x1355 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18264if(!x1355.valid){
18265continue;
18266}
18267IkReal x1352=((-1.0)*(x1355.value));
18268IkReal x1353=x1330;
18269IkReal x1354=((-1.0)*x1353);
18270sj1=-1.0;
18271cj1=0;
18272j1=-1.5707963267949;
18273sj2=gconst35;
18274cj2=gconst36;
18275j2=x1352;
18276IkReal gconst34=x1352;
18277IkReal gconst35=(new_r11*x1354);
18278IkReal gconst36=(new_r01*x1354);
18279IkReal x1356=new_r01*new_r01;
18280CheckValue<IkReal> x1359=IKPowWithIntegerCheck((x1356+(new_r11*new_r11)),-1);
18281if(!x1359.valid){
18282continue;
18283}
18284IkReal x1357=x1359.value;
18285IkReal x1358=((1.0)*x1357);
18286j0eval[0]=((IKabs(((((-1.0)*x1356*x1358))+(new_r00*new_r00))))+(IKabs((((new_r00*new_r10))+(((-1.0)*new_r01*new_r11*x1358))))));
18287if( IKabs(j0eval[0]) < 0.0000010000000000 )
18288{
18289{
18290IkReal evalcond[2];
18291bool bgotonextstatement = true;
18292do
18293{
18294evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
18295evalcond[1]=gconst36;
18296if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
18297{
18298bgotonextstatement=false;
18299{
18300IkReal j0eval[3];
18301IkReal x1360=((-1.0)*new_r01);
18302CheckValue<IkReal> x1362 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1360),IKFAST_ATAN2_MAGTHRESH);
18303if(!x1362.valid){
18304continue;
18305}
18306IkReal x1361=((-1.0)*(x1362.value));
18307sj1=-1.0;
18308cj1=0;
18309j1=-1.5707963267949;
18310sj2=gconst35;
18311cj2=gconst36;
18312j2=x1361;
18313new_r00=0;
18314new_r10=0;
18315new_r21=0;
18316new_r22=0;
18317IkReal gconst34=x1361;
18318IkReal gconst35=((-1.0)*new_r11);
18319IkReal gconst36=x1360;
18320j0eval[0]=-1.0;
18321j0eval[1]=-1.0;
18322j0eval[2]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11))));
18323if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
18324{
18325{
18326IkReal j0eval[3];
18327IkReal x1363=((-1.0)*new_r01);
18328CheckValue<IkReal> x1365 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1363),IKFAST_ATAN2_MAGTHRESH);
18329if(!x1365.valid){
18330continue;
18331}
18332IkReal x1364=((-1.0)*(x1365.value));
18333sj1=-1.0;
18334cj1=0;
18335j1=-1.5707963267949;
18336sj2=gconst35;
18337cj2=gconst36;
18338j2=x1364;
18339new_r00=0;
18340new_r10=0;
18341new_r21=0;
18342new_r22=0;
18343IkReal gconst34=x1364;
18344IkReal gconst35=((-1.0)*new_r11);
18345IkReal gconst36=x1363;
18346j0eval[0]=1.0;
18347j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11))));
18348j0eval[2]=1.0;
18349if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
18350{
18351{
18352IkReal j0eval[3];
18353IkReal x1366=((-1.0)*new_r01);
18354CheckValue<IkReal> x1368 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1366),IKFAST_ATAN2_MAGTHRESH);
18355if(!x1368.valid){
18356continue;
18357}
18358IkReal x1367=((-1.0)*(x1368.value));
18359sj1=-1.0;
18360cj1=0;
18361j1=-1.5707963267949;
18362sj2=gconst35;
18363cj2=gconst36;
18364j2=x1367;
18365new_r00=0;
18366new_r10=0;
18367new_r21=0;
18368new_r22=0;
18369IkReal gconst34=x1367;
18370IkReal gconst35=((-1.0)*new_r11);
18371IkReal gconst36=x1366;
18372j0eval[0]=1.0;
18373j0eval[1]=1.0;
18374j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01)))))));
18375if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
18376{
18377continue; // 3 cases reached
18378
18379} else
18380{
18381{
18382IkReal j0array[1], cj0array[1], sj0array[1];
18383bool j0valid[1]={false};
18384_nj0 = 1;
18385CheckValue<IkReal> x1369=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1);
18386if(!x1369.valid){
18387continue;
18388}
18389CheckValue<IkReal> x1370 = IKatan2WithCheck(IkReal((gconst36*new_r11)),IkReal(((-1.0)*gconst35*new_r11)),IKFAST_ATAN2_MAGTHRESH);
18390if(!x1370.valid){
18391continue;
18392}
18393j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1369.value)))+(x1370.value));
18394sj0array[0]=IKsin(j0array[0]);
18395cj0array[0]=IKcos(j0array[0]);
18396if( j0array[0] > IKPI )
18397{
18398 j0array[0]-=IK2PI;
18399}
18400else if( j0array[0] < -IKPI )
18401{ j0array[0]+=IK2PI;
18402}
18403j0valid[0] = true;
18404for(int ij0 = 0; ij0 < 1; ++ij0)
18405{
18406if( !j0valid[ij0] )
18407{
18408 continue;
18409}
18410_ij0[0] = ij0; _ij0[1] = -1;
18411for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18412{
18413if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18414{
18415 j0valid[iij0]=false; _ij0[1] = iij0; break;
18416}
18417}
18418j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18419{
18420IkReal evalcond[6];
18421IkReal x1371=IKcos(j0);
18422IkReal x1372=IKsin(j0);
18423IkReal x1373=((1.0)*gconst36);
18424IkReal x1374=(gconst35*x1371);
18425IkReal x1375=(gconst36*x1372);
18426IkReal x1376=((1.0)*x1372);
18427IkReal x1377=(((gconst35*x1376))+((x1371*x1373)));
18428evalcond[0]=(x1375+(((-1.0)*x1374)));
18429evalcond[1]=((((-1.0)*new_r01*x1376))+gconst35+((new_r11*x1371)));
18430evalcond[2]=(x1374+(((-1.0)*x1372*x1373))+new_r11);
18431evalcond[3]=((-1.0)*x1377);
18432evalcond[4]=((((-1.0)*x1373))+((new_r11*x1372))+((new_r01*x1371)));
18433evalcond[5]=((((-1.0)*x1377))+new_r01);
18434if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
18435{
18436continue;
18437}
18438}
18439
18440{
18441std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18442vinfos[0].jointtype = 1;
18443vinfos[0].foffset = j0;
18444vinfos[0].indices[0] = _ij0[0];
18445vinfos[0].indices[1] = _ij0[1];
18446vinfos[0].maxsolutions = _nj0;
18447vinfos[1].jointtype = 1;
18448vinfos[1].foffset = j1;
18449vinfos[1].indices[0] = _ij1[0];
18450vinfos[1].indices[1] = _ij1[1];
18451vinfos[1].maxsolutions = _nj1;
18452vinfos[2].jointtype = 1;
18453vinfos[2].foffset = j2;
18454vinfos[2].indices[0] = _ij2[0];
18455vinfos[2].indices[1] = _ij2[1];
18456vinfos[2].maxsolutions = _nj2;
18457vinfos[3].jointtype = 1;
18458vinfos[3].foffset = j3;
18459vinfos[3].indices[0] = _ij3[0];
18460vinfos[3].indices[1] = _ij3[1];
18461vinfos[3].maxsolutions = _nj3;
18462vinfos[4].jointtype = 1;
18463vinfos[4].foffset = j4;
18464vinfos[4].indices[0] = _ij4[0];
18465vinfos[4].indices[1] = _ij4[1];
18466vinfos[4].maxsolutions = _nj4;
18467vinfos[5].jointtype = 1;
18468vinfos[5].foffset = j5;
18469vinfos[5].indices[0] = _ij5[0];
18470vinfos[5].indices[1] = _ij5[1];
18471vinfos[5].maxsolutions = _nj5;
18472std::vector<int> vfree(0);
18473solutions.AddSolution(vinfos,vfree);
18474}
18475}
18476}
18477
18478}
18479
18480}
18481
18482} else
18483{
18484{
18485IkReal j0array[1], cj0array[1], sj0array[1];
18486bool j0valid[1]={false};
18487_nj0 = 1;
18488CheckValue<IkReal> x1378 = IKatan2WithCheck(IkReal((gconst35*new_r01)),IkReal((gconst36*new_r01)),IKFAST_ATAN2_MAGTHRESH);
18489if(!x1378.valid){
18490continue;
18491}
18492CheckValue<IkReal> x1379=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1);
18493if(!x1379.valid){
18494continue;
18495}
18496j0array[0]=((-1.5707963267949)+(x1378.value)+(((1.5707963267949)*(x1379.value))));
18497sj0array[0]=IKsin(j0array[0]);
18498cj0array[0]=IKcos(j0array[0]);
18499if( j0array[0] > IKPI )
18500{
18501 j0array[0]-=IK2PI;
18502}
18503else if( j0array[0] < -IKPI )
18504{ j0array[0]+=IK2PI;
18505}
18506j0valid[0] = true;
18507for(int ij0 = 0; ij0 < 1; ++ij0)
18508{
18509if( !j0valid[ij0] )
18510{
18511 continue;
18512}
18513_ij0[0] = ij0; _ij0[1] = -1;
18514for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18515{
18516if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18517{
18518 j0valid[iij0]=false; _ij0[1] = iij0; break;
18519}
18520}
18521j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18522{
18523IkReal evalcond[6];
18524IkReal x1380=IKcos(j0);
18525IkReal x1381=IKsin(j0);
18526IkReal x1382=((1.0)*gconst36);
18527IkReal x1383=(gconst35*x1380);
18528IkReal x1384=(gconst36*x1381);
18529IkReal x1385=((1.0)*x1381);
18530IkReal x1386=(((gconst35*x1385))+((x1380*x1382)));
18531evalcond[0]=(x1384+(((-1.0)*x1383)));
18532evalcond[1]=(((new_r11*x1380))+gconst35+(((-1.0)*new_r01*x1385)));
18533evalcond[2]=(x1383+(((-1.0)*x1381*x1382))+new_r11);
18534evalcond[3]=((-1.0)*x1386);
18535evalcond[4]=((((-1.0)*x1382))+((new_r11*x1381))+((new_r01*x1380)));
18536evalcond[5]=((((-1.0)*x1386))+new_r01);
18537if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
18538{
18539continue;
18540}
18541}
18542
18543{
18544std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18545vinfos[0].jointtype = 1;
18546vinfos[0].foffset = j0;
18547vinfos[0].indices[0] = _ij0[0];
18548vinfos[0].indices[1] = _ij0[1];
18549vinfos[0].maxsolutions = _nj0;
18550vinfos[1].jointtype = 1;
18551vinfos[1].foffset = j1;
18552vinfos[1].indices[0] = _ij1[0];
18553vinfos[1].indices[1] = _ij1[1];
18554vinfos[1].maxsolutions = _nj1;
18555vinfos[2].jointtype = 1;
18556vinfos[2].foffset = j2;
18557vinfos[2].indices[0] = _ij2[0];
18558vinfos[2].indices[1] = _ij2[1];
18559vinfos[2].maxsolutions = _nj2;
18560vinfos[3].jointtype = 1;
18561vinfos[3].foffset = j3;
18562vinfos[3].indices[0] = _ij3[0];
18563vinfos[3].indices[1] = _ij3[1];
18564vinfos[3].maxsolutions = _nj3;
18565vinfos[4].jointtype = 1;
18566vinfos[4].foffset = j4;
18567vinfos[4].indices[0] = _ij4[0];
18568vinfos[4].indices[1] = _ij4[1];
18569vinfos[4].maxsolutions = _nj4;
18570vinfos[5].jointtype = 1;
18571vinfos[5].foffset = j5;
18572vinfos[5].indices[0] = _ij5[0];
18573vinfos[5].indices[1] = _ij5[1];
18574vinfos[5].maxsolutions = _nj5;
18575std::vector<int> vfree(0);
18576solutions.AddSolution(vinfos,vfree);
18577}
18578}
18579}
18580
18581}
18582
18583}
18584
18585} else
18586{
18587{
18588IkReal j0array[1], cj0array[1], sj0array[1];
18589bool j0valid[1]={false};
18590_nj0 = 1;
18591CheckValue<IkReal> x1387=IKPowWithIntegerCheck(IKsign((((gconst36*new_r01))+((gconst35*new_r11)))),-1);
18592if(!x1387.valid){
18593continue;
18594}
18595CheckValue<IkReal> x1388 = IKatan2WithCheck(IkReal((gconst35*gconst36)),IkReal(gconst36*gconst36),IKFAST_ATAN2_MAGTHRESH);
18596if(!x1388.valid){
18597continue;
18598}
18599j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1387.value)))+(x1388.value));
18600sj0array[0]=IKsin(j0array[0]);
18601cj0array[0]=IKcos(j0array[0]);
18602if( j0array[0] > IKPI )
18603{
18604 j0array[0]-=IK2PI;
18605}
18606else if( j0array[0] < -IKPI )
18607{ j0array[0]+=IK2PI;
18608}
18609j0valid[0] = true;
18610for(int ij0 = 0; ij0 < 1; ++ij0)
18611{
18612if( !j0valid[ij0] )
18613{
18614 continue;
18615}
18616_ij0[0] = ij0; _ij0[1] = -1;
18617for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18618{
18619if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18620{
18621 j0valid[iij0]=false; _ij0[1] = iij0; break;
18622}
18623}
18624j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18625{
18626IkReal evalcond[6];
18627IkReal x1389=IKcos(j0);
18628IkReal x1390=IKsin(j0);
18629IkReal x1391=((1.0)*gconst36);
18630IkReal x1392=(gconst35*x1389);
18631IkReal x1393=(gconst36*x1390);
18632IkReal x1394=((1.0)*x1390);
18633IkReal x1395=(((gconst35*x1394))+((x1389*x1391)));
18634evalcond[0]=(x1393+(((-1.0)*x1392)));
18635evalcond[1]=(((new_r11*x1389))+gconst35+(((-1.0)*new_r01*x1394)));
18636evalcond[2]=(x1392+(((-1.0)*x1390*x1391))+new_r11);
18637evalcond[3]=((-1.0)*x1395);
18638evalcond[4]=(((new_r11*x1390))+((new_r01*x1389))+(((-1.0)*x1391)));
18639evalcond[5]=(new_r01+(((-1.0)*x1395)));
18640if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
18641{
18642continue;
18643}
18644}
18645
18646{
18647std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18648vinfos[0].jointtype = 1;
18649vinfos[0].foffset = j0;
18650vinfos[0].indices[0] = _ij0[0];
18651vinfos[0].indices[1] = _ij0[1];
18652vinfos[0].maxsolutions = _nj0;
18653vinfos[1].jointtype = 1;
18654vinfos[1].foffset = j1;
18655vinfos[1].indices[0] = _ij1[0];
18656vinfos[1].indices[1] = _ij1[1];
18657vinfos[1].maxsolutions = _nj1;
18658vinfos[2].jointtype = 1;
18659vinfos[2].foffset = j2;
18660vinfos[2].indices[0] = _ij2[0];
18661vinfos[2].indices[1] = _ij2[1];
18662vinfos[2].maxsolutions = _nj2;
18663vinfos[3].jointtype = 1;
18664vinfos[3].foffset = j3;
18665vinfos[3].indices[0] = _ij3[0];
18666vinfos[3].indices[1] = _ij3[1];
18667vinfos[3].maxsolutions = _nj3;
18668vinfos[4].jointtype = 1;
18669vinfos[4].foffset = j4;
18670vinfos[4].indices[0] = _ij4[0];
18671vinfos[4].indices[1] = _ij4[1];
18672vinfos[4].maxsolutions = _nj4;
18673vinfos[5].jointtype = 1;
18674vinfos[5].foffset = j5;
18675vinfos[5].indices[0] = _ij5[0];
18676vinfos[5].indices[1] = _ij5[1];
18677vinfos[5].maxsolutions = _nj5;
18678std::vector<int> vfree(0);
18679solutions.AddSolution(vinfos,vfree);
18680}
18681}
18682}
18683
18684}
18685
18686}
18687
18688}
18689} while(0);
18690if( bgotonextstatement )
18691{
18692bool bgotonextstatement = true;
18693do
18694{
18695evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
18696if( IKabs(evalcond[0]) < 0.0000050000000000 )
18697{
18698bgotonextstatement=false;
18699{
18700IkReal j0eval[1];
18701CheckValue<IkReal> x1397 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
18702if(!x1397.valid){
18703continue;
18704}
18705IkReal x1396=((-1.0)*(x1397.value));
18706sj1=-1.0;
18707cj1=0;
18708j1=-1.5707963267949;
18709sj2=gconst35;
18710cj2=gconst36;
18711j2=x1396;
18712new_r00=0;
18713new_r01=0;
18714new_r12=0;
18715new_r22=0;
18716IkReal gconst34=x1396;
18717IkReal x1398 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
18718if(IKabs(x1398)==0){
18719continue;
18720}
18721IkReal gconst35=((-1.0)*new_r11*(pow(x1398,-0.5)));
18722IkReal gconst36=0;
18723j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
18724if( IKabs(j0eval[0]) < 0.0000010000000000 )
18725{
18726{
18727IkReal j0eval[1];
18728CheckValue<IkReal> x1400 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
18729if(!x1400.valid){
18730continue;
18731}
18732IkReal x1399=((-1.0)*(x1400.value));
18733sj1=-1.0;
18734cj1=0;
18735j1=-1.5707963267949;
18736sj2=gconst35;
18737cj2=gconst36;
18738j2=x1399;
18739new_r00=0;
18740new_r01=0;
18741new_r12=0;
18742new_r22=0;
18743IkReal gconst34=x1399;
18744IkReal x1401 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
18745if(IKabs(x1401)==0){
18746continue;
18747}
18748IkReal gconst35=((-1.0)*new_r11*(pow(x1401,-0.5)));
18749IkReal gconst36=0;
18750j0eval[0]=new_r11;
18751if( IKabs(j0eval[0]) < 0.0000010000000000 )
18752{
18753{
18754IkReal j0eval[2];
18755CheckValue<IkReal> x1403 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
18756if(!x1403.valid){
18757continue;
18758}
18759IkReal x1402=((-1.0)*(x1403.value));
18760sj1=-1.0;
18761cj1=0;
18762j1=-1.5707963267949;
18763sj2=gconst35;
18764cj2=gconst36;
18765j2=x1402;
18766new_r00=0;
18767new_r01=0;
18768new_r12=0;
18769new_r22=0;
18770IkReal gconst34=x1402;
18771IkReal x1404 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
18772if(IKabs(x1404)==0){
18773continue;
18774}
18775IkReal gconst35=((-1.0)*new_r11*(pow(x1404,-0.5)));
18776IkReal gconst36=0;
18777j0eval[0]=new_r10;
18778j0eval[1]=new_r11;
18779if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
18780{
18781continue; // 3 cases reached
18782
18783} else
18784{
18785{
18786IkReal j0array[1], cj0array[1], sj0array[1];
18787bool j0valid[1]={false};
18788_nj0 = 1;
18789CheckValue<IkReal> x1405=IKPowWithIntegerCheck(new_r10,-1);
18790if(!x1405.valid){
18791continue;
18792}
18793CheckValue<IkReal> x1406=IKPowWithIntegerCheck(new_r11,-1);
18794if(!x1406.valid){
18795continue;
18796}
18797if( IKabs((gconst35*(x1405.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst35*(x1406.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst35*(x1405.value)))+IKsqr(((-1.0)*gconst35*(x1406.value)))-1) <= IKFAST_SINCOS_THRESH )
18798 continue;
18799j0array[0]=IKatan2((gconst35*(x1405.value)), ((-1.0)*gconst35*(x1406.value)));
18800sj0array[0]=IKsin(j0array[0]);
18801cj0array[0]=IKcos(j0array[0]);
18802if( j0array[0] > IKPI )
18803{
18804 j0array[0]-=IK2PI;
18805}
18806else if( j0array[0] < -IKPI )
18807{ j0array[0]+=IK2PI;
18808}
18809j0valid[0] = true;
18810for(int ij0 = 0; ij0 < 1; ++ij0)
18811{
18812if( !j0valid[ij0] )
18813{
18814 continue;
18815}
18816_ij0[0] = ij0; _ij0[1] = -1;
18817for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18818{
18819if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18820{
18821 j0valid[iij0]=false; _ij0[1] = iij0; break;
18822}
18823}
18824j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18825{
18826IkReal evalcond[8];
18827IkReal x1407=IKcos(j0);
18828IkReal x1408=IKsin(j0);
18829IkReal x1409=((1.0)*gconst35);
18830IkReal x1410=((-1.0)*x1407);
18831evalcond[0]=(new_r11*x1408);
18832evalcond[1]=(new_r10*x1410);
18833evalcond[2]=(gconst35*x1410);
18834evalcond[3]=((-1.0)*gconst35*x1408);
18835evalcond[4]=(gconst35+((new_r11*x1407)));
18836evalcond[5]=(new_r11+((gconst35*x1407)));
18837evalcond[6]=(new_r10+(((-1.0)*x1408*x1409)));
18838evalcond[7]=(((new_r10*x1408))+(((-1.0)*x1409)));
18839if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
18840{
18841continue;
18842}
18843}
18844
18845{
18846std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18847vinfos[0].jointtype = 1;
18848vinfos[0].foffset = j0;
18849vinfos[0].indices[0] = _ij0[0];
18850vinfos[0].indices[1] = _ij0[1];
18851vinfos[0].maxsolutions = _nj0;
18852vinfos[1].jointtype = 1;
18853vinfos[1].foffset = j1;
18854vinfos[1].indices[0] = _ij1[0];
18855vinfos[1].indices[1] = _ij1[1];
18856vinfos[1].maxsolutions = _nj1;
18857vinfos[2].jointtype = 1;
18858vinfos[2].foffset = j2;
18859vinfos[2].indices[0] = _ij2[0];
18860vinfos[2].indices[1] = _ij2[1];
18861vinfos[2].maxsolutions = _nj2;
18862vinfos[3].jointtype = 1;
18863vinfos[3].foffset = j3;
18864vinfos[3].indices[0] = _ij3[0];
18865vinfos[3].indices[1] = _ij3[1];
18866vinfos[3].maxsolutions = _nj3;
18867vinfos[4].jointtype = 1;
18868vinfos[4].foffset = j4;
18869vinfos[4].indices[0] = _ij4[0];
18870vinfos[4].indices[1] = _ij4[1];
18871vinfos[4].maxsolutions = _nj4;
18872vinfos[5].jointtype = 1;
18873vinfos[5].foffset = j5;
18874vinfos[5].indices[0] = _ij5[0];
18875vinfos[5].indices[1] = _ij5[1];
18876vinfos[5].maxsolutions = _nj5;
18877std::vector<int> vfree(0);
18878solutions.AddSolution(vinfos,vfree);
18879}
18880}
18881}
18882
18883}
18884
18885}
18886
18887} else
18888{
18889{
18890IkReal j0array[1], cj0array[1], sj0array[1];
18891bool j0valid[1]={false};
18892_nj0 = 1;
18893CheckValue<IkReal> x1411=IKPowWithIntegerCheck(gconst35,-1);
18894if(!x1411.valid){
18895continue;
18896}
18897CheckValue<IkReal> x1412=IKPowWithIntegerCheck(new_r11,-1);
18898if(!x1412.valid){
18899continue;
18900}
18901if( IKabs((new_r10*(x1411.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst35*(x1412.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1411.value)))+IKsqr(((-1.0)*gconst35*(x1412.value)))-1) <= IKFAST_SINCOS_THRESH )
18902 continue;
18903j0array[0]=IKatan2((new_r10*(x1411.value)), ((-1.0)*gconst35*(x1412.value)));
18904sj0array[0]=IKsin(j0array[0]);
18905cj0array[0]=IKcos(j0array[0]);
18906if( j0array[0] > IKPI )
18907{
18908 j0array[0]-=IK2PI;
18909}
18910else if( j0array[0] < -IKPI )
18911{ j0array[0]+=IK2PI;
18912}
18913j0valid[0] = true;
18914for(int ij0 = 0; ij0 < 1; ++ij0)
18915{
18916if( !j0valid[ij0] )
18917{
18918 continue;
18919}
18920_ij0[0] = ij0; _ij0[1] = -1;
18921for(int iij0 = ij0+1; iij0 < 1; ++iij0)
18922{
18923if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
18924{
18925 j0valid[iij0]=false; _ij0[1] = iij0; break;
18926}
18927}
18928j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
18929{
18930IkReal evalcond[8];
18931IkReal x1413=IKcos(j0);
18932IkReal x1414=IKsin(j0);
18933IkReal x1415=((1.0)*gconst35);
18934IkReal x1416=((-1.0)*x1413);
18935evalcond[0]=(new_r11*x1414);
18936evalcond[1]=(new_r10*x1416);
18937evalcond[2]=(gconst35*x1416);
18938evalcond[3]=((-1.0)*gconst35*x1414);
18939evalcond[4]=(gconst35+((new_r11*x1413)));
18940evalcond[5]=(((gconst35*x1413))+new_r11);
18941evalcond[6]=((((-1.0)*x1414*x1415))+new_r10);
18942evalcond[7]=((((-1.0)*x1415))+((new_r10*x1414)));
18943if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
18944{
18945continue;
18946}
18947}
18948
18949{
18950std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
18951vinfos[0].jointtype = 1;
18952vinfos[0].foffset = j0;
18953vinfos[0].indices[0] = _ij0[0];
18954vinfos[0].indices[1] = _ij0[1];
18955vinfos[0].maxsolutions = _nj0;
18956vinfos[1].jointtype = 1;
18957vinfos[1].foffset = j1;
18958vinfos[1].indices[0] = _ij1[0];
18959vinfos[1].indices[1] = _ij1[1];
18960vinfos[1].maxsolutions = _nj1;
18961vinfos[2].jointtype = 1;
18962vinfos[2].foffset = j2;
18963vinfos[2].indices[0] = _ij2[0];
18964vinfos[2].indices[1] = _ij2[1];
18965vinfos[2].maxsolutions = _nj2;
18966vinfos[3].jointtype = 1;
18967vinfos[3].foffset = j3;
18968vinfos[3].indices[0] = _ij3[0];
18969vinfos[3].indices[1] = _ij3[1];
18970vinfos[3].maxsolutions = _nj3;
18971vinfos[4].jointtype = 1;
18972vinfos[4].foffset = j4;
18973vinfos[4].indices[0] = _ij4[0];
18974vinfos[4].indices[1] = _ij4[1];
18975vinfos[4].maxsolutions = _nj4;
18976vinfos[5].jointtype = 1;
18977vinfos[5].foffset = j5;
18978vinfos[5].indices[0] = _ij5[0];
18979vinfos[5].indices[1] = _ij5[1];
18980vinfos[5].maxsolutions = _nj5;
18981std::vector<int> vfree(0);
18982solutions.AddSolution(vinfos,vfree);
18983}
18984}
18985}
18986
18987}
18988
18989}
18990
18991} else
18992{
18993{
18994IkReal j0array[1], cj0array[1], sj0array[1];
18995bool j0valid[1]={false};
18996_nj0 = 1;
18997CheckValue<IkReal> x1417 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
18998if(!x1417.valid){
18999continue;
19000}
19001CheckValue<IkReal> x1418=IKPowWithIntegerCheck(IKsign(gconst35),-1);
19002if(!x1418.valid){
19003continue;
19004}
19005j0array[0]=((-1.5707963267949)+(x1417.value)+(((1.5707963267949)*(x1418.value))));
19006sj0array[0]=IKsin(j0array[0]);
19007cj0array[0]=IKcos(j0array[0]);
19008if( j0array[0] > IKPI )
19009{
19010 j0array[0]-=IK2PI;
19011}
19012else if( j0array[0] < -IKPI )
19013{ j0array[0]+=IK2PI;
19014}
19015j0valid[0] = true;
19016for(int ij0 = 0; ij0 < 1; ++ij0)
19017{
19018if( !j0valid[ij0] )
19019{
19020 continue;
19021}
19022_ij0[0] = ij0; _ij0[1] = -1;
19023for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19024{
19025if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19026{
19027 j0valid[iij0]=false; _ij0[1] = iij0; break;
19028}
19029}
19030j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19031{
19032IkReal evalcond[8];
19033IkReal x1419=IKcos(j0);
19034IkReal x1420=IKsin(j0);
19035IkReal x1421=((1.0)*gconst35);
19036IkReal x1422=((-1.0)*x1419);
19037evalcond[0]=(new_r11*x1420);
19038evalcond[1]=(new_r10*x1422);
19039evalcond[2]=(gconst35*x1422);
19040evalcond[3]=((-1.0)*gconst35*x1420);
19041evalcond[4]=(gconst35+((new_r11*x1419)));
19042evalcond[5]=(((gconst35*x1419))+new_r11);
19043evalcond[6]=((((-1.0)*x1420*x1421))+new_r10);
19044evalcond[7]=(((new_r10*x1420))+(((-1.0)*x1421)));
19045if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19046{
19047continue;
19048}
19049}
19050
19051{
19052std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19053vinfos[0].jointtype = 1;
19054vinfos[0].foffset = j0;
19055vinfos[0].indices[0] = _ij0[0];
19056vinfos[0].indices[1] = _ij0[1];
19057vinfos[0].maxsolutions = _nj0;
19058vinfos[1].jointtype = 1;
19059vinfos[1].foffset = j1;
19060vinfos[1].indices[0] = _ij1[0];
19061vinfos[1].indices[1] = _ij1[1];
19062vinfos[1].maxsolutions = _nj1;
19063vinfos[2].jointtype = 1;
19064vinfos[2].foffset = j2;
19065vinfos[2].indices[0] = _ij2[0];
19066vinfos[2].indices[1] = _ij2[1];
19067vinfos[2].maxsolutions = _nj2;
19068vinfos[3].jointtype = 1;
19069vinfos[3].foffset = j3;
19070vinfos[3].indices[0] = _ij3[0];
19071vinfos[3].indices[1] = _ij3[1];
19072vinfos[3].maxsolutions = _nj3;
19073vinfos[4].jointtype = 1;
19074vinfos[4].foffset = j4;
19075vinfos[4].indices[0] = _ij4[0];
19076vinfos[4].indices[1] = _ij4[1];
19077vinfos[4].maxsolutions = _nj4;
19078vinfos[5].jointtype = 1;
19079vinfos[5].foffset = j5;
19080vinfos[5].indices[0] = _ij5[0];
19081vinfos[5].indices[1] = _ij5[1];
19082vinfos[5].maxsolutions = _nj5;
19083std::vector<int> vfree(0);
19084solutions.AddSolution(vinfos,vfree);
19085}
19086}
19087}
19088
19089}
19090
19091}
19092
19093}
19094} while(0);
19095if( bgotonextstatement )
19096{
19097bool bgotonextstatement = true;
19098do
19099{
19100evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
19101if( IKabs(evalcond[0]) < 0.0000050000000000 )
19102{
19103bgotonextstatement=false;
19104{
19105IkReal j0eval[1];
19106IkReal x1423=((-1.0)*new_r01);
19107CheckValue<IkReal> x1425 = IKatan2WithCheck(IkReal(0),IkReal(x1423),IKFAST_ATAN2_MAGTHRESH);
19108if(!x1425.valid){
19109continue;
19110}
19111IkReal x1424=((-1.0)*(x1425.value));
19112sj1=-1.0;
19113cj1=0;
19114j1=-1.5707963267949;
19115sj2=gconst35;
19116cj2=gconst36;
19117j2=x1424;
19118new_r11=0;
19119new_r10=0;
19120new_r22=0;
19121new_r02=0;
19122IkReal gconst34=x1424;
19123IkReal gconst35=0;
19124IkReal x1426 = new_r01*new_r01;
19125if(IKabs(x1426)==0){
19126continue;
19127}
19128IkReal gconst36=(x1423*(pow(x1426,-0.5)));
19129j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
19130if( IKabs(j0eval[0]) < 0.0000010000000000 )
19131{
19132{
19133IkReal j0eval[1];
19134IkReal x1427=((-1.0)*new_r01);
19135CheckValue<IkReal> x1429 = IKatan2WithCheck(IkReal(0),IkReal(x1427),IKFAST_ATAN2_MAGTHRESH);
19136if(!x1429.valid){
19137continue;
19138}
19139IkReal x1428=((-1.0)*(x1429.value));
19140sj1=-1.0;
19141cj1=0;
19142j1=-1.5707963267949;
19143sj2=gconst35;
19144cj2=gconst36;
19145j2=x1428;
19146new_r11=0;
19147new_r10=0;
19148new_r22=0;
19149new_r02=0;
19150IkReal gconst34=x1428;
19151IkReal gconst35=0;
19152IkReal x1430 = new_r01*new_r01;
19153if(IKabs(x1430)==0){
19154continue;
19155}
19156IkReal gconst36=(x1427*(pow(x1430,-0.5)));
19157j0eval[0]=new_r00;
19158if( IKabs(j0eval[0]) < 0.0000010000000000 )
19159{
19160{
19161IkReal j0eval[2];
19162IkReal x1431=((-1.0)*new_r01);
19163CheckValue<IkReal> x1433 = IKatan2WithCheck(IkReal(0),IkReal(x1431),IKFAST_ATAN2_MAGTHRESH);
19164if(!x1433.valid){
19165continue;
19166}
19167IkReal x1432=((-1.0)*(x1433.value));
19168sj1=-1.0;
19169cj1=0;
19170j1=-1.5707963267949;
19171sj2=gconst35;
19172cj2=gconst36;
19173j2=x1432;
19174new_r11=0;
19175new_r10=0;
19176new_r22=0;
19177new_r02=0;
19178IkReal gconst34=x1432;
19179IkReal gconst35=0;
19180IkReal x1434 = new_r01*new_r01;
19181if(IKabs(x1434)==0){
19182continue;
19183}
19184IkReal gconst36=(x1431*(pow(x1434,-0.5)));
19185j0eval[0]=new_r00;
19186j0eval[1]=new_r01;
19187if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
19188{
19189continue; // 3 cases reached
19190
19191} else
19192{
19193{
19194IkReal j0array[1], cj0array[1], sj0array[1];
19195bool j0valid[1]={false};
19196_nj0 = 1;
19197CheckValue<IkReal> x1435=IKPowWithIntegerCheck(new_r00,-1);
19198if(!x1435.valid){
19199continue;
19200}
19201CheckValue<IkReal> x1436=IKPowWithIntegerCheck(new_r01,-1);
19202if(!x1436.valid){
19203continue;
19204}
19205if( IKabs(((-1.0)*gconst36*(x1435.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst36*(x1436.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst36*(x1435.value)))+IKsqr((gconst36*(x1436.value)))-1) <= IKFAST_SINCOS_THRESH )
19206 continue;
19207j0array[0]=IKatan2(((-1.0)*gconst36*(x1435.value)), (gconst36*(x1436.value)));
19208sj0array[0]=IKsin(j0array[0]);
19209cj0array[0]=IKcos(j0array[0]);
19210if( j0array[0] > IKPI )
19211{
19212 j0array[0]-=IK2PI;
19213}
19214else if( j0array[0] < -IKPI )
19215{ j0array[0]+=IK2PI;
19216}
19217j0valid[0] = true;
19218for(int ij0 = 0; ij0 < 1; ++ij0)
19219{
19220if( !j0valid[ij0] )
19221{
19222 continue;
19223}
19224_ij0[0] = ij0; _ij0[1] = -1;
19225for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19226{
19227if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19228{
19229 j0valid[iij0]=false; _ij0[1] = iij0; break;
19230}
19231}
19232j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19233{
19234IkReal evalcond[8];
19235IkReal x1437=IKsin(j0);
19236IkReal x1438=IKcos(j0);
19237IkReal x1439=((1.0)*gconst36);
19238IkReal x1440=((-1.0)*x1437);
19239evalcond[0]=(new_r00*x1438);
19240evalcond[1]=(new_r01*x1440);
19241evalcond[2]=(gconst36*x1440);
19242evalcond[3]=((-1.0)*gconst36*x1438);
19243evalcond[4]=(((new_r00*x1437))+gconst36);
19244evalcond[5]=(((gconst36*x1437))+new_r00);
19245evalcond[6]=((((-1.0)*x1438*x1439))+new_r01);
19246evalcond[7]=(((new_r01*x1438))+(((-1.0)*x1439)));
19247if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19248{
19249continue;
19250}
19251}
19252
19253{
19254std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19255vinfos[0].jointtype = 1;
19256vinfos[0].foffset = j0;
19257vinfos[0].indices[0] = _ij0[0];
19258vinfos[0].indices[1] = _ij0[1];
19259vinfos[0].maxsolutions = _nj0;
19260vinfos[1].jointtype = 1;
19261vinfos[1].foffset = j1;
19262vinfos[1].indices[0] = _ij1[0];
19263vinfos[1].indices[1] = _ij1[1];
19264vinfos[1].maxsolutions = _nj1;
19265vinfos[2].jointtype = 1;
19266vinfos[2].foffset = j2;
19267vinfos[2].indices[0] = _ij2[0];
19268vinfos[2].indices[1] = _ij2[1];
19269vinfos[2].maxsolutions = _nj2;
19270vinfos[3].jointtype = 1;
19271vinfos[3].foffset = j3;
19272vinfos[3].indices[0] = _ij3[0];
19273vinfos[3].indices[1] = _ij3[1];
19274vinfos[3].maxsolutions = _nj3;
19275vinfos[4].jointtype = 1;
19276vinfos[4].foffset = j4;
19277vinfos[4].indices[0] = _ij4[0];
19278vinfos[4].indices[1] = _ij4[1];
19279vinfos[4].maxsolutions = _nj4;
19280vinfos[5].jointtype = 1;
19281vinfos[5].foffset = j5;
19282vinfos[5].indices[0] = _ij5[0];
19283vinfos[5].indices[1] = _ij5[1];
19284vinfos[5].maxsolutions = _nj5;
19285std::vector<int> vfree(0);
19286solutions.AddSolution(vinfos,vfree);
19287}
19288}
19289}
19290
19291}
19292
19293}
19294
19295} else
19296{
19297{
19298IkReal j0array[1], cj0array[1], sj0array[1];
19299bool j0valid[1]={false};
19300_nj0 = 1;
19301CheckValue<IkReal> x1441=IKPowWithIntegerCheck(new_r00,-1);
19302if(!x1441.valid){
19303continue;
19304}
19305CheckValue<IkReal> x1442=IKPowWithIntegerCheck(gconst36,-1);
19306if(!x1442.valid){
19307continue;
19308}
19309if( IKabs(((-1.0)*gconst36*(x1441.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1442.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst36*(x1441.value)))+IKsqr((new_r01*(x1442.value)))-1) <= IKFAST_SINCOS_THRESH )
19310 continue;
19311j0array[0]=IKatan2(((-1.0)*gconst36*(x1441.value)), (new_r01*(x1442.value)));
19312sj0array[0]=IKsin(j0array[0]);
19313cj0array[0]=IKcos(j0array[0]);
19314if( j0array[0] > IKPI )
19315{
19316 j0array[0]-=IK2PI;
19317}
19318else if( j0array[0] < -IKPI )
19319{ j0array[0]+=IK2PI;
19320}
19321j0valid[0] = true;
19322for(int ij0 = 0; ij0 < 1; ++ij0)
19323{
19324if( !j0valid[ij0] )
19325{
19326 continue;
19327}
19328_ij0[0] = ij0; _ij0[1] = -1;
19329for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19330{
19331if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19332{
19333 j0valid[iij0]=false; _ij0[1] = iij0; break;
19334}
19335}
19336j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19337{
19338IkReal evalcond[8];
19339IkReal x1443=IKsin(j0);
19340IkReal x1444=IKcos(j0);
19341IkReal x1445=((1.0)*gconst36);
19342IkReal x1446=((-1.0)*x1443);
19343evalcond[0]=(new_r00*x1444);
19344evalcond[1]=(new_r01*x1446);
19345evalcond[2]=(gconst36*x1446);
19346evalcond[3]=((-1.0)*gconst36*x1444);
19347evalcond[4]=(gconst36+((new_r00*x1443)));
19348evalcond[5]=(((gconst36*x1443))+new_r00);
19349evalcond[6]=(new_r01+(((-1.0)*x1444*x1445)));
19350evalcond[7]=(((new_r01*x1444))+(((-1.0)*x1445)));
19351if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19352{
19353continue;
19354}
19355}
19356
19357{
19358std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19359vinfos[0].jointtype = 1;
19360vinfos[0].foffset = j0;
19361vinfos[0].indices[0] = _ij0[0];
19362vinfos[0].indices[1] = _ij0[1];
19363vinfos[0].maxsolutions = _nj0;
19364vinfos[1].jointtype = 1;
19365vinfos[1].foffset = j1;
19366vinfos[1].indices[0] = _ij1[0];
19367vinfos[1].indices[1] = _ij1[1];
19368vinfos[1].maxsolutions = _nj1;
19369vinfos[2].jointtype = 1;
19370vinfos[2].foffset = j2;
19371vinfos[2].indices[0] = _ij2[0];
19372vinfos[2].indices[1] = _ij2[1];
19373vinfos[2].maxsolutions = _nj2;
19374vinfos[3].jointtype = 1;
19375vinfos[3].foffset = j3;
19376vinfos[3].indices[0] = _ij3[0];
19377vinfos[3].indices[1] = _ij3[1];
19378vinfos[3].maxsolutions = _nj3;
19379vinfos[4].jointtype = 1;
19380vinfos[4].foffset = j4;
19381vinfos[4].indices[0] = _ij4[0];
19382vinfos[4].indices[1] = _ij4[1];
19383vinfos[4].maxsolutions = _nj4;
19384vinfos[5].jointtype = 1;
19385vinfos[5].foffset = j5;
19386vinfos[5].indices[0] = _ij5[0];
19387vinfos[5].indices[1] = _ij5[1];
19388vinfos[5].maxsolutions = _nj5;
19389std::vector<int> vfree(0);
19390solutions.AddSolution(vinfos,vfree);
19391}
19392}
19393}
19394
19395}
19396
19397}
19398
19399} else
19400{
19401{
19402IkReal j0array[1], cj0array[1], sj0array[1];
19403bool j0valid[1]={false};
19404_nj0 = 1;
19405CheckValue<IkReal> x1447 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
19406if(!x1447.valid){
19407continue;
19408}
19409CheckValue<IkReal> x1448=IKPowWithIntegerCheck(IKsign(gconst36),-1);
19410if(!x1448.valid){
19411continue;
19412}
19413j0array[0]=((-1.5707963267949)+(x1447.value)+(((1.5707963267949)*(x1448.value))));
19414sj0array[0]=IKsin(j0array[0]);
19415cj0array[0]=IKcos(j0array[0]);
19416if( j0array[0] > IKPI )
19417{
19418 j0array[0]-=IK2PI;
19419}
19420else if( j0array[0] < -IKPI )
19421{ j0array[0]+=IK2PI;
19422}
19423j0valid[0] = true;
19424for(int ij0 = 0; ij0 < 1; ++ij0)
19425{
19426if( !j0valid[ij0] )
19427{
19428 continue;
19429}
19430_ij0[0] = ij0; _ij0[1] = -1;
19431for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19432{
19433if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19434{
19435 j0valid[iij0]=false; _ij0[1] = iij0; break;
19436}
19437}
19438j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19439{
19440IkReal evalcond[8];
19441IkReal x1449=IKsin(j0);
19442IkReal x1450=IKcos(j0);
19443IkReal x1451=((1.0)*gconst36);
19444IkReal x1452=((-1.0)*x1449);
19445evalcond[0]=(new_r00*x1450);
19446evalcond[1]=(new_r01*x1452);
19447evalcond[2]=(gconst36*x1452);
19448evalcond[3]=((-1.0)*gconst36*x1450);
19449evalcond[4]=(gconst36+((new_r00*x1449)));
19450evalcond[5]=(((gconst36*x1449))+new_r00);
19451evalcond[6]=(new_r01+(((-1.0)*x1450*x1451)));
19452evalcond[7]=((((-1.0)*x1451))+((new_r01*x1450)));
19453if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19454{
19455continue;
19456}
19457}
19458
19459{
19460std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19461vinfos[0].jointtype = 1;
19462vinfos[0].foffset = j0;
19463vinfos[0].indices[0] = _ij0[0];
19464vinfos[0].indices[1] = _ij0[1];
19465vinfos[0].maxsolutions = _nj0;
19466vinfos[1].jointtype = 1;
19467vinfos[1].foffset = j1;
19468vinfos[1].indices[0] = _ij1[0];
19469vinfos[1].indices[1] = _ij1[1];
19470vinfos[1].maxsolutions = _nj1;
19471vinfos[2].jointtype = 1;
19472vinfos[2].foffset = j2;
19473vinfos[2].indices[0] = _ij2[0];
19474vinfos[2].indices[1] = _ij2[1];
19475vinfos[2].maxsolutions = _nj2;
19476vinfos[3].jointtype = 1;
19477vinfos[3].foffset = j3;
19478vinfos[3].indices[0] = _ij3[0];
19479vinfos[3].indices[1] = _ij3[1];
19480vinfos[3].maxsolutions = _nj3;
19481vinfos[4].jointtype = 1;
19482vinfos[4].foffset = j4;
19483vinfos[4].indices[0] = _ij4[0];
19484vinfos[4].indices[1] = _ij4[1];
19485vinfos[4].maxsolutions = _nj4;
19486vinfos[5].jointtype = 1;
19487vinfos[5].foffset = j5;
19488vinfos[5].indices[0] = _ij5[0];
19489vinfos[5].indices[1] = _ij5[1];
19490vinfos[5].maxsolutions = _nj5;
19491std::vector<int> vfree(0);
19492solutions.AddSolution(vinfos,vfree);
19493}
19494}
19495}
19496
19497}
19498
19499}
19500
19501}
19502} while(0);
19503if( bgotonextstatement )
19504{
19505bool bgotonextstatement = true;
19506do
19507{
19508if( 1 )
19509{
19510bgotonextstatement=false;
19511continue; // branch miss [j0]
19512
19513}
19514} while(0);
19515if( bgotonextstatement )
19516{
19517}
19518}
19519}
19520}
19521}
19522
19523} else
19524{
19525{
19526IkReal j0array[1], cj0array[1], sj0array[1];
19527bool j0valid[1]={false};
19528_nj0 = 1;
19529IkReal x1453=((1.0)*gconst36);
19530CheckValue<IkReal> x1454=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x1453))+((gconst35*new_r00)))),-1);
19531if(!x1454.valid){
19532continue;
19533}
19534CheckValue<IkReal> x1455 = IKatan2WithCheck(IkReal(((((-1.0)*gconst35*x1453))+((new_r00*new_r10)))),IkReal(((((-1.0)*gconst36*x1453))+(new_r00*new_r00))),IKFAST_ATAN2_MAGTHRESH);
19535if(!x1455.valid){
19536continue;
19537}
19538j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1454.value)))+(x1455.value));
19539sj0array[0]=IKsin(j0array[0]);
19540cj0array[0]=IKcos(j0array[0]);
19541if( j0array[0] > IKPI )
19542{
19543 j0array[0]-=IK2PI;
19544}
19545else if( j0array[0] < -IKPI )
19546{ j0array[0]+=IK2PI;
19547}
19548j0valid[0] = true;
19549for(int ij0 = 0; ij0 < 1; ++ij0)
19550{
19551if( !j0valid[ij0] )
19552{
19553 continue;
19554}
19555_ij0[0] = ij0; _ij0[1] = -1;
19556for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19557{
19558if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19559{
19560 j0valid[iij0]=false; _ij0[1] = iij0; break;
19561}
19562}
19563j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19564{
19565IkReal evalcond[8];
19566IkReal x1456=IKsin(j0);
19567IkReal x1457=IKcos(j0);
19568IkReal x1458=((1.0)*gconst35);
19569IkReal x1459=(gconst35*x1457);
19570IkReal x1460=((1.0)*x1457);
19571IkReal x1461=(gconst36*x1456);
19572IkReal x1462=(((x1456*x1458))+((gconst36*x1460)));
19573evalcond[0]=(gconst35+((new_r11*x1457))+(((-1.0)*new_r01*x1456)));
19574evalcond[1]=((((-1.0)*new_r10*x1460))+gconst36+((new_r00*x1456)));
19575evalcond[2]=((((-1.0)*x1457*x1458))+x1461+new_r00);
19576evalcond[3]=(x1459+new_r11+(((-1.0)*x1461)));
19577evalcond[4]=((((-1.0)*x1458))+((new_r00*x1457))+((new_r10*x1456)));
19578evalcond[5]=(((new_r01*x1457))+((new_r11*x1456))+(((-1.0)*gconst36)));
19579evalcond[6]=((((-1.0)*x1462))+new_r01);
19580evalcond[7]=((((-1.0)*x1462))+new_r10);
19581if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19582{
19583continue;
19584}
19585}
19586
19587{
19588std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19589vinfos[0].jointtype = 1;
19590vinfos[0].foffset = j0;
19591vinfos[0].indices[0] = _ij0[0];
19592vinfos[0].indices[1] = _ij0[1];
19593vinfos[0].maxsolutions = _nj0;
19594vinfos[1].jointtype = 1;
19595vinfos[1].foffset = j1;
19596vinfos[1].indices[0] = _ij1[0];
19597vinfos[1].indices[1] = _ij1[1];
19598vinfos[1].maxsolutions = _nj1;
19599vinfos[2].jointtype = 1;
19600vinfos[2].foffset = j2;
19601vinfos[2].indices[0] = _ij2[0];
19602vinfos[2].indices[1] = _ij2[1];
19603vinfos[2].maxsolutions = _nj2;
19604vinfos[3].jointtype = 1;
19605vinfos[3].foffset = j3;
19606vinfos[3].indices[0] = _ij3[0];
19607vinfos[3].indices[1] = _ij3[1];
19608vinfos[3].maxsolutions = _nj3;
19609vinfos[4].jointtype = 1;
19610vinfos[4].foffset = j4;
19611vinfos[4].indices[0] = _ij4[0];
19612vinfos[4].indices[1] = _ij4[1];
19613vinfos[4].maxsolutions = _nj4;
19614vinfos[5].jointtype = 1;
19615vinfos[5].foffset = j5;
19616vinfos[5].indices[0] = _ij5[0];
19617vinfos[5].indices[1] = _ij5[1];
19618vinfos[5].maxsolutions = _nj5;
19619std::vector<int> vfree(0);
19620solutions.AddSolution(vinfos,vfree);
19621}
19622}
19623}
19624
19625}
19626
19627}
19628
19629} else
19630{
19631{
19632IkReal j0array[1], cj0array[1], sj0array[1];
19633bool j0valid[1]={false};
19634_nj0 = 1;
19635CheckValue<IkReal> x1463 = IKatan2WithCheck(IkReal((((gconst35*new_r00))+((gconst35*new_r11)))),IkReal((((gconst35*new_r01))+(((-1.0)*gconst35*new_r10)))),IKFAST_ATAN2_MAGTHRESH);
19636if(!x1463.valid){
19637continue;
19638}
19639CheckValue<IkReal> x1464=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
19640if(!x1464.valid){
19641continue;
19642}
19643j0array[0]=((-1.5707963267949)+(x1463.value)+(((1.5707963267949)*(x1464.value))));
19644sj0array[0]=IKsin(j0array[0]);
19645cj0array[0]=IKcos(j0array[0]);
19646if( j0array[0] > IKPI )
19647{
19648 j0array[0]-=IK2PI;
19649}
19650else if( j0array[0] < -IKPI )
19651{ j0array[0]+=IK2PI;
19652}
19653j0valid[0] = true;
19654for(int ij0 = 0; ij0 < 1; ++ij0)
19655{
19656if( !j0valid[ij0] )
19657{
19658 continue;
19659}
19660_ij0[0] = ij0; _ij0[1] = -1;
19661for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19662{
19663if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19664{
19665 j0valid[iij0]=false; _ij0[1] = iij0; break;
19666}
19667}
19668j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19669{
19670IkReal evalcond[8];
19671IkReal x1465=IKsin(j0);
19672IkReal x1466=IKcos(j0);
19673IkReal x1467=((1.0)*gconst35);
19674IkReal x1468=(gconst35*x1466);
19675IkReal x1469=((1.0)*x1466);
19676IkReal x1470=(gconst36*x1465);
19677IkReal x1471=(((gconst36*x1469))+((x1465*x1467)));
19678evalcond[0]=((((-1.0)*new_r01*x1465))+gconst35+((new_r11*x1466)));
19679evalcond[1]=((((-1.0)*new_r10*x1469))+((new_r00*x1465))+gconst36);
19680evalcond[2]=((((-1.0)*x1466*x1467))+x1470+new_r00);
19681evalcond[3]=((((-1.0)*x1470))+x1468+new_r11);
19682evalcond[4]=(((new_r00*x1466))+(((-1.0)*x1467))+((new_r10*x1465)));
19683evalcond[5]=(((new_r01*x1466))+((new_r11*x1465))+(((-1.0)*gconst36)));
19684evalcond[6]=((((-1.0)*x1471))+new_r01);
19685evalcond[7]=((((-1.0)*x1471))+new_r10);
19686if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19687{
19688continue;
19689}
19690}
19691
19692{
19693std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19694vinfos[0].jointtype = 1;
19695vinfos[0].foffset = j0;
19696vinfos[0].indices[0] = _ij0[0];
19697vinfos[0].indices[1] = _ij0[1];
19698vinfos[0].maxsolutions = _nj0;
19699vinfos[1].jointtype = 1;
19700vinfos[1].foffset = j1;
19701vinfos[1].indices[0] = _ij1[0];
19702vinfos[1].indices[1] = _ij1[1];
19703vinfos[1].maxsolutions = _nj1;
19704vinfos[2].jointtype = 1;
19705vinfos[2].foffset = j2;
19706vinfos[2].indices[0] = _ij2[0];
19707vinfos[2].indices[1] = _ij2[1];
19708vinfos[2].maxsolutions = _nj2;
19709vinfos[3].jointtype = 1;
19710vinfos[3].foffset = j3;
19711vinfos[3].indices[0] = _ij3[0];
19712vinfos[3].indices[1] = _ij3[1];
19713vinfos[3].maxsolutions = _nj3;
19714vinfos[4].jointtype = 1;
19715vinfos[4].foffset = j4;
19716vinfos[4].indices[0] = _ij4[0];
19717vinfos[4].indices[1] = _ij4[1];
19718vinfos[4].maxsolutions = _nj4;
19719vinfos[5].jointtype = 1;
19720vinfos[5].foffset = j5;
19721vinfos[5].indices[0] = _ij5[0];
19722vinfos[5].indices[1] = _ij5[1];
19723vinfos[5].maxsolutions = _nj5;
19724std::vector<int> vfree(0);
19725solutions.AddSolution(vinfos,vfree);
19726}
19727}
19728}
19729
19730}
19731
19732}
19733
19734} else
19735{
19736{
19737IkReal j0array[1], cj0array[1], sj0array[1];
19738bool j0valid[1]={false};
19739_nj0 = 1;
19740CheckValue<IkReal> x1472=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
19741if(!x1472.valid){
19742continue;
19743}
19744CheckValue<IkReal> x1473 = IKatan2WithCheck(IkReal((((gconst36*new_r11))+((gconst35*new_r10)))),IkReal((((gconst35*new_r00))+((gconst36*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
19745if(!x1473.valid){
19746continue;
19747}
19748j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1472.value)))+(x1473.value));
19749sj0array[0]=IKsin(j0array[0]);
19750cj0array[0]=IKcos(j0array[0]);
19751if( j0array[0] > IKPI )
19752{
19753 j0array[0]-=IK2PI;
19754}
19755else if( j0array[0] < -IKPI )
19756{ j0array[0]+=IK2PI;
19757}
19758j0valid[0] = true;
19759for(int ij0 = 0; ij0 < 1; ++ij0)
19760{
19761if( !j0valid[ij0] )
19762{
19763 continue;
19764}
19765_ij0[0] = ij0; _ij0[1] = -1;
19766for(int iij0 = ij0+1; iij0 < 1; ++iij0)
19767{
19768if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
19769{
19770 j0valid[iij0]=false; _ij0[1] = iij0; break;
19771}
19772}
19773j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
19774{
19775IkReal evalcond[8];
19776IkReal x1474=IKsin(j0);
19777IkReal x1475=IKcos(j0);
19778IkReal x1476=((1.0)*gconst35);
19779IkReal x1477=(gconst35*x1475);
19780IkReal x1478=((1.0)*x1475);
19781IkReal x1479=(gconst36*x1474);
19782IkReal x1480=(((x1474*x1476))+((gconst36*x1478)));
19783evalcond[0]=(((new_r11*x1475))+gconst35+(((-1.0)*new_r01*x1474)));
19784evalcond[1]=(gconst36+((new_r00*x1474))+(((-1.0)*new_r10*x1478)));
19785evalcond[2]=((((-1.0)*x1475*x1476))+x1479+new_r00);
19786evalcond[3]=((((-1.0)*x1479))+x1477+new_r11);
19787evalcond[4]=(((new_r10*x1474))+((new_r00*x1475))+(((-1.0)*x1476)));
19788evalcond[5]=(((new_r11*x1474))+((new_r01*x1475))+(((-1.0)*gconst36)));
19789evalcond[6]=((((-1.0)*x1480))+new_r01);
19790evalcond[7]=((((-1.0)*x1480))+new_r10);
19791if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
19792{
19793continue;
19794}
19795}
19796
19797{
19798std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
19799vinfos[0].jointtype = 1;
19800vinfos[0].foffset = j0;
19801vinfos[0].indices[0] = _ij0[0];
19802vinfos[0].indices[1] = _ij0[1];
19803vinfos[0].maxsolutions = _nj0;
19804vinfos[1].jointtype = 1;
19805vinfos[1].foffset = j1;
19806vinfos[1].indices[0] = _ij1[0];
19807vinfos[1].indices[1] = _ij1[1];
19808vinfos[1].maxsolutions = _nj1;
19809vinfos[2].jointtype = 1;
19810vinfos[2].foffset = j2;
19811vinfos[2].indices[0] = _ij2[0];
19812vinfos[2].indices[1] = _ij2[1];
19813vinfos[2].maxsolutions = _nj2;
19814vinfos[3].jointtype = 1;
19815vinfos[3].foffset = j3;
19816vinfos[3].indices[0] = _ij3[0];
19817vinfos[3].indices[1] = _ij3[1];
19818vinfos[3].maxsolutions = _nj3;
19819vinfos[4].jointtype = 1;
19820vinfos[4].foffset = j4;
19821vinfos[4].indices[0] = _ij4[0];
19822vinfos[4].indices[1] = _ij4[1];
19823vinfos[4].maxsolutions = _nj4;
19824vinfos[5].jointtype = 1;
19825vinfos[5].foffset = j5;
19826vinfos[5].indices[0] = _ij5[0];
19827vinfos[5].indices[1] = _ij5[1];
19828vinfos[5].maxsolutions = _nj5;
19829std::vector<int> vfree(0);
19830solutions.AddSolution(vinfos,vfree);
19831}
19832}
19833}
19834
19835}
19836
19837}
19838
19839}
19840} while(0);
19841if( bgotonextstatement )
19842{
19843bool bgotonextstatement = true;
19844do
19845{
19846IkReal x1483 = ((new_r01*new_r01)+(new_r11*new_r11));
19847if(IKabs(x1483)==0){
19848continue;
19849}
19850IkReal x1481=pow(x1483,-0.5);
19851IkReal x1482=((1.0)*x1481);
19852CheckValue<IkReal> x1484 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19853if(!x1484.valid){
19854continue;
19855}
19856IkReal gconst37=((3.14159265358979)+(((-1.0)*(x1484.value))));
19857IkReal gconst38=(new_r11*x1482);
19858IkReal gconst39=(new_r01*x1482);
19859CheckValue<IkReal> x1485 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19860if(!x1485.valid){
19861continue;
19862}
19863evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1485.value)+j2)))), 6.28318530717959)));
19864if( IKabs(evalcond[0]) < 0.0000050000000000 )
19865{
19866bgotonextstatement=false;
19867{
19868IkReal j0eval[3];
19869CheckValue<IkReal> x1489 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19870if(!x1489.valid){
19871continue;
19872}
19873IkReal x1486=((1.0)*(x1489.value));
19874IkReal x1487=x1481;
19875IkReal x1488=((1.0)*x1487);
19876sj1=-1.0;
19877cj1=0;
19878j1=-1.5707963267949;
19879sj2=gconst38;
19880cj2=gconst39;
19881j2=((3.14159265)+(((-1.0)*x1486)));
19882IkReal gconst37=((3.14159265358979)+(((-1.0)*x1486)));
19883IkReal gconst38=(new_r11*x1488);
19884IkReal gconst39=(new_r01*x1488);
19885IkReal x1490=new_r01*new_r01;
19886IkReal x1491=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)));
19887IkReal x1492=x1481;
19888IkReal x1493=(new_r11*x1492);
19889j0eval[0]=x1491;
19890j0eval[1]=IKsign(x1491);
19891j0eval[2]=((IKabs((((new_r00*x1493))+((x1490*x1492)))))+(IKabs((((new_r01*x1493))+((new_r10*x1493))))));
19892if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
19893{
19894{
19895IkReal j0eval[1];
19896CheckValue<IkReal> x1497 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19897if(!x1497.valid){
19898continue;
19899}
19900IkReal x1494=((1.0)*(x1497.value));
19901IkReal x1495=x1481;
19902IkReal x1496=((1.0)*x1495);
19903sj1=-1.0;
19904cj1=0;
19905j1=-1.5707963267949;
19906sj2=gconst38;
19907cj2=gconst39;
19908j2=((3.14159265)+(((-1.0)*x1494)));
19909IkReal gconst37=((3.14159265358979)+(((-1.0)*x1494)));
19910IkReal gconst38=(new_r11*x1496);
19911IkReal gconst39=(new_r01*x1496);
19912IkReal x1498=new_r01*new_r01;
19913IkReal x1499=new_r11*new_r11*new_r11;
19914CheckValue<IkReal> x1503=IKPowWithIntegerCheck(((new_r11*new_r11)+x1498),-1);
19915if(!x1503.valid){
19916continue;
19917}
19918IkReal x1500=x1503.value;
19919IkReal x1501=(x1498*x1500);
19920IkReal x1502=(x1499*x1500);
19921j0eval[0]=((IKabs((((new_r10*x1502))+((new_r01*new_r11*x1500))+((new_r10*new_r11*x1501)))))+(IKabs((((new_r00*new_r11*x1501))+x1501+((new_r00*x1502))))));
19922if( IKabs(j0eval[0]) < 0.0000010000000000 )
19923{
19924{
19925IkReal j0eval[3];
19926CheckValue<IkReal> x1507 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19927if(!x1507.valid){
19928continue;
19929}
19930IkReal x1504=((1.0)*(x1507.value));
19931IkReal x1505=x1481;
19932IkReal x1506=((1.0)*x1505);
19933sj1=-1.0;
19934cj1=0;
19935j1=-1.5707963267949;
19936sj2=gconst38;
19937cj2=gconst39;
19938j2=((3.14159265)+(((-1.0)*x1504)));
19939IkReal gconst37=((3.14159265358979)+(((-1.0)*x1504)));
19940IkReal gconst38=(new_r11*x1506);
19941IkReal gconst39=(new_r01*x1506);
19942IkReal x1508=new_r11*new_r11;
19943IkReal x1509=(new_r10*new_r11);
19944IkReal x1510=(((new_r00*new_r01))+x1509);
19945IkReal x1511=x1481;
19946IkReal x1512=(new_r11*x1511);
19947j0eval[0]=x1510;
19948j0eval[1]=IKsign(x1510);
19949j0eval[2]=((IKabs(((((-1.0)*x1509*x1511))+((new_r01*x1512)))))+(IKabs((((x1508*x1511))+((new_r00*x1512))))));
19950if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
19951{
19952{
19953IkReal evalcond[2];
19954bool bgotonextstatement = true;
19955do
19956{
19957evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00)));
19958if( IKabs(evalcond[0]) < 0.0000050000000000 )
19959{
19960bgotonextstatement=false;
19961{
19962IkReal j0eval[1];
19963CheckValue<IkReal> x1514 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
19964if(!x1514.valid){
19965continue;
19966}
19967IkReal x1513=((1.0)*(x1514.value));
19968sj1=-1.0;
19969cj1=0;
19970j1=-1.5707963267949;
19971sj2=gconst38;
19972cj2=gconst39;
19973j2=((3.14159265)+(((-1.0)*x1513)));
19974new_r11=0;
19975new_r00=0;
19976IkReal gconst37=((3.14159265358979)+(((-1.0)*x1513)));
19977IkReal gconst38=0;
19978IkReal x1515 = new_r01*new_r01;
19979if(IKabs(x1515)==0){
19980continue;
19981}
19982IkReal gconst39=((1.0)*new_r01*(pow(x1515,-0.5)));
19983j0eval[0]=new_r10;
19984if( IKabs(j0eval[0]) < 0.0000010000000000 )
19985{
19986{
19987IkReal j0array[2], cj0array[2], sj0array[2];
19988bool j0valid[2]={false};
19989_nj0 = 2;
19990CheckValue<IkReal> x1516=IKPowWithIntegerCheck(gconst39,-1);
19991if(!x1516.valid){
19992continue;
19993}
19994cj0array[0]=(new_r01*(x1516.value));
19995if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
19996{
19997 j0valid[0] = j0valid[1] = true;
19998 j0array[0] = IKacos(cj0array[0]);
19999 sj0array[0] = IKsin(j0array[0]);
20000 cj0array[1] = cj0array[0];
20001 j0array[1] = -j0array[0];
20002 sj0array[1] = -sj0array[0];
20003}
20004else if( isnan(cj0array[0]) )
20005{
20006 // probably any value will work
20007 j0valid[0] = true;
20008 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
20009}
20010for(int ij0 = 0; ij0 < 2; ++ij0)
20011{
20012if( !j0valid[ij0] )
20013{
20014 continue;
20015}
20016_ij0[0] = ij0; _ij0[1] = -1;
20017for(int iij0 = ij0+1; iij0 < 2; ++iij0)
20018{
20019if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20020{
20021 j0valid[iij0]=false; _ij0[1] = iij0; break;
20022}
20023}
20024j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20025{
20026IkReal evalcond[6];
20027IkReal x1517=IKsin(j0);
20028IkReal x1518=IKcos(j0);
20029IkReal x1519=((1.0)*x1518);
20030evalcond[0]=(new_r10*x1517);
20031evalcond[1]=(gconst39*x1517);
20032evalcond[2]=((-1.0)*new_r01*x1517);
20033evalcond[3]=((((-1.0)*new_r10*x1519))+gconst39);
20034evalcond[4]=((((-1.0)*gconst39*x1519))+new_r10);
20035evalcond[5]=(((new_r01*x1518))+(((-1.0)*gconst39)));
20036if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20037{
20038continue;
20039}
20040}
20041
20042{
20043std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20044vinfos[0].jointtype = 1;
20045vinfos[0].foffset = j0;
20046vinfos[0].indices[0] = _ij0[0];
20047vinfos[0].indices[1] = _ij0[1];
20048vinfos[0].maxsolutions = _nj0;
20049vinfos[1].jointtype = 1;
20050vinfos[1].foffset = j1;
20051vinfos[1].indices[0] = _ij1[0];
20052vinfos[1].indices[1] = _ij1[1];
20053vinfos[1].maxsolutions = _nj1;
20054vinfos[2].jointtype = 1;
20055vinfos[2].foffset = j2;
20056vinfos[2].indices[0] = _ij2[0];
20057vinfos[2].indices[1] = _ij2[1];
20058vinfos[2].maxsolutions = _nj2;
20059vinfos[3].jointtype = 1;
20060vinfos[3].foffset = j3;
20061vinfos[3].indices[0] = _ij3[0];
20062vinfos[3].indices[1] = _ij3[1];
20063vinfos[3].maxsolutions = _nj3;
20064vinfos[4].jointtype = 1;
20065vinfos[4].foffset = j4;
20066vinfos[4].indices[0] = _ij4[0];
20067vinfos[4].indices[1] = _ij4[1];
20068vinfos[4].maxsolutions = _nj4;
20069vinfos[5].jointtype = 1;
20070vinfos[5].foffset = j5;
20071vinfos[5].indices[0] = _ij5[0];
20072vinfos[5].indices[1] = _ij5[1];
20073vinfos[5].maxsolutions = _nj5;
20074std::vector<int> vfree(0);
20075solutions.AddSolution(vinfos,vfree);
20076}
20077}
20078}
20079
20080} else
20081{
20082{
20083IkReal j0array[2], cj0array[2], sj0array[2];
20084bool j0valid[2]={false};
20085_nj0 = 2;
20086CheckValue<IkReal> x1520=IKPowWithIntegerCheck(new_r10,-1);
20087if(!x1520.valid){
20088continue;
20089}
20090cj0array[0]=(gconst39*(x1520.value));
20091if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
20092{
20093 j0valid[0] = j0valid[1] = true;
20094 j0array[0] = IKacos(cj0array[0]);
20095 sj0array[0] = IKsin(j0array[0]);
20096 cj0array[1] = cj0array[0];
20097 j0array[1] = -j0array[0];
20098 sj0array[1] = -sj0array[0];
20099}
20100else if( isnan(cj0array[0]) )
20101{
20102 // probably any value will work
20103 j0valid[0] = true;
20104 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
20105}
20106for(int ij0 = 0; ij0 < 2; ++ij0)
20107{
20108if( !j0valid[ij0] )
20109{
20110 continue;
20111}
20112_ij0[0] = ij0; _ij0[1] = -1;
20113for(int iij0 = ij0+1; iij0 < 2; ++iij0)
20114{
20115if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20116{
20117 j0valid[iij0]=false; _ij0[1] = iij0; break;
20118}
20119}
20120j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20121{
20122IkReal evalcond[6];
20123IkReal x1521=IKsin(j0);
20124IkReal x1522=IKcos(j0);
20125IkReal x1523=((1.0)*gconst39);
20126IkReal x1524=(x1522*x1523);
20127evalcond[0]=(new_r10*x1521);
20128evalcond[1]=(gconst39*x1521);
20129evalcond[2]=((-1.0)*new_r01*x1521);
20130evalcond[3]=((((-1.0)*x1524))+new_r01);
20131evalcond[4]=((((-1.0)*x1524))+new_r10);
20132evalcond[5]=((((-1.0)*x1523))+((new_r01*x1522)));
20133if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20134{
20135continue;
20136}
20137}
20138
20139{
20140std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20141vinfos[0].jointtype = 1;
20142vinfos[0].foffset = j0;
20143vinfos[0].indices[0] = _ij0[0];
20144vinfos[0].indices[1] = _ij0[1];
20145vinfos[0].maxsolutions = _nj0;
20146vinfos[1].jointtype = 1;
20147vinfos[1].foffset = j1;
20148vinfos[1].indices[0] = _ij1[0];
20149vinfos[1].indices[1] = _ij1[1];
20150vinfos[1].maxsolutions = _nj1;
20151vinfos[2].jointtype = 1;
20152vinfos[2].foffset = j2;
20153vinfos[2].indices[0] = _ij2[0];
20154vinfos[2].indices[1] = _ij2[1];
20155vinfos[2].maxsolutions = _nj2;
20156vinfos[3].jointtype = 1;
20157vinfos[3].foffset = j3;
20158vinfos[3].indices[0] = _ij3[0];
20159vinfos[3].indices[1] = _ij3[1];
20160vinfos[3].maxsolutions = _nj3;
20161vinfos[4].jointtype = 1;
20162vinfos[4].foffset = j4;
20163vinfos[4].indices[0] = _ij4[0];
20164vinfos[4].indices[1] = _ij4[1];
20165vinfos[4].maxsolutions = _nj4;
20166vinfos[5].jointtype = 1;
20167vinfos[5].foffset = j5;
20168vinfos[5].indices[0] = _ij5[0];
20169vinfos[5].indices[1] = _ij5[1];
20170vinfos[5].maxsolutions = _nj5;
20171std::vector<int> vfree(0);
20172solutions.AddSolution(vinfos,vfree);
20173}
20174}
20175}
20176
20177}
20178
20179}
20180
20181}
20182} while(0);
20183if( bgotonextstatement )
20184{
20185bool bgotonextstatement = true;
20186do
20187{
20188evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
20189evalcond[1]=gconst39;
20190if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
20191{
20192bgotonextstatement=false;
20193{
20194IkReal j0eval[4];
20195CheckValue<IkReal> x1526 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20196if(!x1526.valid){
20197continue;
20198}
20199IkReal x1525=((1.0)*(x1526.value));
20200sj1=-1.0;
20201cj1=0;
20202j1=-1.5707963267949;
20203sj2=gconst38;
20204cj2=gconst39;
20205j2=((3.14159265)+(((-1.0)*x1525)));
20206new_r00=0;
20207new_r10=0;
20208new_r21=0;
20209new_r22=0;
20210IkReal gconst37=((3.14159265358979)+(((-1.0)*x1525)));
20211IkReal gconst38=((1.0)*new_r11);
20212IkReal gconst39=((1.0)*new_r01);
20213j0eval[0]=1.0;
20214j0eval[1]=1.0;
20215j0eval[2]=new_r01;
20216j0eval[3]=1.0;
20217if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 )
20218{
20219{
20220IkReal j0eval[4];
20221CheckValue<IkReal> x1528 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20222if(!x1528.valid){
20223continue;
20224}
20225IkReal x1527=((1.0)*(x1528.value));
20226sj1=-1.0;
20227cj1=0;
20228j1=-1.5707963267949;
20229sj2=gconst38;
20230cj2=gconst39;
20231j2=((3.14159265)+(((-1.0)*x1527)));
20232new_r00=0;
20233new_r10=0;
20234new_r21=0;
20235new_r22=0;
20236IkReal gconst37=((3.14159265358979)+(((-1.0)*x1527)));
20237IkReal gconst38=((1.0)*new_r11);
20238IkReal gconst39=((1.0)*new_r01);
20239j0eval[0]=1.0;
20240j0eval[1]=new_r01;
20241j0eval[2]=1.0;
20242j0eval[3]=1.0;
20243if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 )
20244{
20245{
20246IkReal j0eval[3];
20247CheckValue<IkReal> x1530 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20248if(!x1530.valid){
20249continue;
20250}
20251IkReal x1529=((1.0)*(x1530.value));
20252sj1=-1.0;
20253cj1=0;
20254j1=-1.5707963267949;
20255sj2=gconst38;
20256cj2=gconst39;
20257j2=((3.14159265)+(((-1.0)*x1529)));
20258new_r00=0;
20259new_r10=0;
20260new_r21=0;
20261new_r22=0;
20262IkReal gconst37=((3.14159265358979)+(((-1.0)*x1529)));
20263IkReal gconst38=((1.0)*new_r11);
20264IkReal gconst39=((1.0)*new_r01);
20265j0eval[0]=1.0;
20266j0eval[1]=1.0;
20267j0eval[2]=((IKabs(((-1.0)+(new_r01*new_r01))))+(IKabs(((1.0)*new_r01*new_r11))));
20268if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
20269{
20270continue; // 3 cases reached
20271
20272} else
20273{
20274{
20275IkReal j0array[1], cj0array[1], sj0array[1];
20276bool j0valid[1]={false};
20277_nj0 = 1;
20278CheckValue<IkReal> x1531 = IKatan2WithCheck(IkReal((gconst39*new_r11)),IkReal(((-1.0)*gconst38*new_r11)),IKFAST_ATAN2_MAGTHRESH);
20279if(!x1531.valid){
20280continue;
20281}
20282CheckValue<IkReal> x1532=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1);
20283if(!x1532.valid){
20284continue;
20285}
20286j0array[0]=((-1.5707963267949)+(x1531.value)+(((1.5707963267949)*(x1532.value))));
20287sj0array[0]=IKsin(j0array[0]);
20288cj0array[0]=IKcos(j0array[0]);
20289if( j0array[0] > IKPI )
20290{
20291 j0array[0]-=IK2PI;
20292}
20293else if( j0array[0] < -IKPI )
20294{ j0array[0]+=IK2PI;
20295}
20296j0valid[0] = true;
20297for(int ij0 = 0; ij0 < 1; ++ij0)
20298{
20299if( !j0valid[ij0] )
20300{
20301 continue;
20302}
20303_ij0[0] = ij0; _ij0[1] = -1;
20304for(int iij0 = ij0+1; iij0 < 1; ++iij0)
20305{
20306if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20307{
20308 j0valid[iij0]=false; _ij0[1] = iij0; break;
20309}
20310}
20311j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20312{
20313IkReal evalcond[6];
20314IkReal x1533=IKcos(j0);
20315IkReal x1534=IKsin(j0);
20316IkReal x1535=((1.0)*gconst39);
20317IkReal x1536=(gconst38*x1533);
20318IkReal x1537=((1.0)*x1534);
20319IkReal x1538=(((x1533*x1535))+((gconst38*x1537)));
20320evalcond[0]=(((gconst39*x1534))+(((-1.0)*x1536)));
20321evalcond[1]=(gconst38+(((-1.0)*new_r01*x1537))+((new_r11*x1533)));
20322evalcond[2]=(x1536+(((-1.0)*x1534*x1535))+new_r11);
20323evalcond[3]=((-1.0)*x1538);
20324evalcond[4]=((((-1.0)*x1535))+((new_r01*x1533))+((new_r11*x1534)));
20325evalcond[5]=((((-1.0)*x1538))+new_r01);
20326if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20327{
20328continue;
20329}
20330}
20331
20332{
20333std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20334vinfos[0].jointtype = 1;
20335vinfos[0].foffset = j0;
20336vinfos[0].indices[0] = _ij0[0];
20337vinfos[0].indices[1] = _ij0[1];
20338vinfos[0].maxsolutions = _nj0;
20339vinfos[1].jointtype = 1;
20340vinfos[1].foffset = j1;
20341vinfos[1].indices[0] = _ij1[0];
20342vinfos[1].indices[1] = _ij1[1];
20343vinfos[1].maxsolutions = _nj1;
20344vinfos[2].jointtype = 1;
20345vinfos[2].foffset = j2;
20346vinfos[2].indices[0] = _ij2[0];
20347vinfos[2].indices[1] = _ij2[1];
20348vinfos[2].maxsolutions = _nj2;
20349vinfos[3].jointtype = 1;
20350vinfos[3].foffset = j3;
20351vinfos[3].indices[0] = _ij3[0];
20352vinfos[3].indices[1] = _ij3[1];
20353vinfos[3].maxsolutions = _nj3;
20354vinfos[4].jointtype = 1;
20355vinfos[4].foffset = j4;
20356vinfos[4].indices[0] = _ij4[0];
20357vinfos[4].indices[1] = _ij4[1];
20358vinfos[4].maxsolutions = _nj4;
20359vinfos[5].jointtype = 1;
20360vinfos[5].foffset = j5;
20361vinfos[5].indices[0] = _ij5[0];
20362vinfos[5].indices[1] = _ij5[1];
20363vinfos[5].maxsolutions = _nj5;
20364std::vector<int> vfree(0);
20365solutions.AddSolution(vinfos,vfree);
20366}
20367}
20368}
20369
20370}
20371
20372}
20373
20374} else
20375{
20376{
20377IkReal j0array[1], cj0array[1], sj0array[1];
20378bool j0valid[1]={false};
20379_nj0 = 1;
20380CheckValue<IkReal> x1539 = IKatan2WithCheck(IkReal((gconst38*new_r01)),IkReal((gconst39*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20381if(!x1539.valid){
20382continue;
20383}
20384CheckValue<IkReal> x1540=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1);
20385if(!x1540.valid){
20386continue;
20387}
20388j0array[0]=((-1.5707963267949)+(x1539.value)+(((1.5707963267949)*(x1540.value))));
20389sj0array[0]=IKsin(j0array[0]);
20390cj0array[0]=IKcos(j0array[0]);
20391if( j0array[0] > IKPI )
20392{
20393 j0array[0]-=IK2PI;
20394}
20395else if( j0array[0] < -IKPI )
20396{ j0array[0]+=IK2PI;
20397}
20398j0valid[0] = true;
20399for(int ij0 = 0; ij0 < 1; ++ij0)
20400{
20401if( !j0valid[ij0] )
20402{
20403 continue;
20404}
20405_ij0[0] = ij0; _ij0[1] = -1;
20406for(int iij0 = ij0+1; iij0 < 1; ++iij0)
20407{
20408if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20409{
20410 j0valid[iij0]=false; _ij0[1] = iij0; break;
20411}
20412}
20413j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20414{
20415IkReal evalcond[6];
20416IkReal x1541=IKcos(j0);
20417IkReal x1542=IKsin(j0);
20418IkReal x1543=((1.0)*gconst39);
20419IkReal x1544=(gconst38*x1541);
20420IkReal x1545=((1.0)*x1542);
20421IkReal x1546=(((x1541*x1543))+((gconst38*x1545)));
20422evalcond[0]=((((-1.0)*x1544))+((gconst39*x1542)));
20423evalcond[1]=(((new_r11*x1541))+gconst38+(((-1.0)*new_r01*x1545)));
20424evalcond[2]=(x1544+(((-1.0)*x1542*x1543))+new_r11);
20425evalcond[3]=((-1.0)*x1546);
20426evalcond[4]=(((new_r01*x1541))+((new_r11*x1542))+(((-1.0)*x1543)));
20427evalcond[5]=(new_r01+(((-1.0)*x1546)));
20428if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20429{
20430continue;
20431}
20432}
20433
20434{
20435std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20436vinfos[0].jointtype = 1;
20437vinfos[0].foffset = j0;
20438vinfos[0].indices[0] = _ij0[0];
20439vinfos[0].indices[1] = _ij0[1];
20440vinfos[0].maxsolutions = _nj0;
20441vinfos[1].jointtype = 1;
20442vinfos[1].foffset = j1;
20443vinfos[1].indices[0] = _ij1[0];
20444vinfos[1].indices[1] = _ij1[1];
20445vinfos[1].maxsolutions = _nj1;
20446vinfos[2].jointtype = 1;
20447vinfos[2].foffset = j2;
20448vinfos[2].indices[0] = _ij2[0];
20449vinfos[2].indices[1] = _ij2[1];
20450vinfos[2].maxsolutions = _nj2;
20451vinfos[3].jointtype = 1;
20452vinfos[3].foffset = j3;
20453vinfos[3].indices[0] = _ij3[0];
20454vinfos[3].indices[1] = _ij3[1];
20455vinfos[3].maxsolutions = _nj3;
20456vinfos[4].jointtype = 1;
20457vinfos[4].foffset = j4;
20458vinfos[4].indices[0] = _ij4[0];
20459vinfos[4].indices[1] = _ij4[1];
20460vinfos[4].maxsolutions = _nj4;
20461vinfos[5].jointtype = 1;
20462vinfos[5].foffset = j5;
20463vinfos[5].indices[0] = _ij5[0];
20464vinfos[5].indices[1] = _ij5[1];
20465vinfos[5].maxsolutions = _nj5;
20466std::vector<int> vfree(0);
20467solutions.AddSolution(vinfos,vfree);
20468}
20469}
20470}
20471
20472}
20473
20474}
20475
20476} else
20477{
20478{
20479IkReal j0array[1], cj0array[1], sj0array[1];
20480bool j0valid[1]={false};
20481_nj0 = 1;
20482CheckValue<IkReal> x1547 = IKatan2WithCheck(IkReal((gconst38*gconst39)),IkReal(gconst39*gconst39),IKFAST_ATAN2_MAGTHRESH);
20483if(!x1547.valid){
20484continue;
20485}
20486CheckValue<IkReal> x1548=IKPowWithIntegerCheck(IKsign((((gconst39*new_r01))+((gconst38*new_r11)))),-1);
20487if(!x1548.valid){
20488continue;
20489}
20490j0array[0]=((-1.5707963267949)+(x1547.value)+(((1.5707963267949)*(x1548.value))));
20491sj0array[0]=IKsin(j0array[0]);
20492cj0array[0]=IKcos(j0array[0]);
20493if( j0array[0] > IKPI )
20494{
20495 j0array[0]-=IK2PI;
20496}
20497else if( j0array[0] < -IKPI )
20498{ j0array[0]+=IK2PI;
20499}
20500j0valid[0] = true;
20501for(int ij0 = 0; ij0 < 1; ++ij0)
20502{
20503if( !j0valid[ij0] )
20504{
20505 continue;
20506}
20507_ij0[0] = ij0; _ij0[1] = -1;
20508for(int iij0 = ij0+1; iij0 < 1; ++iij0)
20509{
20510if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20511{
20512 j0valid[iij0]=false; _ij0[1] = iij0; break;
20513}
20514}
20515j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20516{
20517IkReal evalcond[6];
20518IkReal x1549=IKcos(j0);
20519IkReal x1550=IKsin(j0);
20520IkReal x1551=((1.0)*gconst39);
20521IkReal x1552=(gconst38*x1549);
20522IkReal x1553=((1.0)*x1550);
20523IkReal x1554=(((x1549*x1551))+((gconst38*x1553)));
20524evalcond[0]=((((-1.0)*x1552))+((gconst39*x1550)));
20525evalcond[1]=(((new_r11*x1549))+gconst38+(((-1.0)*new_r01*x1553)));
20526evalcond[2]=(x1552+(((-1.0)*x1550*x1551))+new_r11);
20527evalcond[3]=((-1.0)*x1554);
20528evalcond[4]=(((new_r01*x1549))+((new_r11*x1550))+(((-1.0)*x1551)));
20529evalcond[5]=((((-1.0)*x1554))+new_r01);
20530if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20531{
20532continue;
20533}
20534}
20535
20536{
20537std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20538vinfos[0].jointtype = 1;
20539vinfos[0].foffset = j0;
20540vinfos[0].indices[0] = _ij0[0];
20541vinfos[0].indices[1] = _ij0[1];
20542vinfos[0].maxsolutions = _nj0;
20543vinfos[1].jointtype = 1;
20544vinfos[1].foffset = j1;
20545vinfos[1].indices[0] = _ij1[0];
20546vinfos[1].indices[1] = _ij1[1];
20547vinfos[1].maxsolutions = _nj1;
20548vinfos[2].jointtype = 1;
20549vinfos[2].foffset = j2;
20550vinfos[2].indices[0] = _ij2[0];
20551vinfos[2].indices[1] = _ij2[1];
20552vinfos[2].maxsolutions = _nj2;
20553vinfos[3].jointtype = 1;
20554vinfos[3].foffset = j3;
20555vinfos[3].indices[0] = _ij3[0];
20556vinfos[3].indices[1] = _ij3[1];
20557vinfos[3].maxsolutions = _nj3;
20558vinfos[4].jointtype = 1;
20559vinfos[4].foffset = j4;
20560vinfos[4].indices[0] = _ij4[0];
20561vinfos[4].indices[1] = _ij4[1];
20562vinfos[4].maxsolutions = _nj4;
20563vinfos[5].jointtype = 1;
20564vinfos[5].foffset = j5;
20565vinfos[5].indices[0] = _ij5[0];
20566vinfos[5].indices[1] = _ij5[1];
20567vinfos[5].maxsolutions = _nj5;
20568std::vector<int> vfree(0);
20569solutions.AddSolution(vinfos,vfree);
20570}
20571}
20572}
20573
20574}
20575
20576}
20577
20578}
20579} while(0);
20580if( bgotonextstatement )
20581{
20582bool bgotonextstatement = true;
20583do
20584{
20585evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01)));
20586if( IKabs(evalcond[0]) < 0.0000050000000000 )
20587{
20588bgotonextstatement=false;
20589{
20590IkReal j0array[2], cj0array[2], sj0array[2];
20591bool j0valid[2]={false};
20592_nj0 = 2;
20593CheckValue<IkReal> x1555=IKPowWithIntegerCheck(gconst38,-1);
20594if(!x1555.valid){
20595continue;
20596}
20597cj0array[0]=(new_r00*(x1555.value));
20598if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH )
20599{
20600 j0valid[0] = j0valid[1] = true;
20601 j0array[0] = IKacos(cj0array[0]);
20602 sj0array[0] = IKsin(j0array[0]);
20603 cj0array[1] = cj0array[0];
20604 j0array[1] = -j0array[0];
20605 sj0array[1] = -sj0array[0];
20606}
20607else if( isnan(cj0array[0]) )
20608{
20609 // probably any value will work
20610 j0valid[0] = true;
20611 cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0;
20612}
20613for(int ij0 = 0; ij0 < 2; ++ij0)
20614{
20615if( !j0valid[ij0] )
20616{
20617 continue;
20618}
20619_ij0[0] = ij0; _ij0[1] = -1;
20620for(int iij0 = ij0+1; iij0 < 2; ++iij0)
20621{
20622if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20623{
20624 j0valid[iij0]=false; _ij0[1] = iij0; break;
20625}
20626}
20627j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20628{
20629IkReal evalcond[6];
20630IkReal x1556=IKsin(j0);
20631IkReal x1557=IKcos(j0);
20632evalcond[0]=(new_r00*x1556);
20633evalcond[1]=(new_r11*x1556);
20634evalcond[2]=((-1.0)*gconst38*x1556);
20635evalcond[3]=(gconst38+((new_r11*x1557)));
20636evalcond[4]=(new_r11+((gconst38*x1557)));
20637evalcond[5]=(((new_r00*x1557))+(((-1.0)*gconst38)));
20638if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH )
20639{
20640continue;
20641}
20642}
20643
20644{
20645std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20646vinfos[0].jointtype = 1;
20647vinfos[0].foffset = j0;
20648vinfos[0].indices[0] = _ij0[0];
20649vinfos[0].indices[1] = _ij0[1];
20650vinfos[0].maxsolutions = _nj0;
20651vinfos[1].jointtype = 1;
20652vinfos[1].foffset = j1;
20653vinfos[1].indices[0] = _ij1[0];
20654vinfos[1].indices[1] = _ij1[1];
20655vinfos[1].maxsolutions = _nj1;
20656vinfos[2].jointtype = 1;
20657vinfos[2].foffset = j2;
20658vinfos[2].indices[0] = _ij2[0];
20659vinfos[2].indices[1] = _ij2[1];
20660vinfos[2].maxsolutions = _nj2;
20661vinfos[3].jointtype = 1;
20662vinfos[3].foffset = j3;
20663vinfos[3].indices[0] = _ij3[0];
20664vinfos[3].indices[1] = _ij3[1];
20665vinfos[3].maxsolutions = _nj3;
20666vinfos[4].jointtype = 1;
20667vinfos[4].foffset = j4;
20668vinfos[4].indices[0] = _ij4[0];
20669vinfos[4].indices[1] = _ij4[1];
20670vinfos[4].maxsolutions = _nj4;
20671vinfos[5].jointtype = 1;
20672vinfos[5].foffset = j5;
20673vinfos[5].indices[0] = _ij5[0];
20674vinfos[5].indices[1] = _ij5[1];
20675vinfos[5].maxsolutions = _nj5;
20676std::vector<int> vfree(0);
20677solutions.AddSolution(vinfos,vfree);
20678}
20679}
20680}
20681
20682}
20683} while(0);
20684if( bgotonextstatement )
20685{
20686bool bgotonextstatement = true;
20687do
20688{
20689evalcond[0]=IKabs(new_r11);
20690if( IKabs(evalcond[0]) < 0.0000050000000000 )
20691{
20692bgotonextstatement=false;
20693{
20694IkReal j0eval[1];
20695CheckValue<IkReal> x1559 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20696if(!x1559.valid){
20697continue;
20698}
20699IkReal x1558=((1.0)*(x1559.value));
20700sj1=-1.0;
20701cj1=0;
20702j1=-1.5707963267949;
20703sj2=gconst38;
20704cj2=gconst39;
20705j2=((3.14159265)+(((-1.0)*x1558)));
20706new_r11=0;
20707IkReal gconst37=((3.14159265358979)+(((-1.0)*x1558)));
20708IkReal gconst38=0;
20709IkReal x1560 = new_r01*new_r01;
20710if(IKabs(x1560)==0){
20711continue;
20712}
20713IkReal gconst39=((1.0)*new_r01*(pow(x1560,-0.5)));
20714j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01)));
20715if( IKabs(j0eval[0]) < 0.0000010000000000 )
20716{
20717{
20718IkReal j0eval[1];
20719CheckValue<IkReal> x1562 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20720if(!x1562.valid){
20721continue;
20722}
20723IkReal x1561=((1.0)*(x1562.value));
20724sj1=-1.0;
20725cj1=0;
20726j1=-1.5707963267949;
20727sj2=gconst38;
20728cj2=gconst39;
20729j2=((3.14159265)+(((-1.0)*x1561)));
20730new_r11=0;
20731IkReal gconst37=((3.14159265358979)+(((-1.0)*x1561)));
20732IkReal gconst38=0;
20733IkReal x1563 = new_r01*new_r01;
20734if(IKabs(x1563)==0){
20735continue;
20736}
20737IkReal gconst39=((1.0)*new_r01*(pow(x1563,-0.5)));
20738j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
20739if( IKabs(j0eval[0]) < 0.0000010000000000 )
20740{
20741{
20742IkReal j0eval[1];
20743CheckValue<IkReal> x1565 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH);
20744if(!x1565.valid){
20745continue;
20746}
20747IkReal x1564=((1.0)*(x1565.value));
20748sj1=-1.0;
20749cj1=0;
20750j1=-1.5707963267949;
20751sj2=gconst38;
20752cj2=gconst39;
20753j2=((3.14159265)+(((-1.0)*x1564)));
20754new_r11=0;
20755IkReal gconst37=((3.14159265358979)+(((-1.0)*x1564)));
20756IkReal gconst38=0;
20757IkReal x1566 = new_r01*new_r01;
20758if(IKabs(x1566)==0){
20759continue;
20760}
20761IkReal gconst39=((1.0)*new_r01*(pow(x1566,-0.5)));
20762j0eval[0]=new_r01;
20763if( IKabs(j0eval[0]) < 0.0000010000000000 )
20764{
20765continue; // 3 cases reached
20766
20767} else
20768{
20769{
20770IkReal j0array[1], cj0array[1], sj0array[1];
20771bool j0valid[1]={false};
20772_nj0 = 1;
20773CheckValue<IkReal> x1567=IKPowWithIntegerCheck(gconst39,-1);
20774if(!x1567.valid){
20775continue;
20776}
20777CheckValue<IkReal> x1568=IKPowWithIntegerCheck(new_r01,-1);
20778if(!x1568.valid){
20779continue;
20780}
20781if( IKabs(((-1.0)*new_r00*(x1567.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst39*(x1568.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00*(x1567.value)))+IKsqr((gconst39*(x1568.value)))-1) <= IKFAST_SINCOS_THRESH )
20782 continue;
20783j0array[0]=IKatan2(((-1.0)*new_r00*(x1567.value)), (gconst39*(x1568.value)));
20784sj0array[0]=IKsin(j0array[0]);
20785cj0array[0]=IKcos(j0array[0]);
20786if( j0array[0] > IKPI )
20787{
20788 j0array[0]-=IK2PI;
20789}
20790else if( j0array[0] < -IKPI )
20791{ j0array[0]+=IK2PI;
20792}
20793j0valid[0] = true;
20794for(int ij0 = 0; ij0 < 1; ++ij0)
20795{
20796if( !j0valid[ij0] )
20797{
20798 continue;
20799}
20800_ij0[0] = ij0; _ij0[1] = -1;
20801for(int iij0 = ij0+1; iij0 < 1; ++iij0)
20802{
20803if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20804{
20805 j0valid[iij0]=false; _ij0[1] = iij0; break;
20806}
20807}
20808j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20809{
20810IkReal evalcond[8];
20811IkReal x1569=IKsin(j0);
20812IkReal x1570=IKcos(j0);
20813IkReal x1571=((1.0)*x1570);
20814IkReal x1572=(gconst39*x1571);
20815IkReal x1573=((-1.0)*x1569);
20816evalcond[0]=(new_r01*x1573);
20817evalcond[1]=(gconst39*x1573);
20818evalcond[2]=(((gconst39*x1569))+new_r00);
20819evalcond[3]=(new_r01+(((-1.0)*x1572)));
20820evalcond[4]=(new_r10+(((-1.0)*x1572)));
20821evalcond[5]=(((new_r01*x1570))+(((-1.0)*gconst39)));
20822evalcond[6]=(((new_r00*x1570))+((new_r10*x1569)));
20823evalcond[7]=(((new_r00*x1569))+(((-1.0)*new_r10*x1571))+gconst39);
20824if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
20825{
20826continue;
20827}
20828}
20829
20830{
20831std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20832vinfos[0].jointtype = 1;
20833vinfos[0].foffset = j0;
20834vinfos[0].indices[0] = _ij0[0];
20835vinfos[0].indices[1] = _ij0[1];
20836vinfos[0].maxsolutions = _nj0;
20837vinfos[1].jointtype = 1;
20838vinfos[1].foffset = j1;
20839vinfos[1].indices[0] = _ij1[0];
20840vinfos[1].indices[1] = _ij1[1];
20841vinfos[1].maxsolutions = _nj1;
20842vinfos[2].jointtype = 1;
20843vinfos[2].foffset = j2;
20844vinfos[2].indices[0] = _ij2[0];
20845vinfos[2].indices[1] = _ij2[1];
20846vinfos[2].maxsolutions = _nj2;
20847vinfos[3].jointtype = 1;
20848vinfos[3].foffset = j3;
20849vinfos[3].indices[0] = _ij3[0];
20850vinfos[3].indices[1] = _ij3[1];
20851vinfos[3].maxsolutions = _nj3;
20852vinfos[4].jointtype = 1;
20853vinfos[4].foffset = j4;
20854vinfos[4].indices[0] = _ij4[0];
20855vinfos[4].indices[1] = _ij4[1];
20856vinfos[4].maxsolutions = _nj4;
20857vinfos[5].jointtype = 1;
20858vinfos[5].foffset = j5;
20859vinfos[5].indices[0] = _ij5[0];
20860vinfos[5].indices[1] = _ij5[1];
20861vinfos[5].maxsolutions = _nj5;
20862std::vector<int> vfree(0);
20863solutions.AddSolution(vinfos,vfree);
20864}
20865}
20866}
20867
20868}
20869
20870}
20871
20872} else
20873{
20874{
20875IkReal j0array[1], cj0array[1], sj0array[1];
20876bool j0valid[1]={false};
20877_nj0 = 1;
20878CheckValue<IkReal> x1574 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
20879if(!x1574.valid){
20880continue;
20881}
20882CheckValue<IkReal> x1575=IKPowWithIntegerCheck(IKsign(gconst39),-1);
20883if(!x1575.valid){
20884continue;
20885}
20886j0array[0]=((-1.5707963267949)+(x1574.value)+(((1.5707963267949)*(x1575.value))));
20887sj0array[0]=IKsin(j0array[0]);
20888cj0array[0]=IKcos(j0array[0]);
20889if( j0array[0] > IKPI )
20890{
20891 j0array[0]-=IK2PI;
20892}
20893else if( j0array[0] < -IKPI )
20894{ j0array[0]+=IK2PI;
20895}
20896j0valid[0] = true;
20897for(int ij0 = 0; ij0 < 1; ++ij0)
20898{
20899if( !j0valid[ij0] )
20900{
20901 continue;
20902}
20903_ij0[0] = ij0; _ij0[1] = -1;
20904for(int iij0 = ij0+1; iij0 < 1; ++iij0)
20905{
20906if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
20907{
20908 j0valid[iij0]=false; _ij0[1] = iij0; break;
20909}
20910}
20911j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
20912{
20913IkReal evalcond[8];
20914IkReal x1576=IKsin(j0);
20915IkReal x1577=IKcos(j0);
20916IkReal x1578=((1.0)*x1577);
20917IkReal x1579=(gconst39*x1578);
20918IkReal x1580=((-1.0)*x1576);
20919evalcond[0]=(new_r01*x1580);
20920evalcond[1]=(gconst39*x1580);
20921evalcond[2]=(((gconst39*x1576))+new_r00);
20922evalcond[3]=(new_r01+(((-1.0)*x1579)));
20923evalcond[4]=(new_r10+(((-1.0)*x1579)));
20924evalcond[5]=(((new_r01*x1577))+(((-1.0)*gconst39)));
20925evalcond[6]=(((new_r00*x1577))+((new_r10*x1576)));
20926evalcond[7]=(((new_r00*x1576))+(((-1.0)*new_r10*x1578))+gconst39);
20927if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
20928{
20929continue;
20930}
20931}
20932
20933{
20934std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
20935vinfos[0].jointtype = 1;
20936vinfos[0].foffset = j0;
20937vinfos[0].indices[0] = _ij0[0];
20938vinfos[0].indices[1] = _ij0[1];
20939vinfos[0].maxsolutions = _nj0;
20940vinfos[1].jointtype = 1;
20941vinfos[1].foffset = j1;
20942vinfos[1].indices[0] = _ij1[0];
20943vinfos[1].indices[1] = _ij1[1];
20944vinfos[1].maxsolutions = _nj1;
20945vinfos[2].jointtype = 1;
20946vinfos[2].foffset = j2;
20947vinfos[2].indices[0] = _ij2[0];
20948vinfos[2].indices[1] = _ij2[1];
20949vinfos[2].maxsolutions = _nj2;
20950vinfos[3].jointtype = 1;
20951vinfos[3].foffset = j3;
20952vinfos[3].indices[0] = _ij3[0];
20953vinfos[3].indices[1] = _ij3[1];
20954vinfos[3].maxsolutions = _nj3;
20955vinfos[4].jointtype = 1;
20956vinfos[4].foffset = j4;
20957vinfos[4].indices[0] = _ij4[0];
20958vinfos[4].indices[1] = _ij4[1];
20959vinfos[4].maxsolutions = _nj4;
20960vinfos[5].jointtype = 1;
20961vinfos[5].foffset = j5;
20962vinfos[5].indices[0] = _ij5[0];
20963vinfos[5].indices[1] = _ij5[1];
20964vinfos[5].maxsolutions = _nj5;
20965std::vector<int> vfree(0);
20966solutions.AddSolution(vinfos,vfree);
20967}
20968}
20969}
20970
20971}
20972
20973}
20974
20975} else
20976{
20977{
20978IkReal j0array[1], cj0array[1], sj0array[1];
20979bool j0valid[1]={false};
20980_nj0 = 1;
20981CheckValue<IkReal> x1581 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH);
20982if(!x1581.valid){
20983continue;
20984}
20985CheckValue<IkReal> x1582=IKPowWithIntegerCheck(IKsign(gconst39),-1);
20986if(!x1582.valid){
20987continue;
20988}
20989j0array[0]=((-1.5707963267949)+(x1581.value)+(((1.5707963267949)*(x1582.value))));
20990sj0array[0]=IKsin(j0array[0]);
20991cj0array[0]=IKcos(j0array[0]);
20992if( j0array[0] > IKPI )
20993{
20994 j0array[0]-=IK2PI;
20995}
20996else if( j0array[0] < -IKPI )
20997{ j0array[0]+=IK2PI;
20998}
20999j0valid[0] = true;
21000for(int ij0 = 0; ij0 < 1; ++ij0)
21001{
21002if( !j0valid[ij0] )
21003{
21004 continue;
21005}
21006_ij0[0] = ij0; _ij0[1] = -1;
21007for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21008{
21009if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21010{
21011 j0valid[iij0]=false; _ij0[1] = iij0; break;
21012}
21013}
21014j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21015{
21016IkReal evalcond[8];
21017IkReal x1583=IKsin(j0);
21018IkReal x1584=IKcos(j0);
21019IkReal x1585=((1.0)*x1584);
21020IkReal x1586=(gconst39*x1585);
21021IkReal x1587=((-1.0)*x1583);
21022evalcond[0]=(new_r01*x1587);
21023evalcond[1]=(gconst39*x1587);
21024evalcond[2]=(((gconst39*x1583))+new_r00);
21025evalcond[3]=((((-1.0)*x1586))+new_r01);
21026evalcond[4]=((((-1.0)*x1586))+new_r10);
21027evalcond[5]=(((new_r01*x1584))+(((-1.0)*gconst39)));
21028evalcond[6]=(((new_r10*x1583))+((new_r00*x1584)));
21029evalcond[7]=(((new_r00*x1583))+(((-1.0)*new_r10*x1585))+gconst39);
21030if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21031{
21032continue;
21033}
21034}
21035
21036{
21037std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21038vinfos[0].jointtype = 1;
21039vinfos[0].foffset = j0;
21040vinfos[0].indices[0] = _ij0[0];
21041vinfos[0].indices[1] = _ij0[1];
21042vinfos[0].maxsolutions = _nj0;
21043vinfos[1].jointtype = 1;
21044vinfos[1].foffset = j1;
21045vinfos[1].indices[0] = _ij1[0];
21046vinfos[1].indices[1] = _ij1[1];
21047vinfos[1].maxsolutions = _nj1;
21048vinfos[2].jointtype = 1;
21049vinfos[2].foffset = j2;
21050vinfos[2].indices[0] = _ij2[0];
21051vinfos[2].indices[1] = _ij2[1];
21052vinfos[2].maxsolutions = _nj2;
21053vinfos[3].jointtype = 1;
21054vinfos[3].foffset = j3;
21055vinfos[3].indices[0] = _ij3[0];
21056vinfos[3].indices[1] = _ij3[1];
21057vinfos[3].maxsolutions = _nj3;
21058vinfos[4].jointtype = 1;
21059vinfos[4].foffset = j4;
21060vinfos[4].indices[0] = _ij4[0];
21061vinfos[4].indices[1] = _ij4[1];
21062vinfos[4].maxsolutions = _nj4;
21063vinfos[5].jointtype = 1;
21064vinfos[5].foffset = j5;
21065vinfos[5].indices[0] = _ij5[0];
21066vinfos[5].indices[1] = _ij5[1];
21067vinfos[5].maxsolutions = _nj5;
21068std::vector<int> vfree(0);
21069solutions.AddSolution(vinfos,vfree);
21070}
21071}
21072}
21073
21074}
21075
21076}
21077
21078}
21079} while(0);
21080if( bgotonextstatement )
21081{
21082bool bgotonextstatement = true;
21083do
21084{
21085evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
21086if( IKabs(evalcond[0]) < 0.0000050000000000 )
21087{
21088bgotonextstatement=false;
21089{
21090IkReal j0eval[1];
21091CheckValue<IkReal> x1589 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
21092if(!x1589.valid){
21093continue;
21094}
21095IkReal x1588=((1.0)*(x1589.value));
21096sj1=-1.0;
21097cj1=0;
21098j1=-1.5707963267949;
21099sj2=gconst38;
21100cj2=gconst39;
21101j2=((3.14159265)+(((-1.0)*x1588)));
21102new_r00=0;
21103new_r01=0;
21104new_r12=0;
21105new_r22=0;
21106IkReal gconst37=((3.14159265358979)+(((-1.0)*x1588)));
21107IkReal x1590 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
21108if(IKabs(x1590)==0){
21109continue;
21110}
21111IkReal gconst38=((1.0)*new_r11*(pow(x1590,-0.5)));
21112IkReal gconst39=0;
21113j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10)));
21114if( IKabs(j0eval[0]) < 0.0000010000000000 )
21115{
21116{
21117IkReal j0eval[1];
21118CheckValue<IkReal> x1592 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
21119if(!x1592.valid){
21120continue;
21121}
21122IkReal x1591=((1.0)*(x1592.value));
21123sj1=-1.0;
21124cj1=0;
21125j1=-1.5707963267949;
21126sj2=gconst38;
21127cj2=gconst39;
21128j2=((3.14159265)+(((-1.0)*x1591)));
21129new_r00=0;
21130new_r01=0;
21131new_r12=0;
21132new_r22=0;
21133IkReal gconst37=((3.14159265358979)+(((-1.0)*x1591)));
21134IkReal x1593 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
21135if(IKabs(x1593)==0){
21136continue;
21137}
21138IkReal gconst38=((1.0)*new_r11*(pow(x1593,-0.5)));
21139IkReal gconst39=0;
21140j0eval[0]=new_r11;
21141if( IKabs(j0eval[0]) < 0.0000010000000000 )
21142{
21143{
21144IkReal j0eval[2];
21145CheckValue<IkReal> x1595 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH);
21146if(!x1595.valid){
21147continue;
21148}
21149IkReal x1594=((1.0)*(x1595.value));
21150sj1=-1.0;
21151cj1=0;
21152j1=-1.5707963267949;
21153sj2=gconst38;
21154cj2=gconst39;
21155j2=((3.14159265)+(((-1.0)*x1594)));
21156new_r00=0;
21157new_r01=0;
21158new_r12=0;
21159new_r22=0;
21160IkReal gconst37=((3.14159265358979)+(((-1.0)*x1594)));
21161IkReal x1596 = ((1.0)+(((-1.0)*(new_r10*new_r10))));
21162if(IKabs(x1596)==0){
21163continue;
21164}
21165IkReal gconst38=((1.0)*new_r11*(pow(x1596,-0.5)));
21166IkReal gconst39=0;
21167j0eval[0]=new_r10;
21168j0eval[1]=new_r11;
21169if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
21170{
21171continue; // 3 cases reached
21172
21173} else
21174{
21175{
21176IkReal j0array[1], cj0array[1], sj0array[1];
21177bool j0valid[1]={false};
21178_nj0 = 1;
21179CheckValue<IkReal> x1597=IKPowWithIntegerCheck(new_r10,-1);
21180if(!x1597.valid){
21181continue;
21182}
21183CheckValue<IkReal> x1598=IKPowWithIntegerCheck(new_r11,-1);
21184if(!x1598.valid){
21185continue;
21186}
21187if( IKabs((gconst38*(x1597.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst38*(x1598.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst38*(x1597.value)))+IKsqr(((-1.0)*gconst38*(x1598.value)))-1) <= IKFAST_SINCOS_THRESH )
21188 continue;
21189j0array[0]=IKatan2((gconst38*(x1597.value)), ((-1.0)*gconst38*(x1598.value)));
21190sj0array[0]=IKsin(j0array[0]);
21191cj0array[0]=IKcos(j0array[0]);
21192if( j0array[0] > IKPI )
21193{
21194 j0array[0]-=IK2PI;
21195}
21196else if( j0array[0] < -IKPI )
21197{ j0array[0]+=IK2PI;
21198}
21199j0valid[0] = true;
21200for(int ij0 = 0; ij0 < 1; ++ij0)
21201{
21202if( !j0valid[ij0] )
21203{
21204 continue;
21205}
21206_ij0[0] = ij0; _ij0[1] = -1;
21207for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21208{
21209if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21210{
21211 j0valid[iij0]=false; _ij0[1] = iij0; break;
21212}
21213}
21214j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21215{
21216IkReal evalcond[8];
21217IkReal x1599=IKcos(j0);
21218IkReal x1600=IKsin(j0);
21219IkReal x1601=(gconst38*x1600);
21220IkReal x1602=(gconst38*x1599);
21221evalcond[0]=(new_r11*x1600);
21222evalcond[1]=((-1.0)*new_r10*x1599);
21223evalcond[2]=((-1.0)*x1602);
21224evalcond[3]=((-1.0)*x1601);
21225evalcond[4]=(((new_r11*x1599))+gconst38);
21226evalcond[5]=(x1602+new_r11);
21227evalcond[6]=((((-1.0)*x1601))+new_r10);
21228evalcond[7]=(((new_r10*x1600))+(((-1.0)*gconst38)));
21229if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21230{
21231continue;
21232}
21233}
21234
21235{
21236std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21237vinfos[0].jointtype = 1;
21238vinfos[0].foffset = j0;
21239vinfos[0].indices[0] = _ij0[0];
21240vinfos[0].indices[1] = _ij0[1];
21241vinfos[0].maxsolutions = _nj0;
21242vinfos[1].jointtype = 1;
21243vinfos[1].foffset = j1;
21244vinfos[1].indices[0] = _ij1[0];
21245vinfos[1].indices[1] = _ij1[1];
21246vinfos[1].maxsolutions = _nj1;
21247vinfos[2].jointtype = 1;
21248vinfos[2].foffset = j2;
21249vinfos[2].indices[0] = _ij2[0];
21250vinfos[2].indices[1] = _ij2[1];
21251vinfos[2].maxsolutions = _nj2;
21252vinfos[3].jointtype = 1;
21253vinfos[3].foffset = j3;
21254vinfos[3].indices[0] = _ij3[0];
21255vinfos[3].indices[1] = _ij3[1];
21256vinfos[3].maxsolutions = _nj3;
21257vinfos[4].jointtype = 1;
21258vinfos[4].foffset = j4;
21259vinfos[4].indices[0] = _ij4[0];
21260vinfos[4].indices[1] = _ij4[1];
21261vinfos[4].maxsolutions = _nj4;
21262vinfos[5].jointtype = 1;
21263vinfos[5].foffset = j5;
21264vinfos[5].indices[0] = _ij5[0];
21265vinfos[5].indices[1] = _ij5[1];
21266vinfos[5].maxsolutions = _nj5;
21267std::vector<int> vfree(0);
21268solutions.AddSolution(vinfos,vfree);
21269}
21270}
21271}
21272
21273}
21274
21275}
21276
21277} else
21278{
21279{
21280IkReal j0array[1], cj0array[1], sj0array[1];
21281bool j0valid[1]={false};
21282_nj0 = 1;
21283CheckValue<IkReal> x1603=IKPowWithIntegerCheck(gconst38,-1);
21284if(!x1603.valid){
21285continue;
21286}
21287CheckValue<IkReal> x1604=IKPowWithIntegerCheck(new_r11,-1);
21288if(!x1604.valid){
21289continue;
21290}
21291if( IKabs((new_r10*(x1603.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst38*(x1604.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1603.value)))+IKsqr(((-1.0)*gconst38*(x1604.value)))-1) <= IKFAST_SINCOS_THRESH )
21292 continue;
21293j0array[0]=IKatan2((new_r10*(x1603.value)), ((-1.0)*gconst38*(x1604.value)));
21294sj0array[0]=IKsin(j0array[0]);
21295cj0array[0]=IKcos(j0array[0]);
21296if( j0array[0] > IKPI )
21297{
21298 j0array[0]-=IK2PI;
21299}
21300else if( j0array[0] < -IKPI )
21301{ j0array[0]+=IK2PI;
21302}
21303j0valid[0] = true;
21304for(int ij0 = 0; ij0 < 1; ++ij0)
21305{
21306if( !j0valid[ij0] )
21307{
21308 continue;
21309}
21310_ij0[0] = ij0; _ij0[1] = -1;
21311for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21312{
21313if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21314{
21315 j0valid[iij0]=false; _ij0[1] = iij0; break;
21316}
21317}
21318j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21319{
21320IkReal evalcond[8];
21321IkReal x1605=IKcos(j0);
21322IkReal x1606=IKsin(j0);
21323IkReal x1607=(gconst38*x1606);
21324IkReal x1608=(gconst38*x1605);
21325evalcond[0]=(new_r11*x1606);
21326evalcond[1]=((-1.0)*new_r10*x1605);
21327evalcond[2]=((-1.0)*x1608);
21328evalcond[3]=((-1.0)*x1607);
21329evalcond[4]=(gconst38+((new_r11*x1605)));
21330evalcond[5]=(x1608+new_r11);
21331evalcond[6]=((((-1.0)*x1607))+new_r10);
21332evalcond[7]=(((new_r10*x1606))+(((-1.0)*gconst38)));
21333if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21334{
21335continue;
21336}
21337}
21338
21339{
21340std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21341vinfos[0].jointtype = 1;
21342vinfos[0].foffset = j0;
21343vinfos[0].indices[0] = _ij0[0];
21344vinfos[0].indices[1] = _ij0[1];
21345vinfos[0].maxsolutions = _nj0;
21346vinfos[1].jointtype = 1;
21347vinfos[1].foffset = j1;
21348vinfos[1].indices[0] = _ij1[0];
21349vinfos[1].indices[1] = _ij1[1];
21350vinfos[1].maxsolutions = _nj1;
21351vinfos[2].jointtype = 1;
21352vinfos[2].foffset = j2;
21353vinfos[2].indices[0] = _ij2[0];
21354vinfos[2].indices[1] = _ij2[1];
21355vinfos[2].maxsolutions = _nj2;
21356vinfos[3].jointtype = 1;
21357vinfos[3].foffset = j3;
21358vinfos[3].indices[0] = _ij3[0];
21359vinfos[3].indices[1] = _ij3[1];
21360vinfos[3].maxsolutions = _nj3;
21361vinfos[4].jointtype = 1;
21362vinfos[4].foffset = j4;
21363vinfos[4].indices[0] = _ij4[0];
21364vinfos[4].indices[1] = _ij4[1];
21365vinfos[4].maxsolutions = _nj4;
21366vinfos[5].jointtype = 1;
21367vinfos[5].foffset = j5;
21368vinfos[5].indices[0] = _ij5[0];
21369vinfos[5].indices[1] = _ij5[1];
21370vinfos[5].maxsolutions = _nj5;
21371std::vector<int> vfree(0);
21372solutions.AddSolution(vinfos,vfree);
21373}
21374}
21375}
21376
21377}
21378
21379}
21380
21381} else
21382{
21383{
21384IkReal j0array[1], cj0array[1], sj0array[1];
21385bool j0valid[1]={false};
21386_nj0 = 1;
21387CheckValue<IkReal> x1609 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH);
21388if(!x1609.valid){
21389continue;
21390}
21391CheckValue<IkReal> x1610=IKPowWithIntegerCheck(IKsign(gconst38),-1);
21392if(!x1610.valid){
21393continue;
21394}
21395j0array[0]=((-1.5707963267949)+(x1609.value)+(((1.5707963267949)*(x1610.value))));
21396sj0array[0]=IKsin(j0array[0]);
21397cj0array[0]=IKcos(j0array[0]);
21398if( j0array[0] > IKPI )
21399{
21400 j0array[0]-=IK2PI;
21401}
21402else if( j0array[0] < -IKPI )
21403{ j0array[0]+=IK2PI;
21404}
21405j0valid[0] = true;
21406for(int ij0 = 0; ij0 < 1; ++ij0)
21407{
21408if( !j0valid[ij0] )
21409{
21410 continue;
21411}
21412_ij0[0] = ij0; _ij0[1] = -1;
21413for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21414{
21415if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21416{
21417 j0valid[iij0]=false; _ij0[1] = iij0; break;
21418}
21419}
21420j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21421{
21422IkReal evalcond[8];
21423IkReal x1611=IKcos(j0);
21424IkReal x1612=IKsin(j0);
21425IkReal x1613=(gconst38*x1612);
21426IkReal x1614=(gconst38*x1611);
21427evalcond[0]=(new_r11*x1612);
21428evalcond[1]=((-1.0)*new_r10*x1611);
21429evalcond[2]=((-1.0)*x1614);
21430evalcond[3]=((-1.0)*x1613);
21431evalcond[4]=(((new_r11*x1611))+gconst38);
21432evalcond[5]=(x1614+new_r11);
21433evalcond[6]=((((-1.0)*x1613))+new_r10);
21434evalcond[7]=(((new_r10*x1612))+(((-1.0)*gconst38)));
21435if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21436{
21437continue;
21438}
21439}
21440
21441{
21442std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21443vinfos[0].jointtype = 1;
21444vinfos[0].foffset = j0;
21445vinfos[0].indices[0] = _ij0[0];
21446vinfos[0].indices[1] = _ij0[1];
21447vinfos[0].maxsolutions = _nj0;
21448vinfos[1].jointtype = 1;
21449vinfos[1].foffset = j1;
21450vinfos[1].indices[0] = _ij1[0];
21451vinfos[1].indices[1] = _ij1[1];
21452vinfos[1].maxsolutions = _nj1;
21453vinfos[2].jointtype = 1;
21454vinfos[2].foffset = j2;
21455vinfos[2].indices[0] = _ij2[0];
21456vinfos[2].indices[1] = _ij2[1];
21457vinfos[2].maxsolutions = _nj2;
21458vinfos[3].jointtype = 1;
21459vinfos[3].foffset = j3;
21460vinfos[3].indices[0] = _ij3[0];
21461vinfos[3].indices[1] = _ij3[1];
21462vinfos[3].maxsolutions = _nj3;
21463vinfos[4].jointtype = 1;
21464vinfos[4].foffset = j4;
21465vinfos[4].indices[0] = _ij4[0];
21466vinfos[4].indices[1] = _ij4[1];
21467vinfos[4].maxsolutions = _nj4;
21468vinfos[5].jointtype = 1;
21469vinfos[5].foffset = j5;
21470vinfos[5].indices[0] = _ij5[0];
21471vinfos[5].indices[1] = _ij5[1];
21472vinfos[5].maxsolutions = _nj5;
21473std::vector<int> vfree(0);
21474solutions.AddSolution(vinfos,vfree);
21475}
21476}
21477}
21478
21479}
21480
21481}
21482
21483}
21484} while(0);
21485if( bgotonextstatement )
21486{
21487bool bgotonextstatement = true;
21488do
21489{
21490if( 1 )
21491{
21492bgotonextstatement=false;
21493continue; // branch miss [j0]
21494
21495}
21496} while(0);
21497if( bgotonextstatement )
21498{
21499}
21500}
21501}
21502}
21503}
21504}
21505}
21506
21507} else
21508{
21509{
21510IkReal j0array[1], cj0array[1], sj0array[1];
21511bool j0valid[1]={false};
21512_nj0 = 1;
21513CheckValue<IkReal> x1615 = IKatan2WithCheck(IkReal((((gconst38*new_r00))+((gconst38*new_r11)))),IkReal(((((-1.0)*gconst38*new_r10))+((gconst38*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
21514if(!x1615.valid){
21515continue;
21516}
21517CheckValue<IkReal> x1616=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1);
21518if(!x1616.valid){
21519continue;
21520}
21521j0array[0]=((-1.5707963267949)+(x1615.value)+(((1.5707963267949)*(x1616.value))));
21522sj0array[0]=IKsin(j0array[0]);
21523cj0array[0]=IKcos(j0array[0]);
21524if( j0array[0] > IKPI )
21525{
21526 j0array[0]-=IK2PI;
21527}
21528else if( j0array[0] < -IKPI )
21529{ j0array[0]+=IK2PI;
21530}
21531j0valid[0] = true;
21532for(int ij0 = 0; ij0 < 1; ++ij0)
21533{
21534if( !j0valid[ij0] )
21535{
21536 continue;
21537}
21538_ij0[0] = ij0; _ij0[1] = -1;
21539for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21540{
21541if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21542{
21543 j0valid[iij0]=false; _ij0[1] = iij0; break;
21544}
21545}
21546j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21547{
21548IkReal evalcond[8];
21549IkReal x1617=IKsin(j0);
21550IkReal x1618=IKcos(j0);
21551IkReal x1619=((1.0)*gconst39);
21552IkReal x1620=((1.0)*gconst38);
21553IkReal x1621=((1.0)*x1618);
21554IkReal x1622=(((x1617*x1620))+((x1618*x1619)));
21555evalcond[0]=(((new_r11*x1618))+(((-1.0)*new_r01*x1617))+gconst38);
21556evalcond[1]=((((-1.0)*new_r10*x1621))+gconst39+((new_r00*x1617)));
21557evalcond[2]=(((gconst39*x1617))+new_r00+(((-1.0)*x1618*x1620)));
21558evalcond[3]=(((gconst38*x1618))+(((-1.0)*x1617*x1619))+new_r11);
21559evalcond[4]=(((new_r10*x1617))+(((-1.0)*x1620))+((new_r00*x1618)));
21560evalcond[5]=(((new_r11*x1617))+(((-1.0)*x1619))+((new_r01*x1618)));
21561evalcond[6]=((((-1.0)*x1622))+new_r01);
21562evalcond[7]=((((-1.0)*x1622))+new_r10);
21563if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21564{
21565continue;
21566}
21567}
21568
21569{
21570std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21571vinfos[0].jointtype = 1;
21572vinfos[0].foffset = j0;
21573vinfos[0].indices[0] = _ij0[0];
21574vinfos[0].indices[1] = _ij0[1];
21575vinfos[0].maxsolutions = _nj0;
21576vinfos[1].jointtype = 1;
21577vinfos[1].foffset = j1;
21578vinfos[1].indices[0] = _ij1[0];
21579vinfos[1].indices[1] = _ij1[1];
21580vinfos[1].maxsolutions = _nj1;
21581vinfos[2].jointtype = 1;
21582vinfos[2].foffset = j2;
21583vinfos[2].indices[0] = _ij2[0];
21584vinfos[2].indices[1] = _ij2[1];
21585vinfos[2].maxsolutions = _nj2;
21586vinfos[3].jointtype = 1;
21587vinfos[3].foffset = j3;
21588vinfos[3].indices[0] = _ij3[0];
21589vinfos[3].indices[1] = _ij3[1];
21590vinfos[3].maxsolutions = _nj3;
21591vinfos[4].jointtype = 1;
21592vinfos[4].foffset = j4;
21593vinfos[4].indices[0] = _ij4[0];
21594vinfos[4].indices[1] = _ij4[1];
21595vinfos[4].maxsolutions = _nj4;
21596vinfos[5].jointtype = 1;
21597vinfos[5].foffset = j5;
21598vinfos[5].indices[0] = _ij5[0];
21599vinfos[5].indices[1] = _ij5[1];
21600vinfos[5].maxsolutions = _nj5;
21601std::vector<int> vfree(0);
21602solutions.AddSolution(vinfos,vfree);
21603}
21604}
21605}
21606
21607}
21608
21609}
21610
21611} else
21612{
21613{
21614IkReal j0array[1], cj0array[1], sj0array[1];
21615bool j0valid[1]={false};
21616_nj0 = 1;
21617CheckValue<IkReal> x1623=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst38*new_r00))+((gconst39*new_r10)))),-1);
21618if(!x1623.valid){
21619continue;
21620}
21621CheckValue<IkReal> x1624 = IKatan2WithCheck(IkReal((((new_r10*new_r11))+((gconst38*gconst39)))),IkReal((((new_r00*new_r11))+(gconst39*gconst39))),IKFAST_ATAN2_MAGTHRESH);
21622if(!x1624.valid){
21623continue;
21624}
21625j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1623.value)))+(x1624.value));
21626sj0array[0]=IKsin(j0array[0]);
21627cj0array[0]=IKcos(j0array[0]);
21628if( j0array[0] > IKPI )
21629{
21630 j0array[0]-=IK2PI;
21631}
21632else if( j0array[0] < -IKPI )
21633{ j0array[0]+=IK2PI;
21634}
21635j0valid[0] = true;
21636for(int ij0 = 0; ij0 < 1; ++ij0)
21637{
21638if( !j0valid[ij0] )
21639{
21640 continue;
21641}
21642_ij0[0] = ij0; _ij0[1] = -1;
21643for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21644{
21645if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21646{
21647 j0valid[iij0]=false; _ij0[1] = iij0; break;
21648}
21649}
21650j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21651{
21652IkReal evalcond[8];
21653IkReal x1625=IKsin(j0);
21654IkReal x1626=IKcos(j0);
21655IkReal x1627=((1.0)*gconst39);
21656IkReal x1628=((1.0)*gconst38);
21657IkReal x1629=((1.0)*x1626);
21658IkReal x1630=(((x1626*x1627))+((x1625*x1628)));
21659evalcond[0]=(((new_r11*x1626))+(((-1.0)*new_r01*x1625))+gconst38);
21660evalcond[1]=((((-1.0)*new_r10*x1629))+gconst39+((new_r00*x1625)));
21661evalcond[2]=(((gconst39*x1625))+new_r00+(((-1.0)*x1626*x1628)));
21662evalcond[3]=(((gconst38*x1626))+(((-1.0)*x1625*x1627))+new_r11);
21663evalcond[4]=(((new_r10*x1625))+(((-1.0)*x1628))+((new_r00*x1626)));
21664evalcond[5]=(((new_r11*x1625))+((new_r01*x1626))+(((-1.0)*x1627)));
21665evalcond[6]=((((-1.0)*x1630))+new_r01);
21666evalcond[7]=((((-1.0)*x1630))+new_r10);
21667if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21668{
21669continue;
21670}
21671}
21672
21673{
21674std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21675vinfos[0].jointtype = 1;
21676vinfos[0].foffset = j0;
21677vinfos[0].indices[0] = _ij0[0];
21678vinfos[0].indices[1] = _ij0[1];
21679vinfos[0].maxsolutions = _nj0;
21680vinfos[1].jointtype = 1;
21681vinfos[1].foffset = j1;
21682vinfos[1].indices[0] = _ij1[0];
21683vinfos[1].indices[1] = _ij1[1];
21684vinfos[1].maxsolutions = _nj1;
21685vinfos[2].jointtype = 1;
21686vinfos[2].foffset = j2;
21687vinfos[2].indices[0] = _ij2[0];
21688vinfos[2].indices[1] = _ij2[1];
21689vinfos[2].maxsolutions = _nj2;
21690vinfos[3].jointtype = 1;
21691vinfos[3].foffset = j3;
21692vinfos[3].indices[0] = _ij3[0];
21693vinfos[3].indices[1] = _ij3[1];
21694vinfos[3].maxsolutions = _nj3;
21695vinfos[4].jointtype = 1;
21696vinfos[4].foffset = j4;
21697vinfos[4].indices[0] = _ij4[0];
21698vinfos[4].indices[1] = _ij4[1];
21699vinfos[4].maxsolutions = _nj4;
21700vinfos[5].jointtype = 1;
21701vinfos[5].foffset = j5;
21702vinfos[5].indices[0] = _ij5[0];
21703vinfos[5].indices[1] = _ij5[1];
21704vinfos[5].maxsolutions = _nj5;
21705std::vector<int> vfree(0);
21706solutions.AddSolution(vinfos,vfree);
21707}
21708}
21709}
21710
21711}
21712
21713}
21714
21715} else
21716{
21717{
21718IkReal j0array[1], cj0array[1], sj0array[1];
21719bool j0valid[1]={false};
21720_nj0 = 1;
21721CheckValue<IkReal> x1631 = IKatan2WithCheck(IkReal((((gconst39*new_r11))+((gconst38*new_r10)))),IkReal((((gconst39*new_r01))+((gconst38*new_r00)))),IKFAST_ATAN2_MAGTHRESH);
21722if(!x1631.valid){
21723continue;
21724}
21725CheckValue<IkReal> x1632=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
21726if(!x1632.valid){
21727continue;
21728}
21729j0array[0]=((-1.5707963267949)+(x1631.value)+(((1.5707963267949)*(x1632.value))));
21730sj0array[0]=IKsin(j0array[0]);
21731cj0array[0]=IKcos(j0array[0]);
21732if( j0array[0] > IKPI )
21733{
21734 j0array[0]-=IK2PI;
21735}
21736else if( j0array[0] < -IKPI )
21737{ j0array[0]+=IK2PI;
21738}
21739j0valid[0] = true;
21740for(int ij0 = 0; ij0 < 1; ++ij0)
21741{
21742if( !j0valid[ij0] )
21743{
21744 continue;
21745}
21746_ij0[0] = ij0; _ij0[1] = -1;
21747for(int iij0 = ij0+1; iij0 < 1; ++iij0)
21748{
21749if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21750{
21751 j0valid[iij0]=false; _ij0[1] = iij0; break;
21752}
21753}
21754j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21755{
21756IkReal evalcond[8];
21757IkReal x1633=IKsin(j0);
21758IkReal x1634=IKcos(j0);
21759IkReal x1635=((1.0)*gconst39);
21760IkReal x1636=((1.0)*gconst38);
21761IkReal x1637=((1.0)*x1634);
21762IkReal x1638=(((x1634*x1635))+((x1633*x1636)));
21763evalcond[0]=(((new_r11*x1634))+gconst38+(((-1.0)*new_r01*x1633)));
21764evalcond[1]=(gconst39+((new_r00*x1633))+(((-1.0)*new_r10*x1637)));
21765evalcond[2]=((((-1.0)*x1634*x1636))+((gconst39*x1633))+new_r00);
21766evalcond[3]=((((-1.0)*x1633*x1635))+((gconst38*x1634))+new_r11);
21767evalcond[4]=(((new_r10*x1633))+(((-1.0)*x1636))+((new_r00*x1634)));
21768evalcond[5]=(((new_r11*x1633))+(((-1.0)*x1635))+((new_r01*x1634)));
21769evalcond[6]=((((-1.0)*x1638))+new_r01);
21770evalcond[7]=((((-1.0)*x1638))+new_r10);
21771if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
21772{
21773continue;
21774}
21775}
21776
21777{
21778std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21779vinfos[0].jointtype = 1;
21780vinfos[0].foffset = j0;
21781vinfos[0].indices[0] = _ij0[0];
21782vinfos[0].indices[1] = _ij0[1];
21783vinfos[0].maxsolutions = _nj0;
21784vinfos[1].jointtype = 1;
21785vinfos[1].foffset = j1;
21786vinfos[1].indices[0] = _ij1[0];
21787vinfos[1].indices[1] = _ij1[1];
21788vinfos[1].maxsolutions = _nj1;
21789vinfos[2].jointtype = 1;
21790vinfos[2].foffset = j2;
21791vinfos[2].indices[0] = _ij2[0];
21792vinfos[2].indices[1] = _ij2[1];
21793vinfos[2].maxsolutions = _nj2;
21794vinfos[3].jointtype = 1;
21795vinfos[3].foffset = j3;
21796vinfos[3].indices[0] = _ij3[0];
21797vinfos[3].indices[1] = _ij3[1];
21798vinfos[3].maxsolutions = _nj3;
21799vinfos[4].jointtype = 1;
21800vinfos[4].foffset = j4;
21801vinfos[4].indices[0] = _ij4[0];
21802vinfos[4].indices[1] = _ij4[1];
21803vinfos[4].maxsolutions = _nj4;
21804vinfos[5].jointtype = 1;
21805vinfos[5].foffset = j5;
21806vinfos[5].indices[0] = _ij5[0];
21807vinfos[5].indices[1] = _ij5[1];
21808vinfos[5].maxsolutions = _nj5;
21809std::vector<int> vfree(0);
21810solutions.AddSolution(vinfos,vfree);
21811}
21812}
21813}
21814
21815}
21816
21817}
21818
21819}
21820} while(0);
21821if( bgotonextstatement )
21822{
21823bool bgotonextstatement = true;
21824do
21825{
21826evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01)));
21827if( IKabs(evalcond[0]) < 0.0000050000000000 )
21828{
21829bgotonextstatement=false;
21830{
21831IkReal j0eval[1];
21832sj1=-1.0;
21833cj1=0;
21834j1=-1.5707963267949;
21835new_r11=0;
21836new_r01=0;
21837new_r22=0;
21838new_r20=0;
21839j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
21840if( IKabs(j0eval[0]) < 0.0000010000000000 )
21841{
21842continue; // no branches [j0]
21843
21844} else
21845{
21846{
21847IkReal j0array[2], cj0array[2], sj0array[2];
21848bool j0valid[2]={false};
21849_nj0 = 2;
21850CheckValue<IkReal> x1640 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
21851if(!x1640.valid){
21852continue;
21853}
21854IkReal x1639=x1640.value;
21855j0array[0]=((-1.0)*x1639);
21856sj0array[0]=IKsin(j0array[0]);
21857cj0array[0]=IKcos(j0array[0]);
21858j0array[1]=((3.14159265358979)+(((-1.0)*x1639)));
21859sj0array[1]=IKsin(j0array[1]);
21860cj0array[1]=IKcos(j0array[1]);
21861if( j0array[0] > IKPI )
21862{
21863 j0array[0]-=IK2PI;
21864}
21865else if( j0array[0] < -IKPI )
21866{ j0array[0]+=IK2PI;
21867}
21868j0valid[0] = true;
21869if( j0array[1] > IKPI )
21870{
21871 j0array[1]-=IK2PI;
21872}
21873else if( j0array[1] < -IKPI )
21874{ j0array[1]+=IK2PI;
21875}
21876j0valid[1] = true;
21877for(int ij0 = 0; ij0 < 2; ++ij0)
21878{
21879if( !j0valid[ij0] )
21880{
21881 continue;
21882}
21883_ij0[0] = ij0; _ij0[1] = -1;
21884for(int iij0 = ij0+1; iij0 < 2; ++iij0)
21885{
21886if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
21887{
21888 j0valid[iij0]=false; _ij0[1] = iij0; break;
21889}
21890}
21891j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
21892{
21893IkReal evalcond[1];
21894evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0)))));
21895if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
21896{
21897continue;
21898}
21899}
21900
21901{
21902std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
21903vinfos[0].jointtype = 1;
21904vinfos[0].foffset = j0;
21905vinfos[0].indices[0] = _ij0[0];
21906vinfos[0].indices[1] = _ij0[1];
21907vinfos[0].maxsolutions = _nj0;
21908vinfos[1].jointtype = 1;
21909vinfos[1].foffset = j1;
21910vinfos[1].indices[0] = _ij1[0];
21911vinfos[1].indices[1] = _ij1[1];
21912vinfos[1].maxsolutions = _nj1;
21913vinfos[2].jointtype = 1;
21914vinfos[2].foffset = j2;
21915vinfos[2].indices[0] = _ij2[0];
21916vinfos[2].indices[1] = _ij2[1];
21917vinfos[2].maxsolutions = _nj2;
21918vinfos[3].jointtype = 1;
21919vinfos[3].foffset = j3;
21920vinfos[3].indices[0] = _ij3[0];
21921vinfos[3].indices[1] = _ij3[1];
21922vinfos[3].maxsolutions = _nj3;
21923vinfos[4].jointtype = 1;
21924vinfos[4].foffset = j4;
21925vinfos[4].indices[0] = _ij4[0];
21926vinfos[4].indices[1] = _ij4[1];
21927vinfos[4].maxsolutions = _nj4;
21928vinfos[5].jointtype = 1;
21929vinfos[5].foffset = j5;
21930vinfos[5].indices[0] = _ij5[0];
21931vinfos[5].indices[1] = _ij5[1];
21932vinfos[5].maxsolutions = _nj5;
21933std::vector<int> vfree(0);
21934solutions.AddSolution(vinfos,vfree);
21935}
21936}
21937}
21938
21939}
21940
21941}
21942
21943}
21944} while(0);
21945if( bgotonextstatement )
21946{
21947bool bgotonextstatement = true;
21948do
21949{
21950evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10)));
21951if( IKabs(evalcond[0]) < 0.0000050000000000 )
21952{
21953bgotonextstatement=false;
21954{
21955IkReal j0eval[3];
21956sj1=-1.0;
21957cj1=0;
21958j1=-1.5707963267949;
21959new_r11=0;
21960new_r10=0;
21961new_r22=0;
21962new_r02=0;
21963j0eval[0]=new_r00;
21964j0eval[1]=((IKabs(cj2))+(IKabs(sj2)));
21965j0eval[2]=IKsign(new_r00);
21966if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
21967{
21968{
21969IkReal j0eval[2];
21970sj1=-1.0;
21971cj1=0;
21972j1=-1.5707963267949;
21973new_r11=0;
21974new_r10=0;
21975new_r22=0;
21976new_r02=0;
21977j0eval[0]=new_r01;
21978j0eval[1]=new_r00;
21979if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
21980{
21981{
21982IkReal j0eval[2];
21983sj1=-1.0;
21984cj1=0;
21985j1=-1.5707963267949;
21986new_r11=0;
21987new_r10=0;
21988new_r22=0;
21989new_r02=0;
21990j0eval[0]=new_r00;
21991j0eval[1]=sj2;
21992if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
21993{
21994{
21995IkReal evalcond[1];
21996bool bgotonextstatement = true;
21997do
21998{
21999evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j2))), 6.28318530717959)));
22000if( IKabs(evalcond[0]) < 0.0000050000000000 )
22001{
22002bgotonextstatement=false;
22003{
22004IkReal j0array[1], cj0array[1], sj0array[1];
22005bool j0valid[1]={false};
22006_nj0 = 1;
22007if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH )
22008 continue;
22009j0array[0]=IKatan2(((-1.0)*new_r00), new_r01);
22010sj0array[0]=IKsin(j0array[0]);
22011cj0array[0]=IKcos(j0array[0]);
22012if( j0array[0] > IKPI )
22013{
22014 j0array[0]-=IK2PI;
22015}
22016else if( j0array[0] < -IKPI )
22017{ j0array[0]+=IK2PI;
22018}
22019j0valid[0] = true;
22020for(int ij0 = 0; ij0 < 1; ++ij0)
22021{
22022if( !j0valid[ij0] )
22023{
22024 continue;
22025}
22026_ij0[0] = ij0; _ij0[1] = -1;
22027for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22028{
22029if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22030{
22031 j0valid[iij0]=false; _ij0[1] = iij0; break;
22032}
22033}
22034j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22035{
22036IkReal evalcond[8];
22037IkReal x1641=IKsin(j0);
22038IkReal x1642=IKcos(j0);
22039IkReal x1643=((-1.0)*x1641);
22040evalcond[0]=(new_r00*x1642);
22041evalcond[1]=(x1641+new_r00);
22042evalcond[2]=x1643;
22043evalcond[3]=((-1.0)*x1642);
22044evalcond[4]=(new_r01*x1643);
22045evalcond[5]=((1.0)+((new_r00*x1641)));
22046evalcond[6]=((-1.0)+((new_r01*x1642)));
22047evalcond[7]=((((-1.0)*x1642))+new_r01);
22048if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22049{
22050continue;
22051}
22052}
22053
22054{
22055std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22056vinfos[0].jointtype = 1;
22057vinfos[0].foffset = j0;
22058vinfos[0].indices[0] = _ij0[0];
22059vinfos[0].indices[1] = _ij0[1];
22060vinfos[0].maxsolutions = _nj0;
22061vinfos[1].jointtype = 1;
22062vinfos[1].foffset = j1;
22063vinfos[1].indices[0] = _ij1[0];
22064vinfos[1].indices[1] = _ij1[1];
22065vinfos[1].maxsolutions = _nj1;
22066vinfos[2].jointtype = 1;
22067vinfos[2].foffset = j2;
22068vinfos[2].indices[0] = _ij2[0];
22069vinfos[2].indices[1] = _ij2[1];
22070vinfos[2].maxsolutions = _nj2;
22071vinfos[3].jointtype = 1;
22072vinfos[3].foffset = j3;
22073vinfos[3].indices[0] = _ij3[0];
22074vinfos[3].indices[1] = _ij3[1];
22075vinfos[3].maxsolutions = _nj3;
22076vinfos[4].jointtype = 1;
22077vinfos[4].foffset = j4;
22078vinfos[4].indices[0] = _ij4[0];
22079vinfos[4].indices[1] = _ij4[1];
22080vinfos[4].maxsolutions = _nj4;
22081vinfos[5].jointtype = 1;
22082vinfos[5].foffset = j5;
22083vinfos[5].indices[0] = _ij5[0];
22084vinfos[5].indices[1] = _ij5[1];
22085vinfos[5].maxsolutions = _nj5;
22086std::vector<int> vfree(0);
22087solutions.AddSolution(vinfos,vfree);
22088}
22089}
22090}
22091
22092}
22093} while(0);
22094if( bgotonextstatement )
22095{
22096bool bgotonextstatement = true;
22097do
22098{
22099evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2)))), 6.28318530717959)));
22100if( IKabs(evalcond[0]) < 0.0000050000000000 )
22101{
22102bgotonextstatement=false;
22103{
22104IkReal j0array[1], cj0array[1], sj0array[1];
22105bool j0valid[1]={false};
22106_nj0 = 1;
22107if( IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r00)+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH )
22108 continue;
22109j0array[0]=IKatan2(new_r00, ((-1.0)*new_r01));
22110sj0array[0]=IKsin(j0array[0]);
22111cj0array[0]=IKcos(j0array[0]);
22112if( j0array[0] > IKPI )
22113{
22114 j0array[0]-=IK2PI;
22115}
22116else if( j0array[0] < -IKPI )
22117{ j0array[0]+=IK2PI;
22118}
22119j0valid[0] = true;
22120for(int ij0 = 0; ij0 < 1; ++ij0)
22121{
22122if( !j0valid[ij0] )
22123{
22124 continue;
22125}
22126_ij0[0] = ij0; _ij0[1] = -1;
22127for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22128{
22129if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22130{
22131 j0valid[iij0]=false; _ij0[1] = iij0; break;
22132}
22133}
22134j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22135{
22136IkReal evalcond[8];
22137IkReal x1644=IKcos(j0);
22138IkReal x1645=IKsin(j0);
22139evalcond[0]=x1645;
22140evalcond[1]=x1644;
22141evalcond[2]=(new_r00*x1644);
22142evalcond[3]=(x1644+new_r01);
22143evalcond[4]=((-1.0)*new_r01*x1645);
22144evalcond[5]=((-1.0)+((new_r00*x1645)));
22145evalcond[6]=((1.0)+((new_r01*x1644)));
22146evalcond[7]=((((-1.0)*x1645))+new_r00);
22147if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22148{
22149continue;
22150}
22151}
22152
22153{
22154std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22155vinfos[0].jointtype = 1;
22156vinfos[0].foffset = j0;
22157vinfos[0].indices[0] = _ij0[0];
22158vinfos[0].indices[1] = _ij0[1];
22159vinfos[0].maxsolutions = _nj0;
22160vinfos[1].jointtype = 1;
22161vinfos[1].foffset = j1;
22162vinfos[1].indices[0] = _ij1[0];
22163vinfos[1].indices[1] = _ij1[1];
22164vinfos[1].maxsolutions = _nj1;
22165vinfos[2].jointtype = 1;
22166vinfos[2].foffset = j2;
22167vinfos[2].indices[0] = _ij2[0];
22168vinfos[2].indices[1] = _ij2[1];
22169vinfos[2].maxsolutions = _nj2;
22170vinfos[3].jointtype = 1;
22171vinfos[3].foffset = j3;
22172vinfos[3].indices[0] = _ij3[0];
22173vinfos[3].indices[1] = _ij3[1];
22174vinfos[3].maxsolutions = _nj3;
22175vinfos[4].jointtype = 1;
22176vinfos[4].foffset = j4;
22177vinfos[4].indices[0] = _ij4[0];
22178vinfos[4].indices[1] = _ij4[1];
22179vinfos[4].maxsolutions = _nj4;
22180vinfos[5].jointtype = 1;
22181vinfos[5].foffset = j5;
22182vinfos[5].indices[0] = _ij5[0];
22183vinfos[5].indices[1] = _ij5[1];
22184vinfos[5].maxsolutions = _nj5;
22185std::vector<int> vfree(0);
22186solutions.AddSolution(vinfos,vfree);
22187}
22188}
22189}
22190
22191}
22192} while(0);
22193if( bgotonextstatement )
22194{
22195bool bgotonextstatement = true;
22196do
22197{
22198if( 1 )
22199{
22200bgotonextstatement=false;
22201continue; // branch miss [j0]
22202
22203}
22204} while(0);
22205if( bgotonextstatement )
22206{
22207}
22208}
22209}
22210}
22211
22212} else
22213{
22214{
22215IkReal j0array[1], cj0array[1], sj0array[1];
22216bool j0valid[1]={false};
22217_nj0 = 1;
22218CheckValue<IkReal> x1648=IKPowWithIntegerCheck(new_r00,-1);
22219if(!x1648.valid){
22220continue;
22221}
22222IkReal x1646=x1648.value;
22223IkReal x1647=((-1.0)*x1646);
22224CheckValue<IkReal> x1649=IKPowWithIntegerCheck(sj2,-1);
22225if(!x1649.valid){
22226continue;
22227}
22228if( IKabs((cj2*x1647)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1647*(cj2*cj2)*(x1649.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((cj2*x1647))+IKsqr((x1647*(cj2*cj2)*(x1649.value)))-1) <= IKFAST_SINCOS_THRESH )
22229 continue;
22230j0array[0]=IKatan2((cj2*x1647), (x1647*(cj2*cj2)*(x1649.value)));
22231sj0array[0]=IKsin(j0array[0]);
22232cj0array[0]=IKcos(j0array[0]);
22233if( j0array[0] > IKPI )
22234{
22235 j0array[0]-=IK2PI;
22236}
22237else if( j0array[0] < -IKPI )
22238{ j0array[0]+=IK2PI;
22239}
22240j0valid[0] = true;
22241for(int ij0 = 0; ij0 < 1; ++ij0)
22242{
22243if( !j0valid[ij0] )
22244{
22245 continue;
22246}
22247_ij0[0] = ij0; _ij0[1] = -1;
22248for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22249{
22250if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22251{
22252 j0valid[iij0]=false; _ij0[1] = iij0; break;
22253}
22254}
22255j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22256{
22257IkReal evalcond[8];
22258IkReal x1650=IKsin(j0);
22259IkReal x1651=IKcos(j0);
22260IkReal x1652=((1.0)*sj2);
22261IkReal x1653=((1.0)*cj2);
22262IkReal x1654=(cj2*x1650);
22263IkReal x1655=(((x1650*x1652))+((x1651*x1653)));
22264evalcond[0]=(cj2+((new_r00*x1650)));
22265evalcond[1]=(sj2+(((-1.0)*new_r01*x1650)));
22266evalcond[2]=((((-1.0)*x1652))+((new_r00*x1651)));
22267evalcond[3]=((((-1.0)*x1653))+((new_r01*x1651)));
22268evalcond[4]=((((-1.0)*x1650*x1653))+((sj2*x1651)));
22269evalcond[5]=(x1654+new_r00+(((-1.0)*x1651*x1652)));
22270evalcond[6]=((-1.0)*x1655);
22271evalcond[7]=((((-1.0)*x1655))+new_r01);
22272if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22273{
22274continue;
22275}
22276}
22277
22278{
22279std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22280vinfos[0].jointtype = 1;
22281vinfos[0].foffset = j0;
22282vinfos[0].indices[0] = _ij0[0];
22283vinfos[0].indices[1] = _ij0[1];
22284vinfos[0].maxsolutions = _nj0;
22285vinfos[1].jointtype = 1;
22286vinfos[1].foffset = j1;
22287vinfos[1].indices[0] = _ij1[0];
22288vinfos[1].indices[1] = _ij1[1];
22289vinfos[1].maxsolutions = _nj1;
22290vinfos[2].jointtype = 1;
22291vinfos[2].foffset = j2;
22292vinfos[2].indices[0] = _ij2[0];
22293vinfos[2].indices[1] = _ij2[1];
22294vinfos[2].maxsolutions = _nj2;
22295vinfos[3].jointtype = 1;
22296vinfos[3].foffset = j3;
22297vinfos[3].indices[0] = _ij3[0];
22298vinfos[3].indices[1] = _ij3[1];
22299vinfos[3].maxsolutions = _nj3;
22300vinfos[4].jointtype = 1;
22301vinfos[4].foffset = j4;
22302vinfos[4].indices[0] = _ij4[0];
22303vinfos[4].indices[1] = _ij4[1];
22304vinfos[4].maxsolutions = _nj4;
22305vinfos[5].jointtype = 1;
22306vinfos[5].foffset = j5;
22307vinfos[5].indices[0] = _ij5[0];
22308vinfos[5].indices[1] = _ij5[1];
22309vinfos[5].maxsolutions = _nj5;
22310std::vector<int> vfree(0);
22311solutions.AddSolution(vinfos,vfree);
22312}
22313}
22314}
22315
22316}
22317
22318}
22319
22320} else
22321{
22322{
22323IkReal j0array[1], cj0array[1], sj0array[1];
22324bool j0valid[1]={false};
22325_nj0 = 1;
22326CheckValue<IkReal> x1656=IKPowWithIntegerCheck(new_r01,-1);
22327if(!x1656.valid){
22328continue;
22329}
22330CheckValue<IkReal> x1657=IKPowWithIntegerCheck(new_r00,-1);
22331if(!x1657.valid){
22332continue;
22333}
22334if( IKabs((sj2*(x1656.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((sj2*(x1657.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x1656.value)))+IKsqr((sj2*(x1657.value)))-1) <= IKFAST_SINCOS_THRESH )
22335 continue;
22336j0array[0]=IKatan2((sj2*(x1656.value)), (sj2*(x1657.value)));
22337sj0array[0]=IKsin(j0array[0]);
22338cj0array[0]=IKcos(j0array[0]);
22339if( j0array[0] > IKPI )
22340{
22341 j0array[0]-=IK2PI;
22342}
22343else if( j0array[0] < -IKPI )
22344{ j0array[0]+=IK2PI;
22345}
22346j0valid[0] = true;
22347for(int ij0 = 0; ij0 < 1; ++ij0)
22348{
22349if( !j0valid[ij0] )
22350{
22351 continue;
22352}
22353_ij0[0] = ij0; _ij0[1] = -1;
22354for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22355{
22356if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22357{
22358 j0valid[iij0]=false; _ij0[1] = iij0; break;
22359}
22360}
22361j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22362{
22363IkReal evalcond[8];
22364IkReal x1658=IKsin(j0);
22365IkReal x1659=IKcos(j0);
22366IkReal x1660=((1.0)*sj2);
22367IkReal x1661=((1.0)*cj2);
22368IkReal x1662=(cj2*x1658);
22369IkReal x1663=(((x1658*x1660))+((x1659*x1661)));
22370evalcond[0]=(cj2+((new_r00*x1658)));
22371evalcond[1]=(sj2+(((-1.0)*new_r01*x1658)));
22372evalcond[2]=(((new_r00*x1659))+(((-1.0)*x1660)));
22373evalcond[3]=((((-1.0)*x1661))+((new_r01*x1659)));
22374evalcond[4]=(((sj2*x1659))+(((-1.0)*x1658*x1661)));
22375evalcond[5]=(x1662+new_r00+(((-1.0)*x1659*x1660)));
22376evalcond[6]=((-1.0)*x1663);
22377evalcond[7]=((((-1.0)*x1663))+new_r01);
22378if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22379{
22380continue;
22381}
22382}
22383
22384{
22385std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22386vinfos[0].jointtype = 1;
22387vinfos[0].foffset = j0;
22388vinfos[0].indices[0] = _ij0[0];
22389vinfos[0].indices[1] = _ij0[1];
22390vinfos[0].maxsolutions = _nj0;
22391vinfos[1].jointtype = 1;
22392vinfos[1].foffset = j1;
22393vinfos[1].indices[0] = _ij1[0];
22394vinfos[1].indices[1] = _ij1[1];
22395vinfos[1].maxsolutions = _nj1;
22396vinfos[2].jointtype = 1;
22397vinfos[2].foffset = j2;
22398vinfos[2].indices[0] = _ij2[0];
22399vinfos[2].indices[1] = _ij2[1];
22400vinfos[2].maxsolutions = _nj2;
22401vinfos[3].jointtype = 1;
22402vinfos[3].foffset = j3;
22403vinfos[3].indices[0] = _ij3[0];
22404vinfos[3].indices[1] = _ij3[1];
22405vinfos[3].maxsolutions = _nj3;
22406vinfos[4].jointtype = 1;
22407vinfos[4].foffset = j4;
22408vinfos[4].indices[0] = _ij4[0];
22409vinfos[4].indices[1] = _ij4[1];
22410vinfos[4].maxsolutions = _nj4;
22411vinfos[5].jointtype = 1;
22412vinfos[5].foffset = j5;
22413vinfos[5].indices[0] = _ij5[0];
22414vinfos[5].indices[1] = _ij5[1];
22415vinfos[5].maxsolutions = _nj5;
22416std::vector<int> vfree(0);
22417solutions.AddSolution(vinfos,vfree);
22418}
22419}
22420}
22421
22422}
22423
22424}
22425
22426} else
22427{
22428{
22429IkReal j0array[1], cj0array[1], sj0array[1];
22430bool j0valid[1]={false};
22431_nj0 = 1;
22432CheckValue<IkReal> x1664=IKPowWithIntegerCheck(IKsign(new_r00),-1);
22433if(!x1664.valid){
22434continue;
22435}
22436CheckValue<IkReal> x1665 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(sj2),IKFAST_ATAN2_MAGTHRESH);
22437if(!x1665.valid){
22438continue;
22439}
22440j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1664.value)))+(x1665.value));
22441sj0array[0]=IKsin(j0array[0]);
22442cj0array[0]=IKcos(j0array[0]);
22443if( j0array[0] > IKPI )
22444{
22445 j0array[0]-=IK2PI;
22446}
22447else if( j0array[0] < -IKPI )
22448{ j0array[0]+=IK2PI;
22449}
22450j0valid[0] = true;
22451for(int ij0 = 0; ij0 < 1; ++ij0)
22452{
22453if( !j0valid[ij0] )
22454{
22455 continue;
22456}
22457_ij0[0] = ij0; _ij0[1] = -1;
22458for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22459{
22460if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22461{
22462 j0valid[iij0]=false; _ij0[1] = iij0; break;
22463}
22464}
22465j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22466{
22467IkReal evalcond[8];
22468IkReal x1666=IKsin(j0);
22469IkReal x1667=IKcos(j0);
22470IkReal x1668=((1.0)*sj2);
22471IkReal x1669=((1.0)*cj2);
22472IkReal x1670=(cj2*x1666);
22473IkReal x1671=(((x1667*x1669))+((x1666*x1668)));
22474evalcond[0]=(cj2+((new_r00*x1666)));
22475evalcond[1]=(sj2+(((-1.0)*new_r01*x1666)));
22476evalcond[2]=((((-1.0)*x1668))+((new_r00*x1667)));
22477evalcond[3]=(((new_r01*x1667))+(((-1.0)*x1669)));
22478evalcond[4]=(((sj2*x1667))+(((-1.0)*x1666*x1669)));
22479evalcond[5]=(x1670+(((-1.0)*x1667*x1668))+new_r00);
22480evalcond[6]=((-1.0)*x1671);
22481evalcond[7]=(new_r01+(((-1.0)*x1671)));
22482if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22483{
22484continue;
22485}
22486}
22487
22488{
22489std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22490vinfos[0].jointtype = 1;
22491vinfos[0].foffset = j0;
22492vinfos[0].indices[0] = _ij0[0];
22493vinfos[0].indices[1] = _ij0[1];
22494vinfos[0].maxsolutions = _nj0;
22495vinfos[1].jointtype = 1;
22496vinfos[1].foffset = j1;
22497vinfos[1].indices[0] = _ij1[0];
22498vinfos[1].indices[1] = _ij1[1];
22499vinfos[1].maxsolutions = _nj1;
22500vinfos[2].jointtype = 1;
22501vinfos[2].foffset = j2;
22502vinfos[2].indices[0] = _ij2[0];
22503vinfos[2].indices[1] = _ij2[1];
22504vinfos[2].maxsolutions = _nj2;
22505vinfos[3].jointtype = 1;
22506vinfos[3].foffset = j3;
22507vinfos[3].indices[0] = _ij3[0];
22508vinfos[3].indices[1] = _ij3[1];
22509vinfos[3].maxsolutions = _nj3;
22510vinfos[4].jointtype = 1;
22511vinfos[4].foffset = j4;
22512vinfos[4].indices[0] = _ij4[0];
22513vinfos[4].indices[1] = _ij4[1];
22514vinfos[4].maxsolutions = _nj4;
22515vinfos[5].jointtype = 1;
22516vinfos[5].foffset = j5;
22517vinfos[5].indices[0] = _ij5[0];
22518vinfos[5].indices[1] = _ij5[1];
22519vinfos[5].maxsolutions = _nj5;
22520std::vector<int> vfree(0);
22521solutions.AddSolution(vinfos,vfree);
22522}
22523}
22524}
22525
22526}
22527
22528}
22529
22530}
22531} while(0);
22532if( bgotonextstatement )
22533{
22534bool bgotonextstatement = true;
22535do
22536{
22537evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01)));
22538if( IKabs(evalcond[0]) < 0.0000050000000000 )
22539{
22540bgotonextstatement=false;
22541{
22542IkReal j0eval[3];
22543sj1=-1.0;
22544cj1=0;
22545j1=-1.5707963267949;
22546new_r00=0;
22547new_r01=0;
22548new_r12=0;
22549new_r22=0;
22550j0eval[0]=new_r10;
22551j0eval[1]=IKsign(new_r10);
22552j0eval[2]=((IKabs(cj2))+(IKabs(sj2)));
22553if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
22554{
22555{
22556IkReal j0eval[3];
22557sj1=-1.0;
22558cj1=0;
22559j1=-1.5707963267949;
22560new_r00=0;
22561new_r01=0;
22562new_r12=0;
22563new_r22=0;
22564j0eval[0]=new_r11;
22565j0eval[1]=IKsign(new_r11);
22566j0eval[2]=((IKabs(cj2))+(IKabs(sj2)));
22567if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 )
22568{
22569{
22570IkReal j0eval[2];
22571sj1=-1.0;
22572cj1=0;
22573j1=-1.5707963267949;
22574new_r00=0;
22575new_r01=0;
22576new_r12=0;
22577new_r22=0;
22578j0eval[0]=new_r10;
22579j0eval[1]=new_r11;
22580if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 )
22581{
22582continue; // no branches [j0]
22583
22584} else
22585{
22586{
22587IkReal j0array[1], cj0array[1], sj0array[1];
22588bool j0valid[1]={false};
22589_nj0 = 1;
22590CheckValue<IkReal> x1672=IKPowWithIntegerCheck(new_r10,-1);
22591if(!x1672.valid){
22592continue;
22593}
22594CheckValue<IkReal> x1673=IKPowWithIntegerCheck(new_r11,-1);
22595if(!x1673.valid){
22596continue;
22597}
22598if( IKabs((sj2*(x1672.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj2*(x1673.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x1672.value)))+IKsqr(((-1.0)*sj2*(x1673.value)))-1) <= IKFAST_SINCOS_THRESH )
22599 continue;
22600j0array[0]=IKatan2((sj2*(x1672.value)), ((-1.0)*sj2*(x1673.value)));
22601sj0array[0]=IKsin(j0array[0]);
22602cj0array[0]=IKcos(j0array[0]);
22603if( j0array[0] > IKPI )
22604{
22605 j0array[0]-=IK2PI;
22606}
22607else if( j0array[0] < -IKPI )
22608{ j0array[0]+=IK2PI;
22609}
22610j0valid[0] = true;
22611for(int ij0 = 0; ij0 < 1; ++ij0)
22612{
22613if( !j0valid[ij0] )
22614{
22615 continue;
22616}
22617_ij0[0] = ij0; _ij0[1] = -1;
22618for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22619{
22620if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22621{
22622 j0valid[iij0]=false; _ij0[1] = iij0; break;
22623}
22624}
22625j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22626{
22627IkReal evalcond[8];
22628IkReal x1674=IKcos(j0);
22629IkReal x1675=IKsin(j0);
22630IkReal x1676=((1.0)*sj2);
22631IkReal x1677=(sj2*x1674);
22632IkReal x1678=((1.0)*x1674);
22633IkReal x1679=(cj2*x1675);
22634IkReal x1680=(((x1675*x1676))+((cj2*x1678)));
22635evalcond[0]=(sj2+((new_r11*x1674)));
22636evalcond[1]=(cj2+(((-1.0)*new_r10*x1678)));
22637evalcond[2]=(((new_r10*x1675))+(((-1.0)*x1676)));
22638evalcond[3]=(((new_r11*x1675))+(((-1.0)*cj2)));
22639evalcond[4]=(x1679+(((-1.0)*x1674*x1676)));
22640evalcond[5]=(x1677+(((-1.0)*x1679))+new_r11);
22641evalcond[6]=((-1.0)*x1680);
22642evalcond[7]=((((-1.0)*x1680))+new_r10);
22643if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22644{
22645continue;
22646}
22647}
22648
22649{
22650std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22651vinfos[0].jointtype = 1;
22652vinfos[0].foffset = j0;
22653vinfos[0].indices[0] = _ij0[0];
22654vinfos[0].indices[1] = _ij0[1];
22655vinfos[0].maxsolutions = _nj0;
22656vinfos[1].jointtype = 1;
22657vinfos[1].foffset = j1;
22658vinfos[1].indices[0] = _ij1[0];
22659vinfos[1].indices[1] = _ij1[1];
22660vinfos[1].maxsolutions = _nj1;
22661vinfos[2].jointtype = 1;
22662vinfos[2].foffset = j2;
22663vinfos[2].indices[0] = _ij2[0];
22664vinfos[2].indices[1] = _ij2[1];
22665vinfos[2].maxsolutions = _nj2;
22666vinfos[3].jointtype = 1;
22667vinfos[3].foffset = j3;
22668vinfos[3].indices[0] = _ij3[0];
22669vinfos[3].indices[1] = _ij3[1];
22670vinfos[3].maxsolutions = _nj3;
22671vinfos[4].jointtype = 1;
22672vinfos[4].foffset = j4;
22673vinfos[4].indices[0] = _ij4[0];
22674vinfos[4].indices[1] = _ij4[1];
22675vinfos[4].maxsolutions = _nj4;
22676vinfos[5].jointtype = 1;
22677vinfos[5].foffset = j5;
22678vinfos[5].indices[0] = _ij5[0];
22679vinfos[5].indices[1] = _ij5[1];
22680vinfos[5].maxsolutions = _nj5;
22681std::vector<int> vfree(0);
22682solutions.AddSolution(vinfos,vfree);
22683}
22684}
22685}
22686
22687}
22688
22689}
22690
22691} else
22692{
22693{
22694IkReal j0array[1], cj0array[1], sj0array[1];
22695bool j0valid[1]={false};
22696_nj0 = 1;
22697CheckValue<IkReal> x1681=IKPowWithIntegerCheck(IKsign(new_r11),-1);
22698if(!x1681.valid){
22699continue;
22700}
22701CheckValue<IkReal> x1682 = IKatan2WithCheck(IkReal(cj2),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH);
22702if(!x1682.valid){
22703continue;
22704}
22705j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1681.value)))+(x1682.value));
22706sj0array[0]=IKsin(j0array[0]);
22707cj0array[0]=IKcos(j0array[0]);
22708if( j0array[0] > IKPI )
22709{
22710 j0array[0]-=IK2PI;
22711}
22712else if( j0array[0] < -IKPI )
22713{ j0array[0]+=IK2PI;
22714}
22715j0valid[0] = true;
22716for(int ij0 = 0; ij0 < 1; ++ij0)
22717{
22718if( !j0valid[ij0] )
22719{
22720 continue;
22721}
22722_ij0[0] = ij0; _ij0[1] = -1;
22723for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22724{
22725if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22726{
22727 j0valid[iij0]=false; _ij0[1] = iij0; break;
22728}
22729}
22730j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22731{
22732IkReal evalcond[8];
22733IkReal x1683=IKcos(j0);
22734IkReal x1684=IKsin(j0);
22735IkReal x1685=((1.0)*sj2);
22736IkReal x1686=(sj2*x1683);
22737IkReal x1687=((1.0)*x1683);
22738IkReal x1688=(cj2*x1684);
22739IkReal x1689=(((x1684*x1685))+((cj2*x1687)));
22740evalcond[0]=(sj2+((new_r11*x1683)));
22741evalcond[1]=(cj2+(((-1.0)*new_r10*x1687)));
22742evalcond[2]=((((-1.0)*x1685))+((new_r10*x1684)));
22743evalcond[3]=(((new_r11*x1684))+(((-1.0)*cj2)));
22744evalcond[4]=(x1688+(((-1.0)*x1683*x1685)));
22745evalcond[5]=(x1686+(((-1.0)*x1688))+new_r11);
22746evalcond[6]=((-1.0)*x1689);
22747evalcond[7]=((((-1.0)*x1689))+new_r10);
22748if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22749{
22750continue;
22751}
22752}
22753
22754{
22755std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22756vinfos[0].jointtype = 1;
22757vinfos[0].foffset = j0;
22758vinfos[0].indices[0] = _ij0[0];
22759vinfos[0].indices[1] = _ij0[1];
22760vinfos[0].maxsolutions = _nj0;
22761vinfos[1].jointtype = 1;
22762vinfos[1].foffset = j1;
22763vinfos[1].indices[0] = _ij1[0];
22764vinfos[1].indices[1] = _ij1[1];
22765vinfos[1].maxsolutions = _nj1;
22766vinfos[2].jointtype = 1;
22767vinfos[2].foffset = j2;
22768vinfos[2].indices[0] = _ij2[0];
22769vinfos[2].indices[1] = _ij2[1];
22770vinfos[2].maxsolutions = _nj2;
22771vinfos[3].jointtype = 1;
22772vinfos[3].foffset = j3;
22773vinfos[3].indices[0] = _ij3[0];
22774vinfos[3].indices[1] = _ij3[1];
22775vinfos[3].maxsolutions = _nj3;
22776vinfos[4].jointtype = 1;
22777vinfos[4].foffset = j4;
22778vinfos[4].indices[0] = _ij4[0];
22779vinfos[4].indices[1] = _ij4[1];
22780vinfos[4].maxsolutions = _nj4;
22781vinfos[5].jointtype = 1;
22782vinfos[5].foffset = j5;
22783vinfos[5].indices[0] = _ij5[0];
22784vinfos[5].indices[1] = _ij5[1];
22785vinfos[5].maxsolutions = _nj5;
22786std::vector<int> vfree(0);
22787solutions.AddSolution(vinfos,vfree);
22788}
22789}
22790}
22791
22792}
22793
22794}
22795
22796} else
22797{
22798{
22799IkReal j0array[1], cj0array[1], sj0array[1];
22800bool j0valid[1]={false};
22801_nj0 = 1;
22802CheckValue<IkReal> x1690=IKPowWithIntegerCheck(IKsign(new_r10),-1);
22803if(!x1690.valid){
22804continue;
22805}
22806CheckValue<IkReal> x1691 = IKatan2WithCheck(IkReal(sj2),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH);
22807if(!x1691.valid){
22808continue;
22809}
22810j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1690.value)))+(x1691.value));
22811sj0array[0]=IKsin(j0array[0]);
22812cj0array[0]=IKcos(j0array[0]);
22813if( j0array[0] > IKPI )
22814{
22815 j0array[0]-=IK2PI;
22816}
22817else if( j0array[0] < -IKPI )
22818{ j0array[0]+=IK2PI;
22819}
22820j0valid[0] = true;
22821for(int ij0 = 0; ij0 < 1; ++ij0)
22822{
22823if( !j0valid[ij0] )
22824{
22825 continue;
22826}
22827_ij0[0] = ij0; _ij0[1] = -1;
22828for(int iij0 = ij0+1; iij0 < 1; ++iij0)
22829{
22830if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22831{
22832 j0valid[iij0]=false; _ij0[1] = iij0; break;
22833}
22834}
22835j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22836{
22837IkReal evalcond[8];
22838IkReal x1692=IKcos(j0);
22839IkReal x1693=IKsin(j0);
22840IkReal x1694=((1.0)*sj2);
22841IkReal x1695=(sj2*x1692);
22842IkReal x1696=((1.0)*x1692);
22843IkReal x1697=(cj2*x1693);
22844IkReal x1698=(((x1693*x1694))+((cj2*x1696)));
22845evalcond[0]=(sj2+((new_r11*x1692)));
22846evalcond[1]=(cj2+(((-1.0)*new_r10*x1696)));
22847evalcond[2]=((((-1.0)*x1694))+((new_r10*x1693)));
22848evalcond[3]=(((new_r11*x1693))+(((-1.0)*cj2)));
22849evalcond[4]=((((-1.0)*x1692*x1694))+x1697);
22850evalcond[5]=(x1695+(((-1.0)*x1697))+new_r11);
22851evalcond[6]=((-1.0)*x1698);
22852evalcond[7]=((((-1.0)*x1698))+new_r10);
22853if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
22854{
22855continue;
22856}
22857}
22858
22859{
22860std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22861vinfos[0].jointtype = 1;
22862vinfos[0].foffset = j0;
22863vinfos[0].indices[0] = _ij0[0];
22864vinfos[0].indices[1] = _ij0[1];
22865vinfos[0].maxsolutions = _nj0;
22866vinfos[1].jointtype = 1;
22867vinfos[1].foffset = j1;
22868vinfos[1].indices[0] = _ij1[0];
22869vinfos[1].indices[1] = _ij1[1];
22870vinfos[1].maxsolutions = _nj1;
22871vinfos[2].jointtype = 1;
22872vinfos[2].foffset = j2;
22873vinfos[2].indices[0] = _ij2[0];
22874vinfos[2].indices[1] = _ij2[1];
22875vinfos[2].maxsolutions = _nj2;
22876vinfos[3].jointtype = 1;
22877vinfos[3].foffset = j3;
22878vinfos[3].indices[0] = _ij3[0];
22879vinfos[3].indices[1] = _ij3[1];
22880vinfos[3].maxsolutions = _nj3;
22881vinfos[4].jointtype = 1;
22882vinfos[4].foffset = j4;
22883vinfos[4].indices[0] = _ij4[0];
22884vinfos[4].indices[1] = _ij4[1];
22885vinfos[4].maxsolutions = _nj4;
22886vinfos[5].jointtype = 1;
22887vinfos[5].foffset = j5;
22888vinfos[5].indices[0] = _ij5[0];
22889vinfos[5].indices[1] = _ij5[1];
22890vinfos[5].maxsolutions = _nj5;
22891std::vector<int> vfree(0);
22892solutions.AddSolution(vinfos,vfree);
22893}
22894}
22895}
22896
22897}
22898
22899}
22900
22901}
22902} while(0);
22903if( bgotonextstatement )
22904{
22905bool bgotonextstatement = true;
22906do
22907{
22908evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00)));
22909if( IKabs(evalcond[0]) < 0.0000050000000000 )
22910{
22911bgotonextstatement=false;
22912{
22913IkReal j0eval[1];
22914sj1=-1.0;
22915cj1=0;
22916j1=-1.5707963267949;
22917new_r00=0;
22918new_r10=0;
22919new_r21=0;
22920new_r22=0;
22921j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
22922if( IKabs(j0eval[0]) < 0.0000010000000000 )
22923{
22924continue; // no branches [j0]
22925
22926} else
22927{
22928{
22929IkReal j0array[2], cj0array[2], sj0array[2];
22930bool j0valid[2]={false};
22931_nj0 = 2;
22932CheckValue<IkReal> x1700 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
22933if(!x1700.valid){
22934continue;
22935}
22936IkReal x1699=x1700.value;
22937j0array[0]=((-1.0)*x1699);
22938sj0array[0]=IKsin(j0array[0]);
22939cj0array[0]=IKcos(j0array[0]);
22940j0array[1]=((3.14159265358979)+(((-1.0)*x1699)));
22941sj0array[1]=IKsin(j0array[1]);
22942cj0array[1]=IKcos(j0array[1]);
22943if( j0array[0] > IKPI )
22944{
22945 j0array[0]-=IK2PI;
22946}
22947else if( j0array[0] < -IKPI )
22948{ j0array[0]+=IK2PI;
22949}
22950j0valid[0] = true;
22951if( j0array[1] > IKPI )
22952{
22953 j0array[1]-=IK2PI;
22954}
22955else if( j0array[1] < -IKPI )
22956{ j0array[1]+=IK2PI;
22957}
22958j0valid[1] = true;
22959for(int ij0 = 0; ij0 < 2; ++ij0)
22960{
22961if( !j0valid[ij0] )
22962{
22963 continue;
22964}
22965_ij0[0] = ij0; _ij0[1] = -1;
22966for(int iij0 = ij0+1; iij0 < 2; ++iij0)
22967{
22968if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
22969{
22970 j0valid[iij0]=false; _ij0[1] = iij0; break;
22971}
22972}
22973j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
22974{
22975IkReal evalcond[1];
22976evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0)))));
22977if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH )
22978{
22979continue;
22980}
22981}
22982
22983{
22984std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
22985vinfos[0].jointtype = 1;
22986vinfos[0].foffset = j0;
22987vinfos[0].indices[0] = _ij0[0];
22988vinfos[0].indices[1] = _ij0[1];
22989vinfos[0].maxsolutions = _nj0;
22990vinfos[1].jointtype = 1;
22991vinfos[1].foffset = j1;
22992vinfos[1].indices[0] = _ij1[0];
22993vinfos[1].indices[1] = _ij1[1];
22994vinfos[1].maxsolutions = _nj1;
22995vinfos[2].jointtype = 1;
22996vinfos[2].foffset = j2;
22997vinfos[2].indices[0] = _ij2[0];
22998vinfos[2].indices[1] = _ij2[1];
22999vinfos[2].maxsolutions = _nj2;
23000vinfos[3].jointtype = 1;
23001vinfos[3].foffset = j3;
23002vinfos[3].indices[0] = _ij3[0];
23003vinfos[3].indices[1] = _ij3[1];
23004vinfos[3].maxsolutions = _nj3;
23005vinfos[4].jointtype = 1;
23006vinfos[4].foffset = j4;
23007vinfos[4].indices[0] = _ij4[0];
23008vinfos[4].indices[1] = _ij4[1];
23009vinfos[4].maxsolutions = _nj4;
23010vinfos[5].jointtype = 1;
23011vinfos[5].foffset = j5;
23012vinfos[5].indices[0] = _ij5[0];
23013vinfos[5].indices[1] = _ij5[1];
23014vinfos[5].maxsolutions = _nj5;
23015std::vector<int> vfree(0);
23016solutions.AddSolution(vinfos,vfree);
23017}
23018}
23019}
23020
23021}
23022
23023}
23024
23025}
23026} while(0);
23027if( bgotonextstatement )
23028{
23029bool bgotonextstatement = true;
23030do
23031{
23032if( 1 )
23033{
23034bgotonextstatement=false;
23035continue; // branch miss [j0]
23036
23037}
23038} while(0);
23039if( bgotonextstatement )
23040{
23041}
23042}
23043}
23044}
23045}
23046}
23047}
23048}
23049}
23050}
23051
23052} else
23053{
23054{
23055IkReal j0array[1], cj0array[1], sj0array[1];
23056bool j0valid[1]={false};
23057_nj0 = 1;
23058IkReal x1701=((1.0)*new_r00);
23059CheckValue<IkReal> x1702=IKPowWithIntegerCheck(IKsign(((((-1.0)*sj2*x1701))+((cj2*new_r10)))),-1);
23060if(!x1702.valid){
23061continue;
23062}
23063CheckValue<IkReal> x1703 = IKatan2WithCheck(IkReal((((cj2*sj2))+(((-1.0)*new_r10*x1701)))),IkReal(((cj2*cj2)+(((-1.0)*new_r00*x1701)))),IKFAST_ATAN2_MAGTHRESH);
23064if(!x1703.valid){
23065continue;
23066}
23067j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1702.value)))+(x1703.value));
23068sj0array[0]=IKsin(j0array[0]);
23069cj0array[0]=IKcos(j0array[0]);
23070if( j0array[0] > IKPI )
23071{
23072 j0array[0]-=IK2PI;
23073}
23074else if( j0array[0] < -IKPI )
23075{ j0array[0]+=IK2PI;
23076}
23077j0valid[0] = true;
23078for(int ij0 = 0; ij0 < 1; ++ij0)
23079{
23080if( !j0valid[ij0] )
23081{
23082 continue;
23083}
23084_ij0[0] = ij0; _ij0[1] = -1;
23085for(int iij0 = ij0+1; iij0 < 1; ++iij0)
23086{
23087if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23088{
23089 j0valid[iij0]=false; _ij0[1] = iij0; break;
23090}
23091}
23092j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23093{
23094IkReal evalcond[8];
23095IkReal x1704=IKsin(j0);
23096IkReal x1705=IKcos(j0);
23097IkReal x1706=((1.0)*sj2);
23098IkReal x1707=(sj2*x1705);
23099IkReal x1708=((1.0)*x1705);
23100IkReal x1709=(cj2*x1704);
23101IkReal x1710=(((x1704*x1706))+((cj2*x1708)));
23102evalcond[0]=(sj2+(((-1.0)*new_r01*x1704))+((new_r11*x1705)));
23103evalcond[1]=(cj2+((new_r00*x1704))+(((-1.0)*new_r10*x1708)));
23104evalcond[2]=(x1709+(((-1.0)*x1705*x1706))+new_r00);
23105evalcond[3]=(x1707+(((-1.0)*x1709))+new_r11);
23106evalcond[4]=(((new_r00*x1705))+(((-1.0)*x1706))+((new_r10*x1704)));
23107evalcond[5]=(((new_r01*x1705))+((new_r11*x1704))+(((-1.0)*cj2)));
23108evalcond[6]=((((-1.0)*x1710))+new_r01);
23109evalcond[7]=((((-1.0)*x1710))+new_r10);
23110if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
23111{
23112continue;
23113}
23114}
23115
23116{
23117std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23118vinfos[0].jointtype = 1;
23119vinfos[0].foffset = j0;
23120vinfos[0].indices[0] = _ij0[0];
23121vinfos[0].indices[1] = _ij0[1];
23122vinfos[0].maxsolutions = _nj0;
23123vinfos[1].jointtype = 1;
23124vinfos[1].foffset = j1;
23125vinfos[1].indices[0] = _ij1[0];
23126vinfos[1].indices[1] = _ij1[1];
23127vinfos[1].maxsolutions = _nj1;
23128vinfos[2].jointtype = 1;
23129vinfos[2].foffset = j2;
23130vinfos[2].indices[0] = _ij2[0];
23131vinfos[2].indices[1] = _ij2[1];
23132vinfos[2].maxsolutions = _nj2;
23133vinfos[3].jointtype = 1;
23134vinfos[3].foffset = j3;
23135vinfos[3].indices[0] = _ij3[0];
23136vinfos[3].indices[1] = _ij3[1];
23137vinfos[3].maxsolutions = _nj3;
23138vinfos[4].jointtype = 1;
23139vinfos[4].foffset = j4;
23140vinfos[4].indices[0] = _ij4[0];
23141vinfos[4].indices[1] = _ij4[1];
23142vinfos[4].maxsolutions = _nj4;
23143vinfos[5].jointtype = 1;
23144vinfos[5].foffset = j5;
23145vinfos[5].indices[0] = _ij5[0];
23146vinfos[5].indices[1] = _ij5[1];
23147vinfos[5].maxsolutions = _nj5;
23148std::vector<int> vfree(0);
23149solutions.AddSolution(vinfos,vfree);
23150}
23151}
23152}
23153
23154}
23155
23156}
23157
23158} else
23159{
23160{
23161IkReal j0array[1], cj0array[1], sj0array[1];
23162bool j0valid[1]={false};
23163_nj0 = 1;
23164IkReal x1711=((1.0)*sj2);
23165CheckValue<IkReal> x1712 = IKatan2WithCheck(IkReal(((-1.0)+(cj2*cj2)+(new_r11*new_r11))),IkReal((((new_r01*new_r11))+(((-1.0)*cj2*x1711)))),IKFAST_ATAN2_MAGTHRESH);
23166if(!x1712.valid){
23167continue;
23168}
23169CheckValue<IkReal> x1713=IKPowWithIntegerCheck(IKsign((((cj2*new_r11))+(((-1.0)*new_r01*x1711)))),-1);
23170if(!x1713.valid){
23171continue;
23172}
23173j0array[0]=((-1.5707963267949)+(x1712.value)+(((1.5707963267949)*(x1713.value))));
23174sj0array[0]=IKsin(j0array[0]);
23175cj0array[0]=IKcos(j0array[0]);
23176if( j0array[0] > IKPI )
23177{
23178 j0array[0]-=IK2PI;
23179}
23180else if( j0array[0] < -IKPI )
23181{ j0array[0]+=IK2PI;
23182}
23183j0valid[0] = true;
23184for(int ij0 = 0; ij0 < 1; ++ij0)
23185{
23186if( !j0valid[ij0] )
23187{
23188 continue;
23189}
23190_ij0[0] = ij0; _ij0[1] = -1;
23191for(int iij0 = ij0+1; iij0 < 1; ++iij0)
23192{
23193if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23194{
23195 j0valid[iij0]=false; _ij0[1] = iij0; break;
23196}
23197}
23198j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23199{
23200IkReal evalcond[8];
23201IkReal x1714=IKsin(j0);
23202IkReal x1715=IKcos(j0);
23203IkReal x1716=((1.0)*sj2);
23204IkReal x1717=(sj2*x1715);
23205IkReal x1718=((1.0)*x1715);
23206IkReal x1719=(cj2*x1714);
23207IkReal x1720=(((x1714*x1716))+((cj2*x1718)));
23208evalcond[0]=(((new_r11*x1715))+sj2+(((-1.0)*new_r01*x1714)));
23209evalcond[1]=(cj2+((new_r00*x1714))+(((-1.0)*new_r10*x1718)));
23210evalcond[2]=(x1719+(((-1.0)*x1715*x1716))+new_r00);
23211evalcond[3]=(x1717+(((-1.0)*x1719))+new_r11);
23212evalcond[4]=(((new_r10*x1714))+(((-1.0)*x1716))+((new_r00*x1715)));
23213evalcond[5]=(((new_r11*x1714))+((new_r01*x1715))+(((-1.0)*cj2)));
23214evalcond[6]=(new_r01+(((-1.0)*x1720)));
23215evalcond[7]=(new_r10+(((-1.0)*x1720)));
23216if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
23217{
23218continue;
23219}
23220}
23221
23222{
23223std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23224vinfos[0].jointtype = 1;
23225vinfos[0].foffset = j0;
23226vinfos[0].indices[0] = _ij0[0];
23227vinfos[0].indices[1] = _ij0[1];
23228vinfos[0].maxsolutions = _nj0;
23229vinfos[1].jointtype = 1;
23230vinfos[1].foffset = j1;
23231vinfos[1].indices[0] = _ij1[0];
23232vinfos[1].indices[1] = _ij1[1];
23233vinfos[1].maxsolutions = _nj1;
23234vinfos[2].jointtype = 1;
23235vinfos[2].foffset = j2;
23236vinfos[2].indices[0] = _ij2[0];
23237vinfos[2].indices[1] = _ij2[1];
23238vinfos[2].maxsolutions = _nj2;
23239vinfos[3].jointtype = 1;
23240vinfos[3].foffset = j3;
23241vinfos[3].indices[0] = _ij3[0];
23242vinfos[3].indices[1] = _ij3[1];
23243vinfos[3].maxsolutions = _nj3;
23244vinfos[4].jointtype = 1;
23245vinfos[4].foffset = j4;
23246vinfos[4].indices[0] = _ij4[0];
23247vinfos[4].indices[1] = _ij4[1];
23248vinfos[4].maxsolutions = _nj4;
23249vinfos[5].jointtype = 1;
23250vinfos[5].foffset = j5;
23251vinfos[5].indices[0] = _ij5[0];
23252vinfos[5].indices[1] = _ij5[1];
23253vinfos[5].maxsolutions = _nj5;
23254std::vector<int> vfree(0);
23255solutions.AddSolution(vinfos,vfree);
23256}
23257}
23258}
23259
23260}
23261
23262}
23263
23264} else
23265{
23266{
23267IkReal j0array[1], cj0array[1], sj0array[1];
23268bool j0valid[1]={false};
23269_nj0 = 1;
23270CheckValue<IkReal> x1721 = IKatan2WithCheck(IkReal((((new_r10*sj2))+((cj2*new_r11)))),IkReal((((new_r00*sj2))+((cj2*new_r01)))),IKFAST_ATAN2_MAGTHRESH);
23271if(!x1721.valid){
23272continue;
23273}
23274CheckValue<IkReal> x1722=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1);
23275if(!x1722.valid){
23276continue;
23277}
23278j0array[0]=((-1.5707963267949)+(x1721.value)+(((1.5707963267949)*(x1722.value))));
23279sj0array[0]=IKsin(j0array[0]);
23280cj0array[0]=IKcos(j0array[0]);
23281if( j0array[0] > IKPI )
23282{
23283 j0array[0]-=IK2PI;
23284}
23285else if( j0array[0] < -IKPI )
23286{ j0array[0]+=IK2PI;
23287}
23288j0valid[0] = true;
23289for(int ij0 = 0; ij0 < 1; ++ij0)
23290{
23291if( !j0valid[ij0] )
23292{
23293 continue;
23294}
23295_ij0[0] = ij0; _ij0[1] = -1;
23296for(int iij0 = ij0+1; iij0 < 1; ++iij0)
23297{
23298if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23299{
23300 j0valid[iij0]=false; _ij0[1] = iij0; break;
23301}
23302}
23303j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23304{
23305IkReal evalcond[8];
23306IkReal x1723=IKsin(j0);
23307IkReal x1724=IKcos(j0);
23308IkReal x1725=((1.0)*sj2);
23309IkReal x1726=(sj2*x1724);
23310IkReal x1727=((1.0)*x1724);
23311IkReal x1728=(cj2*x1723);
23312IkReal x1729=(((x1723*x1725))+((cj2*x1727)));
23313evalcond[0]=(sj2+((new_r11*x1724))+(((-1.0)*new_r01*x1723)));
23314evalcond[1]=(cj2+(((-1.0)*new_r10*x1727))+((new_r00*x1723)));
23315evalcond[2]=(x1728+(((-1.0)*x1724*x1725))+new_r00);
23316evalcond[3]=(x1726+new_r11+(((-1.0)*x1728)));
23317evalcond[4]=(((new_r10*x1723))+(((-1.0)*x1725))+((new_r00*x1724)));
23318evalcond[5]=(((new_r11*x1723))+(((-1.0)*cj2))+((new_r01*x1724)));
23319evalcond[6]=(new_r01+(((-1.0)*x1729)));
23320evalcond[7]=(new_r10+(((-1.0)*x1729)));
23321if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
23322{
23323continue;
23324}
23325}
23326
23327{
23328std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23329vinfos[0].jointtype = 1;
23330vinfos[0].foffset = j0;
23331vinfos[0].indices[0] = _ij0[0];
23332vinfos[0].indices[1] = _ij0[1];
23333vinfos[0].maxsolutions = _nj0;
23334vinfos[1].jointtype = 1;
23335vinfos[1].foffset = j1;
23336vinfos[1].indices[0] = _ij1[0];
23337vinfos[1].indices[1] = _ij1[1];
23338vinfos[1].maxsolutions = _nj1;
23339vinfos[2].jointtype = 1;
23340vinfos[2].foffset = j2;
23341vinfos[2].indices[0] = _ij2[0];
23342vinfos[2].indices[1] = _ij2[1];
23343vinfos[2].maxsolutions = _nj2;
23344vinfos[3].jointtype = 1;
23345vinfos[3].foffset = j3;
23346vinfos[3].indices[0] = _ij3[0];
23347vinfos[3].indices[1] = _ij3[1];
23348vinfos[3].maxsolutions = _nj3;
23349vinfos[4].jointtype = 1;
23350vinfos[4].foffset = j4;
23351vinfos[4].indices[0] = _ij4[0];
23352vinfos[4].indices[1] = _ij4[1];
23353vinfos[4].maxsolutions = _nj4;
23354vinfos[5].jointtype = 1;
23355vinfos[5].foffset = j5;
23356vinfos[5].indices[0] = _ij5[0];
23357vinfos[5].indices[1] = _ij5[1];
23358vinfos[5].maxsolutions = _nj5;
23359std::vector<int> vfree(0);
23360solutions.AddSolution(vinfos,vfree);
23361}
23362}
23363}
23364
23365}
23366
23367}
23368
23369}
23370} while(0);
23371if( bgotonextstatement )
23372{
23373bool bgotonextstatement = true;
23374do
23375{
23376evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02)));
23377if( IKabs(evalcond[0]) < 0.0000050000000000 )
23378{
23379bgotonextstatement=false;
23380{
23381IkReal j0eval[1];
23382new_r02=0;
23383new_r12=0;
23384new_r20=0;
23385new_r21=0;
23386j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00)));
23387if( IKabs(j0eval[0]) < 0.0000010000000000 )
23388{
23389{
23390IkReal j0eval[1];
23391new_r02=0;
23392new_r12=0;
23393new_r20=0;
23394new_r21=0;
23395j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01)));
23396if( IKabs(j0eval[0]) < 0.0000010000000000 )
23397{
23398{
23399IkReal j0eval[1];
23400new_r02=0;
23401new_r12=0;
23402new_r20=0;
23403new_r21=0;
23404j0eval[0]=((IKabs((new_r10*new_r22)))+(IKabs((new_r00*new_r22))));
23405if( IKabs(j0eval[0]) < 0.0000010000000000 )
23406{
23407continue; // no branches [j0]
23408
23409} else
23410{
23411{
23412IkReal j0array[2], cj0array[2], sj0array[2];
23413bool j0valid[2]={false};
23414_nj0 = 2;
23415IkReal x1730=((-1.0)*new_r22);
23416CheckValue<IkReal> x1732 = IKatan2WithCheck(IkReal((new_r00*x1730)),IkReal((new_r10*x1730)),IKFAST_ATAN2_MAGTHRESH);
23417if(!x1732.valid){
23418continue;
23419}
23420IkReal x1731=x1732.value;
23421j0array[0]=((-1.0)*x1731);
23422sj0array[0]=IKsin(j0array[0]);
23423cj0array[0]=IKcos(j0array[0]);
23424j0array[1]=((3.14159265358979)+(((-1.0)*x1731)));
23425sj0array[1]=IKsin(j0array[1]);
23426cj0array[1]=IKcos(j0array[1]);
23427if( j0array[0] > IKPI )
23428{
23429 j0array[0]-=IK2PI;
23430}
23431else if( j0array[0] < -IKPI )
23432{ j0array[0]+=IK2PI;
23433}
23434j0valid[0] = true;
23435if( j0array[1] > IKPI )
23436{
23437 j0array[1]-=IK2PI;
23438}
23439else if( j0array[1] < -IKPI )
23440{ j0array[1]+=IK2PI;
23441}
23442j0valid[1] = true;
23443for(int ij0 = 0; ij0 < 2; ++ij0)
23444{
23445if( !j0valid[ij0] )
23446{
23447 continue;
23448}
23449_ij0[0] = ij0; _ij0[1] = -1;
23450for(int iij0 = ij0+1; iij0 < 2; ++iij0)
23451{
23452if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23453{
23454 j0valid[iij0]=false; _ij0[1] = iij0; break;
23455}
23456}
23457j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23458{
23459IkReal evalcond[5];
23460IkReal x1733=IKsin(j0);
23461IkReal x1734=IKcos(j0);
23462IkReal x1735=((1.0)*x1734);
23463IkReal x1736=(new_r11*x1733);
23464evalcond[0]=(((new_r10*x1733))+((new_r00*x1734)));
23465evalcond[1]=(x1736+((new_r01*x1734)));
23466evalcond[2]=(((new_r11*x1734))+(((-1.0)*new_r01*x1733)));
23467evalcond[3]=((((-1.0)*new_r10*x1735))+((new_r00*x1733)));
23468evalcond[4]=((((-1.0)*new_r22*x1736))+(((-1.0)*new_r01*new_r22*x1735)));
23469if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
23470{
23471continue;
23472}
23473}
23474
23475{
23476std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23477vinfos[0].jointtype = 1;
23478vinfos[0].foffset = j0;
23479vinfos[0].indices[0] = _ij0[0];
23480vinfos[0].indices[1] = _ij0[1];
23481vinfos[0].maxsolutions = _nj0;
23482vinfos[1].jointtype = 1;
23483vinfos[1].foffset = j1;
23484vinfos[1].indices[0] = _ij1[0];
23485vinfos[1].indices[1] = _ij1[1];
23486vinfos[1].maxsolutions = _nj1;
23487vinfos[2].jointtype = 1;
23488vinfos[2].foffset = j2;
23489vinfos[2].indices[0] = _ij2[0];
23490vinfos[2].indices[1] = _ij2[1];
23491vinfos[2].maxsolutions = _nj2;
23492vinfos[3].jointtype = 1;
23493vinfos[3].foffset = j3;
23494vinfos[3].indices[0] = _ij3[0];
23495vinfos[3].indices[1] = _ij3[1];
23496vinfos[3].maxsolutions = _nj3;
23497vinfos[4].jointtype = 1;
23498vinfos[4].foffset = j4;
23499vinfos[4].indices[0] = _ij4[0];
23500vinfos[4].indices[1] = _ij4[1];
23501vinfos[4].maxsolutions = _nj4;
23502vinfos[5].jointtype = 1;
23503vinfos[5].foffset = j5;
23504vinfos[5].indices[0] = _ij5[0];
23505vinfos[5].indices[1] = _ij5[1];
23506vinfos[5].maxsolutions = _nj5;
23507std::vector<int> vfree(0);
23508solutions.AddSolution(vinfos,vfree);
23509}
23510}
23511}
23512
23513}
23514
23515}
23516
23517} else
23518{
23519{
23520IkReal j0array[2], cj0array[2], sj0array[2];
23521bool j0valid[2]={false};
23522_nj0 = 2;
23523CheckValue<IkReal> x1738 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH);
23524if(!x1738.valid){
23525continue;
23526}
23527IkReal x1737=x1738.value;
23528j0array[0]=((-1.0)*x1737);
23529sj0array[0]=IKsin(j0array[0]);
23530cj0array[0]=IKcos(j0array[0]);
23531j0array[1]=((3.14159265358979)+(((-1.0)*x1737)));
23532sj0array[1]=IKsin(j0array[1]);
23533cj0array[1]=IKcos(j0array[1]);
23534if( j0array[0] > IKPI )
23535{
23536 j0array[0]-=IK2PI;
23537}
23538else if( j0array[0] < -IKPI )
23539{ j0array[0]+=IK2PI;
23540}
23541j0valid[0] = true;
23542if( j0array[1] > IKPI )
23543{
23544 j0array[1]-=IK2PI;
23545}
23546else if( j0array[1] < -IKPI )
23547{ j0array[1]+=IK2PI;
23548}
23549j0valid[1] = true;
23550for(int ij0 = 0; ij0 < 2; ++ij0)
23551{
23552if( !j0valid[ij0] )
23553{
23554 continue;
23555}
23556_ij0[0] = ij0; _ij0[1] = -1;
23557for(int iij0 = ij0+1; iij0 < 2; ++iij0)
23558{
23559if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23560{
23561 j0valid[iij0]=false; _ij0[1] = iij0; break;
23562}
23563}
23564j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23565{
23566IkReal evalcond[5];
23567IkReal x1739=IKcos(j0);
23568IkReal x1740=IKsin(j0);
23569IkReal x1741=((1.0)*new_r22);
23570IkReal x1742=(new_r10*x1740);
23571IkReal x1743=(new_r00*x1739);
23572evalcond[0]=(x1742+x1743);
23573evalcond[1]=(((new_r11*x1739))+(((-1.0)*new_r01*x1740)));
23574evalcond[2]=(((new_r00*x1740))+(((-1.0)*new_r10*x1739)));
23575evalcond[3]=((((-1.0)*x1741*x1742))+(((-1.0)*x1741*x1743)));
23576evalcond[4]=((((-1.0)*new_r11*x1740*x1741))+(((-1.0)*new_r01*x1739*x1741)));
23577if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
23578{
23579continue;
23580}
23581}
23582
23583{
23584std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23585vinfos[0].jointtype = 1;
23586vinfos[0].foffset = j0;
23587vinfos[0].indices[0] = _ij0[0];
23588vinfos[0].indices[1] = _ij0[1];
23589vinfos[0].maxsolutions = _nj0;
23590vinfos[1].jointtype = 1;
23591vinfos[1].foffset = j1;
23592vinfos[1].indices[0] = _ij1[0];
23593vinfos[1].indices[1] = _ij1[1];
23594vinfos[1].maxsolutions = _nj1;
23595vinfos[2].jointtype = 1;
23596vinfos[2].foffset = j2;
23597vinfos[2].indices[0] = _ij2[0];
23598vinfos[2].indices[1] = _ij2[1];
23599vinfos[2].maxsolutions = _nj2;
23600vinfos[3].jointtype = 1;
23601vinfos[3].foffset = j3;
23602vinfos[3].indices[0] = _ij3[0];
23603vinfos[3].indices[1] = _ij3[1];
23604vinfos[3].maxsolutions = _nj3;
23605vinfos[4].jointtype = 1;
23606vinfos[4].foffset = j4;
23607vinfos[4].indices[0] = _ij4[0];
23608vinfos[4].indices[1] = _ij4[1];
23609vinfos[4].maxsolutions = _nj4;
23610vinfos[5].jointtype = 1;
23611vinfos[5].foffset = j5;
23612vinfos[5].indices[0] = _ij5[0];
23613vinfos[5].indices[1] = _ij5[1];
23614vinfos[5].maxsolutions = _nj5;
23615std::vector<int> vfree(0);
23616solutions.AddSolution(vinfos,vfree);
23617}
23618}
23619}
23620
23621}
23622
23623}
23624
23625} else
23626{
23627{
23628IkReal j0array[2], cj0array[2], sj0array[2];
23629bool j0valid[2]={false};
23630_nj0 = 2;
23631CheckValue<IkReal> x1745 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH);
23632if(!x1745.valid){
23633continue;
23634}
23635IkReal x1744=x1745.value;
23636j0array[0]=((-1.0)*x1744);
23637sj0array[0]=IKsin(j0array[0]);
23638cj0array[0]=IKcos(j0array[0]);
23639j0array[1]=((3.14159265358979)+(((-1.0)*x1744)));
23640sj0array[1]=IKsin(j0array[1]);
23641cj0array[1]=IKcos(j0array[1]);
23642if( j0array[0] > IKPI )
23643{
23644 j0array[0]-=IK2PI;
23645}
23646else if( j0array[0] < -IKPI )
23647{ j0array[0]+=IK2PI;
23648}
23649j0valid[0] = true;
23650if( j0array[1] > IKPI )
23651{
23652 j0array[1]-=IK2PI;
23653}
23654else if( j0array[1] < -IKPI )
23655{ j0array[1]+=IK2PI;
23656}
23657j0valid[1] = true;
23658for(int ij0 = 0; ij0 < 2; ++ij0)
23659{
23660if( !j0valid[ij0] )
23661{
23662 continue;
23663}
23664_ij0[0] = ij0; _ij0[1] = -1;
23665for(int iij0 = ij0+1; iij0 < 2; ++iij0)
23666{
23667if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23668{
23669 j0valid[iij0]=false; _ij0[1] = iij0; break;
23670}
23671}
23672j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23673{
23674IkReal evalcond[5];
23675IkReal x1746=IKcos(j0);
23676IkReal x1747=IKsin(j0);
23677IkReal x1748=((1.0)*new_r10);
23678IkReal x1749=((1.0)*new_r01);
23679IkReal x1750=(new_r22*x1747);
23680IkReal x1751=(new_r22*x1746);
23681evalcond[0]=(((new_r01*x1746))+((new_r11*x1747)));
23682evalcond[1]=((((-1.0)*x1747*x1749))+((new_r11*x1746)));
23683evalcond[2]=((((-1.0)*x1746*x1748))+((new_r00*x1747)));
23684evalcond[3]=((((-1.0)*x1748*x1750))+(((-1.0)*new_r00*x1751)));
23685evalcond[4]=((((-1.0)*x1749*x1751))+(((-1.0)*new_r11*x1750)));
23686if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH )
23687{
23688continue;
23689}
23690}
23691
23692{
23693std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23694vinfos[0].jointtype = 1;
23695vinfos[0].foffset = j0;
23696vinfos[0].indices[0] = _ij0[0];
23697vinfos[0].indices[1] = _ij0[1];
23698vinfos[0].maxsolutions = _nj0;
23699vinfos[1].jointtype = 1;
23700vinfos[1].foffset = j1;
23701vinfos[1].indices[0] = _ij1[0];
23702vinfos[1].indices[1] = _ij1[1];
23703vinfos[1].maxsolutions = _nj1;
23704vinfos[2].jointtype = 1;
23705vinfos[2].foffset = j2;
23706vinfos[2].indices[0] = _ij2[0];
23707vinfos[2].indices[1] = _ij2[1];
23708vinfos[2].maxsolutions = _nj2;
23709vinfos[3].jointtype = 1;
23710vinfos[3].foffset = j3;
23711vinfos[3].indices[0] = _ij3[0];
23712vinfos[3].indices[1] = _ij3[1];
23713vinfos[3].maxsolutions = _nj3;
23714vinfos[4].jointtype = 1;
23715vinfos[4].foffset = j4;
23716vinfos[4].indices[0] = _ij4[0];
23717vinfos[4].indices[1] = _ij4[1];
23718vinfos[4].maxsolutions = _nj4;
23719vinfos[5].jointtype = 1;
23720vinfos[5].foffset = j5;
23721vinfos[5].indices[0] = _ij5[0];
23722vinfos[5].indices[1] = _ij5[1];
23723vinfos[5].maxsolutions = _nj5;
23724std::vector<int> vfree(0);
23725solutions.AddSolution(vinfos,vfree);
23726}
23727}
23728}
23729
23730}
23731
23732}
23733
23734}
23735} while(0);
23736if( bgotonextstatement )
23737{
23738bool bgotonextstatement = true;
23739do
23740{
23741if( 1 )
23742{
23743bgotonextstatement=false;
23744continue; // branch miss [j0]
23745
23746}
23747} while(0);
23748if( bgotonextstatement )
23749{
23750}
23751}
23752}
23753}
23754}
23755
23756} else
23757{
23758{
23759IkReal j0array[1], cj0array[1], sj0array[1];
23760bool j0valid[1]={false};
23761_nj0 = 1;
23762CheckValue<IkReal> x1753=IKPowWithIntegerCheck(cj1,-1);
23763if(!x1753.valid){
23764continue;
23765}
23766IkReal x1752=x1753.value;
23767CheckValue<IkReal> x1754=IKPowWithIntegerCheck(new_r01,-1);
23768if(!x1754.valid){
23769continue;
23770}
23771if( IKabs((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r02*x1752)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11))))))+IKsqr((new_r02*x1752))-1) <= IKFAST_SINCOS_THRESH )
23772 continue;
23773j0array[0]=IKatan2((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11))))), (new_r02*x1752));
23774sj0array[0]=IKsin(j0array[0]);
23775cj0array[0]=IKcos(j0array[0]);
23776if( j0array[0] > IKPI )
23777{
23778 j0array[0]-=IK2PI;
23779}
23780else if( j0array[0] < -IKPI )
23781{ j0array[0]+=IK2PI;
23782}
23783j0valid[0] = true;
23784for(int ij0 = 0; ij0 < 1; ++ij0)
23785{
23786if( !j0valid[ij0] )
23787{
23788 continue;
23789}
23790_ij0[0] = ij0; _ij0[1] = -1;
23791for(int iij0 = ij0+1; iij0 < 1; ++iij0)
23792{
23793if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23794{
23795 j0valid[iij0]=false; _ij0[1] = iij0; break;
23796}
23797}
23798j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23799{
23800IkReal evalcond[18];
23801IkReal x1755=IKcos(j0);
23802IkReal x1756=IKsin(j0);
23803IkReal x1757=(sj1*sj2);
23804IkReal x1758=((1.0)*sj1);
23805IkReal x1759=(cj2*sj1);
23806IkReal x1760=((1.0)*cj1);
23807IkReal x1761=((1.0)*cj2);
23808IkReal x1762=(new_r10*x1756);
23809IkReal x1763=(new_r01*x1755);
23810IkReal x1764=(new_r00*x1755);
23811IkReal x1765=((1.0)*x1756);
23812IkReal x1766=(new_r11*x1756);
23813IkReal x1767=(new_r12*x1756);
23814IkReal x1768=(new_r02*x1755);
23815evalcond[0]=((((-1.0)*x1755*x1760))+new_r02);
23816evalcond[1]=((((-1.0)*x1756*x1760))+new_r12);
23817evalcond[2]=((((-1.0)*new_r02*x1765))+((new_r12*x1755)));
23818evalcond[3]=(sj2+(((-1.0)*new_r01*x1765))+((new_r11*x1755)));
23819evalcond[4]=(cj2+((new_r00*x1756))+(((-1.0)*new_r10*x1755)));
23820evalcond[5]=(((cj2*x1756))+new_r00+((x1755*x1757)));
23821evalcond[6]=(((sj2*x1755))+new_r11+((x1756*x1759)));
23822evalcond[7]=((((-1.0)*x1760))+x1768+x1767);
23823evalcond[8]=(x1762+x1764+x1757);
23824evalcond[9]=(x1763+x1766+x1759);
23825evalcond[10]=((((-1.0)*sj2*x1765))+new_r01+((x1755*x1759)));
23826evalcond[11]=((((-1.0)*x1755*x1761))+new_r10+((x1756*x1757)));
23827evalcond[12]=(((new_r20*sj1))+((cj1*x1762))+((cj1*x1764)));
23828evalcond[13]=(((new_r21*sj1))+((cj1*x1763))+((cj1*x1766)));
23829evalcond[14]=((-1.0)+((new_r22*sj1))+((cj1*x1768))+((cj1*x1767)));
23830evalcond[15]=(((cj1*new_r22))+(((-1.0)*x1758*x1767))+(((-1.0)*x1758*x1768)));
23831evalcond[16]=((((-1.0)*sj2))+((cj1*new_r20))+(((-1.0)*x1758*x1764))+(((-1.0)*x1758*x1762)));
23832evalcond[17]=((((-1.0)*x1761))+((cj1*new_r21))+(((-1.0)*x1758*x1763))+(((-1.0)*x1758*x1766)));
23833if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
23834{
23835continue;
23836}
23837}
23838
23839{
23840std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23841vinfos[0].jointtype = 1;
23842vinfos[0].foffset = j0;
23843vinfos[0].indices[0] = _ij0[0];
23844vinfos[0].indices[1] = _ij0[1];
23845vinfos[0].maxsolutions = _nj0;
23846vinfos[1].jointtype = 1;
23847vinfos[1].foffset = j1;
23848vinfos[1].indices[0] = _ij1[0];
23849vinfos[1].indices[1] = _ij1[1];
23850vinfos[1].maxsolutions = _nj1;
23851vinfos[2].jointtype = 1;
23852vinfos[2].foffset = j2;
23853vinfos[2].indices[0] = _ij2[0];
23854vinfos[2].indices[1] = _ij2[1];
23855vinfos[2].maxsolutions = _nj2;
23856vinfos[3].jointtype = 1;
23857vinfos[3].foffset = j3;
23858vinfos[3].indices[0] = _ij3[0];
23859vinfos[3].indices[1] = _ij3[1];
23860vinfos[3].maxsolutions = _nj3;
23861vinfos[4].jointtype = 1;
23862vinfos[4].foffset = j4;
23863vinfos[4].indices[0] = _ij4[0];
23864vinfos[4].indices[1] = _ij4[1];
23865vinfos[4].maxsolutions = _nj4;
23866vinfos[5].jointtype = 1;
23867vinfos[5].foffset = j5;
23868vinfos[5].indices[0] = _ij5[0];
23869vinfos[5].indices[1] = _ij5[1];
23870vinfos[5].maxsolutions = _nj5;
23871std::vector<int> vfree(0);
23872solutions.AddSolution(vinfos,vfree);
23873}
23874}
23875}
23876
23877}
23878
23879}
23880
23881} else
23882{
23883{
23884IkReal j0array[1], cj0array[1], sj0array[1];
23885bool j0valid[1]={false};
23886_nj0 = 1;
23887CheckValue<IkReal> x1769=IKPowWithIntegerCheck(IKsign(cj1),-1);
23888if(!x1769.valid){
23889continue;
23890}
23891CheckValue<IkReal> x1770 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH);
23892if(!x1770.valid){
23893continue;
23894}
23895j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1769.value)))+(x1770.value));
23896sj0array[0]=IKsin(j0array[0]);
23897cj0array[0]=IKcos(j0array[0]);
23898if( j0array[0] > IKPI )
23899{
23900 j0array[0]-=IK2PI;
23901}
23902else if( j0array[0] < -IKPI )
23903{ j0array[0]+=IK2PI;
23904}
23905j0valid[0] = true;
23906for(int ij0 = 0; ij0 < 1; ++ij0)
23907{
23908if( !j0valid[ij0] )
23909{
23910 continue;
23911}
23912_ij0[0] = ij0; _ij0[1] = -1;
23913for(int iij0 = ij0+1; iij0 < 1; ++iij0)
23914{
23915if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
23916{
23917 j0valid[iij0]=false; _ij0[1] = iij0; break;
23918}
23919}
23920j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
23921{
23922IkReal evalcond[18];
23923IkReal x1771=IKcos(j0);
23924IkReal x1772=IKsin(j0);
23925IkReal x1773=(sj1*sj2);
23926IkReal x1774=((1.0)*sj1);
23927IkReal x1775=(cj2*sj1);
23928IkReal x1776=((1.0)*cj1);
23929IkReal x1777=((1.0)*cj2);
23930IkReal x1778=(new_r10*x1772);
23931IkReal x1779=(new_r01*x1771);
23932IkReal x1780=(new_r00*x1771);
23933IkReal x1781=((1.0)*x1772);
23934IkReal x1782=(new_r11*x1772);
23935IkReal x1783=(new_r12*x1772);
23936IkReal x1784=(new_r02*x1771);
23937evalcond[0]=((((-1.0)*x1771*x1776))+new_r02);
23938evalcond[1]=((((-1.0)*x1772*x1776))+new_r12);
23939evalcond[2]=((((-1.0)*new_r02*x1781))+((new_r12*x1771)));
23940evalcond[3]=(sj2+(((-1.0)*new_r01*x1781))+((new_r11*x1771)));
23941evalcond[4]=(cj2+((new_r00*x1772))+(((-1.0)*new_r10*x1771)));
23942evalcond[5]=(((x1771*x1773))+new_r00+((cj2*x1772)));
23943evalcond[6]=(((sj2*x1771))+new_r11+((x1772*x1775)));
23944evalcond[7]=(x1783+x1784+(((-1.0)*x1776)));
23945evalcond[8]=(x1780+x1773+x1778);
23946evalcond[9]=(x1782+x1775+x1779);
23947evalcond[10]=(((x1771*x1775))+new_r01+(((-1.0)*sj2*x1781)));
23948evalcond[11]=((((-1.0)*x1771*x1777))+new_r10+((x1772*x1773)));
23949evalcond[12]=(((new_r20*sj1))+((cj1*x1780))+((cj1*x1778)));
23950evalcond[13]=(((cj1*x1782))+((new_r21*sj1))+((cj1*x1779)));
23951evalcond[14]=((-1.0)+((cj1*x1784))+((cj1*x1783))+((new_r22*sj1)));
23952evalcond[15]=((((-1.0)*x1774*x1784))+(((-1.0)*x1774*x1783))+((cj1*new_r22)));
23953evalcond[16]=((((-1.0)*sj2))+(((-1.0)*x1774*x1780))+((cj1*new_r20))+(((-1.0)*x1774*x1778)));
23954evalcond[17]=((((-1.0)*x1774*x1782))+((cj1*new_r21))+(((-1.0)*x1777))+(((-1.0)*x1774*x1779)));
23955if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
23956{
23957continue;
23958}
23959}
23960
23961{
23962std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
23963vinfos[0].jointtype = 1;
23964vinfos[0].foffset = j0;
23965vinfos[0].indices[0] = _ij0[0];
23966vinfos[0].indices[1] = _ij0[1];
23967vinfos[0].maxsolutions = _nj0;
23968vinfos[1].jointtype = 1;
23969vinfos[1].foffset = j1;
23970vinfos[1].indices[0] = _ij1[0];
23971vinfos[1].indices[1] = _ij1[1];
23972vinfos[1].maxsolutions = _nj1;
23973vinfos[2].jointtype = 1;
23974vinfos[2].foffset = j2;
23975vinfos[2].indices[0] = _ij2[0];
23976vinfos[2].indices[1] = _ij2[1];
23977vinfos[2].maxsolutions = _nj2;
23978vinfos[3].jointtype = 1;
23979vinfos[3].foffset = j3;
23980vinfos[3].indices[0] = _ij3[0];
23981vinfos[3].indices[1] = _ij3[1];
23982vinfos[3].maxsolutions = _nj3;
23983vinfos[4].jointtype = 1;
23984vinfos[4].foffset = j4;
23985vinfos[4].indices[0] = _ij4[0];
23986vinfos[4].indices[1] = _ij4[1];
23987vinfos[4].maxsolutions = _nj4;
23988vinfos[5].jointtype = 1;
23989vinfos[5].foffset = j5;
23990vinfos[5].indices[0] = _ij5[0];
23991vinfos[5].indices[1] = _ij5[1];
23992vinfos[5].maxsolutions = _nj5;
23993std::vector<int> vfree(0);
23994solutions.AddSolution(vinfos,vfree);
23995}
23996}
23997}
23998
23999}
24000
24001}
24002}
24003}
24004
24005}
24006
24007}
24008
24009} else
24010{
24011{
24012IkReal j0array[1], cj0array[1], sj0array[1];
24013bool j0valid[1]={false};
24014_nj0 = 1;
24015CheckValue<IkReal> x1785=IKPowWithIntegerCheck(IKsign(cj1),-1);
24016if(!x1785.valid){
24017continue;
24018}
24019CheckValue<IkReal> x1786 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH);
24020if(!x1786.valid){
24021continue;
24022}
24023j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1785.value)))+(x1786.value));
24024sj0array[0]=IKsin(j0array[0]);
24025cj0array[0]=IKcos(j0array[0]);
24026if( j0array[0] > IKPI )
24027{
24028 j0array[0]-=IK2PI;
24029}
24030else if( j0array[0] < -IKPI )
24031{ j0array[0]+=IK2PI;
24032}
24033j0valid[0] = true;
24034for(int ij0 = 0; ij0 < 1; ++ij0)
24035{
24036if( !j0valid[ij0] )
24037{
24038 continue;
24039}
24040_ij0[0] = ij0; _ij0[1] = -1;
24041for(int iij0 = ij0+1; iij0 < 1; ++iij0)
24042{
24043if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
24044{
24045 j0valid[iij0]=false; _ij0[1] = iij0; break;
24046}
24047}
24048j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
24049{
24050IkReal evalcond[8];
24051IkReal x1787=IKcos(j0);
24052IkReal x1788=IKsin(j0);
24053IkReal x1789=(cj1*x1787);
24054IkReal x1790=(cj1*x1788);
24055IkReal x1791=((1.0)*x1788);
24056IkReal x1792=(new_r02*x1787);
24057evalcond[0]=((((-1.0)*x1789))+new_r02);
24058evalcond[1]=((((-1.0)*x1790))+new_r12);
24059evalcond[2]=(((new_r12*x1787))+(((-1.0)*new_r02*x1791)));
24060evalcond[3]=(x1792+((new_r12*x1788))+(((-1.0)*cj1)));
24061evalcond[4]=(((new_r20*sj1))+((new_r10*x1790))+((new_r00*x1789)));
24062evalcond[5]=(((new_r11*x1790))+((new_r01*x1789))+((new_r21*sj1)));
24063evalcond[6]=((-1.0)+((new_r12*x1790))+((new_r22*sj1))+((new_r02*x1789)));
24064evalcond[7]=(((cj1*new_r22))+(((-1.0)*new_r12*sj1*x1791))+(((-1.0)*sj1*x1792)));
24065if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24066{
24067continue;
24068}
24069}
24070
24071{
24072IkReal j2eval[3];
24073j2eval[0]=cj1;
24074j2eval[1]=IKsign(cj1);
24075j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21)));
24076if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
24077{
24078{
24079IkReal j2eval[2];
24080j2eval[0]=cj1;
24081j2eval[1]=sj0;
24082if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 )
24083{
24084{
24085IkReal j2eval[3];
24086j2eval[0]=cj1;
24087j2eval[1]=sj0;
24088j2eval[2]=sj1;
24089if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 )
24090{
24091{
24092IkReal evalcond[5];
24093bool bgotonextstatement = true;
24094do
24095{
24096evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959)));
24097evalcond[1]=new_r02;
24098evalcond[2]=new_r12;
24099evalcond[3]=new_r20;
24100evalcond[4]=new_r21;
24101if( 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 )
24102{
24103bgotonextstatement=false;
24104{
24105IkReal j2array[1], cj2array[1], sj2array[1];
24106bool j2valid[1]={false};
24107_nj2 = 1;
24108IkReal x1793=((1.0)*cj0);
24109if( IKabs((((new_r01*sj0))+(((-1.0)*new_r00*x1793)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+(((-1.0)*new_r00*x1793))))+IKsqr(((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH )
24110 continue;
24111j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x1793))), ((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0))));
24112sj2array[0]=IKsin(j2array[0]);
24113cj2array[0]=IKcos(j2array[0]);
24114if( j2array[0] > IKPI )
24115{
24116 j2array[0]-=IK2PI;
24117}
24118else if( j2array[0] < -IKPI )
24119{ j2array[0]+=IK2PI;
24120}
24121j2valid[0] = true;
24122for(int ij2 = 0; ij2 < 1; ++ij2)
24123{
24124if( !j2valid[ij2] )
24125{
24126 continue;
24127}
24128_ij2[0] = ij2; _ij2[1] = -1;
24129for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24130{
24131if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24132{
24133 j2valid[iij2]=false; _ij2[1] = iij2; break;
24134}
24135}
24136j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24137{
24138IkReal evalcond[8];
24139IkReal x1794=IKsin(j2);
24140IkReal x1795=IKcos(j2);
24141IkReal x1796=((1.0)*cj0);
24142IkReal x1797=(sj0*x1795);
24143IkReal x1798=(cj0*x1794);
24144IkReal x1799=(sj0*x1794);
24145IkReal x1800=(x1798+x1797);
24146evalcond[0]=(x1794+((new_r10*sj0))+((cj0*new_r00)));
24147evalcond[1]=(x1795+((new_r11*sj0))+((cj0*new_r01)));
24148evalcond[2]=((((-1.0)*new_r01*sj0))+x1794+((cj0*new_r11)));
24149evalcond[3]=((((-1.0)*new_r10*x1796))+x1795+((new_r00*sj0)));
24150evalcond[4]=(x1800+new_r00);
24151evalcond[5]=(x1800+new_r11);
24152evalcond[6]=((((-1.0)*x1799))+new_r01+((cj0*x1795)));
24153evalcond[7]=((((-1.0)*x1795*x1796))+x1799+new_r10);
24154if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24155{
24156continue;
24157}
24158}
24159
24160{
24161std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24162vinfos[0].jointtype = 1;
24163vinfos[0].foffset = j0;
24164vinfos[0].indices[0] = _ij0[0];
24165vinfos[0].indices[1] = _ij0[1];
24166vinfos[0].maxsolutions = _nj0;
24167vinfos[1].jointtype = 1;
24168vinfos[1].foffset = j1;
24169vinfos[1].indices[0] = _ij1[0];
24170vinfos[1].indices[1] = _ij1[1];
24171vinfos[1].maxsolutions = _nj1;
24172vinfos[2].jointtype = 1;
24173vinfos[2].foffset = j2;
24174vinfos[2].indices[0] = _ij2[0];
24175vinfos[2].indices[1] = _ij2[1];
24176vinfos[2].maxsolutions = _nj2;
24177vinfos[3].jointtype = 1;
24178vinfos[3].foffset = j3;
24179vinfos[3].indices[0] = _ij3[0];
24180vinfos[3].indices[1] = _ij3[1];
24181vinfos[3].maxsolutions = _nj3;
24182vinfos[4].jointtype = 1;
24183vinfos[4].foffset = j4;
24184vinfos[4].indices[0] = _ij4[0];
24185vinfos[4].indices[1] = _ij4[1];
24186vinfos[4].maxsolutions = _nj4;
24187vinfos[5].jointtype = 1;
24188vinfos[5].foffset = j5;
24189vinfos[5].indices[0] = _ij5[0];
24190vinfos[5].indices[1] = _ij5[1];
24191vinfos[5].maxsolutions = _nj5;
24192std::vector<int> vfree(0);
24193solutions.AddSolution(vinfos,vfree);
24194}
24195}
24196}
24197
24198}
24199} while(0);
24200if( bgotonextstatement )
24201{
24202bool bgotonextstatement = true;
24203do
24204{
24205evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959)));
24206evalcond[1]=new_r02;
24207evalcond[2]=new_r12;
24208evalcond[3]=new_r20;
24209evalcond[4]=new_r21;
24210if( 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 )
24211{
24212bgotonextstatement=false;
24213{
24214IkReal j2array[1], cj2array[1], sj2array[1];
24215bool j2valid[1]={false};
24216_nj2 = 1;
24217if( IKabs((((new_r01*sj0))+((cj0*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r01))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+((cj0*new_r00))))+IKsqr((((cj0*new_r01))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH )
24218 continue;
24219j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0))));
24220sj2array[0]=IKsin(j2array[0]);
24221cj2array[0]=IKcos(j2array[0]);
24222if( j2array[0] > IKPI )
24223{
24224 j2array[0]-=IK2PI;
24225}
24226else if( j2array[0] < -IKPI )
24227{ j2array[0]+=IK2PI;
24228}
24229j2valid[0] = true;
24230for(int ij2 = 0; ij2 < 1; ++ij2)
24231{
24232if( !j2valid[ij2] )
24233{
24234 continue;
24235}
24236_ij2[0] = ij2; _ij2[1] = -1;
24237for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24238{
24239if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24240{
24241 j2valid[iij2]=false; _ij2[1] = iij2; break;
24242}
24243}
24244j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24245{
24246IkReal evalcond[8];
24247IkReal x1801=IKsin(j2);
24248IkReal x1802=IKcos(j2);
24249IkReal x1803=((1.0)*sj0);
24250IkReal x1804=((1.0)*cj0);
24251IkReal x1805=((1.0)*x1802);
24252IkReal x1806=(((x1802*x1804))+((x1801*x1803)));
24253evalcond[0]=((((-1.0)*new_r01*x1803))+x1801+((cj0*new_r11)));
24254evalcond[1]=(((new_r00*sj0))+x1802+(((-1.0)*new_r10*x1804)));
24255evalcond[2]=(((new_r10*sj0))+((cj0*new_r00))+(((-1.0)*x1801)));
24256evalcond[3]=(((new_r11*sj0))+(((-1.0)*x1805))+((cj0*new_r01)));
24257evalcond[4]=(((sj0*x1802))+(((-1.0)*x1801*x1804))+new_r00);
24258evalcond[5]=(((cj0*x1801))+(((-1.0)*x1802*x1803))+new_r11);
24259evalcond[6]=((((-1.0)*x1806))+new_r01);
24260evalcond[7]=((((-1.0)*x1806))+new_r10);
24261if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24262{
24263continue;
24264}
24265}
24266
24267{
24268std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24269vinfos[0].jointtype = 1;
24270vinfos[0].foffset = j0;
24271vinfos[0].indices[0] = _ij0[0];
24272vinfos[0].indices[1] = _ij0[1];
24273vinfos[0].maxsolutions = _nj0;
24274vinfos[1].jointtype = 1;
24275vinfos[1].foffset = j1;
24276vinfos[1].indices[0] = _ij1[0];
24277vinfos[1].indices[1] = _ij1[1];
24278vinfos[1].maxsolutions = _nj1;
24279vinfos[2].jointtype = 1;
24280vinfos[2].foffset = j2;
24281vinfos[2].indices[0] = _ij2[0];
24282vinfos[2].indices[1] = _ij2[1];
24283vinfos[2].maxsolutions = _nj2;
24284vinfos[3].jointtype = 1;
24285vinfos[3].foffset = j3;
24286vinfos[3].indices[0] = _ij3[0];
24287vinfos[3].indices[1] = _ij3[1];
24288vinfos[3].maxsolutions = _nj3;
24289vinfos[4].jointtype = 1;
24290vinfos[4].foffset = j4;
24291vinfos[4].indices[0] = _ij4[0];
24292vinfos[4].indices[1] = _ij4[1];
24293vinfos[4].maxsolutions = _nj4;
24294vinfos[5].jointtype = 1;
24295vinfos[5].foffset = j5;
24296vinfos[5].indices[0] = _ij5[0];
24297vinfos[5].indices[1] = _ij5[1];
24298vinfos[5].maxsolutions = _nj5;
24299std::vector<int> vfree(0);
24300solutions.AddSolution(vinfos,vfree);
24301}
24302}
24303}
24304
24305}
24306} while(0);
24307if( bgotonextstatement )
24308{
24309bool bgotonextstatement = true;
24310do
24311{
24312evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959)));
24313evalcond[1]=new_r12;
24314if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
24315{
24316bgotonextstatement=false;
24317{
24318IkReal j2array[1], cj2array[1], sj2array[1];
24319bool j2valid[1]={false};
24320_nj2 = 1;
24321if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH )
24322 continue;
24323j2array[0]=IKatan2(((-1.0)*new_r11), new_r10);
24324sj2array[0]=IKsin(j2array[0]);
24325cj2array[0]=IKcos(j2array[0]);
24326if( j2array[0] > IKPI )
24327{
24328 j2array[0]-=IK2PI;
24329}
24330else if( j2array[0] < -IKPI )
24331{ j2array[0]+=IK2PI;
24332}
24333j2valid[0] = true;
24334for(int ij2 = 0; ij2 < 1; ++ij2)
24335{
24336if( !j2valid[ij2] )
24337{
24338 continue;
24339}
24340_ij2[0] = ij2; _ij2[1] = -1;
24341for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24342{
24343if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24344{
24345 j2valid[iij2]=false; _ij2[1] = iij2; break;
24346}
24347}
24348j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24349{
24350IkReal evalcond[8];
24351IkReal x1807=IKsin(j2);
24352IkReal x1808=IKcos(j2);
24353IkReal x1809=((1.0)*sj1);
24354IkReal x1810=((1.0)*cj1);
24355evalcond[0]=(x1807+new_r11);
24356evalcond[1]=(x1808+(((-1.0)*new_r10)));
24357evalcond[2]=(((sj1*x1807))+new_r00);
24358evalcond[3]=(((sj1*x1808))+new_r01);
24359evalcond[4]=((((-1.0)*x1807*x1810))+new_r20);
24360evalcond[5]=((((-1.0)*x1808*x1810))+new_r21);
24361evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x1809))+(((-1.0)*x1807)));
24362evalcond[7]=((((-1.0)*new_r01*x1809))+((cj1*new_r21))+(((-1.0)*x1808)));
24363if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24364{
24365continue;
24366}
24367}
24368
24369{
24370std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24371vinfos[0].jointtype = 1;
24372vinfos[0].foffset = j0;
24373vinfos[0].indices[0] = _ij0[0];
24374vinfos[0].indices[1] = _ij0[1];
24375vinfos[0].maxsolutions = _nj0;
24376vinfos[1].jointtype = 1;
24377vinfos[1].foffset = j1;
24378vinfos[1].indices[0] = _ij1[0];
24379vinfos[1].indices[1] = _ij1[1];
24380vinfos[1].maxsolutions = _nj1;
24381vinfos[2].jointtype = 1;
24382vinfos[2].foffset = j2;
24383vinfos[2].indices[0] = _ij2[0];
24384vinfos[2].indices[1] = _ij2[1];
24385vinfos[2].maxsolutions = _nj2;
24386vinfos[3].jointtype = 1;
24387vinfos[3].foffset = j3;
24388vinfos[3].indices[0] = _ij3[0];
24389vinfos[3].indices[1] = _ij3[1];
24390vinfos[3].maxsolutions = _nj3;
24391vinfos[4].jointtype = 1;
24392vinfos[4].foffset = j4;
24393vinfos[4].indices[0] = _ij4[0];
24394vinfos[4].indices[1] = _ij4[1];
24395vinfos[4].maxsolutions = _nj4;
24396vinfos[5].jointtype = 1;
24397vinfos[5].foffset = j5;
24398vinfos[5].indices[0] = _ij5[0];
24399vinfos[5].indices[1] = _ij5[1];
24400vinfos[5].maxsolutions = _nj5;
24401std::vector<int> vfree(0);
24402solutions.AddSolution(vinfos,vfree);
24403}
24404}
24405}
24406
24407}
24408} while(0);
24409if( bgotonextstatement )
24410{
24411bool bgotonextstatement = true;
24412do
24413{
24414evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959)));
24415evalcond[1]=new_r12;
24416if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
24417{
24418bgotonextstatement=false;
24419{
24420IkReal j2array[1], cj2array[1], sj2array[1];
24421bool j2valid[1]={false};
24422_nj2 = 1;
24423if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH )
24424 continue;
24425j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10));
24426sj2array[0]=IKsin(j2array[0]);
24427cj2array[0]=IKcos(j2array[0]);
24428if( j2array[0] > IKPI )
24429{
24430 j2array[0]-=IK2PI;
24431}
24432else if( j2array[0] < -IKPI )
24433{ j2array[0]+=IK2PI;
24434}
24435j2valid[0] = true;
24436for(int ij2 = 0; ij2 < 1; ++ij2)
24437{
24438if( !j2valid[ij2] )
24439{
24440 continue;
24441}
24442_ij2[0] = ij2; _ij2[1] = -1;
24443for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24444{
24445if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24446{
24447 j2valid[iij2]=false; _ij2[1] = iij2; break;
24448}
24449}
24450j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24451{
24452IkReal evalcond[8];
24453IkReal x1811=IKsin(j2);
24454IkReal x1812=IKcos(j2);
24455IkReal x1813=((1.0)*cj1);
24456evalcond[0]=(x1812+new_r10);
24457evalcond[1]=(x1811+(((-1.0)*new_r11)));
24458evalcond[2]=((((-1.0)*x1811*x1813))+new_r20);
24459evalcond[3]=((((-1.0)*x1812*x1813))+new_r21);
24460evalcond[4]=(((sj1*x1811))+(((-1.0)*new_r00)));
24461evalcond[5]=(((sj1*x1812))+(((-1.0)*new_r01)));
24462evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x1811)));
24463evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x1812)));
24464if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24465{
24466continue;
24467}
24468}
24469
24470{
24471std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24472vinfos[0].jointtype = 1;
24473vinfos[0].foffset = j0;
24474vinfos[0].indices[0] = _ij0[0];
24475vinfos[0].indices[1] = _ij0[1];
24476vinfos[0].maxsolutions = _nj0;
24477vinfos[1].jointtype = 1;
24478vinfos[1].foffset = j1;
24479vinfos[1].indices[0] = _ij1[0];
24480vinfos[1].indices[1] = _ij1[1];
24481vinfos[1].maxsolutions = _nj1;
24482vinfos[2].jointtype = 1;
24483vinfos[2].foffset = j2;
24484vinfos[2].indices[0] = _ij2[0];
24485vinfos[2].indices[1] = _ij2[1];
24486vinfos[2].maxsolutions = _nj2;
24487vinfos[3].jointtype = 1;
24488vinfos[3].foffset = j3;
24489vinfos[3].indices[0] = _ij3[0];
24490vinfos[3].indices[1] = _ij3[1];
24491vinfos[3].maxsolutions = _nj3;
24492vinfos[4].jointtype = 1;
24493vinfos[4].foffset = j4;
24494vinfos[4].indices[0] = _ij4[0];
24495vinfos[4].indices[1] = _ij4[1];
24496vinfos[4].maxsolutions = _nj4;
24497vinfos[5].jointtype = 1;
24498vinfos[5].foffset = j5;
24499vinfos[5].indices[0] = _ij5[0];
24500vinfos[5].indices[1] = _ij5[1];
24501vinfos[5].maxsolutions = _nj5;
24502std::vector<int> vfree(0);
24503solutions.AddSolution(vinfos,vfree);
24504}
24505}
24506}
24507
24508}
24509} while(0);
24510if( bgotonextstatement )
24511{
24512bool bgotonextstatement = true;
24513do
24514{
24515evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959)));
24516evalcond[1]=new_r22;
24517if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
24518{
24519bgotonextstatement=false;
24520{
24521IkReal j2array[1], cj2array[1], sj2array[1];
24522bool j2valid[1]={false};
24523_nj2 = 1;
24524if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH )
24525 continue;
24526j2array[0]=IKatan2(new_r20, new_r21);
24527sj2array[0]=IKsin(j2array[0]);
24528cj2array[0]=IKcos(j2array[0]);
24529if( j2array[0] > IKPI )
24530{
24531 j2array[0]-=IK2PI;
24532}
24533else if( j2array[0] < -IKPI )
24534{ j2array[0]+=IK2PI;
24535}
24536j2valid[0] = true;
24537for(int ij2 = 0; ij2 < 1; ++ij2)
24538{
24539if( !j2valid[ij2] )
24540{
24541 continue;
24542}
24543_ij2[0] = ij2; _ij2[1] = -1;
24544for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24545{
24546if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24547{
24548 j2valid[iij2]=false; _ij2[1] = iij2; break;
24549}
24550}
24551j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24552{
24553IkReal evalcond[8];
24554IkReal x1814=IKcos(j2);
24555IkReal x1815=IKsin(j2);
24556IkReal x1816=((1.0)*sj0);
24557IkReal x1817=((1.0)*x1814);
24558evalcond[0]=(new_r20+(((-1.0)*x1815)));
24559evalcond[1]=((((-1.0)*x1817))+new_r21);
24560evalcond[2]=(((sj0*x1814))+new_r00);
24561evalcond[3]=(((cj0*x1815))+new_r11);
24562evalcond[4]=((((-1.0)*x1815*x1816))+new_r01);
24563evalcond[5]=((((-1.0)*new_r02*x1817))+new_r10);
24564evalcond[6]=((((-1.0)*new_r01*x1816))+x1815+((cj0*new_r11)));
24565evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1814);
24566if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24567{
24568continue;
24569}
24570}
24571
24572{
24573std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24574vinfos[0].jointtype = 1;
24575vinfos[0].foffset = j0;
24576vinfos[0].indices[0] = _ij0[0];
24577vinfos[0].indices[1] = _ij0[1];
24578vinfos[0].maxsolutions = _nj0;
24579vinfos[1].jointtype = 1;
24580vinfos[1].foffset = j1;
24581vinfos[1].indices[0] = _ij1[0];
24582vinfos[1].indices[1] = _ij1[1];
24583vinfos[1].maxsolutions = _nj1;
24584vinfos[2].jointtype = 1;
24585vinfos[2].foffset = j2;
24586vinfos[2].indices[0] = _ij2[0];
24587vinfos[2].indices[1] = _ij2[1];
24588vinfos[2].maxsolutions = _nj2;
24589vinfos[3].jointtype = 1;
24590vinfos[3].foffset = j3;
24591vinfos[3].indices[0] = _ij3[0];
24592vinfos[3].indices[1] = _ij3[1];
24593vinfos[3].maxsolutions = _nj3;
24594vinfos[4].jointtype = 1;
24595vinfos[4].foffset = j4;
24596vinfos[4].indices[0] = _ij4[0];
24597vinfos[4].indices[1] = _ij4[1];
24598vinfos[4].maxsolutions = _nj4;
24599vinfos[5].jointtype = 1;
24600vinfos[5].foffset = j5;
24601vinfos[5].indices[0] = _ij5[0];
24602vinfos[5].indices[1] = _ij5[1];
24603vinfos[5].maxsolutions = _nj5;
24604std::vector<int> vfree(0);
24605solutions.AddSolution(vinfos,vfree);
24606}
24607}
24608}
24609
24610}
24611} while(0);
24612if( bgotonextstatement )
24613{
24614bool bgotonextstatement = true;
24615do
24616{
24617evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959)));
24618evalcond[1]=new_r22;
24619if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 )
24620{
24621bgotonextstatement=false;
24622{
24623IkReal j2array[1], cj2array[1], sj2array[1];
24624bool j2valid[1]={false};
24625_nj2 = 1;
24626if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH )
24627 continue;
24628j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21));
24629sj2array[0]=IKsin(j2array[0]);
24630cj2array[0]=IKcos(j2array[0]);
24631if( j2array[0] > IKPI )
24632{
24633 j2array[0]-=IK2PI;
24634}
24635else if( j2array[0] < -IKPI )
24636{ j2array[0]+=IK2PI;
24637}
24638j2valid[0] = true;
24639for(int ij2 = 0; ij2 < 1; ++ij2)
24640{
24641if( !j2valid[ij2] )
24642{
24643 continue;
24644}
24645_ij2[0] = ij2; _ij2[1] = -1;
24646for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24647{
24648if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24649{
24650 j2valid[iij2]=false; _ij2[1] = iij2; break;
24651}
24652}
24653j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24654{
24655IkReal evalcond[8];
24656IkReal x1818=IKcos(j2);
24657IkReal x1819=IKsin(j2);
24658IkReal x1820=((1.0)*sj0);
24659evalcond[0]=(x1819+new_r20);
24660evalcond[1]=(x1818+new_r21);
24661evalcond[2]=(((sj0*x1818))+new_r00);
24662evalcond[3]=(((cj0*x1819))+new_r11);
24663evalcond[4]=(((new_r02*x1818))+new_r10);
24664evalcond[5]=((((-1.0)*x1819*x1820))+new_r01);
24665evalcond[6]=((((-1.0)*new_r01*x1820))+x1819+((cj0*new_r11)));
24666evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1818);
24667if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24668{
24669continue;
24670}
24671}
24672
24673{
24674std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24675vinfos[0].jointtype = 1;
24676vinfos[0].foffset = j0;
24677vinfos[0].indices[0] = _ij0[0];
24678vinfos[0].indices[1] = _ij0[1];
24679vinfos[0].maxsolutions = _nj0;
24680vinfos[1].jointtype = 1;
24681vinfos[1].foffset = j1;
24682vinfos[1].indices[0] = _ij1[0];
24683vinfos[1].indices[1] = _ij1[1];
24684vinfos[1].maxsolutions = _nj1;
24685vinfos[2].jointtype = 1;
24686vinfos[2].foffset = j2;
24687vinfos[2].indices[0] = _ij2[0];
24688vinfos[2].indices[1] = _ij2[1];
24689vinfos[2].maxsolutions = _nj2;
24690vinfos[3].jointtype = 1;
24691vinfos[3].foffset = j3;
24692vinfos[3].indices[0] = _ij3[0];
24693vinfos[3].indices[1] = _ij3[1];
24694vinfos[3].maxsolutions = _nj3;
24695vinfos[4].jointtype = 1;
24696vinfos[4].foffset = j4;
24697vinfos[4].indices[0] = _ij4[0];
24698vinfos[4].indices[1] = _ij4[1];
24699vinfos[4].maxsolutions = _nj4;
24700vinfos[5].jointtype = 1;
24701vinfos[5].foffset = j5;
24702vinfos[5].indices[0] = _ij5[0];
24703vinfos[5].indices[1] = _ij5[1];
24704vinfos[5].maxsolutions = _nj5;
24705std::vector<int> vfree(0);
24706solutions.AddSolution(vinfos,vfree);
24707}
24708}
24709}
24710
24711}
24712} while(0);
24713if( bgotonextstatement )
24714{
24715bool bgotonextstatement = true;
24716do
24717{
24718evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21)));
24719if( IKabs(evalcond[0]) < 0.0000050000000000 )
24720{
24721bgotonextstatement=false;
24722{
24723IkReal j2eval[1];
24724new_r21=0;
24725new_r20=0;
24726new_r02=0;
24727new_r12=0;
24728j2eval[0]=IKabs(new_r22);
24729if( IKabs(j2eval[0]) < 0.0000000100000000 )
24730{
24731continue; // no branches [j2]
24732
24733} else
24734{
24735IkReal op[2+1], zeror[2];
24736int numroots;
24737op[0]=((-1.0)*new_r22);
24738op[1]=0;
24739op[2]=new_r22;
24740polyroots2(op,zeror,numroots);
24741IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1];
24742int numsolutions = 0;
24743for(int ij2 = 0; ij2 < numroots; ++ij2)
24744{
24745IkReal htj2 = zeror[ij2];
24746tempj2array[0]=((2.0)*(atan(htj2)));
24747for(int kj2 = 0; kj2 < 1; ++kj2)
24748{
24749j2array[numsolutions] = tempj2array[kj2];
24750if( j2array[numsolutions] > IKPI )
24751{
24752 j2array[numsolutions]-=IK2PI;
24753}
24754else if( j2array[numsolutions] < -IKPI )
24755{
24756 j2array[numsolutions]+=IK2PI;
24757}
24758sj2array[numsolutions] = IKsin(j2array[numsolutions]);
24759cj2array[numsolutions] = IKcos(j2array[numsolutions]);
24760numsolutions++;
24761}
24762}
24763bool j2valid[2]={true,true};
24764_nj2 = 2;
24765for(int ij2 = 0; ij2 < numsolutions; ++ij2)
24766 {
24767if( !j2valid[ij2] )
24768{
24769 continue;
24770}
24771 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24772htj2 = IKtan(j2/2);
24773
24774_ij2[0] = ij2; _ij2[1] = -1;
24775for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2)
24776{
24777if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24778{
24779 j2valid[iij2]=false; _ij2[1] = iij2; break;
24780}
24781}
24782{
24783std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24784vinfos[0].jointtype = 1;
24785vinfos[0].foffset = j0;
24786vinfos[0].indices[0] = _ij0[0];
24787vinfos[0].indices[1] = _ij0[1];
24788vinfos[0].maxsolutions = _nj0;
24789vinfos[1].jointtype = 1;
24790vinfos[1].foffset = j1;
24791vinfos[1].indices[0] = _ij1[0];
24792vinfos[1].indices[1] = _ij1[1];
24793vinfos[1].maxsolutions = _nj1;
24794vinfos[2].jointtype = 1;
24795vinfos[2].foffset = j2;
24796vinfos[2].indices[0] = _ij2[0];
24797vinfos[2].indices[1] = _ij2[1];
24798vinfos[2].maxsolutions = _nj2;
24799vinfos[3].jointtype = 1;
24800vinfos[3].foffset = j3;
24801vinfos[3].indices[0] = _ij3[0];
24802vinfos[3].indices[1] = _ij3[1];
24803vinfos[3].maxsolutions = _nj3;
24804vinfos[4].jointtype = 1;
24805vinfos[4].foffset = j4;
24806vinfos[4].indices[0] = _ij4[0];
24807vinfos[4].indices[1] = _ij4[1];
24808vinfos[4].maxsolutions = _nj4;
24809vinfos[5].jointtype = 1;
24810vinfos[5].foffset = j5;
24811vinfos[5].indices[0] = _ij5[0];
24812vinfos[5].indices[1] = _ij5[1];
24813vinfos[5].maxsolutions = _nj5;
24814std::vector<int> vfree(0);
24815solutions.AddSolution(vinfos,vfree);
24816}
24817 }
24818
24819}
24820
24821}
24822
24823}
24824} while(0);
24825if( bgotonextstatement )
24826{
24827bool bgotonextstatement = true;
24828do
24829{
24830if( 1 )
24831{
24832bgotonextstatement=false;
24833continue; // branch miss [j2]
24834
24835}
24836} while(0);
24837if( bgotonextstatement )
24838{
24839}
24840}
24841}
24842}
24843}
24844}
24845}
24846}
24847}
24848
24849} else
24850{
24851{
24852IkReal j2array[1], cj2array[1], sj2array[1];
24853bool j2valid[1]={false};
24854_nj2 = 1;
24855CheckValue<IkReal> x1822=IKPowWithIntegerCheck(cj1,-1);
24856if(!x1822.valid){
24857continue;
24858}
24859IkReal x1821=x1822.value;
24860CheckValue<IkReal> x1823=IKPowWithIntegerCheck(sj0,-1);
24861if(!x1823.valid){
24862continue;
24863}
24864CheckValue<IkReal> x1824=IKPowWithIntegerCheck(sj1,-1);
24865if(!x1824.valid){
24866continue;
24867}
24868if( IKabs((new_r20*x1821)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x1821))+IKsqr((x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))))-1) <= IKFAST_SINCOS_THRESH )
24869 continue;
24870j2array[0]=IKatan2((new_r20*x1821), (x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))));
24871sj2array[0]=IKsin(j2array[0]);
24872cj2array[0]=IKcos(j2array[0]);
24873if( j2array[0] > IKPI )
24874{
24875 j2array[0]-=IK2PI;
24876}
24877else if( j2array[0] < -IKPI )
24878{ j2array[0]+=IK2PI;
24879}
24880j2valid[0] = true;
24881for(int ij2 = 0; ij2 < 1; ++ij2)
24882{
24883if( !j2valid[ij2] )
24884{
24885 continue;
24886}
24887_ij2[0] = ij2; _ij2[1] = -1;
24888for(int iij2 = ij2+1; iij2 < 1; ++iij2)
24889{
24890if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
24891{
24892 j2valid[iij2]=false; _ij2[1] = iij2; break;
24893}
24894}
24895j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
24896{
24897IkReal evalcond[12];
24898IkReal x1825=IKsin(j2);
24899IkReal x1826=IKcos(j2);
24900IkReal x1827=((1.0)*sj0);
24901IkReal x1828=(cj0*new_r00);
24902IkReal x1829=((1.0)*cj0);
24903IkReal x1830=((1.0)*x1826);
24904IkReal x1831=(sj1*x1825);
24905IkReal x1832=(sj1*x1826);
24906IkReal x1833=((1.0)*x1825);
24907evalcond[0]=(new_r20+(((-1.0)*cj1*x1833)));
24908evalcond[1]=(new_r21+(((-1.0)*cj1*x1830)));
24909evalcond[2]=((((-1.0)*new_r01*x1827))+x1825+((cj0*new_r11)));
24910evalcond[3]=((((-1.0)*new_r10*x1829))+((new_r00*sj0))+x1826);
24911evalcond[4]=(((new_r10*sj0))+x1828+x1831);
24912evalcond[5]=(((new_r11*sj0))+x1832+((cj0*new_r01)));
24913evalcond[6]=(((cj0*x1831))+((sj0*x1826))+new_r00);
24914evalcond[7]=(((cj0*x1825))+((sj0*x1832))+new_r11);
24915evalcond[8]=(((cj0*x1832))+(((-1.0)*x1825*x1827))+new_r01);
24916evalcond[9]=(((sj0*x1831))+(((-1.0)*x1826*x1829))+new_r10);
24917evalcond[10]=(((cj1*new_r20))+(((-1.0)*x1833))+(((-1.0)*sj1*x1828))+(((-1.0)*new_r10*sj1*x1827)));
24918evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1827))+(((-1.0)*x1830))+(((-1.0)*new_r01*sj1*x1829)));
24919if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
24920{
24921continue;
24922}
24923}
24924
24925{
24926std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
24927vinfos[0].jointtype = 1;
24928vinfos[0].foffset = j0;
24929vinfos[0].indices[0] = _ij0[0];
24930vinfos[0].indices[1] = _ij0[1];
24931vinfos[0].maxsolutions = _nj0;
24932vinfos[1].jointtype = 1;
24933vinfos[1].foffset = j1;
24934vinfos[1].indices[0] = _ij1[0];
24935vinfos[1].indices[1] = _ij1[1];
24936vinfos[1].maxsolutions = _nj1;
24937vinfos[2].jointtype = 1;
24938vinfos[2].foffset = j2;
24939vinfos[2].indices[0] = _ij2[0];
24940vinfos[2].indices[1] = _ij2[1];
24941vinfos[2].maxsolutions = _nj2;
24942vinfos[3].jointtype = 1;
24943vinfos[3].foffset = j3;
24944vinfos[3].indices[0] = _ij3[0];
24945vinfos[3].indices[1] = _ij3[1];
24946vinfos[3].maxsolutions = _nj3;
24947vinfos[4].jointtype = 1;
24948vinfos[4].foffset = j4;
24949vinfos[4].indices[0] = _ij4[0];
24950vinfos[4].indices[1] = _ij4[1];
24951vinfos[4].maxsolutions = _nj4;
24952vinfos[5].jointtype = 1;
24953vinfos[5].foffset = j5;
24954vinfos[5].indices[0] = _ij5[0];
24955vinfos[5].indices[1] = _ij5[1];
24956vinfos[5].maxsolutions = _nj5;
24957std::vector<int> vfree(0);
24958solutions.AddSolution(vinfos,vfree);
24959}
24960}
24961}
24962
24963}
24964
24965}
24966
24967} else
24968{
24969{
24970IkReal j2array[1], cj2array[1], sj2array[1];
24971bool j2valid[1]={false};
24972_nj2 = 1;
24973CheckValue<IkReal> x1835=IKPowWithIntegerCheck(cj1,-1);
24974if(!x1835.valid){
24975continue;
24976}
24977IkReal x1834=x1835.value;
24978CheckValue<IkReal> x1836=IKPowWithIntegerCheck(sj0,-1);
24979if(!x1836.valid){
24980continue;
24981}
24982if( IKabs((new_r20*x1834)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x1834))+IKsqr((x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))))-1) <= IKFAST_SINCOS_THRESH )
24983 continue;
24984j2array[0]=IKatan2((new_r20*x1834), (x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))));
24985sj2array[0]=IKsin(j2array[0]);
24986cj2array[0]=IKcos(j2array[0]);
24987if( j2array[0] > IKPI )
24988{
24989 j2array[0]-=IK2PI;
24990}
24991else if( j2array[0] < -IKPI )
24992{ j2array[0]+=IK2PI;
24993}
24994j2valid[0] = true;
24995for(int ij2 = 0; ij2 < 1; ++ij2)
24996{
24997if( !j2valid[ij2] )
24998{
24999 continue;
25000}
25001_ij2[0] = ij2; _ij2[1] = -1;
25002for(int iij2 = ij2+1; iij2 < 1; ++iij2)
25003{
25004if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
25005{
25006 j2valid[iij2]=false; _ij2[1] = iij2; break;
25007}
25008}
25009j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
25010{
25011IkReal evalcond[12];
25012IkReal x1837=IKsin(j2);
25013IkReal x1838=IKcos(j2);
25014IkReal x1839=((1.0)*sj0);
25015IkReal x1840=(cj0*new_r00);
25016IkReal x1841=((1.0)*cj0);
25017IkReal x1842=((1.0)*x1838);
25018IkReal x1843=(sj1*x1837);
25019IkReal x1844=(sj1*x1838);
25020IkReal x1845=((1.0)*x1837);
25021evalcond[0]=((((-1.0)*cj1*x1845))+new_r20);
25022evalcond[1]=((((-1.0)*cj1*x1842))+new_r21);
25023evalcond[2]=((((-1.0)*new_r01*x1839))+x1837+((cj0*new_r11)));
25024evalcond[3]=((((-1.0)*new_r10*x1841))+((new_r00*sj0))+x1838);
25025evalcond[4]=(((new_r10*sj0))+x1843+x1840);
25026evalcond[5]=(((new_r11*sj0))+x1844+((cj0*new_r01)));
25027evalcond[6]=(((cj0*x1843))+((sj0*x1838))+new_r00);
25028evalcond[7]=(((cj0*x1837))+((sj0*x1844))+new_r11);
25029evalcond[8]=(((cj0*x1844))+(((-1.0)*x1837*x1839))+new_r01);
25030evalcond[9]=(((sj0*x1843))+new_r10+(((-1.0)*x1838*x1841)));
25031evalcond[10]=((((-1.0)*x1845))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1839))+(((-1.0)*sj1*x1840)));
25032evalcond[11]=((((-1.0)*new_r11*sj1*x1839))+(((-1.0)*new_r01*sj1*x1841))+(((-1.0)*x1842))+((cj1*new_r21)));
25033if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
25034{
25035continue;
25036}
25037}
25038
25039{
25040std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
25041vinfos[0].jointtype = 1;
25042vinfos[0].foffset = j0;
25043vinfos[0].indices[0] = _ij0[0];
25044vinfos[0].indices[1] = _ij0[1];
25045vinfos[0].maxsolutions = _nj0;
25046vinfos[1].jointtype = 1;
25047vinfos[1].foffset = j1;
25048vinfos[1].indices[0] = _ij1[0];
25049vinfos[1].indices[1] = _ij1[1];
25050vinfos[1].maxsolutions = _nj1;
25051vinfos[2].jointtype = 1;
25052vinfos[2].foffset = j2;
25053vinfos[2].indices[0] = _ij2[0];
25054vinfos[2].indices[1] = _ij2[1];
25055vinfos[2].maxsolutions = _nj2;
25056vinfos[3].jointtype = 1;
25057vinfos[3].foffset = j3;
25058vinfos[3].indices[0] = _ij3[0];
25059vinfos[3].indices[1] = _ij3[1];
25060vinfos[3].maxsolutions = _nj3;
25061vinfos[4].jointtype = 1;
25062vinfos[4].foffset = j4;
25063vinfos[4].indices[0] = _ij4[0];
25064vinfos[4].indices[1] = _ij4[1];
25065vinfos[4].maxsolutions = _nj4;
25066vinfos[5].jointtype = 1;
25067vinfos[5].foffset = j5;
25068vinfos[5].indices[0] = _ij5[0];
25069vinfos[5].indices[1] = _ij5[1];
25070vinfos[5].maxsolutions = _nj5;
25071std::vector<int> vfree(0);
25072solutions.AddSolution(vinfos,vfree);
25073}
25074}
25075}
25076
25077}
25078
25079}
25080
25081} else
25082{
25083{
25084IkReal j2array[1], cj2array[1], sj2array[1];
25085bool j2valid[1]={false};
25086_nj2 = 1;
25087CheckValue<IkReal> x1846=IKPowWithIntegerCheck(IKsign(cj1),-1);
25088if(!x1846.valid){
25089continue;
25090}
25091CheckValue<IkReal> x1847 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH);
25092if(!x1847.valid){
25093continue;
25094}
25095j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1846.value)))+(x1847.value));
25096sj2array[0]=IKsin(j2array[0]);
25097cj2array[0]=IKcos(j2array[0]);
25098if( j2array[0] > IKPI )
25099{
25100 j2array[0]-=IK2PI;
25101}
25102else if( j2array[0] < -IKPI )
25103{ j2array[0]+=IK2PI;
25104}
25105j2valid[0] = true;
25106for(int ij2 = 0; ij2 < 1; ++ij2)
25107{
25108if( !j2valid[ij2] )
25109{
25110 continue;
25111}
25112_ij2[0] = ij2; _ij2[1] = -1;
25113for(int iij2 = ij2+1; iij2 < 1; ++iij2)
25114{
25115if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
25116{
25117 j2valid[iij2]=false; _ij2[1] = iij2; break;
25118}
25119}
25120j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
25121{
25122IkReal evalcond[12];
25123IkReal x1848=IKsin(j2);
25124IkReal x1849=IKcos(j2);
25125IkReal x1850=((1.0)*sj0);
25126IkReal x1851=(cj0*new_r00);
25127IkReal x1852=((1.0)*cj0);
25128IkReal x1853=((1.0)*x1849);
25129IkReal x1854=(sj1*x1848);
25130IkReal x1855=(sj1*x1849);
25131IkReal x1856=((1.0)*x1848);
25132evalcond[0]=(new_r20+(((-1.0)*cj1*x1856)));
25133evalcond[1]=(new_r21+(((-1.0)*cj1*x1853)));
25134evalcond[2]=(x1848+(((-1.0)*new_r01*x1850))+((cj0*new_r11)));
25135evalcond[3]=(((new_r00*sj0))+(((-1.0)*new_r10*x1852))+x1849);
25136evalcond[4]=(((new_r10*sj0))+x1851+x1854);
25137evalcond[5]=(((new_r11*sj0))+x1855+((cj0*new_r01)));
25138evalcond[6]=(((sj0*x1849))+new_r00+((cj0*x1854)));
25139evalcond[7]=(((cj0*x1848))+((sj0*x1855))+new_r11);
25140evalcond[8]=((((-1.0)*x1848*x1850))+new_r01+((cj0*x1855)));
25141evalcond[9]=((((-1.0)*x1849*x1852))+((sj0*x1854))+new_r10);
25142evalcond[10]=((((-1.0)*sj1*x1851))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1850))+(((-1.0)*x1856)));
25143evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1850))+(((-1.0)*new_r01*sj1*x1852))+(((-1.0)*x1853)));
25144if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || 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 )
25145{
25146continue;
25147}
25148}
25149
25150{
25151std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
25152vinfos[0].jointtype = 1;
25153vinfos[0].foffset = j0;
25154vinfos[0].indices[0] = _ij0[0];
25155vinfos[0].indices[1] = _ij0[1];
25156vinfos[0].maxsolutions = _nj0;
25157vinfos[1].jointtype = 1;
25158vinfos[1].foffset = j1;
25159vinfos[1].indices[0] = _ij1[0];
25160vinfos[1].indices[1] = _ij1[1];
25161vinfos[1].maxsolutions = _nj1;
25162vinfos[2].jointtype = 1;
25163vinfos[2].foffset = j2;
25164vinfos[2].indices[0] = _ij2[0];
25165vinfos[2].indices[1] = _ij2[1];
25166vinfos[2].maxsolutions = _nj2;
25167vinfos[3].jointtype = 1;
25168vinfos[3].foffset = j3;
25169vinfos[3].indices[0] = _ij3[0];
25170vinfos[3].indices[1] = _ij3[1];
25171vinfos[3].maxsolutions = _nj3;
25172vinfos[4].jointtype = 1;
25173vinfos[4].foffset = j4;
25174vinfos[4].indices[0] = _ij4[0];
25175vinfos[4].indices[1] = _ij4[1];
25176vinfos[4].maxsolutions = _nj4;
25177vinfos[5].jointtype = 1;
25178vinfos[5].foffset = j5;
25179vinfos[5].indices[0] = _ij5[0];
25180vinfos[5].indices[1] = _ij5[1];
25181vinfos[5].maxsolutions = _nj5;
25182std::vector<int> vfree(0);
25183solutions.AddSolution(vinfos,vfree);
25184}
25185}
25186}
25187
25188}
25189
25190}
25191}
25192}
25193
25194}
25195
25196}
25197}
25198}
25199}
25200}static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots)
25201{
25202 using std::complex;
25203 if( rawcoeffs[0] == 0 ) {
25204 // solve with one reduced degree
25205 polyroots2(&rawcoeffs[1], &rawroots[0], numroots);
25206 return;
25207 }
25208 IKFAST_ASSERT(rawcoeffs[0] != 0);
25209 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25210 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25211 complex<IkReal> coeffs[3];
25212 const int maxsteps = 110;
25213 for(int i = 0; i < 3; ++i) {
25214 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25215 }
25216 complex<IkReal> roots[3];
25217 IkReal err[3];
25218 roots[0] = complex<IkReal>(1,0);
25219 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25220 err[0] = 1.0;
25221 err[1] = 1.0;
25222 for(int i = 2; i < 3; ++i) {
25223 roots[i] = roots[i-1]*roots[1];
25224 err[i] = 1.0;
25225 }
25226 for(int step = 0; step < maxsteps; ++step) {
25227 bool changed = false;
25228 for(int i = 0; i < 3; ++i) {
25229 if ( err[i] >= tol ) {
25230 changed = true;
25231 // evaluate
25232 complex<IkReal> x = roots[i] + coeffs[0];
25233 for(int j = 1; j < 3; ++j) {
25234 x = roots[i] * x + coeffs[j];
25235 }
25236 for(int j = 0; j < 3; ++j) {
25237 if( i != j ) {
25238 if( roots[i] != roots[j] ) {
25239 x /= (roots[i] - roots[j]);
25240 }
25241 }
25242 }
25243 roots[i] -= x;
25244 err[i] = abs(x);
25245 }
25246 }
25247 if( !changed ) {
25248 break;
25249 }
25250 }
25251
25252 numroots = 0;
25253 bool visited[3] = {false};
25254 for(int i = 0; i < 3; ++i) {
25255 if( !visited[i] ) {
25256 // might be a multiple root, in which case it will have more error than the other roots
25257 // find any neighboring roots, and take the average
25258 complex<IkReal> newroot=roots[i];
25259 int n = 1;
25260 for(int j = i+1; j < 3; ++j) {
25261 // care about error in real much more than imaginary
25262 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25263 newroot += roots[j];
25264 n += 1;
25265 visited[j] = true;
25266 }
25267 }
25268 if( n > 1 ) {
25269 newroot /= n;
25270 }
25271 // 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
25272 if( IKabs(imag(newroot)) < tolsqrt ) {
25273 rawroots[numroots++] = real(newroot);
25274 }
25275 }
25276 }
25277}
25278static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) {
25279 IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2];
25280 if( det < 0 ) {
25281 numroots=0;
25282 }
25283 else if( det == 0 ) {
25284 rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0];
25285 numroots = 1;
25286 }
25287 else {
25288 det = IKsqrt(det);
25289 rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]);
25290 rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]);
25291 numroots = 2;
25292 }
25293}
25294static inline void polyroots5(IkReal rawcoeffs[5+1], IkReal rawroots[5], int& numroots)
25295{
25296 using std::complex;
25297 if( rawcoeffs[0] == 0 ) {
25298 // solve with one reduced degree
25299 polyroots4(&rawcoeffs[1], &rawroots[0], numroots);
25300 return;
25301 }
25302 IKFAST_ASSERT(rawcoeffs[0] != 0);
25303 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25304 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25305 complex<IkReal> coeffs[5];
25306 const int maxsteps = 110;
25307 for(int i = 0; i < 5; ++i) {
25308 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25309 }
25310 complex<IkReal> roots[5];
25311 IkReal err[5];
25312 roots[0] = complex<IkReal>(1,0);
25313 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25314 err[0] = 1.0;
25315 err[1] = 1.0;
25316 for(int i = 2; i < 5; ++i) {
25317 roots[i] = roots[i-1]*roots[1];
25318 err[i] = 1.0;
25319 }
25320 for(int step = 0; step < maxsteps; ++step) {
25321 bool changed = false;
25322 for(int i = 0; i < 5; ++i) {
25323 if ( err[i] >= tol ) {
25324 changed = true;
25325 // evaluate
25326 complex<IkReal> x = roots[i] + coeffs[0];
25327 for(int j = 1; j < 5; ++j) {
25328 x = roots[i] * x + coeffs[j];
25329 }
25330 for(int j = 0; j < 5; ++j) {
25331 if( i != j ) {
25332 if( roots[i] != roots[j] ) {
25333 x /= (roots[i] - roots[j]);
25334 }
25335 }
25336 }
25337 roots[i] -= x;
25338 err[i] = abs(x);
25339 }
25340 }
25341 if( !changed ) {
25342 break;
25343 }
25344 }
25345
25346 numroots = 0;
25347 bool visited[5] = {false};
25348 for(int i = 0; i < 5; ++i) {
25349 if( !visited[i] ) {
25350 // might be a multiple root, in which case it will have more error than the other roots
25351 // find any neighboring roots, and take the average
25352 complex<IkReal> newroot=roots[i];
25353 int n = 1;
25354 for(int j = i+1; j < 5; ++j) {
25355 // care about error in real much more than imaginary
25356 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25357 newroot += roots[j];
25358 n += 1;
25359 visited[j] = true;
25360 }
25361 }
25362 if( n > 1 ) {
25363 newroot /= n;
25364 }
25365 // 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
25366 if( IKabs(imag(newroot)) < tolsqrt ) {
25367 rawroots[numroots++] = real(newroot);
25368 }
25369 }
25370 }
25371}
25372static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
25373{
25374 using std::complex;
25375 if( rawcoeffs[0] == 0 ) {
25376 // solve with one reduced degree
25377 polyroots3(&rawcoeffs[1], &rawroots[0], numroots);
25378 return;
25379 }
25380 IKFAST_ASSERT(rawcoeffs[0] != 0);
25381 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25382 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25383 complex<IkReal> coeffs[4];
25384 const int maxsteps = 110;
25385 for(int i = 0; i < 4; ++i) {
25386 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25387 }
25388 complex<IkReal> roots[4];
25389 IkReal err[4];
25390 roots[0] = complex<IkReal>(1,0);
25391 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25392 err[0] = 1.0;
25393 err[1] = 1.0;
25394 for(int i = 2; i < 4; ++i) {
25395 roots[i] = roots[i-1]*roots[1];
25396 err[i] = 1.0;
25397 }
25398 for(int step = 0; step < maxsteps; ++step) {
25399 bool changed = false;
25400 for(int i = 0; i < 4; ++i) {
25401 if ( err[i] >= tol ) {
25402 changed = true;
25403 // evaluate
25404 complex<IkReal> x = roots[i] + coeffs[0];
25405 for(int j = 1; j < 4; ++j) {
25406 x = roots[i] * x + coeffs[j];
25407 }
25408 for(int j = 0; j < 4; ++j) {
25409 if( i != j ) {
25410 if( roots[i] != roots[j] ) {
25411 x /= (roots[i] - roots[j]);
25412 }
25413 }
25414 }
25415 roots[i] -= x;
25416 err[i] = abs(x);
25417 }
25418 }
25419 if( !changed ) {
25420 break;
25421 }
25422 }
25423
25424 numroots = 0;
25425 bool visited[4] = {false};
25426 for(int i = 0; i < 4; ++i) {
25427 if( !visited[i] ) {
25428 // might be a multiple root, in which case it will have more error than the other roots
25429 // find any neighboring roots, and take the average
25430 complex<IkReal> newroot=roots[i];
25431 int n = 1;
25432 for(int j = i+1; j < 4; ++j) {
25433 // care about error in real much more than imaginary
25434 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25435 newroot += roots[j];
25436 n += 1;
25437 visited[j] = true;
25438 }
25439 }
25440 if( n > 1 ) {
25441 newroot /= n;
25442 }
25443 // 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
25444 if( IKabs(imag(newroot)) < tolsqrt ) {
25445 rawroots[numroots++] = real(newroot);
25446 }
25447 }
25448 }
25449}
25450static inline void polyroots7(IkReal rawcoeffs[7+1], IkReal rawroots[7], int& numroots)
25451{
25452 using std::complex;
25453 if( rawcoeffs[0] == 0 ) {
25454 // solve with one reduced degree
25455 polyroots6(&rawcoeffs[1], &rawroots[0], numroots);
25456 return;
25457 }
25458 IKFAST_ASSERT(rawcoeffs[0] != 0);
25459 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25460 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25461 complex<IkReal> coeffs[7];
25462 const int maxsteps = 110;
25463 for(int i = 0; i < 7; ++i) {
25464 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25465 }
25466 complex<IkReal> roots[7];
25467 IkReal err[7];
25468 roots[0] = complex<IkReal>(1,0);
25469 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25470 err[0] = 1.0;
25471 err[1] = 1.0;
25472 for(int i = 2; i < 7; ++i) {
25473 roots[i] = roots[i-1]*roots[1];
25474 err[i] = 1.0;
25475 }
25476 for(int step = 0; step < maxsteps; ++step) {
25477 bool changed = false;
25478 for(int i = 0; i < 7; ++i) {
25479 if ( err[i] >= tol ) {
25480 changed = true;
25481 // evaluate
25482 complex<IkReal> x = roots[i] + coeffs[0];
25483 for(int j = 1; j < 7; ++j) {
25484 x = roots[i] * x + coeffs[j];
25485 }
25486 for(int j = 0; j < 7; ++j) {
25487 if( i != j ) {
25488 if( roots[i] != roots[j] ) {
25489 x /= (roots[i] - roots[j]);
25490 }
25491 }
25492 }
25493 roots[i] -= x;
25494 err[i] = abs(x);
25495 }
25496 }
25497 if( !changed ) {
25498 break;
25499 }
25500 }
25501
25502 numroots = 0;
25503 bool visited[7] = {false};
25504 for(int i = 0; i < 7; ++i) {
25505 if( !visited[i] ) {
25506 // might be a multiple root, in which case it will have more error than the other roots
25507 // find any neighboring roots, and take the average
25508 complex<IkReal> newroot=roots[i];
25509 int n = 1;
25510 for(int j = i+1; j < 7; ++j) {
25511 // care about error in real much more than imaginary
25512 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25513 newroot += roots[j];
25514 n += 1;
25515 visited[j] = true;
25516 }
25517 }
25518 if( n > 1 ) {
25519 newroot /= n;
25520 }
25521 // 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
25522 if( IKabs(imag(newroot)) < tolsqrt ) {
25523 rawroots[numroots++] = real(newroot);
25524 }
25525 }
25526 }
25527}
25528static inline void polyroots6(IkReal rawcoeffs[6+1], IkReal rawroots[6], int& numroots)
25529{
25530 using std::complex;
25531 if( rawcoeffs[0] == 0 ) {
25532 // solve with one reduced degree
25533 polyroots5(&rawcoeffs[1], &rawroots[0], numroots);
25534 return;
25535 }
25536 IKFAST_ASSERT(rawcoeffs[0] != 0);
25537 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25538 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25539 complex<IkReal> coeffs[6];
25540 const int maxsteps = 110;
25541 for(int i = 0; i < 6; ++i) {
25542 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25543 }
25544 complex<IkReal> roots[6];
25545 IkReal err[6];
25546 roots[0] = complex<IkReal>(1,0);
25547 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25548 err[0] = 1.0;
25549 err[1] = 1.0;
25550 for(int i = 2; i < 6; ++i) {
25551 roots[i] = roots[i-1]*roots[1];
25552 err[i] = 1.0;
25553 }
25554 for(int step = 0; step < maxsteps; ++step) {
25555 bool changed = false;
25556 for(int i = 0; i < 6; ++i) {
25557 if ( err[i] >= tol ) {
25558 changed = true;
25559 // evaluate
25560 complex<IkReal> x = roots[i] + coeffs[0];
25561 for(int j = 1; j < 6; ++j) {
25562 x = roots[i] * x + coeffs[j];
25563 }
25564 for(int j = 0; j < 6; ++j) {
25565 if( i != j ) {
25566 if( roots[i] != roots[j] ) {
25567 x /= (roots[i] - roots[j]);
25568 }
25569 }
25570 }
25571 roots[i] -= x;
25572 err[i] = abs(x);
25573 }
25574 }
25575 if( !changed ) {
25576 break;
25577 }
25578 }
25579
25580 numroots = 0;
25581 bool visited[6] = {false};
25582 for(int i = 0; i < 6; ++i) {
25583 if( !visited[i] ) {
25584 // might be a multiple root, in which case it will have more error than the other roots
25585 // find any neighboring roots, and take the average
25586 complex<IkReal> newroot=roots[i];
25587 int n = 1;
25588 for(int j = i+1; j < 6; ++j) {
25589 // care about error in real much more than imaginary
25590 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25591 newroot += roots[j];
25592 n += 1;
25593 visited[j] = true;
25594 }
25595 }
25596 if( n > 1 ) {
25597 newroot /= n;
25598 }
25599 // 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
25600 if( IKabs(imag(newroot)) < tolsqrt ) {
25601 rawroots[numroots++] = real(newroot);
25602 }
25603 }
25604 }
25605}
25606static inline void polyroots8(IkReal rawcoeffs[8+1], IkReal rawroots[8], int& numroots)
25607{
25608 using std::complex;
25609 if( rawcoeffs[0] == 0 ) {
25610 // solve with one reduced degree
25611 polyroots7(&rawcoeffs[1], &rawroots[0], numroots);
25612 return;
25613 }
25614 IKFAST_ASSERT(rawcoeffs[0] != 0);
25615 const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
25616 const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
25617 complex<IkReal> coeffs[8];
25618 const int maxsteps = 110;
25619 for(int i = 0; i < 8; ++i) {
25620 coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
25621 }
25622 complex<IkReal> roots[8];
25623 IkReal err[8];
25624 roots[0] = complex<IkReal>(1,0);
25625 roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
25626 err[0] = 1.0;
25627 err[1] = 1.0;
25628 for(int i = 2; i < 8; ++i) {
25629 roots[i] = roots[i-1]*roots[1];
25630 err[i] = 1.0;
25631 }
25632 for(int step = 0; step < maxsteps; ++step) {
25633 bool changed = false;
25634 for(int i = 0; i < 8; ++i) {
25635 if ( err[i] >= tol ) {
25636 changed = true;
25637 // evaluate
25638 complex<IkReal> x = roots[i] + coeffs[0];
25639 for(int j = 1; j < 8; ++j) {
25640 x = roots[i] * x + coeffs[j];
25641 }
25642 for(int j = 0; j < 8; ++j) {
25643 if( i != j ) {
25644 if( roots[i] != roots[j] ) {
25645 x /= (roots[i] - roots[j]);
25646 }
25647 }
25648 }
25649 roots[i] -= x;
25650 err[i] = abs(x);
25651 }
25652 }
25653 if( !changed ) {
25654 break;
25655 }
25656 }
25657
25658 numroots = 0;
25659 bool visited[8] = {false};
25660 for(int i = 0; i < 8; ++i) {
25661 if( !visited[i] ) {
25662 // might be a multiple root, in which case it will have more error than the other roots
25663 // find any neighboring roots, and take the average
25664 complex<IkReal> newroot=roots[i];
25665 int n = 1;
25666 for(int j = i+1; j < 8; ++j) {
25667 // care about error in real much more than imaginary
25668 if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) {
25669 newroot += roots[j];
25670 n += 1;
25671 visited[j] = true;
25672 }
25673 }
25674 if( n > 1 ) {
25675 newroot /= n;
25676 }
25677 // 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
25678 if( IKabs(imag(newroot)) < tolsqrt ) {
25679 rawroots[numroots++] = real(newroot);
25680 }
25681 }
25682 }
25683}
25684};
25685
25686
25687/// solves the inverse kinematics equations.
25688/// \param pfree is an array specifying the free joints of the chain.
25689IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
25690IKSolver solver;
25691return solver.ComputeIk(eetrans,eerot,pfree,solutions);
25692}
25693
25694IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions, void* pOpenRAVEManip) {
25695IKSolver solver;
25696return solver.ComputeIk(eetrans,eerot,pfree,solutions);
25697}
25698
25699IKFAST_API const char* GetKinematicsHash() { return "<robot:GenericRobot - hya (58dbf1259c2cdf57f1e3d77f555c8c6b)>"; }
25700
25701IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; }
25702
25703#ifdef IKFAST_NAMESPACE
25704} // end namespace
25705#endif
25706
25707#ifndef IKFAST_NO_MAIN
25708#include <stdio.h>
25709#include <stdlib.h>
25710#ifdef IKFAST_NAMESPACE
25711using namespace IKFAST_NAMESPACE;
25712#endif
25713int main(int argc, char** argv)
25714{
25715 if( argc != 12+GetNumFreeParameters()+1 ) {
25716 printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
25717 "Returns the ik solutions given the transformation of the end effector specified by\n"
25718 "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
25719 "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
25720 return 1;
25721 }
25722
25723 IkSolutionList<IkReal> solutions;
25724 std::vector<IkReal> vfree(GetNumFreeParameters());
25725 IkReal eerot[9],eetrans[3];
25726 eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
25727 eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
25728 eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
25729 for(std::size_t i = 0; i < vfree.size(); ++i)
25730 vfree[i] = atof(argv[13+i]);
25731 bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
25732
25733 if( !bSuccess ) {
25734 fprintf(stderr,"Failed to get ik solution\n");
25735 return -1;
25736 }
25737
25738 printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
25739 std::vector<IkReal> solvalues(GetNumJoints());
25740 for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
25741 const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
25742 printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
25743 std::vector<IkReal> vsolfree(sol.GetFree().size());
25744 sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
25745 for( std::size_t j = 0; j < solvalues.size(); ++j)
25746 printf("%.15f, ", solvalues[j]);
25747 printf("\n");
25748 }
25749 return 0;
25750}
25751
25752#endif