baxter_left_arm_ikfast_solver.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 #define IKFAST_HAS_LIBRARY
00021 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
00022 using namespace ikfast;
00023 
00024 // check if the included ikfast version matches what this file was compiled with
00025 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
00026 IKFAST_COMPILE_ASSERT(IKFAST_VERSION==61);
00027 
00028 #include <cmath>
00029 #include <vector>
00030 #include <limits>
00031 #include <algorithm>
00032 #include <complex>
00033 
00034 #define IKFAST_STRINGIZE2(s) #s
00035 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
00036 
00037 #ifndef IKFAST_ASSERT
00038 #include <stdexcept>
00039 #include <sstream>
00040 #include <iostream>
00041 
00042 #ifdef _MSC_VER
00043 #ifndef __PRETTY_FUNCTION__
00044 #define __PRETTY_FUNCTION__ __FUNCDNAME__
00045 #endif
00046 #endif
00047 
00048 #ifndef __PRETTY_FUNCTION__
00049 #define __PRETTY_FUNCTION__ __func__
00050 #endif
00051 
00052 #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()); } }
00053 
00054 #endif
00055 
00056 #if defined(_MSC_VER)
00057 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
00058 #else
00059 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
00060 #endif
00061 
00062 #define IK2PI  ((IkReal)6.28318530717959)
00063 #define IKPI  ((IkReal)3.14159265358979)
00064 #define IKPI_2  ((IkReal)1.57079632679490)
00065 
00066 #ifdef _MSC_VER
00067 #ifndef isnan
00068 #define isnan _isnan
00069 #endif
00070 #endif // _MSC_VER
00071 
00072 // lapack routines
00073 extern "C" {
00074   void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
00075   void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
00076   void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
00077   void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
00078   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);
00079   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);
00080 }
00081 
00082 using namespace std; // necessary to get std math routines
00083 
00084 #ifdef IKFAST_NAMESPACE
00085 namespace IKFAST_NAMESPACE {
00086 #endif
00087 
00088 inline float IKabs(float f) { return fabsf(f); }
00089 inline double IKabs(double f) { return fabs(f); }
00090 
00091 inline float IKsqr(float f) { return f*f; }
00092 inline double IKsqr(double f) { return f*f; }
00093 
00094 inline float IKlog(float f) { return logf(f); }
00095 inline double IKlog(double f) { return log(f); }
00096 
00097 // allows asin and acos to exceed 1
00098 #ifndef IKFAST_SINCOS_THRESH
00099 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
00100 #endif
00101 
00102 // used to check input to atan2 for degenerate cases
00103 #ifndef IKFAST_ATAN2_MAGTHRESH
00104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
00105 #endif
00106 
00107 // minimum distance of separate solutions
00108 #ifndef IKFAST_SOLUTION_THRESH
00109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
00110 #endif
00111 
00112 inline float IKasin(float f)
00113 {
00114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00115 if( f <= -1 ) return float(-IKPI_2);
00116 else if( f >= 1 ) return float(IKPI_2);
00117 return asinf(f);
00118 }
00119 inline double IKasin(double f)
00120 {
00121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00122 if( f <= -1 ) return -IKPI_2;
00123 else if( f >= 1 ) return IKPI_2;
00124 return asin(f);
00125 }
00126 
00127 // return positive value in [0,y)
00128 inline float IKfmod(float x, float y)
00129 {
00130     while(x < 0) {
00131         x += y;
00132     }
00133     return fmodf(x,y);
00134 }
00135 
00136 // return positive value in [0,y)
00137 inline double IKfmod(double x, double y)
00138 {
00139     while(x < 0) {
00140         x += y;
00141     }
00142     return fmod(x,y);
00143 }
00144 
00145 inline float IKacos(float f)
00146 {
00147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00148 if( f <= -1 ) return float(IKPI);
00149 else if( f >= 1 ) return float(0);
00150 return acosf(f);
00151 }
00152 inline double IKacos(double f)
00153 {
00154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00155 if( f <= -1 ) return IKPI;
00156 else if( f >= 1 ) return 0;
00157 return acos(f);
00158 }
00159 inline float IKsin(float f) { return sinf(f); }
00160 inline double IKsin(double f) { return sin(f); }
00161 inline float IKcos(float f) { return cosf(f); }
00162 inline double IKcos(double f) { return cos(f); }
00163 inline float IKtan(float f) { return tanf(f); }
00164 inline double IKtan(double f) { return tan(f); }
00165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
00166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
00167 inline float IKatan2(float fy, float fx) {
00168     if( isnan(fy) ) {
00169         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00170         return float(IKPI_2);
00171     }
00172     else if( isnan(fx) ) {
00173         return 0;
00174     }
00175     return atan2f(fy,fx);
00176 }
00177 inline double IKatan2(double fy, double fx) {
00178     if( isnan(fy) ) {
00179         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00180         return IKPI_2;
00181     }
00182     else if( isnan(fx) ) {
00183         return 0;
00184     }
00185     return atan2(fy,fx);
00186 }
00187 
00188 inline float IKsign(float f) {
00189     if( f > 0 ) {
00190         return float(1);
00191     }
00192     else if( f < 0 ) {
00193         return float(-1);
00194     }
00195     return 0;
00196 }
00197 
00198 inline double IKsign(double f) {
00199     if( f > 0 ) {
00200         return 1.0;
00201     }
00202     else if( f < 0 ) {
00203         return -1.0;
00204     }
00205     return 0;
00206 }
00207 
00210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
00211 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42,x43,x44,x45,x46,x47,x48,x49,x50,x51,x52,x53,x54,x55,x56,x57,x58,x59,x60,x61,x62,x63,x64,x65,x66,x67,x68,x69,x70,x71,x72,x73;
00212 x0=IKcos(j[0]);
00213 x1=IKcos(j[2]);
00214 x2=IKsin(j[1]);
00215 x3=IKsin(j[0]);
00216 x4=IKsin(j[2]);
00217 x5=IKsin(j[3]);
00218 x6=IKcos(j[1]);
00219 x7=IKcos(j[3]);
00220 x8=IKsin(j[4]);
00221 x9=IKcos(j[4]);
00222 x10=IKcos(j[6]);
00223 x11=IKsin(j[6]);
00224 x12=IKsin(j[5]);
00225 x13=IKcos(j[5]);
00226 x14=((IkReal(0.0690000000000000))*(x0));
00227 x15=((IkReal(0.0100000000000000))*(x7));
00228 x16=((IkReal(1.00000000000000))*(x3));
00229 x17=((IkReal(0.279525000000000))*(x5));
00230 x18=((IkReal(1.00000000000000))*(x9));
00231 x19=((IkReal(0.279525000000000))*(x9));
00232 x20=((IkReal(1.00000000000000))*(x5));
00233 x21=((IkReal(0.374290000000000))*(x3));
00234 x22=((IkReal(0.374290000000000))*(x0));
00235 x23=((IkReal(1.00000000000000))*(x0));
00236 x24=((IkReal(0.0100000000000000))*(x2));
00237 x25=((IkReal(1.00000000000000))*(x8));
00238 x26=((IkReal(0.279525000000000))*(x8));
00239 x27=((IkReal(0.0690000000000000))*(x3));
00240 x28=((IkReal(0.0100000000000000))*(x0));
00241 x29=((IkReal(-1.00000000000000))*(x9));
00242 x30=((x2)*(x7));
00243 x31=((x1)*(x6));
00244 x32=((IkReal(-1.00000000000000))*(x12));
00245 x33=((x1)*(x2));
00246 x34=((x0)*(x4));
00247 x35=((x5)*(x6));
00248 x36=((x3)*(x6));
00249 x37=((x6)*(x7));
00250 x38=((IkReal(-1.00000000000000))*(x8));
00251 x39=((x1)*(x3));
00252 x40=((x4)*(x6));
00253 x41=((IkReal(-1.00000000000000))*(x13));
00254 x42=((x2)*(x23)*(x4));
00255 x43=((x23)*(x37));
00256 x44=((x16)*(x33));
00257 x45=((x16)*(x37));
00258 x46=((x18)*(x40));
00259 x47=((x39)+(((IkReal(-1.00000000000000))*(x42))));
00260 x48=((((IkReal(-1.00000000000000))*(x44)))+(x34));
00261 x49=((((IkReal(-1.00000000000000))*(x31)*(x7)))+(((x2)*(x5))));
00262 x50=((((x31)*(x5)))+(x30));
00263 x51=((x42)+(((IkReal(-1.00000000000000))*(x1)*(x16))));
00264 x52=((x44)+(((IkReal(-1.00000000000000))*(x23)*(x4))));
00265 x53=((((x23)*(x33)))+(((x16)*(x4))));
00266 x54=((IkReal(-1.00000000000000))*(x53));
00267 x55=((((x1)*(x23)))+(((x16)*(x2)*(x4))));
00268 x56=((x48)*(x7));
00269 x57=((x5)*(x52));
00270 x58=((x51)*(x8));
00271 x59=((x54)*(x7));
00272 x60=((x55)*(x8));
00273 x61=((x5)*(x53));
00274 x62=((x56)+(((IkReal(-1.00000000000000))*(x16)*(x35))));
00275 x63=((((x40)*(x8)))+(((x49)*(x9))));
00276 x64=((x57)+(((IkReal(-1.00000000000000))*(x45))));
00277 x65=((x59)+(((IkReal(-1.00000000000000))*(x0)*(x20)*(x6))));
00278 x66=((x61)+(((IkReal(-1.00000000000000))*(x43))));
00279 x67=((x13)*(x63));
00280 x68=((x12)*(x64));
00281 x69=((x60)+(((x62)*(x9))));
00282 x70=((x58)+(((x65)*(x9))));
00283 x71=((x13)*(x69));
00284 x72=((((IkReal(-1.00000000000000))*(x29)*(x55)))+(((x38)*(x62))));
00285 x73=((x13)*(x70));
00286 eerot[0]=((((x10)*(((((x12)*(x66)))+(x73)))))+(((x11)*(((((x38)*(x65)))+(((x29)*(x47))))))));
00287 eerot[1]=((((x10)*(((((IkReal(-1.00000000000000))*(x25)*(x65)))+(((IkReal(-1.00000000000000))*(x18)*(x47)))))))+(((x11)*(((((x32)*(x66)))+(((x41)*(x70))))))));
00288 eerot[2]=((((x13)*(((x43)+(((IkReal(-1.00000000000000))*(x20)*(x53)))))))+(((x12)*(x70))));
00289 IkReal x74=((IkReal(1.00000000000000))*(x35));
00290 IkReal x75=((IkReal(1.00000000000000))*(x4));
00291 IkReal x76=((IkReal(1.00000000000000))*(x33));
00292 eetrans[0]=((IkReal(0.0556950000000000))+(((x12)*(((((x26)*(x51)))+(((x19)*(((x59)+(((IkReal(-1.00000000000000))*(x0)*(x74)))))))))))+(((IkReal(-1.00000000000000))*(x27)*(x75)))+(x14)+(((IkReal(-1.00000000000000))*(x14)*(x76)))+(((x22)*(x37)))+(((x5)*(((((IkReal(-1.00000000000000))*(x22)*(x76)))+(((IkReal(-1.00000000000000))*(x21)*(x75)))))))+(((x9)*(((((x15)*(x54)))+(((IkReal(-1.00000000000000))*(x28)*(x74)))))))+(((x13)*(((((IkReal(0.279525000000000))*(x0)*(x37)))+(((IkReal(-1.00000000000000))*(x17)*(x53)))))))+(((IkReal(0.364420000000000))*(x0)*(x6)))+(((x8)*(((((x24)*(x34)))+(((IkReal(-0.0100000000000000))*(x39))))))));
00293 eerot[3]=((((x10)*(((x68)+(x71)))))+(((x11)*(x72))));
00294 eerot[4]=((((x10)*(x72)))+(((x11)*(((((IkReal(-1.00000000000000))*(x71)))+(((IkReal(-1.00000000000000))*(x68))))))));
00295 eerot[5]=((((x12)*(x69)))+(((x13)*(((((IkReal(-1.00000000000000))*(x20)*(x52)))+(x45))))));
00296 IkReal x77=((x3)*(x35));
00297 IkReal x78=((IkReal(1.00000000000000))*(x33));
00298 eetrans[1]=((((x12)*(((((x26)*(x55)))+(((x19)*(((x56)+(((IkReal(-1.00000000000000))*(x77)))))))))))+(((IkReal(-1.00000000000000))*(x27)*(x78)))+(x27)+(((x8)*(((((x24)*(x3)*(x4)))+(((x1)*(x28)))))))+(((x9)*(((((x15)*(x48)))+(((IkReal(-0.0100000000000000))*(x77)))))))+(((x21)*(x37)))+(((x13)*(((((IkReal(-1.00000000000000))*(x17)*(x52)))+(((IkReal(0.279525000000000))*(x36)*(x7)))))))+(((x5)*(((((x22)*(x4)))+(((IkReal(-1.00000000000000))*(x21)*(x78)))))))+(((IkReal(0.364420000000000))*(x36)))+(((x14)*(x4))));
00299 eerot[6]=((((x11)*(((x46)+(((x38)*(x49)))))))+(((x10)*(((((x12)*(x50)))+(x67))))));
00300 eerot[7]=((((x10)*(((x46)+(((IkReal(-1.00000000000000))*(x25)*(x49)))))))+(((x11)*(((((x32)*(x50)))+(((x41)*(x63))))))));
00301 eerot[8]=((((x13)*(((((IkReal(-1.00000000000000))*(x30)))+(((IkReal(-1.00000000000000))*(x20)*(x31)))))))+(((x12)*(x63))));
00302 IkReal x79=((IkReal(1.00000000000000))*(x31));
00303 eetrans[2]=((IkReal(0.281388000000000))+(((IkReal(-0.0690000000000000))*(x31)))+(((IkReal(0.0100000000000000))*(x40)*(x8)))+(((IkReal(-0.374290000000000))*(x30)))+(((IkReal(-0.364420000000000))*(x2)))+(((x12)*(((((x19)*(x49)))+(((x26)*(x40)))))))+(((x13)*(((((IkReal(-0.279525000000000))*(x30)))+(((IkReal(-1.00000000000000))*(x17)*(x79)))))))+(((x9)*(((((IkReal(-1.00000000000000))*(x15)*(x79)))+(((x24)*(x5)))))))+(((IkReal(-0.374290000000000))*(x31)*(x5))));
00304 }
00305 
00306 IKFAST_API int GetNumFreeParameters() { return 1; }
00307 IKFAST_API int* GetFreeParameters() { static int freeparams[] = {5}; return freeparams; }
00308 IKFAST_API int GetNumJoints() { return 7; }
00309 
00310 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00311 
00312 IKFAST_API int GetIkType() { return 0x67000001; }
00313 
00314 class IKSolver {
00315 public:
00316 IkReal j0,cj0,sj0,htj0,j1,cj1,sj1,htj1,j2,cj2,sj2,htj2,j3,cj3,sj3,htj3,j4,cj4,sj4,htj4,j6,cj6,sj6,htj6,j5,cj5,sj5,htj5,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;
00317 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij6[2], _nj6,_ij5[2], _nj5;
00318 
00319 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00320 j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; j6=numeric_limits<IkReal>::quiet_NaN(); _ij6[0] = -1; _ij6[1] = -1; _nj6 = -1;  _ij5[0] = -1; _ij5[1] = -1; _nj5 = 0; 
00321 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00322     solutions.Clear();
00323 j5=pfree[0]; cj5=cos(pfree[0]); sj5=sin(pfree[0]);
00324 r00 = eerot[0*3+0];
00325 r01 = eerot[0*3+1];
00326 r02 = eerot[0*3+2];
00327 r10 = eerot[1*3+0];
00328 r11 = eerot[1*3+1];
00329 r12 = eerot[1*3+2];
00330 r20 = eerot[2*3+0];
00331 r21 = eerot[2*3+1];
00332 r22 = eerot[2*3+2];
00333 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00334 
00335 new_r00=((IkReal(-1.00000000000000))*(r01));
00336 new_r01=r00;
00337 new_r02=r02;
00338 new_px=((IkReal(-0.0556950000000000))+(((IkReal(-0.279525000000000))*(r02)))+(px));
00339 new_r10=((IkReal(-1.00000000000000))*(r11));
00340 new_r11=r10;
00341 new_r12=r12;
00342 new_py=((((IkReal(-0.279525000000000))*(r12)))+(py));
00343 new_r20=((IkReal(-1.00000000000000))*(r21));
00344 new_r21=r20;
00345 new_r22=r22;
00346 new_pz=((IkReal(-0.281388000000000))+(((IkReal(-0.279525000000000))*(r22)))+(pz));
00347 r00 = new_r00; r01 = new_r01; r02 = new_r02; r10 = new_r10; r11 = new_r11; r12 = new_r12; r20 = new_r20; r21 = new_r21; r22 = new_r22; px = new_px; py = new_py; pz = new_pz;
00348 pp=(((px)*(px))+((pz)*(pz))+((py)*(py)));
00349 npx=((((py)*(r10)))+(((pz)*(r20)))+(((px)*(r00))));
00350 npy=((((px)*(r01)))+(((pz)*(r21)))+(((py)*(r11))));
00351 npz=((((py)*(r12)))+(((pz)*(r22)))+(((px)*(r02))));
00352 rxp0_0=((((IkReal(-1.00000000000000))*(py)*(r20)))+(((pz)*(r10))));
00353 rxp0_1=((((px)*(r20)))+(((IkReal(-1.00000000000000))*(pz)*(r00))));
00354 rxp0_2=((((py)*(r00)))+(((IkReal(-1.00000000000000))*(px)*(r10))));
00355 rxp1_0=((((pz)*(r11)))+(((IkReal(-1.00000000000000))*(py)*(r21))));
00356 rxp1_1=((((IkReal(-1.00000000000000))*(pz)*(r01)))+(((px)*(r21))));
00357 rxp1_2=((((py)*(r01)))+(((IkReal(-1.00000000000000))*(px)*(r11))));
00358 rxp2_0=((((IkReal(-1.00000000000000))*(py)*(r22)))+(((pz)*(r12))));
00359 rxp2_1=((((px)*(r22)))+(((IkReal(-1.00000000000000))*(pz)*(r02))));
00360 rxp2_2=((((py)*(r02)))+(((IkReal(-1.00000000000000))*(px)*(r12))));
00361 IkReal op[72], zeror[48];
00362 int numroots;
00363 IkReal x80=((IkReal(0.138000000000000))*(px));
00364 IkReal x81=((IkReal(0.748580000000000))*(py));
00365 IkReal x82=((IkReal(0.0200000000000000))*(rxp0_1));
00366 IkReal x83=((IkReal(0.00866840000000000))*(r20));
00367 IkReal x84=((IkReal(0.00728840000000000))*(r00));
00368 IkReal x85=((IkReal(0.0400000000000000))*(rxp1_1));
00369 IkReal x86=((IkReal(0.00590840000000000))*(r20));
00370 IkReal x87=((IkReal(0.276000000000000))*(py));
00371 IkReal x88=((IkReal(1.49716000000000))*(px));
00372 IkReal x89=((IkReal(0.0400000000000000))*(rxp0_0));
00373 IkReal x90=((IkReal(0.0145768000000000))*(r10));
00374 IkReal x91=((IkReal(0.0800000000000000))*(rxp1_0));
00375 IkReal x92=((IkReal(0.0173368000000000))*(r21));
00376 IkReal x93=((IkReal(0.0118168000000000))*(r21));
00377 IkReal x94=((cj5)*(r00));
00378 IkReal x95=((IkReal(0.0959180554000000))*(sj5));
00379 IkReal x96=((cj5)*(r12));
00380 IkReal x97=((cj5)*(r02));
00381 IkReal x98=((r11)*(sj5));
00382 IkReal x99=((r12)*(sj5));
00383 IkReal x100=((r02)*(sj5));
00384 IkReal x101=((rxp1_2)*(sj5));
00385 IkReal x102=((cj5)*(rxp2_2));
00386 IkReal x103=((r00)*(sj5));
00387 IkReal x104=((npx)*(sj5));
00388 IkReal x105=((r10)*(sj5));
00389 IkReal x106=((IkReal(2.00000000000000))*(pp));
00390 IkReal x107=((rxp0_2)*(sj5));
00391 IkReal x108=((IkReal(1.45768000000000))*(sj5));
00392 IkReal x109=((cj5)*(r01));
00393 IkReal x110=((IkReal(1.00000000000000))*(pp));
00394 IkReal x111=((cj5)*(npz));
00395 IkReal x112=((IkReal(4.00000000000000))*(px));
00396 IkReal x113=((r01)*(sj5));
00397 IkReal x114=((cj5)*(r10));
00398 IkReal x115=((npy)*(sj5));
00399 IkReal x116=((IkReal(2.00000000000000))*(py));
00400 IkReal x117=((cj5)*(r11));
00401 IkReal x118=((IkReal(0.0516520200000000))*(x97));
00402 IkReal x119=((IkReal(0.0200000000000000))*(cj5)*(npy));
00403 IkReal x120=((IkReal(0.00138000000000000))*(x100));
00404 IkReal x121=((IkReal(0.0516520200000000))*(x113));
00405 IkReal x122=((IkReal(0.748580000000000))*(x111));
00406 IkReal x123=((IkReal(0.00138000000000000))*(x109));
00407 IkReal x124=((IkReal(0.748580000000000))*(x115));
00408 IkReal x125=((IkReal(0.0200000000000000))*(npz)*(sj5));
00409 IkReal x126=((IkReal(0.0526208923000000))*(x98));
00410 IkReal x127=((IkReal(0.0526208923000000))*(x96));
00411 IkReal x128=((IkReal(0.00748580000000000))*(x117));
00412 IkReal x129=((IkReal(0.866840000000000))*(x102));
00413 IkReal x130=((pp)*(x96));
00414 IkReal x131=((IkReal(0.866840000000000))*(x101));
00415 IkReal x132=((IkReal(0.00748580000000000))*(x99));
00416 IkReal x133=((IkReal(0.728840000000000))*(cj5)*(rxp2_0));
00417 IkReal x134=((IkReal(0.728840000000000))*(rxp1_0)*(sj5));
00418 IkReal x135=((IkReal(0.0149716000000000))*(x114));
00419 IkReal x136=((pp)*(x98));
00420 IkReal x137=((IkReal(0.0479590277000000))*(x98));
00421 IkReal x138=((IkReal(0.0479590277000000))*(x96));
00422 IkReal x139=((IkReal(0.590840000000000))*(x102));
00423 IkReal x140=((IkReal(0.590840000000000))*(x101));
00424 IkReal x141=((IkReal(0.103304040000000))*(x96));
00425 IkReal x142=((IkReal(0.103304040000000))*(x98));
00426 IkReal x143=((IkReal(0.00276000000000000))*(x99));
00427 IkReal x144=((IkReal(0.00276000000000000))*(x117));
00428 IkReal x145=((IkReal(0.0149716000000000))*(x100));
00429 IkReal x146=((IkReal(0.105241784600000))*(x97));
00430 IkReal x147=((IkReal(0.105241784600000))*(x113));
00431 IkReal x148=((IkReal(0.0149716000000000))*(x109));
00432 IkReal x149=((IkReal(1.45768000000000))*(cj5)*(rxp2_1));
00433 IkReal x150=((rxp1_1)*(x108));
00434 IkReal x151=((IkReal(0.0299432000000000))*(x94));
00435 IkReal x152=((IkReal(0.0959180554000000))*(x97));
00436 IkReal x153=((r01)*(x95));
00437 IkReal x154=((IkReal(0.103304040000000))*(x103));
00438 IkReal x155=((IkReal(1.49716000000000))*(x104));
00439 IkReal x156=((IkReal(0.0400000000000000))*(cj5)*(npx));
00440 IkReal x157=((IkReal(0.00276000000000000))*(x94));
00441 IkReal x158=((IkReal(0.105241784600000))*(x105));
00442 IkReal x159=((IkReal(1.73368000000000))*(x107));
00443 IkReal x160=((IkReal(1.18168000000000))*(x107));
00444 IkReal x161=((r10)*(x95));
00445 IkReal x162=((x115)*(x116));
00446 IkReal x163=((x111)*(x116));
00447 IkReal x164=((x110)*(x98));
00448 IkReal x165=((IkReal(4.00000000000000))*(py)*(x104));
00449 IkReal x166=((x105)*(x106));
00450 IkReal x167=((x112)*(x115));
00451 IkReal x168=((x111)*(x112));
00452 IkReal x169=((x106)*(x113));
00453 IkReal x170=((x106)*(x97));
00454 IkReal x171=((IkReal(4.00000000000000))*(pp)*(x103));
00455 IkReal x172=((IkReal(8.00000000000000))*(px)*(x104));
00456 IkReal x173=((x110)*(x96));
00457 IkReal x174=((((IkReal(-1.00000000000000))*(rxp0_0)*(x108)))+(((IkReal(-0.0145768000000000))*(r01))));
00458 IkReal x175=((((IkReal(0.00552000000000000))*(x114)))+(((IkReal(-0.206608080000000))*(x105))));
00459 IkReal x176=((((IkReal(-0.0291536000000000))*(r11)))+(((IkReal(-2.91536000000000))*(rxp0_1)*(sj5))));
00460 IkReal x177=((x133)+(x84));
00461 IkReal x178=((((IkReal(0.0145768000000000))*(r01)))+(((rxp0_0)*(x108))));
00462 IkReal x179=((x129)+(x83));
00463 IkReal x180=((x130)+(x81));
00464 IkReal x181=((x159)+(x92));
00465 IkReal x182=((IkReal(0.00739106770000000))+(x123)+(pp));
00466 IkReal x183=((x119)+(x80));
00467 IkReal x184=((x124)+(x80));
00468 IkReal x185=((IkReal(0.00739106770000000))+(x121)+(pp));
00469 IkReal x186=((x160)+(x93));
00470 IkReal x187=((x134)+(x133));
00471 IkReal x188=((x173)+(x81));
00472 IkReal x189=((x139)+(x140));
00473 IkReal x190=((x170)+(x88));
00474 IkReal x191=((x126)+(x131));
00475 IkReal x192=((x125)+(x122));
00476 IkReal x193=((x172)+(x91));
00477 IkReal x194=((x165)+(x85));
00478 IkReal x195=((x141)+(x143));
00479 IkReal x196=((x177)+(((IkReal(-1.00000000000000))*(x134))));
00480 IkReal x197=((x187)+(((IkReal(-1.00000000000000))*(x84))));
00481 IkReal x198=((((IkReal(-1.00000000000000))*(x150)))+(x149)+(x90));
00482 IkReal x199=((x150)+(((IkReal(-1.00000000000000))*(x90)))+(x149));
00483 IkReal x200=((((IkReal(-1.00000000000000))*(x177)))+(x134));
00484 IkReal x201=((((IkReal(-1.00000000000000))*(x187)))+(x84));
00485 IkReal x202=((x163)+(x132));
00486 IkReal x203=((x127)+(x162));
00487 IkReal x204=((x153)+(x167));
00488 IkReal x205=((x168)+(x145));
00489 IkReal x206=((x171)+(x151));
00490 IkReal x207=((x166)+(x135));
00491 IkReal x208=((x162)+(x137));
00492 IkReal x209=((x128)+(x136)+(x82));
00493 IkReal x210=((x128)+(x164)+(x82));
00494 IkReal x211=((x169)+(x148)+(x89));
00495 IkReal x212=((x124)+(x120)+(x118));
00496 IkReal x213=((x208)+(x86));
00497 IkReal x214=((x194)+(x161));
00498 IkReal x215=((x120)+(x119)+(x118));
00499 IkReal x216=((x158)+(x207));
00500 IkReal x217=((x152)+(x205));
00501 IkReal x218=((((IkReal(-1.00000000000000))*(x154)))+(x157)+(x155)+(((IkReal(-1.00000000000000))*(x156))));
00502 IkReal x219=((x155)+(x154)+(((IkReal(-1.00000000000000))*(x157)))+(((IkReal(-1.00000000000000))*(x156))));
00503 IkReal x220=((((IkReal(-1.00000000000000))*(x142)))+(x195)+(x144)+(((IkReal(-1.00000000000000))*(x87))));
00504 IkReal x221=((x195)+(x142)+(((IkReal(-1.00000000000000))*(x144)))+(((IkReal(-1.00000000000000))*(x87))));
00505 IkReal x222=((((IkReal(-1.00000000000000))*(x192)))+(((IkReal(-1.00000000000000))*(x183)))+(x212)+(x182)+(((IkReal(-1.00000000000000))*(x121))));
00506 IkReal x223=((((IkReal(-1.00000000000000))*(x192)))+(x215)+(x185)+(((IkReal(-1.00000000000000))*(x184)))+(((IkReal(-1.00000000000000))*(x123))));
00507 IkReal x224=((((IkReal(-1.00000000000000))*(x192)))+(((IkReal(-1.00000000000000))*(x215)))+(x184)+(x185)+(((IkReal(-1.00000000000000))*(x123))));
00508 IkReal x225=((((IkReal(-1.00000000000000))*(x192)))+(((IkReal(-1.00000000000000))*(x212)))+(x182)+(x183)+(((IkReal(-1.00000000000000))*(x121))));
00509 op[0]=x222;
00510 op[1]=IkReal(0);
00511 op[2]=x218;
00512 op[3]=IkReal(0);
00513 op[4]=x223;
00514 op[5]=IkReal(0);
00515 op[6]=IkReal(0);
00516 op[7]=x222;
00517 op[8]=IkReal(0);
00518 op[9]=x218;
00519 op[10]=IkReal(0);
00520 op[11]=x223;
00521 op[12]=((((IkReal(-1.00000000000000))*(x210)))+(x179)+(((IkReal(-1.00000000000000))*(x191)))+(((IkReal(-1.00000000000000))*(x202)))+(x180)+(x203));
00522 op[13]=x196;
00523 op[14]=((x194)+(((IkReal(-1.00000000000000))*(x181)))+(((IkReal(-1.00000000000000))*(x216))));
00524 op[15]=x174;
00525 op[16]=((((IkReal(-1.00000000000000))*(x202)))+(x191)+(x180)+(x127)+(x129)+(x209)+(((IkReal(-1.00000000000000))*(x83)))+(((IkReal(-1.00000000000000))*(x162))));
00526 op[17]=x197;
00527 op[18]=x196;
00528 op[19]=((((IkReal(-1.00000000000000))*(x86)))+(((IkReal(-1.00000000000000))*(x210)))+(((IkReal(-1.00000000000000))*(x202)))+(((IkReal(-1.00000000000000))*(x139)))+(((IkReal(-1.00000000000000))*(x138)))+(x180)+(x208)+(x140));
00529 op[20]=x174;
00530 op[21]=((x214)+(x186)+(((IkReal(-1.00000000000000))*(x207))));
00531 op[22]=x197;
00532 op[23]=((((IkReal(-1.00000000000000))*(x189)))+(((IkReal(-1.00000000000000))*(x202)))+(((IkReal(-1.00000000000000))*(x138)))+(x180)+(x209)+(x86)+(((IkReal(-1.00000000000000))*(x208))));
00533 op[24]=x220;
00534 op[25]=IkReal(0);
00535 op[26]=x175;
00536 op[27]=IkReal(0);
00537 op[28]=x221;
00538 op[29]=IkReal(0);
00539 op[30]=IkReal(0);
00540 op[31]=x220;
00541 op[32]=IkReal(0);
00542 op[33]=x175;
00543 op[34]=IkReal(0);
00544 op[35]=x221;
00545 op[36]=((((IkReal(-1.00000000000000))*(x167)))+(x211)+(((IkReal(-1.00000000000000))*(x146)))+(x205)+(((IkReal(-1.00000000000000))*(x190)))+(x147));
00546 op[37]=x198;
00547 op[38]=((((IkReal(-1.00000000000000))*(x193)))+(x206)+(((IkReal(0.210483569200000))*(x103))));
00548 op[39]=x176;
00549 op[40]=((((IkReal(-1.00000000000000))*(x146)))+(x167)+(x205)+(((IkReal(-1.00000000000000))*(x147)))+(((IkReal(-1.00000000000000))*(x190)))+(((IkReal(-1.00000000000000))*(x211))));
00550 op[41]=x199;
00551 op[42]=x198;
00552 op[43]=((((IkReal(-1.00000000000000))*(x204)))+(x211)+(x217)+(((IkReal(-1.00000000000000))*(x190))));
00553 op[44]=x176;
00554 op[45]=((((IkReal(-1.00000000000000))*(x193)))+(x206)+(((IkReal(-0.191836110800000))*(x103))));
00555 op[46]=x199;
00556 op[47]=((x217)+(x204)+(((IkReal(-1.00000000000000))*(x190)))+(((IkReal(-1.00000000000000))*(x211))));
00557 op[48]=x224;
00558 op[49]=IkReal(0);
00559 op[50]=x219;
00560 op[51]=IkReal(0);
00561 op[52]=x225;
00562 op[53]=IkReal(0);
00563 op[54]=IkReal(0);
00564 op[55]=x224;
00565 op[56]=IkReal(0);
00566 op[57]=x219;
00567 op[58]=IkReal(0);
00568 op[59]=x225;
00569 op[60]=((x179)+(((IkReal(-1.00000000000000))*(x188)))+(((IkReal(-1.00000000000000))*(x203)))+(((IkReal(-1.00000000000000))*(x131)))+(x126)+(x202)+(x209));
00570 op[61]=x200;
00571 op[62]=((x216)+(((IkReal(-1.00000000000000))*(x181)))+(((IkReal(-1.00000000000000))*(x194))));
00572 op[63]=x178;
00573 op[64]=((((IkReal(-1.00000000000000))*(x210)))+(((IkReal(-1.00000000000000))*(x188)))+(((IkReal(-1.00000000000000))*(x126)))+(((IkReal(-1.00000000000000))*(x127)))+(x129)+(x162)+(x202)+(((IkReal(-1.00000000000000))*(x83)))+(x131));
00574 op[65]=x201;
00575 op[66]=x200;
00576 op[67]=((((IkReal(-1.00000000000000))*(x188)))+(((IkReal(-1.00000000000000))*(x139)))+(((IkReal(-1.00000000000000))*(x213)))+(x202)+(x209)+(x138)+(x140));
00577 op[68]=x178;
00578 op[69]=((((IkReal(-1.00000000000000))*(x214)))+(x186)+(x207));
00579 op[70]=x201;
00580 op[71]=((((IkReal(-1.00000000000000))*(x210)))+(((IkReal(-1.00000000000000))*(x188)))+(((IkReal(-1.00000000000000))*(x189)))+(x213)+(x202)+(x138));
00581 solvedialyticpoly8qep(op,zeror,numroots);
00582 IkReal j0array[16], cj0array[16], sj0array[16], j6array[16], cj6array[16], sj6array[16], j1array[16], cj1array[16], sj1array[16];
00583 int numsolutions = 0;
00584 for(int ij0 = 0; ij0 < numroots; ij0 += 3)
00585 {
00586 IkReal htj0 = zeror[ij0+0], htj6 = zeror[ij0+1], htj1 = zeror[ij0+2];
00587 j0array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj0)));
00588 j6array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj6)));
00589 j1array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj1)));
00590 IkReal x226=(htj0)*(htj0);
00591 IkReal x227=(htj6)*(htj6);
00592 IkReal x228=(htj1)*(htj1);
00593 cj0array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x226))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x226)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x226))))));
00594 cj6array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x227))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x227)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x227))))));
00595 cj1array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x228))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x228)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x228))))));
00596 sj0array[numsolutions]=((IkReal(2.00000000000000))*(htj0)*(((IKabs(((IkReal(1.00000000000000))+((htj0)*(htj0)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj0)*(htj0))))):(IkReal)1.0e30)));
00597 sj6array[numsolutions]=((IkReal(2.00000000000000))*(htj6)*(((IKabs(((IkReal(1.00000000000000))+((htj6)*(htj6)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj6)*(htj6))))):(IkReal)1.0e30)));
00598 sj1array[numsolutions]=((IkReal(2.00000000000000))*(htj1)*(((IKabs(((IkReal(1.00000000000000))+((htj1)*(htj1)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj1)*(htj1))))):(IkReal)1.0e30)));
00599 if( j0array[numsolutions] > IKPI )
00600 {
00601     j0array[numsolutions]-=IK2PI;
00602 }
00603 else if( j0array[numsolutions] < -IKPI )
00604 {
00605     j0array[numsolutions]+=IK2PI;
00606 }
00607 if( j6array[numsolutions] > IKPI )
00608 {
00609     j6array[numsolutions]-=IK2PI;
00610 }
00611 else if( j6array[numsolutions] < -IKPI )
00612 {
00613     j6array[numsolutions]+=IK2PI;
00614 }
00615 if( j1array[numsolutions] > IKPI )
00616 {
00617     j1array[numsolutions]-=IK2PI;
00618 }
00619 else if( j1array[numsolutions] < -IKPI )
00620 {
00621     j1array[numsolutions]+=IK2PI;
00622 }
00623 numsolutions++;
00624 }
00625 bool j0valid[16]={true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true};
00626 _nj0 = 16;
00627 _nj6 = 1;
00628 _nj1 = 1;
00629 for(int ij0 = 0; ij0 < numsolutions; ++ij0)
00630     {
00631 if( !j0valid[ij0] )
00632 {
00633     continue;
00634 }
00635 _ij0[0] = ij0; _ij0[1] = -1;
00636 _ij6[0] = 0; _ij6[1] = -1;
00637 _ij1[0] = 0; _ij1[1] = -1;
00638 for(int iij0 = ij0+1; iij0 < numsolutions; ++iij0)
00639 {
00640 if( !j0valid[iij0] ) { continue; }
00641 if( IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(cj6array[ij0]-cj6array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj6array[ij0]-sj6array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(cj1array[ij0]-cj1array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij0]-sj1array[iij0]) < IKFAST_SOLUTION_THRESH &&  1 )
00642 {
00643     j0valid[iij0]=false; _ij0[1] = iij0; _ij6[1] = 0; _ij1[1] = 0;  break; 
00644 }
00645 }
00646     j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00647 
00648     j6 = j6array[ij0]; cj6 = cj6array[ij0]; sj6 = sj6array[ij0];
00649 
00650     j1 = j1array[ij0]; cj1 = cj1array[ij0]; sj1 = sj1array[ij0];
00651 
00652 {
00653 IkReal dummyeval[1];
00654 dummyeval[0]=cj1;
00655 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00656 {
00657 {
00658 IkReal dummyeval[1];
00659 dummyeval[0]=sj1;
00660 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00661 {
00662 {
00663 IkReal evalcond[2];
00664 IkReal x229=((cj0)*(cj5));
00665 IkReal x230=((IkReal(0.374290000000000))*(sj0));
00666 IkReal x231=((cj6)*(r11));
00667 IkReal x232=((IkReal(0.0100000000000000))*(sj6));
00668 IkReal x233=((cj6)*(r01));
00669 IkReal x234=((IkReal(0.0100000000000000))*(sj0));
00670 IkReal x235=((cj0)*(sj5));
00671 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
00672 evalcond[1]=((IkReal(0.433420000000000))+(((cj5)*(r10)*(sj0)*(x232)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(sj6)*(x230)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-0.374290000000000))*(r00)*(sj6)*(x235)))+(((IkReal(-1.00000000000000))*(sj5)*(x230)*(x231)))+(((IkReal(0.0100000000000000))*(r02)*(x235)))+(((IkReal(-0.374290000000000))*(x233)*(x235)))+(((r12)*(sj5)*(x234)))+(((r00)*(x229)*(x232)))+(((IkReal(0.0100000000000000))*(x229)*(x233)))+(((cj5)*(x231)*(x234)))+(((cj5)*(r12)*(x230)))+(((IkReal(-1.00000000000000))*(py)*(sj0)))+(((IkReal(0.374290000000000))*(r02)*(x229))));
00673 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  )
00674 {
00675 {
00676 IkReal j2array[1], cj2array[1], sj2array[1];
00677 bool j2valid[1]={false};
00678 _nj2 = 1;
00679 IkReal x236=((cj0)*(r11));
00680 IkReal x237=((r01)*(sj0));
00681 IkReal x238=((cj0)*(r10));
00682 IkReal x239=((IkReal(0.144927536231884))*(sj5));
00683 IkReal x240=((IkReal(5.42449275362319))*(cj5));
00684 IkReal x241=((r00)*(sj0));
00685 IkReal x242=((cj0)*(r12));
00686 IkReal x243=((r02)*(sj0));
00687 IkReal x244=((IkReal(5.42449275362319))*(cj6)*(sj5));
00688 IkReal x245=((IkReal(5.42449275362319))*(sj5)*(sj6));
00689 IkReal x246=((IkReal(0.144927536231884))*(cj5)*(sj6));
00690 IkReal x247=((IkReal(0.144927536231884))*(cj5)*(cj6));
00691 if( IKabs(((((IkReal(-1.00000000000000))*(x238)*(x246)))+(((x241)*(x246)))+(((x240)*(x243)))+(((IkReal(-1.00000000000000))*(x236)*(x247)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x239)*(x242)))+(((x236)*(x244)))+(((x238)*(x245)))+(((IkReal(-1.00000000000000))*(x241)*(x245)))+(((IkReal(-1.00000000000000))*(x240)*(x242)))+(((IkReal(-1.00000000000000))*(x237)*(x244)))+(((x239)*(x243)))+(((x237)*(x247))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r22)*(x240)))+(((IkReal(-14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(r20)*(x245)))+(((r22)*(x239)))+(((r21)*(x247)))+(((IkReal(-1.00000000000000))*(r21)*(x244)))+(((r20)*(x246))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x238)*(x246)))+(((x241)*(x246)))+(((x240)*(x243)))+(((IkReal(-1.00000000000000))*(x236)*(x247)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x239)*(x242)))+(((x236)*(x244)))+(((x238)*(x245)))+(((IkReal(-1.00000000000000))*(x241)*(x245)))+(((IkReal(-1.00000000000000))*(x240)*(x242)))+(((IkReal(-1.00000000000000))*(x237)*(x244)))+(((x239)*(x243)))+(((x237)*(x247)))))+IKsqr(((((r22)*(x240)))+(((IkReal(-14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(r20)*(x245)))+(((r22)*(x239)))+(((r21)*(x247)))+(((IkReal(-1.00000000000000))*(r21)*(x244)))+(((r20)*(x246)))))-1) <= IKFAST_SINCOS_THRESH )
00692     continue;
00693 j2array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x238)*(x246)))+(((x241)*(x246)))+(((x240)*(x243)))+(((IkReal(-1.00000000000000))*(x236)*(x247)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x239)*(x242)))+(((x236)*(x244)))+(((x238)*(x245)))+(((IkReal(-1.00000000000000))*(x241)*(x245)))+(((IkReal(-1.00000000000000))*(x240)*(x242)))+(((IkReal(-1.00000000000000))*(x237)*(x244)))+(((x239)*(x243)))+(((x237)*(x247)))), ((((r22)*(x240)))+(((IkReal(-14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(r20)*(x245)))+(((r22)*(x239)))+(((r21)*(x247)))+(((IkReal(-1.00000000000000))*(r21)*(x244)))+(((r20)*(x246)))));
00694 sj2array[0]=IKsin(j2array[0]);
00695 cj2array[0]=IKcos(j2array[0]);
00696 if( j2array[0] > IKPI )
00697 {
00698     j2array[0]-=IK2PI;
00699 }
00700 else if( j2array[0] < -IKPI )
00701 {    j2array[0]+=IK2PI;
00702 }
00703 j2valid[0] = true;
00704 for(int ij2 = 0; ij2 < 1; ++ij2)
00705 {
00706 if( !j2valid[ij2] )
00707 {
00708     continue;
00709 }
00710 _ij2[0] = ij2; _ij2[1] = -1;
00711 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00712 {
00713 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00714 {
00715     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00716 }
00717 }
00718 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00719 {
00720 IkReal evalcond[2];
00721 IkReal x248=((cj6)*(r11));
00722 IkReal x249=((IkReal(0.374290000000000))*(sj0));
00723 IkReal x250=((IkReal(0.0100000000000000))*(cj5));
00724 IkReal x251=((cj6)*(r21));
00725 IkReal x252=((r10)*(sj6));
00726 IkReal x253=((IkReal(0.374290000000000))*(sj5));
00727 IkReal x254=((IkReal(0.0100000000000000))*(sj5));
00728 IkReal x255=((cj6)*(r01));
00729 IkReal x256=((r20)*(sj6));
00730 IkReal x257=((IkReal(0.374290000000000))*(cj5));
00731 IkReal x258=((cj0)*(r12));
00732 IkReal x259=((r00)*(sj6));
00733 IkReal x260=((cj0)*(x253));
00734 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x254)))+(((x253)*(x256)))+(((IkReal(0.0690000000000000))*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(x250)*(x256)))+(((IkReal(-1.00000000000000))*(x250)*(x251)))+(pz)+(((x251)*(x253)))+(((IkReal(-1.00000000000000))*(r22)*(x257))));
00735 evalcond[1]=((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x254)))+(((IkReal(-1.00000000000000))*(sj0)*(x250)*(x255)))+(((IkReal(-1.00000000000000))*(sj0)*(x250)*(x259)))+(((IkReal(-1.00000000000000))*(cj0)*(py)))+(((IkReal(-1.00000000000000))*(x252)*(x260)))+(((cj0)*(x248)*(x250)))+(((sj5)*(x249)*(x259)))+(((IkReal(-1.00000000000000))*(x248)*(x260)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x249)))+(((x254)*(x258)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((sj5)*(x249)*(x255)))+(((cj0)*(x250)*(x252)))+(((x257)*(x258)))+(((px)*(sj0))));
00736 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00737 {
00738 continue;
00739 }
00740 }
00741 
00742 {
00743 IkReal dummyeval[1];
00744 IkReal gconst40;
00745 IkReal x261=(sj6)*(sj6);
00746 IkReal x262=(cj6)*(cj6);
00747 IkReal x263=((r10)*(sj0));
00748 IkReal x264=((r22)*(sj5));
00749 IkReal x265=((cj0)*(cj5));
00750 IkReal x266=((IkReal(1.00000000000000))*(r20));
00751 IkReal x267=((cj0)*(sj6));
00752 IkReal x268=((r21)*(sj5));
00753 IkReal x269=((sj0)*(sj6));
00754 IkReal x270=((cj6)*(sj5));
00755 IkReal x271=((r21)*(x262));
00756 IkReal x272=((cj5)*(r11)*(sj0));
00757 IkReal x273=((r21)*(x261));
00758 gconst40=IKsign(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x266)*(x270)))+(((cj5)*(x263)*(x271)))+(((cj6)*(x263)*(x264)))+(((IkReal(-1.00000000000000))*(r01)*(x264)*(x267)))+(((cj0)*(cj6)*(r00)*(x264)))+(((IkReal(-1.00000000000000))*(r01)*(x262)*(x265)*(x266)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x266)*(x270)))+(((IkReal(-1.00000000000000))*(x261)*(x266)*(x272)))+(((IkReal(-1.00000000000000))*(r11)*(x264)*(x269)))+(((cj5)*(x263)*(x273)))+(((r02)*(x267)*(x268)))+(((r00)*(x265)*(x271)))+(((r00)*(x265)*(x273)))+(((r12)*(x268)*(x269)))+(((IkReal(-1.00000000000000))*(x262)*(x266)*(x272)))+(((IkReal(-1.00000000000000))*(r01)*(x261)*(x265)*(x266)))));
00759 IkReal x274=(sj6)*(sj6);
00760 IkReal x275=(cj6)*(cj6);
00761 IkReal x276=((r10)*(sj0));
00762 IkReal x277=((r22)*(sj5));
00763 IkReal x278=((cj0)*(cj5));
00764 IkReal x279=((IkReal(1.00000000000000))*(r20));
00765 IkReal x280=((cj0)*(sj6));
00766 IkReal x281=((r21)*(sj5));
00767 IkReal x282=((sj0)*(sj6));
00768 IkReal x283=((cj6)*(sj5));
00769 IkReal x284=((r21)*(x275));
00770 IkReal x285=((cj5)*(r11)*(sj0));
00771 IkReal x286=((r21)*(x274));
00772 dummyeval[0]=((((cj5)*(x276)*(x284)))+(((IkReal(-1.00000000000000))*(r01)*(x275)*(x278)*(x279)))+(((r12)*(x281)*(x282)))+(((IkReal(-1.00000000000000))*(x275)*(x279)*(x285)))+(((cj0)*(cj6)*(r00)*(x277)))+(((IkReal(-1.00000000000000))*(r01)*(x274)*(x278)*(x279)))+(((cj5)*(x276)*(x286)))+(((r02)*(x280)*(x281)))+(((IkReal(-1.00000000000000))*(r11)*(x277)*(x282)))+(((IkReal(-1.00000000000000))*(x274)*(x279)*(x285)))+(((IkReal(-1.00000000000000))*(r01)*(x277)*(x280)))+(((cj6)*(x276)*(x277)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x279)*(x283)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x279)*(x283)))+(((r00)*(x278)*(x286)))+(((r00)*(x278)*(x284))));
00773 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00774 {
00775 {
00776 IkReal dummyeval[1];
00777 IkReal gconst39;
00778 IkReal x287=(cj6)*(cj6);
00779 IkReal x288=(sj6)*(sj6);
00780 IkReal x289=((IkReal(1.00000000000000))*(r01));
00781 IkReal x290=((sj0)*(sj5));
00782 IkReal x291=((cj6)*(r22));
00783 IkReal x292=((r21)*(sj6));
00784 IkReal x293=((r00)*(r21));
00785 IkReal x294=((cj0)*(sj5));
00786 IkReal x295=((cj6)*(r20));
00787 IkReal x296=((r22)*(sj6));
00788 IkReal x297=((cj0)*(cj5));
00789 IkReal x298=((IkReal(1.00000000000000))*(r10));
00790 IkReal x299=((cj5)*(sj0));
00791 IkReal x300=((r20)*(x288));
00792 IkReal x301=((x287)*(x299));
00793 gconst39=IKsign(((((IkReal(-1.00000000000000))*(x289)*(x299)*(x300)))+(((IkReal(-1.00000000000000))*(x291)*(x294)*(x298)))+(((IkReal(-1.00000000000000))*(r02)*(x290)*(x295)))+(((r11)*(x297)*(x300)))+(((r12)*(x294)*(x295)))+(((IkReal(-1.00000000000000))*(r21)*(x288)*(x297)*(x298)))+(((IkReal(-1.00000000000000))*(x289)*(x290)*(x296)))+(((x293)*(x301)))+(((r11)*(r20)*(x287)*(x297)))+(((IkReal(-1.00000000000000))*(r21)*(x287)*(x297)*(x298)))+(((r02)*(x290)*(x292)))+(((IkReal(-1.00000000000000))*(r20)*(x289)*(x301)))+(((x288)*(x293)*(x299)))+(((r11)*(x294)*(x296)))+(((IkReal(-1.00000000000000))*(r12)*(x292)*(x294)))+(((r00)*(x290)*(x291)))));
00794 IkReal x302=(cj6)*(cj6);
00795 IkReal x303=(sj6)*(sj6);
00796 IkReal x304=((IkReal(1.00000000000000))*(r01));
00797 IkReal x305=((sj0)*(sj5));
00798 IkReal x306=((cj6)*(r22));
00799 IkReal x307=((r21)*(sj6));
00800 IkReal x308=((r00)*(r21));
00801 IkReal x309=((cj0)*(sj5));
00802 IkReal x310=((cj6)*(r20));
00803 IkReal x311=((r22)*(sj6));
00804 IkReal x312=((cj0)*(cj5));
00805 IkReal x313=((IkReal(1.00000000000000))*(r10));
00806 IkReal x314=((cj5)*(sj0));
00807 IkReal x315=((r20)*(x303));
00808 IkReal x316=((x302)*(x314));
00809 dummyeval[0]=((((x303)*(x308)*(x314)))+(((x308)*(x316)))+(((IkReal(-1.00000000000000))*(x304)*(x314)*(x315)))+(((r00)*(x305)*(x306)))+(((IkReal(-1.00000000000000))*(x304)*(x305)*(x311)))+(((IkReal(-1.00000000000000))*(r21)*(x302)*(x312)*(x313)))+(((r11)*(x312)*(x315)))+(((IkReal(-1.00000000000000))*(r21)*(x303)*(x312)*(x313)))+(((r02)*(x305)*(x307)))+(((IkReal(-1.00000000000000))*(x306)*(x309)*(x313)))+(((IkReal(-1.00000000000000))*(r12)*(x307)*(x309)))+(((IkReal(-1.00000000000000))*(r02)*(x305)*(x310)))+(((r11)*(r20)*(x302)*(x312)))+(((r11)*(x309)*(x311)))+(((r12)*(x309)*(x310)))+(((IkReal(-1.00000000000000))*(r20)*(x304)*(x316))));
00810 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00811 {
00812 {
00813 IkReal dummyeval[1];
00814 dummyeval[0]=cj2;
00815 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00816 {
00817 {
00818 IkReal evalcond[5];
00819 IkReal x317=((cj5)*(r22));
00820 IkReal x318=((IkReal(0.374290000000000))*(sj5));
00821 IkReal x319=((cj0)*(sj6));
00822 IkReal x320=((cj6)*(r21));
00823 IkReal x321=((IkReal(0.0100000000000000))*(sj5));
00824 IkReal x322=((cj0)*(r02));
00825 IkReal x323=((IkReal(0.0100000000000000))*(cj5));
00826 IkReal x324=((IkReal(1.00000000000000))*(py));
00827 IkReal x325=((r01)*(sj0));
00828 IkReal x326=((r20)*(sj6));
00829 IkReal x327=((r11)*(sj0));
00830 IkReal x328=((IkReal(0.374290000000000))*(cj5));
00831 IkReal x329=((cj0)*(r12));
00832 IkReal x330=((sj0)*(x328));
00833 IkReal x331=((cj6)*(x323));
00834 IkReal x332=((r10)*(sj0)*(sj6));
00835 IkReal x333=((r00)*(sj0)*(sj6));
00836 IkReal x334=((cj0)*(cj6)*(x318));
00837 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
00838 evalcond[1]=((((IkReal(-1.00000000000000))*(x317)))+(((sj5)*(x320)))+(((sj5)*(x326))));
00839 evalcond[2]=((((IkReal(-1.00000000000000))*(x320)*(x323)))+(((x318)*(x326)))+(((IkReal(-1.00000000000000))*(r22)*(x321)))+(((IkReal(-0.374290000000000))*(x317)))+(((x318)*(x320)))+(pz)+(((IkReal(-1.00000000000000))*(x323)*(x326))));
00840 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x334)))+(((IkReal(-1.00000000000000))*(x323)*(x333)))+(((r10)*(x319)*(x323)))+(((IkReal(-1.00000000000000))*(r02)*(x330)))+(((x328)*(x329)))+(((cj6)*(x318)*(x325)))+(((x321)*(x329)))+(((IkReal(-1.00000000000000))*(cj0)*(x324)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x321)))+(((x318)*(x333)))+(((cj0)*(r11)*(x331)))+(((IkReal(-1.00000000000000))*(x325)*(x331)))+(((IkReal(-1.00000000000000))*(r10)*(x318)*(x319)))+(((px)*(sj0))));
00841 evalcond[4]=((IkReal(0.433420000000000))+(((r00)*(x319)*(x323)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x323)*(x332)))+(((x322)*(x328)))+(((r12)*(sj0)*(x321)))+(((cj0)*(r01)*(x331)))+(((x321)*(x322)))+(((IkReal(-1.00000000000000))*(r01)*(x334)))+(((IkReal(-1.00000000000000))*(r00)*(x318)*(x319)))+(((IkReal(-1.00000000000000))*(sj0)*(x324)))+(((r12)*(x330)))+(((x327)*(x331)))+(((IkReal(-1.00000000000000))*(x318)*(x332)))+(((IkReal(-1.00000000000000))*(cj6)*(x318)*(x327))));
00842 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
00843 {
00844 {
00845 IkReal j3array[1], cj3array[1], sj3array[1];
00846 bool j3valid[1]={false};
00847 _nj3 = 1;
00848 IkReal x335=((cj0)*(cj5));
00849 IkReal x336=((IkReal(1.00000000000000))*(cj0));
00850 IkReal x337=((cj6)*(r11));
00851 IkReal x338=((r10)*(sj6));
00852 IkReal x339=((cj5)*(sj0));
00853 IkReal x340=((r00)*(sj5)*(sj6));
00854 IkReal x341=((cj6)*(r01)*(sj5));
00855 IkReal x342=((IkReal(1.00000000000000))*(sj0)*(sj5));
00856 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x336)*(x338)))+(((IkReal(-1.00000000000000))*(r02)*(x339)))+(((r12)*(x335)))+(((sj0)*(x341)))+(((IkReal(-1.00000000000000))*(sj5)*(x336)*(x337)))+(((sj0)*(x340))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r12)*(x339)))+(((r02)*(x335)))+(((IkReal(-1.00000000000000))*(x336)*(x340)))+(((IkReal(-1.00000000000000))*(x336)*(x341)))+(((IkReal(-1.00000000000000))*(x337)*(x342)))+(((IkReal(-1.00000000000000))*(x338)*(x342))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x336)*(x338)))+(((IkReal(-1.00000000000000))*(r02)*(x339)))+(((r12)*(x335)))+(((sj0)*(x341)))+(((IkReal(-1.00000000000000))*(sj5)*(x336)*(x337)))+(((sj0)*(x340)))))+IKsqr(((((r12)*(x339)))+(((r02)*(x335)))+(((IkReal(-1.00000000000000))*(x336)*(x340)))+(((IkReal(-1.00000000000000))*(x336)*(x341)))+(((IkReal(-1.00000000000000))*(x337)*(x342)))+(((IkReal(-1.00000000000000))*(x338)*(x342)))))-1) <= IKFAST_SINCOS_THRESH )
00857     continue;
00858 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x336)*(x338)))+(((IkReal(-1.00000000000000))*(r02)*(x339)))+(((r12)*(x335)))+(((sj0)*(x341)))+(((IkReal(-1.00000000000000))*(sj5)*(x336)*(x337)))+(((sj0)*(x340)))), ((((r12)*(x339)))+(((r02)*(x335)))+(((IkReal(-1.00000000000000))*(x336)*(x340)))+(((IkReal(-1.00000000000000))*(x336)*(x341)))+(((IkReal(-1.00000000000000))*(x337)*(x342)))+(((IkReal(-1.00000000000000))*(x338)*(x342)))));
00859 sj3array[0]=IKsin(j3array[0]);
00860 cj3array[0]=IKcos(j3array[0]);
00861 if( j3array[0] > IKPI )
00862 {
00863     j3array[0]-=IK2PI;
00864 }
00865 else if( j3array[0] < -IKPI )
00866 {    j3array[0]+=IK2PI;
00867 }
00868 j3valid[0] = true;
00869 for(int ij3 = 0; ij3 < 1; ++ij3)
00870 {
00871 if( !j3valid[ij3] )
00872 {
00873     continue;
00874 }
00875 _ij3[0] = ij3; _ij3[1] = -1;
00876 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00877 {
00878 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00879 {
00880     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00881 }
00882 }
00883 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00884 {
00885 IkReal evalcond[2];
00886 IkReal x343=((cj0)*(cj5));
00887 IkReal x344=((IkReal(1.00000000000000))*(cj0));
00888 IkReal x345=((cj6)*(r11));
00889 IkReal x346=((r10)*(sj6));
00890 IkReal x347=((cj5)*(sj0));
00891 IkReal x348=((r00)*(sj5)*(sj6));
00892 IkReal x349=((cj6)*(r01)*(sj5));
00893 IkReal x350=((IkReal(1.00000000000000))*(sj0)*(sj5));
00894 evalcond[0]=((((IkReal(-1.00000000000000))*(sj5)*(x344)*(x346)))+(((IkReal(-1.00000000000000))*(r02)*(x347)))+(((r12)*(x343)))+(((sj0)*(x348)))+(((sj0)*(x349)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((IkReal(-1.00000000000000))*(sj5)*(x344)*(x345))));
00895 evalcond[1]=((((r12)*(x347)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(x344)*(x348)))+(((IkReal(-1.00000000000000))*(x346)*(x350)))+(((IkReal(-1.00000000000000))*(x344)*(x349)))+(((IkReal(-1.00000000000000))*(x345)*(x350)))+(((r02)*(x343))));
00896 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00897 {
00898 continue;
00899 }
00900 }
00901 
00902 {
00903 IkReal dummyeval[1];
00904 IkReal gconst46;
00905 IkReal x351=(cj5)*(cj5);
00906 IkReal x352=(r20)*(r20);
00907 IkReal x353=(sj6)*(sj6);
00908 IkReal x354=(cj6)*(cj6);
00909 IkReal x355=(r21)*(r21);
00910 IkReal x356=((cj6)*(r21));
00911 IkReal x357=((IkReal(2.00000000000000))*(r20)*(sj6));
00912 IkReal x358=((cj5)*(r22)*(sj5));
00913 gconst46=IKsign((((((r22)*(r22))*((sj5)*(sj5))))+(((x353)*(x355)))+(((IkReal(2.00000000000000))*(x356)*(x358)))+(((x357)*(x358)))+(((IkReal(-1.00000000000000))*(x356)*(x357)))+(((x351)*(x356)*(x357)))+(((x351)*(x352)*(x353)))+(((x351)*(x354)*(x355)))+(((x352)*(x354)))));
00914 IkReal x359=(cj5)*(cj5);
00915 IkReal x360=(r20)*(r20);
00916 IkReal x361=(sj6)*(sj6);
00917 IkReal x362=(cj6)*(cj6);
00918 IkReal x363=(r21)*(r21);
00919 IkReal x364=((cj6)*(r21));
00920 IkReal x365=((IkReal(2.00000000000000))*(r20)*(sj6));
00921 IkReal x366=((cj5)*(r22)*(sj5));
00922 dummyeval[0]=((((x359)*(x364)*(x365)))+(((x365)*(x366)))+((((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x364)*(x365)))+(((x359)*(x360)*(x361)))+(((x360)*(x362)))+(((x359)*(x362)*(x363)))+(((IkReal(2.00000000000000))*(x364)*(x366)))+(((x361)*(x363))));
00923 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00924 {
00925 {
00926 IkReal dummyeval[1];
00927 IkReal gconst47;
00928 IkReal x367=(cj6)*(cj6);
00929 IkReal x368=(sj6)*(sj6);
00930 IkReal x369=((IkReal(1.00000000000000))*(r21));
00931 IkReal x370=((cj6)*(r20));
00932 IkReal x371=((r22)*(sj5));
00933 IkReal x372=((r01)*(sj0));
00934 IkReal x373=((r00)*(sj0));
00935 IkReal x374=((cj0)*(r10));
00936 IkReal x375=((r02)*(sj0)*(sj5));
00937 IkReal x376=((cj5)*(x367));
00938 IkReal x377=((cj0)*(r12)*(sj5));
00939 IkReal x378=((IkReal(1.00000000000000))*(cj0)*(r11));
00940 IkReal x379=((cj5)*(x368));
00941 IkReal x380=((r20)*(x379));
00942 gconst47=IKsign(((((IkReal(-1.00000000000000))*(cj6)*(x371)*(x373)))+(((IkReal(-1.00000000000000))*(sj6)*(x369)*(x375)))+(((sj6)*(x371)*(x372)))+(((r21)*(x374)*(x376)))+(((IkReal(-1.00000000000000))*(r20)*(x376)*(x378)))+(((IkReal(-1.00000000000000))*(sj6)*(x371)*(x378)))+(((IkReal(-1.00000000000000))*(x369)*(x373)*(x376)))+(((IkReal(-1.00000000000000))*(x378)*(x380)))+(((r21)*(x374)*(x379)))+(((r21)*(sj6)*(x377)))+(((IkReal(-1.00000000000000))*(x369)*(x373)*(x379)))+(((IkReal(-1.00000000000000))*(x370)*(x377)))+(((cj6)*(x371)*(x374)))+(((r20)*(x372)*(x376)))+(((x372)*(x380)))+(((x370)*(x375)))));
00943 IkReal x381=(cj6)*(cj6);
00944 IkReal x382=(sj6)*(sj6);
00945 IkReal x383=((IkReal(1.00000000000000))*(r21));
00946 IkReal x384=((cj6)*(r20));
00947 IkReal x385=((r22)*(sj5));
00948 IkReal x386=((r01)*(sj0));
00949 IkReal x387=((r00)*(sj0));
00950 IkReal x388=((cj0)*(r10));
00951 IkReal x389=((r02)*(sj0)*(sj5));
00952 IkReal x390=((cj5)*(x381));
00953 IkReal x391=((cj0)*(r12)*(sj5));
00954 IkReal x392=((IkReal(1.00000000000000))*(cj0)*(r11));
00955 IkReal x393=((cj5)*(x382));
00956 IkReal x394=((r20)*(x393));
00957 dummyeval[0]=((((IkReal(-1.00000000000000))*(x383)*(x387)*(x390)))+(((x384)*(x389)))+(((r20)*(x386)*(x390)))+(((IkReal(-1.00000000000000))*(r20)*(x390)*(x392)))+(((x386)*(x394)))+(((IkReal(-1.00000000000000))*(cj6)*(x385)*(x387)))+(((IkReal(-1.00000000000000))*(x383)*(x387)*(x393)))+(((IkReal(-1.00000000000000))*(sj6)*(x383)*(x389)))+(((sj6)*(x385)*(x386)))+(((IkReal(-1.00000000000000))*(sj6)*(x385)*(x392)))+(((IkReal(-1.00000000000000))*(x392)*(x394)))+(((IkReal(-1.00000000000000))*(x384)*(x391)))+(((r21)*(x388)*(x393)))+(((r21)*(sj6)*(x391)))+(((r21)*(x388)*(x390)))+(((cj6)*(x385)*(x388))));
00958 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00959 {
00960 continue;
00961 
00962 } else
00963 {
00964 {
00965 IkReal j4array[1], cj4array[1], sj4array[1];
00966 bool j4valid[1]={false};
00967 _nj4 = 1;
00968 IkReal x395=((sj0)*(sj6));
00969 IkReal x396=((cj0)*(r10));
00970 IkReal x397=((IkReal(1.00000000000000))*(cj5));
00971 IkReal x398=((cj6)*(sj0));
00972 IkReal x399=((cj0)*(r11));
00973 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(r00)*(x398)))+(((cj6)*(x396)))+(((r01)*(x395)))+(((IkReal(-1.00000000000000))*(sj6)*(x399))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((cj5)*(sj6)*(x396)))+(((IkReal(-1.00000000000000))*(r01)*(x397)*(x398)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x399)))+(((IkReal(-1.00000000000000))*(r00)*(x395)*(x397))))))) < IKFAST_ATAN2_MAGTHRESH )
00974     continue;
00975 j4array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(r00)*(x398)))+(((cj6)*(x396)))+(((r01)*(x395)))+(((IkReal(-1.00000000000000))*(sj6)*(x399)))))), ((gconst47)*(((((cj5)*(sj6)*(x396)))+(((IkReal(-1.00000000000000))*(r01)*(x397)*(x398)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x399)))+(((IkReal(-1.00000000000000))*(r00)*(x395)*(x397)))))));
00976 sj4array[0]=IKsin(j4array[0]);
00977 cj4array[0]=IKcos(j4array[0]);
00978 if( j4array[0] > IKPI )
00979 {
00980     j4array[0]-=IK2PI;
00981 }
00982 else if( j4array[0] < -IKPI )
00983 {    j4array[0]+=IK2PI;
00984 }
00985 j4valid[0] = true;
00986 for(int ij4 = 0; ij4 < 1; ++ij4)
00987 {
00988 if( !j4valid[ij4] )
00989 {
00990     continue;
00991 }
00992 _ij4[0] = ij4; _ij4[1] = -1;
00993 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
00994 {
00995 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
00996 {
00997     j4valid[iij4]=false; _ij4[1] = iij4; break; 
00998 }
00999 }
01000 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01001 {
01002 IkReal evalcond[6];
01003 IkReal x400=IKsin(j4);
01004 IkReal x401=IKcos(j4);
01005 IkReal x402=((r22)*(sj5));
01006 IkReal x403=((IkReal(1.00000000000000))*(cj6));
01007 IkReal x404=((IkReal(1.00000000000000))*(cj0));
01008 IkReal x405=((cj5)*(r11));
01009 IkReal x406=((cj5)*(cj6));
01010 IkReal x407=((r11)*(sj6));
01011 IkReal x408=((IkReal(1.00000000000000))*(sj6));
01012 IkReal x409=((cj6)*(r00));
01013 IkReal x410=((r12)*(sj5));
01014 IkReal x411=((r02)*(sj5));
01015 IkReal x412=((cj6)*(r10));
01016 IkReal x413=((cj5)*(sj6));
01017 IkReal x414=((cj5)*(r01));
01018 IkReal x415=((sj0)*(x400));
01019 IkReal x416=((r00)*(x413));
01020 IkReal x417=((cj0)*(x400));
01021 IkReal x418=((sj0)*(x401));
01022 IkReal x419=((r20)*(x401));
01023 IkReal x420=((cj0)*(x401));
01024 IkReal x421=((r21)*(x400));
01025 IkReal x422=((r21)*(x401));
01026 IkReal x423=((r20)*(x400));
01027 IkReal x424=((x401)*(x410));
01028 IkReal x425=((r01)*(sj6)*(x401));
01029 IkReal x426=((cj5)*(r10)*(x408));
01030 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x403)*(x419)))+(((x413)*(x423)))+(((x406)*(x421)))+(((x400)*(x402)))+(((sj6)*(x422))));
01031 evalcond[1]=((((x413)*(x419)))+(((IkReal(-1.00000000000000))*(x408)*(x421)))+(((x406)*(x422)))+(((cj6)*(x423)))+(((x401)*(x402))));
01032 evalcond[2]=((((x412)*(x420)))+(((x415)*(x416)))+(((IkReal(-1.00000000000000))*(r10)*(x400)*(x404)*(x413)))+(((IkReal(-1.00000000000000))*(x401)*(x404)*(x407)))+(((IkReal(-1.00000000000000))*(r00)*(x403)*(x418)))+(((IkReal(-1.00000000000000))*(x400)*(x404)*(x410)))+(((r01)*(sj6)*(x418)))+(((IkReal(-1.00000000000000))*(x403)*(x405)*(x417)))+(((x411)*(x415)))+(((r01)*(x406)*(x415))));
01033 evalcond[3]=((((x409)*(x415)))+(((x411)*(x418)))+(((x416)*(x418)))+(((IkReal(-1.00000000000000))*(r10)*(x403)*(x417)))+(((IkReal(-1.00000000000000))*(r10)*(x401)*(x404)*(x413)))+(cj3)+(((x407)*(x417)))+(((IkReal(-1.00000000000000))*(x403)*(x405)*(x420)))+(((IkReal(-1.00000000000000))*(x404)*(x424)))+(((r01)*(x406)*(x418)))+(((IkReal(-1.00000000000000))*(r01)*(x408)*(x415))));
01034 evalcond[4]=((((IkReal(-1.00000000000000))*(x403)*(x405)*(x415)))+(((IkReal(-1.00000000000000))*(x400)*(x404)*(x416)))+(((IkReal(-1.00000000000000))*(x407)*(x418)))+(((IkReal(-1.00000000000000))*(x400)*(x404)*(x411)))+(((IkReal(-1.00000000000000))*(x403)*(x414)*(x417)))+(((IkReal(-1.00000000000000))*(x415)*(x426)))+(((x412)*(x418)))+(((IkReal(-1.00000000000000))*(x410)*(x415)))+(((IkReal(-1.00000000000000))*(x404)*(x425)))+(((x409)*(x420))));
01035 evalcond[5]=((((IkReal(-1.00000000000000))*(x418)*(x426)))+(((IkReal(-1.00000000000000))*(x410)*(x418)))+(((IkReal(-1.00000000000000))*(x401)*(x404)*(x416)))+(((IkReal(-1.00000000000000))*(x403)*(x405)*(x418)))+(((IkReal(-1.00000000000000))*(x403)*(x414)*(x420)))+(((r01)*(sj6)*(x417)))+(((IkReal(-1.00000000000000))*(r00)*(x403)*(x417)))+(((IkReal(-1.00000000000000))*(sj3)))+(((x407)*(x415)))+(((IkReal(-1.00000000000000))*(r10)*(x403)*(x415)))+(((IkReal(-1.00000000000000))*(x401)*(x404)*(x411))));
01036 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01037 {
01038 continue;
01039 }
01040 }
01041 
01042 {
01043 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01044 vinfos[0].jointtype = 1;
01045 vinfos[0].foffset = j0;
01046 vinfos[0].indices[0] = _ij0[0];
01047 vinfos[0].indices[1] = _ij0[1];
01048 vinfos[0].maxsolutions = _nj0;
01049 vinfos[1].jointtype = 1;
01050 vinfos[1].foffset = j1;
01051 vinfos[1].indices[0] = _ij1[0];
01052 vinfos[1].indices[1] = _ij1[1];
01053 vinfos[1].maxsolutions = _nj1;
01054 vinfos[2].jointtype = 1;
01055 vinfos[2].foffset = j2;
01056 vinfos[2].indices[0] = _ij2[0];
01057 vinfos[2].indices[1] = _ij2[1];
01058 vinfos[2].maxsolutions = _nj2;
01059 vinfos[3].jointtype = 1;
01060 vinfos[3].foffset = j3;
01061 vinfos[3].indices[0] = _ij3[0];
01062 vinfos[3].indices[1] = _ij3[1];
01063 vinfos[3].maxsolutions = _nj3;
01064 vinfos[4].jointtype = 1;
01065 vinfos[4].foffset = j4;
01066 vinfos[4].indices[0] = _ij4[0];
01067 vinfos[4].indices[1] = _ij4[1];
01068 vinfos[4].maxsolutions = _nj4;
01069 vinfos[5].jointtype = 1;
01070 vinfos[5].foffset = j5;
01071 vinfos[5].indices[0] = _ij5[0];
01072 vinfos[5].indices[1] = _ij5[1];
01073 vinfos[5].maxsolutions = _nj5;
01074 vinfos[6].jointtype = 1;
01075 vinfos[6].foffset = j6;
01076 vinfos[6].indices[0] = _ij6[0];
01077 vinfos[6].indices[1] = _ij6[1];
01078 vinfos[6].maxsolutions = _nj6;
01079 std::vector<int> vfree(0);
01080 solutions.AddSolution(vinfos,vfree);
01081 }
01082 }
01083 }
01084 
01085 }
01086 
01087 }
01088 
01089 } else
01090 {
01091 {
01092 IkReal j4array[1], cj4array[1], sj4array[1];
01093 bool j4valid[1]={false};
01094 _nj4 = 1;
01095 if( IKabs(((gconst46)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
01096     continue;
01097 j4array[0]=IKatan2(((gconst46)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst46)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
01098 sj4array[0]=IKsin(j4array[0]);
01099 cj4array[0]=IKcos(j4array[0]);
01100 if( j4array[0] > IKPI )
01101 {
01102     j4array[0]-=IK2PI;
01103 }
01104 else if( j4array[0] < -IKPI )
01105 {    j4array[0]+=IK2PI;
01106 }
01107 j4valid[0] = true;
01108 for(int ij4 = 0; ij4 < 1; ++ij4)
01109 {
01110 if( !j4valid[ij4] )
01111 {
01112     continue;
01113 }
01114 _ij4[0] = ij4; _ij4[1] = -1;
01115 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01116 {
01117 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01118 {
01119     j4valid[iij4]=false; _ij4[1] = iij4; break; 
01120 }
01121 }
01122 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01123 {
01124 IkReal evalcond[6];
01125 IkReal x427=IKsin(j4);
01126 IkReal x428=IKcos(j4);
01127 IkReal x429=((r22)*(sj5));
01128 IkReal x430=((IkReal(1.00000000000000))*(cj6));
01129 IkReal x431=((IkReal(1.00000000000000))*(cj0));
01130 IkReal x432=((cj5)*(r11));
01131 IkReal x433=((cj5)*(cj6));
01132 IkReal x434=((r11)*(sj6));
01133 IkReal x435=((IkReal(1.00000000000000))*(sj6));
01134 IkReal x436=((cj6)*(r00));
01135 IkReal x437=((r12)*(sj5));
01136 IkReal x438=((r02)*(sj5));
01137 IkReal x439=((cj6)*(r10));
01138 IkReal x440=((cj5)*(sj6));
01139 IkReal x441=((cj5)*(r01));
01140 IkReal x442=((sj0)*(x427));
01141 IkReal x443=((r00)*(x440));
01142 IkReal x444=((cj0)*(x427));
01143 IkReal x445=((sj0)*(x428));
01144 IkReal x446=((r20)*(x428));
01145 IkReal x447=((cj0)*(x428));
01146 IkReal x448=((r21)*(x427));
01147 IkReal x449=((r21)*(x428));
01148 IkReal x450=((r20)*(x427));
01149 IkReal x451=((x428)*(x437));
01150 IkReal x452=((r01)*(sj6)*(x428));
01151 IkReal x453=((cj5)*(r10)*(x435));
01152 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x430)*(x446)))+(((x433)*(x448)))+(((x427)*(x429)))+(((x440)*(x450)))+(((sj6)*(x449))));
01153 evalcond[1]=((((x433)*(x449)))+(((cj6)*(x450)))+(((x428)*(x429)))+(((IkReal(-1.00000000000000))*(x435)*(x448)))+(((x440)*(x446))));
01154 evalcond[2]=((((r01)*(x433)*(x442)))+(((x439)*(x447)))+(((IkReal(-1.00000000000000))*(r00)*(x430)*(x445)))+(((x442)*(x443)))+(((x438)*(x442)))+(((IkReal(-1.00000000000000))*(r10)*(x427)*(x431)*(x440)))+(((r01)*(sj6)*(x445)))+(((IkReal(-1.00000000000000))*(x430)*(x432)*(x444)))+(((IkReal(-1.00000000000000))*(x428)*(x431)*(x434)))+(((IkReal(-1.00000000000000))*(x427)*(x431)*(x437))));
01155 evalcond[3]=((((r01)*(x433)*(x445)))+(((IkReal(-1.00000000000000))*(r10)*(x428)*(x431)*(x440)))+(((x436)*(x442)))+(((IkReal(-1.00000000000000))*(r01)*(x435)*(x442)))+(((x438)*(x445)))+(((IkReal(-1.00000000000000))*(x431)*(x451)))+(cj3)+(((IkReal(-1.00000000000000))*(x430)*(x432)*(x447)))+(((IkReal(-1.00000000000000))*(r10)*(x430)*(x444)))+(((x443)*(x445)))+(((x434)*(x444))));
01156 evalcond[4]=((((x436)*(x447)))+(((IkReal(-1.00000000000000))*(x430)*(x432)*(x442)))+(((IkReal(-1.00000000000000))*(x427)*(x431)*(x443)))+(((IkReal(-1.00000000000000))*(x434)*(x445)))+(((IkReal(-1.00000000000000))*(x431)*(x452)))+(((IkReal(-1.00000000000000))*(x430)*(x441)*(x444)))+(((IkReal(-1.00000000000000))*(x437)*(x442)))+(((IkReal(-1.00000000000000))*(x427)*(x431)*(x438)))+(((IkReal(-1.00000000000000))*(x442)*(x453)))+(((x439)*(x445))));
01157 evalcond[5]=((((IkReal(-1.00000000000000))*(x437)*(x445)))+(((IkReal(-1.00000000000000))*(x430)*(x432)*(x445)))+(((IkReal(-1.00000000000000))*(x445)*(x453)))+(((IkReal(-1.00000000000000))*(r10)*(x430)*(x442)))+(((IkReal(-1.00000000000000))*(x428)*(x431)*(x443)))+(((IkReal(-1.00000000000000))*(x428)*(x431)*(x438)))+(((IkReal(-1.00000000000000))*(x430)*(x441)*(x447)))+(((x434)*(x442)))+(((IkReal(-1.00000000000000))*(sj3)))+(((r01)*(sj6)*(x444)))+(((IkReal(-1.00000000000000))*(r00)*(x430)*(x444))));
01158 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01159 {
01160 continue;
01161 }
01162 }
01163 
01164 {
01165 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01166 vinfos[0].jointtype = 1;
01167 vinfos[0].foffset = j0;
01168 vinfos[0].indices[0] = _ij0[0];
01169 vinfos[0].indices[1] = _ij0[1];
01170 vinfos[0].maxsolutions = _nj0;
01171 vinfos[1].jointtype = 1;
01172 vinfos[1].foffset = j1;
01173 vinfos[1].indices[0] = _ij1[0];
01174 vinfos[1].indices[1] = _ij1[1];
01175 vinfos[1].maxsolutions = _nj1;
01176 vinfos[2].jointtype = 1;
01177 vinfos[2].foffset = j2;
01178 vinfos[2].indices[0] = _ij2[0];
01179 vinfos[2].indices[1] = _ij2[1];
01180 vinfos[2].maxsolutions = _nj2;
01181 vinfos[3].jointtype = 1;
01182 vinfos[3].foffset = j3;
01183 vinfos[3].indices[0] = _ij3[0];
01184 vinfos[3].indices[1] = _ij3[1];
01185 vinfos[3].maxsolutions = _nj3;
01186 vinfos[4].jointtype = 1;
01187 vinfos[4].foffset = j4;
01188 vinfos[4].indices[0] = _ij4[0];
01189 vinfos[4].indices[1] = _ij4[1];
01190 vinfos[4].maxsolutions = _nj4;
01191 vinfos[5].jointtype = 1;
01192 vinfos[5].foffset = j5;
01193 vinfos[5].indices[0] = _ij5[0];
01194 vinfos[5].indices[1] = _ij5[1];
01195 vinfos[5].maxsolutions = _nj5;
01196 vinfos[6].jointtype = 1;
01197 vinfos[6].foffset = j6;
01198 vinfos[6].indices[0] = _ij6[0];
01199 vinfos[6].indices[1] = _ij6[1];
01200 vinfos[6].maxsolutions = _nj6;
01201 std::vector<int> vfree(0);
01202 solutions.AddSolution(vinfos,vfree);
01203 }
01204 }
01205 }
01206 
01207 }
01208 
01209 }
01210 }
01211 }
01212 
01213 } else
01214 {
01215 IkReal x454=((cj5)*(r22));
01216 IkReal x455=((IkReal(0.374290000000000))*(sj5));
01217 IkReal x456=((cj0)*(sj6));
01218 IkReal x457=((cj6)*(r21));
01219 IkReal x458=((IkReal(0.0100000000000000))*(sj5));
01220 IkReal x459=((cj0)*(r02));
01221 IkReal x460=((IkReal(0.0100000000000000))*(cj5));
01222 IkReal x461=((IkReal(1.00000000000000))*(py));
01223 IkReal x462=((r01)*(sj0));
01224 IkReal x463=((r20)*(sj6));
01225 IkReal x464=((r11)*(sj0));
01226 IkReal x465=((IkReal(0.374290000000000))*(cj5));
01227 IkReal x466=((cj0)*(r12));
01228 IkReal x467=((sj0)*(x465));
01229 IkReal x468=((cj6)*(x460));
01230 IkReal x469=((r10)*(sj0)*(sj6));
01231 IkReal x470=((r00)*(sj0)*(sj6));
01232 IkReal x471=((cj0)*(cj6)*(x455));
01233 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
01234 evalcond[1]=((((IkReal(-1.00000000000000))*(x454)))+(((sj5)*(x457)))+(((sj5)*(x463))));
01235 evalcond[2]=((((IkReal(-0.374290000000000))*(x454)))+(((x455)*(x457)))+(((IkReal(-1.00000000000000))*(x460)*(x463)))+(((IkReal(-1.00000000000000))*(x457)*(x460)))+(((x455)*(x463)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x458))));
01236 evalcond[3]=((IkReal(-0.0690000000000000))+(((r10)*(x456)*(x460)))+(((x465)*(x466)))+(((IkReal(-1.00000000000000))*(cj0)*(x461)))+(((IkReal(-1.00000000000000))*(x460)*(x470)))+(((IkReal(-1.00000000000000))*(x462)*(x468)))+(((x455)*(x470)))+(((IkReal(-1.00000000000000))*(r10)*(x455)*(x456)))+(((IkReal(-1.00000000000000))*(r02)*(x467)))+(((cj0)*(r11)*(x468)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x471)))+(((cj6)*(x455)*(x462)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x458)))+(((x458)*(x466))));
01237 evalcond[4]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((r00)*(x456)*(x460)))+(((IkReal(-1.00000000000000))*(r00)*(x455)*(x456)))+(((x458)*(x459)))+(((x460)*(x469)))+(((cj0)*(r01)*(x468)))+(((x464)*(x468)))+(((r12)*(sj0)*(x458)))+(((IkReal(-1.00000000000000))*(cj6)*(x455)*(x464)))+(((IkReal(-1.00000000000000))*(x455)*(x469)))+(((r12)*(x467)))+(((IkReal(-1.00000000000000))*(sj0)*(x461)))+(((x459)*(x465)))+(((IkReal(-1.00000000000000))*(r01)*(x471))));
01238 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
01239 {
01240 {
01241 IkReal j3array[1], cj3array[1], sj3array[1];
01242 bool j3valid[1]={false};
01243 _nj3 = 1;
01244 IkReal x472=((cj5)*(r02));
01245 IkReal x473=((cj0)*(sj5));
01246 IkReal x474=((r10)*(sj6));
01247 IkReal x475=((IkReal(1.00000000000000))*(cj6));
01248 IkReal x476=((sj0)*(sj5));
01249 IkReal x477=((cj5)*(r12));
01250 IkReal x478=((IkReal(1.00000000000000))*(r00)*(sj6));
01251 if( IKabs(((((IkReal(-1.00000000000000))*(x476)*(x478)))+(((IkReal(-1.00000000000000))*(cj0)*(x477)))+(((IkReal(-1.00000000000000))*(r01)*(x475)*(x476)))+(((sj0)*(x472)))+(((x473)*(x474)))+(((cj6)*(r11)*(x473))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x473)*(x478)))+(((cj0)*(x472)))+(((IkReal(-1.00000000000000))*(r11)*(x475)*(x476)))+(((IkReal(-1.00000000000000))*(r01)*(x473)*(x475)))+(((IkReal(-1.00000000000000))*(x474)*(x476)))+(((sj0)*(x477))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x476)*(x478)))+(((IkReal(-1.00000000000000))*(cj0)*(x477)))+(((IkReal(-1.00000000000000))*(r01)*(x475)*(x476)))+(((sj0)*(x472)))+(((x473)*(x474)))+(((cj6)*(r11)*(x473)))))+IKsqr(((((IkReal(-1.00000000000000))*(x473)*(x478)))+(((cj0)*(x472)))+(((IkReal(-1.00000000000000))*(r11)*(x475)*(x476)))+(((IkReal(-1.00000000000000))*(r01)*(x473)*(x475)))+(((IkReal(-1.00000000000000))*(x474)*(x476)))+(((sj0)*(x477)))))-1) <= IKFAST_SINCOS_THRESH )
01252     continue;
01253 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x476)*(x478)))+(((IkReal(-1.00000000000000))*(cj0)*(x477)))+(((IkReal(-1.00000000000000))*(r01)*(x475)*(x476)))+(((sj0)*(x472)))+(((x473)*(x474)))+(((cj6)*(r11)*(x473)))), ((((IkReal(-1.00000000000000))*(x473)*(x478)))+(((cj0)*(x472)))+(((IkReal(-1.00000000000000))*(r11)*(x475)*(x476)))+(((IkReal(-1.00000000000000))*(r01)*(x473)*(x475)))+(((IkReal(-1.00000000000000))*(x474)*(x476)))+(((sj0)*(x477)))));
01254 sj3array[0]=IKsin(j3array[0]);
01255 cj3array[0]=IKcos(j3array[0]);
01256 if( j3array[0] > IKPI )
01257 {
01258     j3array[0]-=IK2PI;
01259 }
01260 else if( j3array[0] < -IKPI )
01261 {    j3array[0]+=IK2PI;
01262 }
01263 j3valid[0] = true;
01264 for(int ij3 = 0; ij3 < 1; ++ij3)
01265 {
01266 if( !j3valid[ij3] )
01267 {
01268     continue;
01269 }
01270 _ij3[0] = ij3; _ij3[1] = -1;
01271 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01272 {
01273 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01274 {
01275     j3valid[iij3]=false; _ij3[1] = iij3; break; 
01276 }
01277 }
01278 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01279 {
01280 IkReal evalcond[2];
01281 IkReal x479=((cj0)*(cj5));
01282 IkReal x480=((IkReal(1.00000000000000))*(cj0));
01283 IkReal x481=((cj6)*(r11));
01284 IkReal x482=((r10)*(sj6));
01285 IkReal x483=((cj5)*(sj0));
01286 IkReal x484=((r00)*(sj5)*(sj6));
01287 IkReal x485=((cj6)*(r01)*(sj5));
01288 IkReal x486=((IkReal(1.00000000000000))*(sj0)*(sj5));
01289 evalcond[0]=((((sj0)*(x484)))+(((r12)*(x479)))+(IKsin(j3))+(((IkReal(-1.00000000000000))*(sj5)*(x480)*(x481)))+(((IkReal(-1.00000000000000))*(sj5)*(x480)*(x482)))+(((IkReal(-1.00000000000000))*(r02)*(x483)))+(((sj0)*(x485))));
01290 evalcond[1]=((((IkReal(-1.00000000000000))*(x480)*(x484)))+(((r12)*(x483)))+(((r02)*(x479)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(x482)*(x486)))+(((IkReal(-1.00000000000000))*(x481)*(x486)))+(((IkReal(-1.00000000000000))*(x480)*(x485))));
01291 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
01292 {
01293 continue;
01294 }
01295 }
01296 
01297 {
01298 IkReal dummyeval[1];
01299 IkReal gconst50;
01300 IkReal x487=(r21)*(r21);
01301 IkReal x488=(cj5)*(cj5);
01302 IkReal x489=(sj6)*(sj6);
01303 IkReal x490=(cj6)*(cj6);
01304 IkReal x491=(r20)*(r20);
01305 IkReal x492=((cj6)*(r21));
01306 IkReal x493=((IkReal(2.00000000000000))*(r20)*(sj6));
01307 IkReal x494=((cj5)*(r22)*(sj5));
01308 IkReal x495=((IkReal(1.00000000000000))*(x489));
01309 IkReal x496=((IkReal(1.00000000000000))*(x490));
01310 gconst50=IKsign(((((IkReal(-1.00000000000000))*(x487)*(x488)*(x496)))+(((IkReal(-1.00000000000000))*(x488)*(x492)*(x493)))+(((x492)*(x493)))+(((IkReal(-1.00000000000000))*(x491)*(x496)))+(((IkReal(-2.00000000000000))*(x492)*(x494)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x488)*(x491)*(x495)))+(((IkReal(-1.00000000000000))*(x487)*(x495)))+(((IkReal(-1.00000000000000))*(x493)*(x494)))));
01311 IkReal x497=(r21)*(r21);
01312 IkReal x498=(cj5)*(cj5);
01313 IkReal x499=(sj6)*(sj6);
01314 IkReal x500=(cj6)*(cj6);
01315 IkReal x501=(r20)*(r20);
01316 IkReal x502=((cj6)*(r21));
01317 IkReal x503=((IkReal(2.00000000000000))*(r20)*(sj6));
01318 IkReal x504=((cj5)*(r22)*(sj5));
01319 IkReal x505=((IkReal(1.00000000000000))*(x499));
01320 IkReal x506=((IkReal(1.00000000000000))*(x500));
01321 dummyeval[0]=((((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x497)*(x505)))+(((IkReal(-1.00000000000000))*(x503)*(x504)))+(((IkReal(-1.00000000000000))*(x498)*(x502)*(x503)))+(((IkReal(-1.00000000000000))*(x498)*(x501)*(x505)))+(((x502)*(x503)))+(((IkReal(-1.00000000000000))*(x501)*(x506)))+(((IkReal(-2.00000000000000))*(x502)*(x504)))+(((IkReal(-1.00000000000000))*(x497)*(x498)*(x506))));
01322 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01323 {
01324 {
01325 IkReal dummyeval[1];
01326 IkReal gconst51;
01327 IkReal x507=(cj6)*(cj6);
01328 IkReal x508=(sj6)*(sj6);
01329 IkReal x509=((IkReal(1.00000000000000))*(r01));
01330 IkReal x510=((sj0)*(sj5));
01331 IkReal x511=((cj6)*(r22));
01332 IkReal x512=((r21)*(sj6));
01333 IkReal x513=((r00)*(r21));
01334 IkReal x514=((cj0)*(sj5));
01335 IkReal x515=((cj6)*(r20));
01336 IkReal x516=((r22)*(sj6));
01337 IkReal x517=((cj0)*(cj5));
01338 IkReal x518=((IkReal(1.00000000000000))*(r10));
01339 IkReal x519=((cj5)*(sj0));
01340 IkReal x520=((r20)*(x508));
01341 IkReal x521=((x507)*(x519));
01342 gconst51=IKsign(((((r11)*(x514)*(x516)))+(((IkReal(-1.00000000000000))*(r20)*(x509)*(x521)))+(((IkReal(-1.00000000000000))*(r12)*(x512)*(x514)))+(((r00)*(x510)*(x511)))+(((IkReal(-1.00000000000000))*(r21)*(x508)*(x517)*(x518)))+(((x513)*(x521)))+(((x508)*(x513)*(x519)))+(((IkReal(-1.00000000000000))*(x509)*(x510)*(x516)))+(((r11)*(x517)*(x520)))+(((r11)*(r20)*(x507)*(x517)))+(((IkReal(-1.00000000000000))*(r21)*(x507)*(x517)*(x518)))+(((r02)*(x510)*(x512)))+(((IkReal(-1.00000000000000))*(x511)*(x514)*(x518)))+(((IkReal(-1.00000000000000))*(x509)*(x519)*(x520)))+(((IkReal(-1.00000000000000))*(r02)*(x510)*(x515)))+(((r12)*(x514)*(x515)))));
01343 IkReal x522=(cj6)*(cj6);
01344 IkReal x523=(sj6)*(sj6);
01345 IkReal x524=((IkReal(1.00000000000000))*(r01));
01346 IkReal x525=((sj0)*(sj5));
01347 IkReal x526=((cj6)*(r22));
01348 IkReal x527=((r21)*(sj6));
01349 IkReal x528=((r00)*(r21));
01350 IkReal x529=((cj0)*(sj5));
01351 IkReal x530=((cj6)*(r20));
01352 IkReal x531=((r22)*(sj6));
01353 IkReal x532=((cj0)*(cj5));
01354 IkReal x533=((IkReal(1.00000000000000))*(r10));
01355 IkReal x534=((cj5)*(sj0));
01356 IkReal x535=((r20)*(x523));
01357 IkReal x536=((x522)*(x534));
01358 dummyeval[0]=((((r11)*(x529)*(x531)))+(((r12)*(x529)*(x530)))+(((r00)*(x525)*(x526)))+(((r02)*(x525)*(x527)))+(((IkReal(-1.00000000000000))*(r21)*(x522)*(x532)*(x533)))+(((IkReal(-1.00000000000000))*(r20)*(x524)*(x536)))+(((IkReal(-1.00000000000000))*(x526)*(x529)*(x533)))+(((IkReal(-1.00000000000000))*(r21)*(x523)*(x532)*(x533)))+(((IkReal(-1.00000000000000))*(r02)*(x525)*(x530)))+(((IkReal(-1.00000000000000))*(r12)*(x527)*(x529)))+(((IkReal(-1.00000000000000))*(x524)*(x525)*(x531)))+(((r11)*(x532)*(x535)))+(((x528)*(x536)))+(((r11)*(r20)*(x522)*(x532)))+(((IkReal(-1.00000000000000))*(x524)*(x534)*(x535)))+(((x523)*(x528)*(x534))));
01359 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01360 {
01361 continue;
01362 
01363 } else
01364 {
01365 {
01366 IkReal j4array[1], cj4array[1], sj4array[1];
01367 bool j4valid[1]={false};
01368 _nj4 = 1;
01369 IkReal x537=((sj0)*(sj6));
01370 IkReal x538=((cj0)*(r10));
01371 IkReal x539=((IkReal(1.00000000000000))*(cj5));
01372 IkReal x540=((cj6)*(sj0));
01373 IkReal x541=((cj0)*(r11));
01374 if( IKabs(((gconst51)*(((((r01)*(x537)))+(((IkReal(-1.00000000000000))*(r00)*(x540)))+(((IkReal(-1.00000000000000))*(sj6)*(x541)))+(((cj6)*(x538))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x537)*(x539)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x541)))+(((cj5)*(sj6)*(x538)))+(((IkReal(-1.00000000000000))*(r01)*(x539)*(x540))))))) < IKFAST_ATAN2_MAGTHRESH )
01375     continue;
01376 j4array[0]=IKatan2(((gconst51)*(((((r01)*(x537)))+(((IkReal(-1.00000000000000))*(r00)*(x540)))+(((IkReal(-1.00000000000000))*(sj6)*(x541)))+(((cj6)*(x538)))))), ((gconst51)*(((((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x537)*(x539)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x541)))+(((cj5)*(sj6)*(x538)))+(((IkReal(-1.00000000000000))*(r01)*(x539)*(x540)))))));
01377 sj4array[0]=IKsin(j4array[0]);
01378 cj4array[0]=IKcos(j4array[0]);
01379 if( j4array[0] > IKPI )
01380 {
01381     j4array[0]-=IK2PI;
01382 }
01383 else if( j4array[0] < -IKPI )
01384 {    j4array[0]+=IK2PI;
01385 }
01386 j4valid[0] = true;
01387 for(int ij4 = 0; ij4 < 1; ++ij4)
01388 {
01389 if( !j4valid[ij4] )
01390 {
01391     continue;
01392 }
01393 _ij4[0] = ij4; _ij4[1] = -1;
01394 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01395 {
01396 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01397 {
01398     j4valid[iij4]=false; _ij4[1] = iij4; break; 
01399 }
01400 }
01401 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01402 {
01403 IkReal evalcond[6];
01404 IkReal x542=IKsin(j4);
01405 IkReal x543=IKcos(j4);
01406 IkReal x544=((r22)*(sj5));
01407 IkReal x545=((IkReal(1.00000000000000))*(cj6));
01408 IkReal x546=((IkReal(1.00000000000000))*(cj0));
01409 IkReal x547=((cj5)*(r11));
01410 IkReal x548=((cj5)*(cj6));
01411 IkReal x549=((r11)*(sj6));
01412 IkReal x550=((IkReal(1.00000000000000))*(sj6));
01413 IkReal x551=((cj6)*(r00));
01414 IkReal x552=((r12)*(sj5));
01415 IkReal x553=((r02)*(sj5));
01416 IkReal x554=((cj6)*(r10));
01417 IkReal x555=((cj5)*(sj6));
01418 IkReal x556=((cj5)*(r01));
01419 IkReal x557=((sj0)*(x542));
01420 IkReal x558=((r00)*(x555));
01421 IkReal x559=((cj0)*(x542));
01422 IkReal x560=((sj0)*(x543));
01423 IkReal x561=((r20)*(x543));
01424 IkReal x562=((cj0)*(x543));
01425 IkReal x563=((r21)*(x542));
01426 IkReal x564=((r21)*(x543));
01427 IkReal x565=((r20)*(x542));
01428 IkReal x566=((x543)*(x552));
01429 IkReal x567=((r01)*(sj6)*(x543));
01430 IkReal x568=((cj5)*(r10)*(x550));
01431 evalcond[0]=((IkReal(1.00000000000000))+(((sj6)*(x564)))+(((x542)*(x544)))+(((IkReal(-1.00000000000000))*(x545)*(x561)))+(((x548)*(x563)))+(((x555)*(x565))));
01432 evalcond[1]=((((cj6)*(x565)))+(((x555)*(x561)))+(((IkReal(-1.00000000000000))*(x550)*(x563)))+(((x548)*(x564)))+(((x543)*(x544))));
01433 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x542)*(x546)*(x555)))+(((IkReal(-1.00000000000000))*(x542)*(x546)*(x552)))+(((r01)*(x548)*(x557)))+(((IkReal(-1.00000000000000))*(x543)*(x546)*(x549)))+(((IkReal(-1.00000000000000))*(r00)*(x545)*(x560)))+(((IkReal(-1.00000000000000))*(x545)*(x547)*(x559)))+(((r01)*(sj6)*(x560)))+(((x557)*(x558)))+(((x554)*(x562)))+(((x553)*(x557))));
01434 evalcond[3]=((((r01)*(x548)*(x560)))+(((x553)*(x560)))+(((x549)*(x559)))+(((IkReal(-1.00000000000000))*(r10)*(x545)*(x559)))+(((IkReal(-1.00000000000000))*(r01)*(x550)*(x557)))+(((IkReal(-1.00000000000000))*(r10)*(x543)*(x546)*(x555)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x545)*(x547)*(x562)))+(((x551)*(x557)))+(((IkReal(-1.00000000000000))*(x546)*(x566)))+(((x558)*(x560))));
01435 evalcond[4]=((((IkReal(-1.00000000000000))*(x542)*(x546)*(x553)))+(((IkReal(-1.00000000000000))*(x542)*(x546)*(x558)))+(((IkReal(-1.00000000000000))*(x546)*(x567)))+(((IkReal(-1.00000000000000))*(x557)*(x568)))+(((IkReal(-1.00000000000000))*(x545)*(x547)*(x557)))+(((IkReal(-1.00000000000000))*(x549)*(x560)))+(((IkReal(-1.00000000000000))*(x545)*(x556)*(x559)))+(((x554)*(x560)))+(((x551)*(x562)))+(((IkReal(-1.00000000000000))*(x552)*(x557))));
01436 evalcond[5]=((((IkReal(-1.00000000000000))*(x560)*(x568)))+(((r01)*(sj6)*(x559)))+(((IkReal(-1.00000000000000))*(r00)*(x545)*(x559)))+(((IkReal(-1.00000000000000))*(x545)*(x556)*(x562)))+(((IkReal(-1.00000000000000))*(r10)*(x545)*(x557)))+(((IkReal(-1.00000000000000))*(x545)*(x547)*(x560)))+(((IkReal(-1.00000000000000))*(x543)*(x546)*(x558)))+(((IkReal(-1.00000000000000))*(x552)*(x560)))+(((IkReal(-1.00000000000000))*(x543)*(x546)*(x553)))+(((IkReal(-1.00000000000000))*(sj3)))+(((x549)*(x557))));
01437 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01438 {
01439 continue;
01440 }
01441 }
01442 
01443 {
01444 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01445 vinfos[0].jointtype = 1;
01446 vinfos[0].foffset = j0;
01447 vinfos[0].indices[0] = _ij0[0];
01448 vinfos[0].indices[1] = _ij0[1];
01449 vinfos[0].maxsolutions = _nj0;
01450 vinfos[1].jointtype = 1;
01451 vinfos[1].foffset = j1;
01452 vinfos[1].indices[0] = _ij1[0];
01453 vinfos[1].indices[1] = _ij1[1];
01454 vinfos[1].maxsolutions = _nj1;
01455 vinfos[2].jointtype = 1;
01456 vinfos[2].foffset = j2;
01457 vinfos[2].indices[0] = _ij2[0];
01458 vinfos[2].indices[1] = _ij2[1];
01459 vinfos[2].maxsolutions = _nj2;
01460 vinfos[3].jointtype = 1;
01461 vinfos[3].foffset = j3;
01462 vinfos[3].indices[0] = _ij3[0];
01463 vinfos[3].indices[1] = _ij3[1];
01464 vinfos[3].maxsolutions = _nj3;
01465 vinfos[4].jointtype = 1;
01466 vinfos[4].foffset = j4;
01467 vinfos[4].indices[0] = _ij4[0];
01468 vinfos[4].indices[1] = _ij4[1];
01469 vinfos[4].maxsolutions = _nj4;
01470 vinfos[5].jointtype = 1;
01471 vinfos[5].foffset = j5;
01472 vinfos[5].indices[0] = _ij5[0];
01473 vinfos[5].indices[1] = _ij5[1];
01474 vinfos[5].maxsolutions = _nj5;
01475 vinfos[6].jointtype = 1;
01476 vinfos[6].foffset = j6;
01477 vinfos[6].indices[0] = _ij6[0];
01478 vinfos[6].indices[1] = _ij6[1];
01479 vinfos[6].maxsolutions = _nj6;
01480 std::vector<int> vfree(0);
01481 solutions.AddSolution(vinfos,vfree);
01482 }
01483 }
01484 }
01485 
01486 }
01487 
01488 }
01489 
01490 } else
01491 {
01492 {
01493 IkReal j4array[1], cj4array[1], sj4array[1];
01494 bool j4valid[1]={false};
01495 _nj4 = 1;
01496 if( IKabs(((gconst50)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
01497     continue;
01498 j4array[0]=IKatan2(((gconst50)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst50)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
01499 sj4array[0]=IKsin(j4array[0]);
01500 cj4array[0]=IKcos(j4array[0]);
01501 if( j4array[0] > IKPI )
01502 {
01503     j4array[0]-=IK2PI;
01504 }
01505 else if( j4array[0] < -IKPI )
01506 {    j4array[0]+=IK2PI;
01507 }
01508 j4valid[0] = true;
01509 for(int ij4 = 0; ij4 < 1; ++ij4)
01510 {
01511 if( !j4valid[ij4] )
01512 {
01513     continue;
01514 }
01515 _ij4[0] = ij4; _ij4[1] = -1;
01516 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01517 {
01518 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01519 {
01520     j4valid[iij4]=false; _ij4[1] = iij4; break; 
01521 }
01522 }
01523 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01524 {
01525 IkReal evalcond[6];
01526 IkReal x569=IKsin(j4);
01527 IkReal x570=IKcos(j4);
01528 IkReal x571=((r22)*(sj5));
01529 IkReal x572=((IkReal(1.00000000000000))*(cj6));
01530 IkReal x573=((IkReal(1.00000000000000))*(cj0));
01531 IkReal x574=((cj5)*(r11));
01532 IkReal x575=((cj5)*(cj6));
01533 IkReal x576=((r11)*(sj6));
01534 IkReal x577=((IkReal(1.00000000000000))*(sj6));
01535 IkReal x578=((cj6)*(r00));
01536 IkReal x579=((r12)*(sj5));
01537 IkReal x580=((r02)*(sj5));
01538 IkReal x581=((cj6)*(r10));
01539 IkReal x582=((cj5)*(sj6));
01540 IkReal x583=((cj5)*(r01));
01541 IkReal x584=((sj0)*(x569));
01542 IkReal x585=((r00)*(x582));
01543 IkReal x586=((cj0)*(x569));
01544 IkReal x587=((sj0)*(x570));
01545 IkReal x588=((r20)*(x570));
01546 IkReal x589=((cj0)*(x570));
01547 IkReal x590=((r21)*(x569));
01548 IkReal x591=((r21)*(x570));
01549 IkReal x592=((r20)*(x569));
01550 IkReal x593=((x570)*(x579));
01551 IkReal x594=((r01)*(sj6)*(x570));
01552 IkReal x595=((cj5)*(r10)*(x577));
01553 evalcond[0]=((IkReal(1.00000000000000))+(((sj6)*(x591)))+(((x582)*(x592)))+(((x575)*(x590)))+(((IkReal(-1.00000000000000))*(x572)*(x588)))+(((x569)*(x571))));
01554 evalcond[1]=((((IkReal(-1.00000000000000))*(x577)*(x590)))+(((x575)*(x591)))+(((x570)*(x571)))+(((cj6)*(x592)))+(((x582)*(x588))));
01555 evalcond[2]=((((r01)*(sj6)*(x587)))+(((IkReal(-1.00000000000000))*(x572)*(x574)*(x586)))+(((x584)*(x585)))+(((IkReal(-1.00000000000000))*(r10)*(x569)*(x573)*(x582)))+(((IkReal(-1.00000000000000))*(r00)*(x572)*(x587)))+(((r01)*(x575)*(x584)))+(((IkReal(-1.00000000000000))*(x570)*(x573)*(x576)))+(((x580)*(x584)))+(((IkReal(-1.00000000000000))*(x569)*(x573)*(x579)))+(((x581)*(x589))));
01556 evalcond[3]=((((x580)*(x587)))+(((IkReal(-1.00000000000000))*(r01)*(x577)*(x584)))+(((r01)*(x575)*(x587)))+(((x585)*(x587)))+(((IkReal(-1.00000000000000))*(x572)*(x574)*(x589)))+(((IkReal(-1.00000000000000))*(x573)*(x593)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(r10)*(x572)*(x586)))+(((x578)*(x584)))+(((IkReal(-1.00000000000000))*(r10)*(x570)*(x573)*(x582)))+(((x576)*(x586))));
01557 evalcond[4]=((((IkReal(-1.00000000000000))*(x572)*(x583)*(x586)))+(((x578)*(x589)))+(((x581)*(x587)))+(((IkReal(-1.00000000000000))*(x573)*(x594)))+(((IkReal(-1.00000000000000))*(x584)*(x595)))+(((IkReal(-1.00000000000000))*(x569)*(x573)*(x580)))+(((IkReal(-1.00000000000000))*(x579)*(x584)))+(((IkReal(-1.00000000000000))*(x569)*(x573)*(x585)))+(((IkReal(-1.00000000000000))*(x576)*(x587)))+(((IkReal(-1.00000000000000))*(x572)*(x574)*(x584))));
01558 evalcond[5]=((((IkReal(-1.00000000000000))*(x572)*(x583)*(x589)))+(((IkReal(-1.00000000000000))*(r00)*(x572)*(x586)))+(((IkReal(-1.00000000000000))*(x587)*(x595)))+(((IkReal(-1.00000000000000))*(x572)*(x574)*(x587)))+(((IkReal(-1.00000000000000))*(x570)*(x573)*(x580)))+(((IkReal(-1.00000000000000))*(x579)*(x587)))+(((IkReal(-1.00000000000000))*(x570)*(x573)*(x585)))+(((r01)*(sj6)*(x586)))+(((x576)*(x584)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r10)*(x572)*(x584))));
01559 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01560 {
01561 continue;
01562 }
01563 }
01564 
01565 {
01566 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01567 vinfos[0].jointtype = 1;
01568 vinfos[0].foffset = j0;
01569 vinfos[0].indices[0] = _ij0[0];
01570 vinfos[0].indices[1] = _ij0[1];
01571 vinfos[0].maxsolutions = _nj0;
01572 vinfos[1].jointtype = 1;
01573 vinfos[1].foffset = j1;
01574 vinfos[1].indices[0] = _ij1[0];
01575 vinfos[1].indices[1] = _ij1[1];
01576 vinfos[1].maxsolutions = _nj1;
01577 vinfos[2].jointtype = 1;
01578 vinfos[2].foffset = j2;
01579 vinfos[2].indices[0] = _ij2[0];
01580 vinfos[2].indices[1] = _ij2[1];
01581 vinfos[2].maxsolutions = _nj2;
01582 vinfos[3].jointtype = 1;
01583 vinfos[3].foffset = j3;
01584 vinfos[3].indices[0] = _ij3[0];
01585 vinfos[3].indices[1] = _ij3[1];
01586 vinfos[3].maxsolutions = _nj3;
01587 vinfos[4].jointtype = 1;
01588 vinfos[4].foffset = j4;
01589 vinfos[4].indices[0] = _ij4[0];
01590 vinfos[4].indices[1] = _ij4[1];
01591 vinfos[4].maxsolutions = _nj4;
01592 vinfos[5].jointtype = 1;
01593 vinfos[5].foffset = j5;
01594 vinfos[5].indices[0] = _ij5[0];
01595 vinfos[5].indices[1] = _ij5[1];
01596 vinfos[5].maxsolutions = _nj5;
01597 vinfos[6].jointtype = 1;
01598 vinfos[6].foffset = j6;
01599 vinfos[6].indices[0] = _ij6[0];
01600 vinfos[6].indices[1] = _ij6[1];
01601 vinfos[6].maxsolutions = _nj6;
01602 std::vector<int> vfree(0);
01603 solutions.AddSolution(vinfos,vfree);
01604 }
01605 }
01606 }
01607 
01608 }
01609 
01610 }
01611 }
01612 }
01613 
01614 } else
01615 {
01616 if( 1 )
01617 {
01618 continue;
01619 
01620 } else
01621 {
01622 }
01623 }
01624 }
01625 }
01626 
01627 } else
01628 {
01629 {
01630 IkReal j3array[1], cj3array[1], sj3array[1];
01631 bool j3valid[1]={false};
01632 _nj3 = 1;
01633 IkReal x596=((sj5)*(sj6));
01634 IkReal x597=((IkReal(1.00000000000000))*(cj6)*(sj5));
01635 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x596)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x597)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x596)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x597)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x596))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x596)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x597)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x596)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x597)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x596)))))-1) <= IKFAST_SINCOS_THRESH )
01636     continue;
01637 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x596)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x597)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x596)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x597)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x596)))));
01638 sj3array[0]=IKsin(j3array[0]);
01639 cj3array[0]=IKcos(j3array[0]);
01640 if( j3array[0] > IKPI )
01641 {
01642     j3array[0]-=IK2PI;
01643 }
01644 else if( j3array[0] < -IKPI )
01645 {    j3array[0]+=IK2PI;
01646 }
01647 j3valid[0] = true;
01648 for(int ij3 = 0; ij3 < 1; ++ij3)
01649 {
01650 if( !j3valid[ij3] )
01651 {
01652     continue;
01653 }
01654 _ij3[0] = ij3; _ij3[1] = -1;
01655 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01656 {
01657 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01658 {
01659     j3valid[iij3]=false; _ij3[1] = iij3; break; 
01660 }
01661 }
01662 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01663 {
01664 IkReal evalcond[3];
01665 IkReal x598=IKsin(j3);
01666 IkReal x599=((sj5)*(sj6));
01667 IkReal x600=((cj0)*(cj5));
01668 IkReal x601=((IkReal(1.00000000000000))*(cj0));
01669 IkReal x602=((IkReal(1.00000000000000))*(sj0));
01670 IkReal x603=((IkReal(1.00000000000000))*(x598));
01671 IkReal x604=((cj6)*(r01)*(sj5));
01672 IkReal x605=((cj6)*(r11)*(sj5));
01673 evalcond[0]=((((r20)*(x599)))+(((IkReal(-1.00000000000000))*(cj2)*(x603)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
01674 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r02)*(x602)))+(((r00)*(sj0)*(x599)))+(((IkReal(-1.00000000000000))*(sj2)*(x603)))+(((IkReal(-1.00000000000000))*(x601)*(x605)))+(((IkReal(-1.00000000000000))*(r10)*(x599)*(x601)))+(((sj0)*(x604)))+(((r12)*(x600))));
01675 evalcond[2]=((((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(r10)*(x599)*(x602)))+(((IkReal(-1.00000000000000))*(r00)*(x599)*(x601)))+(((r02)*(x600)))+(((IkReal(-1.00000000000000))*(x602)*(x605)))+(((IkReal(-1.00000000000000))*(x601)*(x604))));
01676 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
01677 {
01678 continue;
01679 }
01680 }
01681 
01682 {
01683 IkReal dummyeval[1];
01684 IkReal gconst41;
01685 IkReal x606=(r21)*(r21);
01686 IkReal x607=(cj5)*(cj5);
01687 IkReal x608=(sj6)*(sj6);
01688 IkReal x609=(cj6)*(cj6);
01689 IkReal x610=(r20)*(r20);
01690 IkReal x611=((cj6)*(r21));
01691 IkReal x612=((IkReal(2.00000000000000))*(r20)*(sj6));
01692 IkReal x613=((cj5)*(r22)*(sj5));
01693 IkReal x614=((IkReal(1.00000000000000))*(x608));
01694 IkReal x615=((IkReal(1.00000000000000))*(x609));
01695 gconst41=IKsign(((((IkReal(-1.00000000000000))*(x606)*(x614)))+(((IkReal(-1.00000000000000))*(x610)*(x615)))+(((IkReal(-1.00000000000000))*(x607)*(x610)*(x614)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x612)*(x613)))+(((IkReal(-2.00000000000000))*(x611)*(x613)))+(((IkReal(-1.00000000000000))*(x606)*(x607)*(x615)))+(((IkReal(-1.00000000000000))*(x607)*(x611)*(x612)))+(((x611)*(x612)))));
01696 IkReal x616=(r21)*(r21);
01697 IkReal x617=(cj5)*(cj5);
01698 IkReal x618=(sj6)*(sj6);
01699 IkReal x619=(cj6)*(cj6);
01700 IkReal x620=(r20)*(r20);
01701 IkReal x621=((cj6)*(r21));
01702 IkReal x622=((IkReal(2.00000000000000))*(r20)*(sj6));
01703 IkReal x623=((cj5)*(r22)*(sj5));
01704 IkReal x624=((IkReal(1.00000000000000))*(x618));
01705 IkReal x625=((IkReal(1.00000000000000))*(x619));
01706 dummyeval[0]=((((IkReal(-1.00000000000000))*(x616)*(x617)*(x625)))+(((IkReal(-1.00000000000000))*(x616)*(x624)))+(((IkReal(-1.00000000000000))*(x620)*(x625)))+(((IkReal(-2.00000000000000))*(x621)*(x623)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((x621)*(x622)))+(((IkReal(-1.00000000000000))*(x622)*(x623)))+(((IkReal(-1.00000000000000))*(x617)*(x620)*(x624)))+(((IkReal(-1.00000000000000))*(x617)*(x621)*(x622))));
01707 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01708 {
01709 {
01710 IkReal dummyeval[1];
01711 IkReal gconst42;
01712 IkReal x626=(cj6)*(cj6);
01713 IkReal x627=(sj6)*(sj6);
01714 IkReal x628=((IkReal(1.00000000000000))*(r01));
01715 IkReal x629=((sj0)*(sj5));
01716 IkReal x630=((cj6)*(r22));
01717 IkReal x631=((r21)*(sj6));
01718 IkReal x632=((r00)*(r21));
01719 IkReal x633=((cj0)*(sj5));
01720 IkReal x634=((cj6)*(r20));
01721 IkReal x635=((r22)*(sj6));
01722 IkReal x636=((cj0)*(cj5));
01723 IkReal x637=((IkReal(1.00000000000000))*(r10));
01724 IkReal x638=((cj5)*(sj0));
01725 IkReal x639=((r20)*(x627));
01726 IkReal x640=((x626)*(x638));
01727 gconst42=IKsign(((((r00)*(x629)*(x630)))+(((r02)*(x629)*(x631)))+(((IkReal(-1.00000000000000))*(r12)*(x631)*(x633)))+(((IkReal(-1.00000000000000))*(x628)*(x638)*(x639)))+(((r12)*(x633)*(x634)))+(((IkReal(-1.00000000000000))*(x630)*(x633)*(x637)))+(((IkReal(-1.00000000000000))*(r21)*(x626)*(x636)*(x637)))+(((IkReal(-1.00000000000000))*(r21)*(x627)*(x636)*(x637)))+(((r11)*(x633)*(x635)))+(((IkReal(-1.00000000000000))*(x628)*(x629)*(x635)))+(((IkReal(-1.00000000000000))*(r02)*(x629)*(x634)))+(((r11)*(r20)*(x626)*(x636)))+(((IkReal(-1.00000000000000))*(r20)*(x628)*(x640)))+(((x632)*(x640)))+(((r11)*(x636)*(x639)))+(((x627)*(x632)*(x638)))));
01728 IkReal x641=(cj6)*(cj6);
01729 IkReal x642=(sj6)*(sj6);
01730 IkReal x643=((IkReal(1.00000000000000))*(r01));
01731 IkReal x644=((sj0)*(sj5));
01732 IkReal x645=((cj6)*(r22));
01733 IkReal x646=((r21)*(sj6));
01734 IkReal x647=((r00)*(r21));
01735 IkReal x648=((cj0)*(sj5));
01736 IkReal x649=((cj6)*(r20));
01737 IkReal x650=((r22)*(sj6));
01738 IkReal x651=((cj0)*(cj5));
01739 IkReal x652=((IkReal(1.00000000000000))*(r10));
01740 IkReal x653=((cj5)*(sj0));
01741 IkReal x654=((r20)*(x642));
01742 IkReal x655=((x641)*(x653));
01743 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(x644)*(x649)))+(((IkReal(-1.00000000000000))*(r21)*(x642)*(x651)*(x652)))+(((r02)*(x644)*(x646)))+(((x642)*(x647)*(x653)))+(((IkReal(-1.00000000000000))*(x643)*(x644)*(x650)))+(((IkReal(-1.00000000000000))*(r20)*(x643)*(x655)))+(((IkReal(-1.00000000000000))*(x643)*(x653)*(x654)))+(((IkReal(-1.00000000000000))*(x645)*(x648)*(x652)))+(((r11)*(r20)*(x641)*(x651)))+(((r00)*(x644)*(x645)))+(((x647)*(x655)))+(((IkReal(-1.00000000000000))*(r21)*(x641)*(x651)*(x652)))+(((IkReal(-1.00000000000000))*(r12)*(x646)*(x648)))+(((r11)*(x648)*(x650)))+(((r12)*(x648)*(x649)))+(((r11)*(x651)*(x654))));
01744 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01745 {
01746 continue;
01747 
01748 } else
01749 {
01750 {
01751 IkReal j4array[1], cj4array[1], sj4array[1];
01752 bool j4valid[1]={false};
01753 _nj4 = 1;
01754 IkReal x656=((r01)*(sj0));
01755 IkReal x657=((cj2)*(sj6));
01756 IkReal x658=((IkReal(1.00000000000000))*(cj0));
01757 IkReal x659=((r10)*(sj2));
01758 IkReal x660=((sj2)*(sj5));
01759 IkReal x661=((cj5)*(sj6));
01760 IkReal x662=((sj2)*(sj6));
01761 IkReal x663=((cj2)*(cj6));
01762 IkReal x664=((cj5)*(cj6)*(sj2));
01763 IkReal x665=((r00)*(sj0)*(sj2));
01764 if( IKabs(((gconst42)*(((((cj6)*(x665)))+(((r20)*(x663)))+(((cj0)*(r11)*(x662)))+(((IkReal(-1.00000000000000))*(r21)*(x657)))+(((IkReal(-1.00000000000000))*(cj6)*(x658)*(x659)))+(((IkReal(-1.00000000000000))*(x656)*(x662))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((cj2)*(r22)*(sj5)))+(((x656)*(x664)))+(((x661)*(x665)))+(((IkReal(-1.00000000000000))*(x658)*(x659)*(x661)))+(((cj5)*(r21)*(x663)))+(((IkReal(-1.00000000000000))*(r11)*(x658)*(x664)))+(((r02)*(sj0)*(x660)))+(((cj5)*(r20)*(x657)))+(((IkReal(-1.00000000000000))*(r12)*(x658)*(x660))))))) < IKFAST_ATAN2_MAGTHRESH )
01765     continue;
01766 j4array[0]=IKatan2(((gconst42)*(((((cj6)*(x665)))+(((r20)*(x663)))+(((cj0)*(r11)*(x662)))+(((IkReal(-1.00000000000000))*(r21)*(x657)))+(((IkReal(-1.00000000000000))*(cj6)*(x658)*(x659)))+(((IkReal(-1.00000000000000))*(x656)*(x662)))))), ((gconst42)*(((((cj2)*(r22)*(sj5)))+(((x656)*(x664)))+(((x661)*(x665)))+(((IkReal(-1.00000000000000))*(x658)*(x659)*(x661)))+(((cj5)*(r21)*(x663)))+(((IkReal(-1.00000000000000))*(r11)*(x658)*(x664)))+(((r02)*(sj0)*(x660)))+(((cj5)*(r20)*(x657)))+(((IkReal(-1.00000000000000))*(r12)*(x658)*(x660)))))));
01767 sj4array[0]=IKsin(j4array[0]);
01768 cj4array[0]=IKcos(j4array[0]);
01769 if( j4array[0] > IKPI )
01770 {
01771     j4array[0]-=IK2PI;
01772 }
01773 else if( j4array[0] < -IKPI )
01774 {    j4array[0]+=IK2PI;
01775 }
01776 j4valid[0] = true;
01777 for(int ij4 = 0; ij4 < 1; ++ij4)
01778 {
01779 if( !j4valid[ij4] )
01780 {
01781     continue;
01782 }
01783 _ij4[0] = ij4; _ij4[1] = -1;
01784 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01785 {
01786 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01787 {
01788     j4valid[iij4]=false; _ij4[1] = iij4; break; 
01789 }
01790 }
01791 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01792 {
01793 IkReal evalcond[6];
01794 IkReal x666=IKsin(j4);
01795 IkReal x667=IKcos(j4);
01796 IkReal x668=((r00)*(sj6));
01797 IkReal x669=((IkReal(1.00000000000000))*(r12));
01798 IkReal x670=((IkReal(1.00000000000000))*(cj6));
01799 IkReal x671=((cj6)*(r01));
01800 IkReal x672=((r11)*(sj6));
01801 IkReal x673=((r01)*(sj6));
01802 IkReal x674=((IkReal(1.00000000000000))*(cj5));
01803 IkReal x675=((IkReal(1.00000000000000))*(sj6));
01804 IkReal x676=((cj5)*(sj6));
01805 IkReal x677=((cj5)*(r11));
01806 IkReal x678=((cj6)*(r00));
01807 IkReal x679=((cj5)*(cj6));
01808 IkReal x680=((r02)*(sj5));
01809 IkReal x681=((cj6)*(r10));
01810 IkReal x682=((r10)*(sj6));
01811 IkReal x683=((cj5)*(r01));
01812 IkReal x684=((sj5)*(x666));
01813 IkReal x685=((cj0)*(x667));
01814 IkReal x686=((cj0)*(x666));
01815 IkReal x687=((sj0)*(x667));
01816 IkReal x688=((sj0)*(x666));
01817 IkReal x689=((r20)*(x667));
01818 IkReal x690=((r21)*(x666));
01819 IkReal x691=((r21)*(x667));
01820 IkReal x692=((r20)*(x666));
01821 IkReal x693=((cj5)*(x688));
01822 evalcond[0]=((((sj6)*(x691)))+(((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x670)*(x689)))+(((r22)*(x684)))+(((x679)*(x690)))+(((x676)*(x692))));
01823 evalcond[1]=((((cj6)*(x692)))+(((x679)*(x691)))+(((cj2)*(cj3)))+(((r22)*(sj5)*(x667)))+(((x676)*(x689)))+(((IkReal(-1.00000000000000))*(x675)*(x690))));
01824 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(x669)*(x684)))+(((x681)*(x685)))+(((x680)*(x688)))+(((x668)*(x693)))+(((IkReal(-1.00000000000000))*(r00)*(x670)*(x687)))+(((x673)*(x687)))+(((IkReal(-1.00000000000000))*(x670)*(x677)*(x686)))+(((x671)*(x693)))+(cj2)+(((IkReal(-1.00000000000000))*(x674)*(x682)*(x686)))+(((IkReal(-1.00000000000000))*(x672)*(x685))));
01825 evalcond[3]=((((x680)*(x687)))+(((cj5)*(x668)*(x687)))+(((IkReal(-1.00000000000000))*(x673)*(x688)))+(((IkReal(-1.00000000000000))*(x670)*(x677)*(x685)))+(((IkReal(-1.00000000000000))*(r10)*(x670)*(x686)))+(((x678)*(x688)))+(((x672)*(x686)))+(((IkReal(-1.00000000000000))*(sj5)*(x669)*(x685)))+(((cj5)*(x671)*(x687)))+(((IkReal(-1.00000000000000))*(x674)*(x682)*(x685)))+(((cj3)*(sj2))));
01826 evalcond[4]=((((IkReal(-1.00000000000000))*(x680)*(x686)))+(((IkReal(-1.00000000000000))*(x668)*(x674)*(x686)))+(((IkReal(-1.00000000000000))*(x670)*(x677)*(x688)))+(((IkReal(-1.00000000000000))*(x670)*(x683)*(x686)))+(((IkReal(-1.00000000000000))*(sj0)*(x669)*(x684)))+(((IkReal(-1.00000000000000))*(x672)*(x687)))+(((x681)*(x687)))+(((IkReal(-1.00000000000000))*(x674)*(x682)*(x688)))+(((IkReal(-1.00000000000000))*(x673)*(x685)))+(((x678)*(x685))));
01827 evalcond[5]=((((IkReal(-1.00000000000000))*(x674)*(x682)*(x687)))+(((IkReal(-1.00000000000000))*(x680)*(x685)))+(((IkReal(-1.00000000000000))*(sj5)*(x669)*(x687)))+(((x673)*(x686)))+(((IkReal(-1.00000000000000))*(r00)*(x670)*(x686)))+(((IkReal(-1.00000000000000))*(x670)*(x677)*(x687)))+(((IkReal(-1.00000000000000))*(x668)*(x674)*(x685)))+(((x672)*(x688)))+(((IkReal(-1.00000000000000))*(x670)*(x683)*(x685)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r10)*(x670)*(x688))));
01828 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01829 {
01830 continue;
01831 }
01832 }
01833 
01834 {
01835 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01836 vinfos[0].jointtype = 1;
01837 vinfos[0].foffset = j0;
01838 vinfos[0].indices[0] = _ij0[0];
01839 vinfos[0].indices[1] = _ij0[1];
01840 vinfos[0].maxsolutions = _nj0;
01841 vinfos[1].jointtype = 1;
01842 vinfos[1].foffset = j1;
01843 vinfos[1].indices[0] = _ij1[0];
01844 vinfos[1].indices[1] = _ij1[1];
01845 vinfos[1].maxsolutions = _nj1;
01846 vinfos[2].jointtype = 1;
01847 vinfos[2].foffset = j2;
01848 vinfos[2].indices[0] = _ij2[0];
01849 vinfos[2].indices[1] = _ij2[1];
01850 vinfos[2].maxsolutions = _nj2;
01851 vinfos[3].jointtype = 1;
01852 vinfos[3].foffset = j3;
01853 vinfos[3].indices[0] = _ij3[0];
01854 vinfos[3].indices[1] = _ij3[1];
01855 vinfos[3].maxsolutions = _nj3;
01856 vinfos[4].jointtype = 1;
01857 vinfos[4].foffset = j4;
01858 vinfos[4].indices[0] = _ij4[0];
01859 vinfos[4].indices[1] = _ij4[1];
01860 vinfos[4].maxsolutions = _nj4;
01861 vinfos[5].jointtype = 1;
01862 vinfos[5].foffset = j5;
01863 vinfos[5].indices[0] = _ij5[0];
01864 vinfos[5].indices[1] = _ij5[1];
01865 vinfos[5].maxsolutions = _nj5;
01866 vinfos[6].jointtype = 1;
01867 vinfos[6].foffset = j6;
01868 vinfos[6].indices[0] = _ij6[0];
01869 vinfos[6].indices[1] = _ij6[1];
01870 vinfos[6].maxsolutions = _nj6;
01871 std::vector<int> vfree(0);
01872 solutions.AddSolution(vinfos,vfree);
01873 }
01874 }
01875 }
01876 
01877 }
01878 
01879 }
01880 
01881 } else
01882 {
01883 {
01884 IkReal j4array[1], cj4array[1], sj4array[1];
01885 bool j4valid[1]={false};
01886 _nj4 = 1;
01887 IkReal x694=((IkReal(1.00000000000000))*(sj2));
01888 IkReal x695=((r22)*(sj5));
01889 IkReal x696=((cj5)*(sj6));
01890 IkReal x697=((cj2)*(cj3));
01891 IkReal x698=((r21)*(sj6));
01892 IkReal x699=((r20)*(x697));
01893 IkReal x700=((cj5)*(cj6)*(r21));
01894 if( IKabs(((gconst41)*(((((cj6)*(x699)))+(((IkReal(-1.00000000000000))*(x697)*(x698)))+(((IkReal(-1.00000000000000))*(r20)*(x694)*(x696)))+(((IkReal(-1.00000000000000))*(x694)*(x695)))+(((IkReal(-1.00000000000000))*(x694)*(x700))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((x697)*(x700)))+(((cj6)*(r20)*(sj2)))+(((IkReal(-1.00000000000000))*(x694)*(x698)))+(((x696)*(x699)))+(((x695)*(x697))))))) < IKFAST_ATAN2_MAGTHRESH )
01895     continue;
01896 j4array[0]=IKatan2(((gconst41)*(((((cj6)*(x699)))+(((IkReal(-1.00000000000000))*(x697)*(x698)))+(((IkReal(-1.00000000000000))*(r20)*(x694)*(x696)))+(((IkReal(-1.00000000000000))*(x694)*(x695)))+(((IkReal(-1.00000000000000))*(x694)*(x700)))))), ((gconst41)*(((((x697)*(x700)))+(((cj6)*(r20)*(sj2)))+(((IkReal(-1.00000000000000))*(x694)*(x698)))+(((x696)*(x699)))+(((x695)*(x697)))))));
01897 sj4array[0]=IKsin(j4array[0]);
01898 cj4array[0]=IKcos(j4array[0]);
01899 if( j4array[0] > IKPI )
01900 {
01901     j4array[0]-=IK2PI;
01902 }
01903 else if( j4array[0] < -IKPI )
01904 {    j4array[0]+=IK2PI;
01905 }
01906 j4valid[0] = true;
01907 for(int ij4 = 0; ij4 < 1; ++ij4)
01908 {
01909 if( !j4valid[ij4] )
01910 {
01911     continue;
01912 }
01913 _ij4[0] = ij4; _ij4[1] = -1;
01914 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01915 {
01916 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01917 {
01918     j4valid[iij4]=false; _ij4[1] = iij4; break; 
01919 }
01920 }
01921 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01922 {
01923 IkReal evalcond[6];
01924 IkReal x701=IKsin(j4);
01925 IkReal x702=IKcos(j4);
01926 IkReal x703=((r00)*(sj6));
01927 IkReal x704=((IkReal(1.00000000000000))*(r12));
01928 IkReal x705=((IkReal(1.00000000000000))*(cj6));
01929 IkReal x706=((cj6)*(r01));
01930 IkReal x707=((r11)*(sj6));
01931 IkReal x708=((r01)*(sj6));
01932 IkReal x709=((IkReal(1.00000000000000))*(cj5));
01933 IkReal x710=((IkReal(1.00000000000000))*(sj6));
01934 IkReal x711=((cj5)*(sj6));
01935 IkReal x712=((cj5)*(r11));
01936 IkReal x713=((cj6)*(r00));
01937 IkReal x714=((cj5)*(cj6));
01938 IkReal x715=((r02)*(sj5));
01939 IkReal x716=((cj6)*(r10));
01940 IkReal x717=((r10)*(sj6));
01941 IkReal x718=((cj5)*(r01));
01942 IkReal x719=((sj5)*(x701));
01943 IkReal x720=((cj0)*(x702));
01944 IkReal x721=((cj0)*(x701));
01945 IkReal x722=((sj0)*(x702));
01946 IkReal x723=((sj0)*(x701));
01947 IkReal x724=((r20)*(x702));
01948 IkReal x725=((r21)*(x701));
01949 IkReal x726=((r21)*(x702));
01950 IkReal x727=((r20)*(x701));
01951 IkReal x728=((cj5)*(x723));
01952 evalcond[0]=((((sj6)*(x726)))+(((r22)*(x719)))+(((IkReal(-1.00000000000000))*(sj2)))+(((x711)*(x727)))+(((x714)*(x725)))+(((IkReal(-1.00000000000000))*(x705)*(x724))));
01953 evalcond[1]=((((x714)*(x726)))+(((cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(x710)*(x725)))+(((r22)*(sj5)*(x702)))+(((x711)*(x724)))+(((cj6)*(x727))));
01954 evalcond[2]=((((x715)*(x723)))+(((x703)*(x728)))+(((x708)*(x722)))+(((x706)*(x728)))+(((x716)*(x720)))+(cj2)+(((IkReal(-1.00000000000000))*(x705)*(x712)*(x721)))+(((IkReal(-1.00000000000000))*(cj0)*(x704)*(x719)))+(((IkReal(-1.00000000000000))*(r00)*(x705)*(x722)))+(((IkReal(-1.00000000000000))*(x709)*(x717)*(x721)))+(((IkReal(-1.00000000000000))*(x707)*(x720))));
01955 evalcond[3]=((((x715)*(x722)))+(((IkReal(-1.00000000000000))*(r10)*(x705)*(x721)))+(((x707)*(x721)))+(((cj5)*(x706)*(x722)))+(((cj5)*(x703)*(x722)))+(((IkReal(-1.00000000000000))*(x709)*(x717)*(x720)))+(((x713)*(x723)))+(((IkReal(-1.00000000000000))*(x705)*(x712)*(x720)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(sj5)*(x704)*(x720)))+(((IkReal(-1.00000000000000))*(x708)*(x723))));
01956 evalcond[4]=((((IkReal(-1.00000000000000))*(x709)*(x717)*(x723)))+(((IkReal(-1.00000000000000))*(x703)*(x709)*(x721)))+(((IkReal(-1.00000000000000))*(sj0)*(x704)*(x719)))+(((IkReal(-1.00000000000000))*(x715)*(x721)))+(((IkReal(-1.00000000000000))*(x708)*(x720)))+(((x713)*(x720)))+(((x716)*(x722)))+(((IkReal(-1.00000000000000))*(x705)*(x718)*(x721)))+(((IkReal(-1.00000000000000))*(x707)*(x722)))+(((IkReal(-1.00000000000000))*(x705)*(x712)*(x723))));
01957 evalcond[5]=((((IkReal(-1.00000000000000))*(x715)*(x720)))+(((IkReal(-1.00000000000000))*(r00)*(x705)*(x721)))+(((IkReal(-1.00000000000000))*(r10)*(x705)*(x723)))+(((x707)*(x723)))+(((IkReal(-1.00000000000000))*(x705)*(x718)*(x720)))+(((IkReal(-1.00000000000000))*(x703)*(x709)*(x720)))+(((IkReal(-1.00000000000000))*(x705)*(x712)*(x722)))+(((IkReal(-1.00000000000000))*(x709)*(x717)*(x722)))+(((IkReal(-1.00000000000000))*(sj3)))+(((x708)*(x721)))+(((IkReal(-1.00000000000000))*(sj5)*(x704)*(x722))));
01958 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01959 {
01960 continue;
01961 }
01962 }
01963 
01964 {
01965 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
01966 vinfos[0].jointtype = 1;
01967 vinfos[0].foffset = j0;
01968 vinfos[0].indices[0] = _ij0[0];
01969 vinfos[0].indices[1] = _ij0[1];
01970 vinfos[0].maxsolutions = _nj0;
01971 vinfos[1].jointtype = 1;
01972 vinfos[1].foffset = j1;
01973 vinfos[1].indices[0] = _ij1[0];
01974 vinfos[1].indices[1] = _ij1[1];
01975 vinfos[1].maxsolutions = _nj1;
01976 vinfos[2].jointtype = 1;
01977 vinfos[2].foffset = j2;
01978 vinfos[2].indices[0] = _ij2[0];
01979 vinfos[2].indices[1] = _ij2[1];
01980 vinfos[2].maxsolutions = _nj2;
01981 vinfos[3].jointtype = 1;
01982 vinfos[3].foffset = j3;
01983 vinfos[3].indices[0] = _ij3[0];
01984 vinfos[3].indices[1] = _ij3[1];
01985 vinfos[3].maxsolutions = _nj3;
01986 vinfos[4].jointtype = 1;
01987 vinfos[4].foffset = j4;
01988 vinfos[4].indices[0] = _ij4[0];
01989 vinfos[4].indices[1] = _ij4[1];
01990 vinfos[4].maxsolutions = _nj4;
01991 vinfos[5].jointtype = 1;
01992 vinfos[5].foffset = j5;
01993 vinfos[5].indices[0] = _ij5[0];
01994 vinfos[5].indices[1] = _ij5[1];
01995 vinfos[5].maxsolutions = _nj5;
01996 vinfos[6].jointtype = 1;
01997 vinfos[6].foffset = j6;
01998 vinfos[6].indices[0] = _ij6[0];
01999 vinfos[6].indices[1] = _ij6[1];
02000 vinfos[6].maxsolutions = _nj6;
02001 std::vector<int> vfree(0);
02002 solutions.AddSolution(vinfos,vfree);
02003 }
02004 }
02005 }
02006 
02007 }
02008 
02009 }
02010 }
02011 }
02012 
02013 }
02014 
02015 }
02016 
02017 } else
02018 {
02019 {
02020 IkReal j4array[1], cj4array[1], sj4array[1];
02021 bool j4valid[1]={false};
02022 _nj4 = 1;
02023 IkReal x729=((r01)*(sj0));
02024 IkReal x730=((IkReal(1.00000000000000))*(cj0));
02025 IkReal x731=((r10)*(sj2));
02026 IkReal x732=((sj2)*(sj5));
02027 IkReal x733=((IkReal(1.00000000000000))*(sj6));
02028 IkReal x734=((cj2)*(r21));
02029 IkReal x735=((cj5)*(sj6));
02030 IkReal x736=((cj2)*(r20));
02031 IkReal x737=((cj5)*(cj6)*(sj2));
02032 IkReal x738=((r00)*(sj0)*(sj2));
02033 if( IKabs(((gconst39)*(((((cj6)*(x736)))+(((cj6)*(x738)))+(((cj0)*(r11)*(sj2)*(sj6)))+(((IkReal(-1.00000000000000))*(x733)*(x734)))+(((IkReal(-1.00000000000000))*(sj2)*(x729)*(x733)))+(((IkReal(-1.00000000000000))*(cj6)*(x730)*(x731))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((cj2)*(r22)*(sj5)))+(((x729)*(x737)))+(((IkReal(-1.00000000000000))*(r12)*(x730)*(x732)))+(((x735)*(x738)))+(((IkReal(-1.00000000000000))*(r11)*(x730)*(x737)))+(((x735)*(x736)))+(((r02)*(sj0)*(x732)))+(((IkReal(-1.00000000000000))*(x730)*(x731)*(x735)))+(((cj5)*(cj6)*(x734))))))) < IKFAST_ATAN2_MAGTHRESH )
02034     continue;
02035 j4array[0]=IKatan2(((gconst39)*(((((cj6)*(x736)))+(((cj6)*(x738)))+(((cj0)*(r11)*(sj2)*(sj6)))+(((IkReal(-1.00000000000000))*(x733)*(x734)))+(((IkReal(-1.00000000000000))*(sj2)*(x729)*(x733)))+(((IkReal(-1.00000000000000))*(cj6)*(x730)*(x731)))))), ((gconst39)*(((((cj2)*(r22)*(sj5)))+(((x729)*(x737)))+(((IkReal(-1.00000000000000))*(r12)*(x730)*(x732)))+(((x735)*(x738)))+(((IkReal(-1.00000000000000))*(r11)*(x730)*(x737)))+(((x735)*(x736)))+(((r02)*(sj0)*(x732)))+(((IkReal(-1.00000000000000))*(x730)*(x731)*(x735)))+(((cj5)*(cj6)*(x734)))))));
02036 sj4array[0]=IKsin(j4array[0]);
02037 cj4array[0]=IKcos(j4array[0]);
02038 if( j4array[0] > IKPI )
02039 {
02040     j4array[0]-=IK2PI;
02041 }
02042 else if( j4array[0] < -IKPI )
02043 {    j4array[0]+=IK2PI;
02044 }
02045 j4valid[0] = true;
02046 for(int ij4 = 0; ij4 < 1; ++ij4)
02047 {
02048 if( !j4valid[ij4] )
02049 {
02050     continue;
02051 }
02052 _ij4[0] = ij4; _ij4[1] = -1;
02053 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
02054 {
02055 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
02056 {
02057     j4valid[iij4]=false; _ij4[1] = iij4; break; 
02058 }
02059 }
02060 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
02061 {
02062 IkReal evalcond[3];
02063 IkReal x739=IKsin(j4);
02064 IkReal x740=IKcos(j4);
02065 IkReal x741=((r00)*(sj6));
02066 IkReal x742=((cj6)*(r01));
02067 IkReal x743=((IkReal(1.00000000000000))*(cj0));
02068 IkReal x744=((IkReal(1.00000000000000))*(sj0));
02069 IkReal x745=((r10)*(sj6));
02070 IkReal x746=((sj5)*(x739));
02071 IkReal x747=((IkReal(1.00000000000000))*(cj6)*(r11));
02072 IkReal x748=((cj5)*(x739));
02073 IkReal x749=((cj6)*(x740));
02074 IkReal x750=((sj0)*(x748));
02075 IkReal x751=((r01)*(sj6)*(x740));
02076 IkReal x752=((r11)*(sj6)*(x740));
02077 evalcond[0]=((((r20)*(sj6)*(x748)))+(((IkReal(-1.00000000000000))*(sj2)))+(((r21)*(sj6)*(x740)))+(((r22)*(x746)))+(((IkReal(-1.00000000000000))*(r20)*(x749)))+(((cj6)*(r21)*(x748))));
02078 evalcond[1]=((((IkReal(-1.00000000000000))*(r12)*(x743)*(x746)))+(((sj0)*(x751)))+(((IkReal(-1.00000000000000))*(x743)*(x752)))+(((IkReal(-1.00000000000000))*(x743)*(x745)*(x748)))+(cj2)+(((x742)*(x750)))+(((x741)*(x750)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x743)*(x748)))+(((IkReal(-1.00000000000000))*(r00)*(x744)*(x749)))+(((cj0)*(r10)*(x749)))+(((r02)*(sj0)*(x746))));
02079 evalcond[2]=((((IkReal(-1.00000000000000))*(x744)*(x745)*(x748)))+(((IkReal(-1.00000000000000))*(x742)*(x743)*(x748)))+(((IkReal(-1.00000000000000))*(r02)*(x743)*(x746)))+(((IkReal(-1.00000000000000))*(x744)*(x752)))+(((cj0)*(r00)*(x749)))+(((IkReal(-1.00000000000000))*(r12)*(x744)*(x746)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x744)*(x748)))+(((IkReal(-1.00000000000000))*(x741)*(x743)*(x748)))+(((r10)*(sj0)*(x749)))+(((IkReal(-1.00000000000000))*(x743)*(x751))));
02080 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
02081 {
02082 continue;
02083 }
02084 }
02085 
02086 {
02087 IkReal dummyeval[1];
02088 IkReal gconst43;
02089 gconst43=IKsign(cj2);
02090 dummyeval[0]=cj2;
02091 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02092 {
02093 {
02094 IkReal dummyeval[1];
02095 dummyeval[0]=cj2;
02096 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02097 {
02098 {
02099 IkReal dummyeval[1];
02100 dummyeval[0]=sj2;
02101 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02102 {
02103 {
02104 IkReal evalcond[9];
02105 IkReal x753=((cj5)*(sj4));
02106 IkReal x754=((IkReal(1.00000000000000))*(sj6));
02107 IkReal x755=((r10)*(sj0));
02108 IkReal x756=((sj4)*(sj5));
02109 IkReal x757=((cj5)*(cj6));
02110 IkReal x758=((r01)*(sj0));
02111 IkReal x759=((IkReal(1.00000000000000))*(r02));
02112 IkReal x760=((IkReal(0.374290000000000))*(cj0));
02113 IkReal x761=((cj5)*(r12));
02114 IkReal x762=((cj6)*(sj5));
02115 IkReal x763=((cj0)*(r11));
02116 IkReal x764=((cj5)*(sj0));
02117 IkReal x765=((r20)*(sj6));
02118 IkReal x766=((IkReal(1.00000000000000))*(sj0));
02119 IkReal x767=((cj4)*(cj5));
02120 IkReal x768=((IkReal(1.00000000000000))*(cj6));
02121 IkReal x769=((IkReal(0.0100000000000000))*(sj5));
02122 IkReal x770=((sj5)*(sj6));
02123 IkReal x771=((cj0)*(r10));
02124 IkReal x772=((cj4)*(cj6));
02125 IkReal x773=((cj0)*(r01));
02126 IkReal x774=((IkReal(1.00000000000000))*(cj4));
02127 IkReal x775=((cj0)*(r00));
02128 IkReal x776=((IkReal(0.374290000000000))*(sj0));
02129 IkReal x777=((cj0)*(r12));
02130 IkReal x778=((IkReal(0.374290000000000))*(sj5));
02131 IkReal x779=((cj4)*(sj6));
02132 IkReal x780=((IkReal(1.00000000000000))*(cj0));
02133 IkReal x781=((r02)*(sj0));
02134 IkReal x782=((IkReal(0.0100000000000000))*(cj5));
02135 IkReal x783=((r11)*(sj0));
02136 IkReal x784=((r00)*(sj0)*(sj6));
02137 IkReal x785=((r00)*(x772));
02138 IkReal x786=((sj6)*(x782));
02139 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
02140 evalcond[1]=((((r22)*(x756)))+(((cj6)*(r21)*(x753)))+(((x753)*(x765)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x768)))+(((r21)*(x779))));
02141 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x769)))+(((IkReal(-0.0100000000000000))*(r21)*(x757)))+(((IkReal(-1.00000000000000))*(x765)*(x782)))+(((IkReal(0.374290000000000))*(r21)*(x762)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x765)*(x778))));
02142 evalcond[3]=((((cj0)*(x761)))+(((x758)*(x762)))+(((IkReal(-1.00000000000000))*(x762)*(x763)))+(((IkReal(-1.00000000000000))*(x759)*(x764)))+(((IkReal(-1.00000000000000))*(sj5)*(x754)*(x771)))+(((r00)*(sj0)*(x770))));
02143 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x753)*(x763)*(x768)))+(((x753)*(x784)))+(((IkReal(-1.00000000000000))*(cj4)*(x754)*(x763)))+(((cj6)*(x753)*(x758)))+(((IkReal(-1.00000000000000))*(x753)*(x754)*(x771)))+(((x756)*(x781)))+(((IkReal(-1.00000000000000))*(x766)*(x785)))+(((x771)*(x772)))+(((x758)*(x779)))+(((IkReal(-1.00000000000000))*(x756)*(x777))));
02144 evalcond[5]=((((sj4)*(sj6)*(x763)))+(((IkReal(-1.00000000000000))*(sj4)*(x754)*(x758)))+(((IkReal(-1.00000000000000))*(sj5)*(x774)*(x777)))+(((r00)*(x764)*(x779)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(sj5)*(x781)))+(((IkReal(-1.00000000000000))*(sj4)*(x768)*(x771)))+(((IkReal(-1.00000000000000))*(x754)*(x767)*(x771)))+(((cj4)*(x757)*(x758)))+(((IkReal(-1.00000000000000))*(x757)*(x763)*(x774))));
02145 evalcond[6]=((((x755)*(x772)))+(((IkReal(-1.00000000000000))*(x753)*(x754)*(x775)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x753)*(x766)))+(((x772)*(x775)))+(((IkReal(-1.00000000000000))*(cj4)*(x754)*(x783)))+(((IkReal(-1.00000000000000))*(x753)*(x768)*(x773)))+(((IkReal(-1.00000000000000))*(x753)*(x754)*(x755)))+(((IkReal(-1.00000000000000))*(cj0)*(x756)*(x759)))+(((IkReal(-1.00000000000000))*(cj4)*(x754)*(x773)))+(((IkReal(-1.00000000000000))*(r12)*(x756)*(x766))));
02146 evalcond[7]=((((IkReal(-0.0100000000000000))*(x757)*(x758)))+(((IkReal(0.374290000000000))*(x758)*(x762)))+(((x769)*(x777)))+(((IkReal(-1.00000000000000))*(r11)*(x760)*(x762)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x764)))+(((IkReal(-1.00000000000000))*(py)*(x780)))+(((IkReal(-1.00000000000000))*(x769)*(x781)))+(((x760)*(x761)))+(((r00)*(x770)*(x776)))+(((x771)*(x786)))+(((IkReal(0.0100000000000000))*(x757)*(x763)))+(((IkReal(-1.00000000000000))*(r10)*(x760)*(x770)))+(((px)*(sj0)))+(((IkReal(-0.374290000000000))*(r02)*(x764))));
02147 evalcond[8]=((IkReal(0.433420000000000))+(((x755)*(x786)))+(((x775)*(x786)))+(((IkReal(-0.374290000000000))*(x755)*(x770)))+(((IkReal(-1.00000000000000))*(r11)*(x762)*(x776)))+(((IkReal(-1.00000000000000))*(py)*(x766)))+(((IkReal(0.0100000000000000))*(x757)*(x773)))+(((x761)*(x776)))+(((cj0)*(r02)*(x769)))+(((IkReal(0.0100000000000000))*(x757)*(x783)))+(((IkReal(-1.00000000000000))*(r01)*(x760)*(x762)))+(((IkReal(-1.00000000000000))*(px)*(x780)))+(((cj5)*(r02)*(x760)))+(((r12)*(sj0)*(x769)))+(((IkReal(-1.00000000000000))*(r00)*(x760)*(x770))));
02148 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
02149 {
02150 {
02151 IkReal j3array[1], cj3array[1], sj3array[1];
02152 bool j3valid[1]={false};
02153 _nj3 = 1;
02154 IkReal x787=((IkReal(1.00000000000000))*(cj4));
02155 IkReal x788=((cj6)*(r21));
02156 IkReal x789=((r20)*(sj6));
02157 if( IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x788)))+(((sj5)*(x789))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x787)*(x788)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x787)*(x789)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x787)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x788)))+(((sj5)*(x789)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x787)*(x788)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x787)*(x789)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x787)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
02158     continue;
02159 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x788)))+(((sj5)*(x789)))), ((((IkReal(-1.00000000000000))*(cj5)*(x787)*(x788)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x787)*(x789)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x787)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
02160 sj3array[0]=IKsin(j3array[0]);
02161 cj3array[0]=IKcos(j3array[0]);
02162 if( j3array[0] > IKPI )
02163 {
02164     j3array[0]-=IK2PI;
02165 }
02166 else if( j3array[0] < -IKPI )
02167 {    j3array[0]+=IK2PI;
02168 }
02169 j3valid[0] = true;
02170 for(int ij3 = 0; ij3 < 1; ++ij3)
02171 {
02172 if( !j3valid[ij3] )
02173 {
02174     continue;
02175 }
02176 _ij3[0] = ij3; _ij3[1] = -1;
02177 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02178 {
02179 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02180 {
02181     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02182 }
02183 }
02184 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02185 {
02186 IkReal evalcond[4];
02187 IkReal x790=IKcos(j3);
02188 IkReal x791=((IkReal(1.00000000000000))*(cj4));
02189 IkReal x792=((sj0)*(sj5));
02190 IkReal x793=((cj0)*(cj5));
02191 IkReal x794=((cj6)*(r01));
02192 IkReal x795=((r00)*(sj6));
02193 IkReal x796=((cj6)*(r11));
02194 IkReal x797=((cj5)*(sj0));
02195 IkReal x798=((cj6)*(sj4));
02196 IkReal x799=((sj4)*(sj6));
02197 IkReal x800=((cj4)*(cj5));
02198 IkReal x801=((cj6)*(r21));
02199 IkReal x802=((r20)*(sj6));
02200 IkReal x803=((r10)*(sj6));
02201 IkReal x804=((IkReal(1.00000000000000))*(IKsin(j3)));
02202 IkReal x805=((IkReal(1.00000000000000))*(cj0)*(sj5));
02203 evalcond[0]=((((IkReal(-1.00000000000000))*(x804)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x801)))+(((sj5)*(x802))));
02204 evalcond[1]=((((x800)*(x801)))+(((r20)*(x798)))+(((x800)*(x802)))+(((cj4)*(r22)*(sj5)))+(x790)+(((IkReal(-1.00000000000000))*(r21)*(x799))));
02205 evalcond[2]=((((IkReal(-1.00000000000000))*(x792)*(x803)))+(((r12)*(x797)))+(((r02)*(x793)))+(((IkReal(-1.00000000000000))*(x794)*(x805)))+(((IkReal(-1.00000000000000))*(x792)*(x796)))+(((IkReal(-1.00000000000000))*(x790)))+(((IkReal(-1.00000000000000))*(x795)*(x805))));
02206 evalcond[3]=((((r11)*(sj0)*(x799)))+(((IkReal(-1.00000000000000))*(x791)*(x797)*(x803)))+(((IkReal(-1.00000000000000))*(x791)*(x793)*(x794)))+(((IkReal(-1.00000000000000))*(x804)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x791)))+(((IkReal(-1.00000000000000))*(r12)*(x791)*(x792)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x798)))+(((cj0)*(r01)*(x799)))+(((IkReal(-1.00000000000000))*(x791)*(x796)*(x797)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x798)))+(((IkReal(-1.00000000000000))*(x791)*(x793)*(x795))));
02207 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02208 {
02209 continue;
02210 }
02211 }
02212 
02213 {
02214 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02215 vinfos[0].jointtype = 1;
02216 vinfos[0].foffset = j0;
02217 vinfos[0].indices[0] = _ij0[0];
02218 vinfos[0].indices[1] = _ij0[1];
02219 vinfos[0].maxsolutions = _nj0;
02220 vinfos[1].jointtype = 1;
02221 vinfos[1].foffset = j1;
02222 vinfos[1].indices[0] = _ij1[0];
02223 vinfos[1].indices[1] = _ij1[1];
02224 vinfos[1].maxsolutions = _nj1;
02225 vinfos[2].jointtype = 1;
02226 vinfos[2].foffset = j2;
02227 vinfos[2].indices[0] = _ij2[0];
02228 vinfos[2].indices[1] = _ij2[1];
02229 vinfos[2].maxsolutions = _nj2;
02230 vinfos[3].jointtype = 1;
02231 vinfos[3].foffset = j3;
02232 vinfos[3].indices[0] = _ij3[0];
02233 vinfos[3].indices[1] = _ij3[1];
02234 vinfos[3].maxsolutions = _nj3;
02235 vinfos[4].jointtype = 1;
02236 vinfos[4].foffset = j4;
02237 vinfos[4].indices[0] = _ij4[0];
02238 vinfos[4].indices[1] = _ij4[1];
02239 vinfos[4].maxsolutions = _nj4;
02240 vinfos[5].jointtype = 1;
02241 vinfos[5].foffset = j5;
02242 vinfos[5].indices[0] = _ij5[0];
02243 vinfos[5].indices[1] = _ij5[1];
02244 vinfos[5].maxsolutions = _nj5;
02245 vinfos[6].jointtype = 1;
02246 vinfos[6].foffset = j6;
02247 vinfos[6].indices[0] = _ij6[0];
02248 vinfos[6].indices[1] = _ij6[1];
02249 vinfos[6].maxsolutions = _nj6;
02250 std::vector<int> vfree(0);
02251 solutions.AddSolution(vinfos,vfree);
02252 }
02253 }
02254 }
02255 
02256 } else
02257 {
02258 IkReal x806=((cj5)*(sj4));
02259 IkReal x807=((IkReal(1.00000000000000))*(sj6));
02260 IkReal x808=((r10)*(sj0));
02261 IkReal x809=((sj4)*(sj5));
02262 IkReal x810=((cj5)*(cj6));
02263 IkReal x811=((r01)*(sj0));
02264 IkReal x812=((IkReal(1.00000000000000))*(r02));
02265 IkReal x813=((IkReal(0.374290000000000))*(cj0));
02266 IkReal x814=((cj5)*(r12));
02267 IkReal x815=((cj6)*(sj5));
02268 IkReal x816=((cj0)*(r11));
02269 IkReal x817=((cj5)*(sj0));
02270 IkReal x818=((r20)*(sj6));
02271 IkReal x819=((IkReal(1.00000000000000))*(sj0));
02272 IkReal x820=((cj4)*(cj5));
02273 IkReal x821=((IkReal(1.00000000000000))*(cj6));
02274 IkReal x822=((IkReal(0.0100000000000000))*(sj5));
02275 IkReal x823=((sj5)*(sj6));
02276 IkReal x824=((cj0)*(r10));
02277 IkReal x825=((cj4)*(cj6));
02278 IkReal x826=((cj0)*(r01));
02279 IkReal x827=((IkReal(1.00000000000000))*(cj4));
02280 IkReal x828=((cj0)*(r00));
02281 IkReal x829=((IkReal(0.374290000000000))*(sj0));
02282 IkReal x830=((cj0)*(r12));
02283 IkReal x831=((IkReal(0.374290000000000))*(sj5));
02284 IkReal x832=((cj4)*(sj6));
02285 IkReal x833=((IkReal(1.00000000000000))*(cj0));
02286 IkReal x834=((r02)*(sj0));
02287 IkReal x835=((IkReal(0.0100000000000000))*(cj5));
02288 IkReal x836=((r11)*(sj0));
02289 IkReal x837=((r00)*(sj0)*(sj6));
02290 IkReal x838=((r00)*(x825));
02291 IkReal x839=((sj6)*(x835));
02292 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
02293 evalcond[1]=((((cj6)*(r21)*(x806)))+(((r21)*(x832)))+(((x806)*(x818)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x821)))+(((r22)*(x809))));
02294 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x818)*(x835)))+(((IkReal(0.374290000000000))*(r21)*(x815)))+(((IkReal(-0.0100000000000000))*(r21)*(x810)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x822)))+(((x818)*(x831))));
02295 evalcond[3]=((((IkReal(-1.00000000000000))*(x815)*(x816)))+(((IkReal(-1.00000000000000))*(sj5)*(x807)*(x824)))+(((r00)*(sj0)*(x823)))+(((cj0)*(x814)))+(((IkReal(-1.00000000000000))*(x812)*(x817)))+(((x811)*(x815))));
02296 evalcond[4]=((IkReal(-1.00000000000000))+(((cj6)*(x806)*(x811)))+(((IkReal(-1.00000000000000))*(x806)*(x807)*(x824)))+(((IkReal(-1.00000000000000))*(x806)*(x816)*(x821)))+(((x824)*(x825)))+(((x811)*(x832)))+(((IkReal(-1.00000000000000))*(cj4)*(x807)*(x816)))+(((IkReal(-1.00000000000000))*(x819)*(x838)))+(((x809)*(x834)))+(((IkReal(-1.00000000000000))*(x809)*(x830)))+(((x806)*(x837))));
02297 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x807)*(x811)))+(((IkReal(-1.00000000000000))*(sj5)*(x827)*(x830)))+(((sj4)*(sj6)*(x816)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((r00)*(x817)*(x832)))+(((IkReal(-1.00000000000000))*(sj4)*(x821)*(x824)))+(((cj4)*(x810)*(x811)))+(((IkReal(-1.00000000000000))*(x810)*(x816)*(x827)))+(((IkReal(-1.00000000000000))*(x807)*(x820)*(x824)))+(((cj4)*(sj5)*(x834))));
02298 evalcond[6]=((((IkReal(-1.00000000000000))*(cj0)*(x809)*(x812)))+(((IkReal(-1.00000000000000))*(x806)*(x821)*(x826)))+(((IkReal(-1.00000000000000))*(cj4)*(x807)*(x826)))+(((IkReal(-1.00000000000000))*(x806)*(x807)*(x828)))+(((IkReal(-1.00000000000000))*(x806)*(x807)*(x808)))+(((IkReal(-1.00000000000000))*(cj4)*(x807)*(x836)))+(((IkReal(-1.00000000000000))*(r12)*(x809)*(x819)))+(((x808)*(x825)))+(((x825)*(x828)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x806)*(x819))));
02299 evalcond[7]=((((x824)*(x839)))+(((IkReal(-1.00000000000000))*(r11)*(x813)*(x815)))+(((r00)*(x823)*(x829)))+(((IkReal(-0.0100000000000000))*(x810)*(x811)))+(((IkReal(-1.00000000000000))*(py)*(x833)))+(((IkReal(-0.374290000000000))*(r02)*(x817)))+(((IkReal(0.0100000000000000))*(x810)*(x816)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x817)))+(((IkReal(0.374290000000000))*(x811)*(x815)))+(((x813)*(x814)))+(((IkReal(-1.00000000000000))*(x822)*(x834)))+(((x822)*(x830)))+(((IkReal(-1.00000000000000))*(r10)*(x813)*(x823)))+(((px)*(sj0))));
02300 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(r00)*(x813)*(x823)))+(((IkReal(-0.374290000000000))*(x808)*(x823)))+(((IkReal(0.0100000000000000))*(x810)*(x826)))+(((x808)*(x839)))+(((IkReal(0.0100000000000000))*(x810)*(x836)))+(((IkReal(-1.00000000000000))*(px)*(x833)))+(((r12)*(sj0)*(x822)))+(((IkReal(-1.00000000000000))*(r11)*(x815)*(x829)))+(((IkReal(-1.00000000000000))*(r01)*(x813)*(x815)))+(((cj5)*(r02)*(x813)))+(((IkReal(-1.00000000000000))*(py)*(x819)))+(((x814)*(x829)))+(((cj0)*(r02)*(x822)))+(((x828)*(x839))));
02301 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
02302 {
02303 {
02304 IkReal j3array[1], cj3array[1], sj3array[1];
02305 bool j3valid[1]={false};
02306 _nj3 = 1;
02307 IkReal x840=((IkReal(1.00000000000000))*(r21));
02308 IkReal x841=((cj4)*(cj5));
02309 IkReal x842=((r20)*(sj6));
02310 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x842)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x840))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x840)))+(((x841)*(x842)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x841))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x842)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x840)))))+IKsqr(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x840)))+(((x841)*(x842)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x841)))))-1) <= IKFAST_SINCOS_THRESH )
02311     continue;
02312 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x842)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x840)))), ((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x840)))+(((x841)*(x842)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x841)))));
02313 sj3array[0]=IKsin(j3array[0]);
02314 cj3array[0]=IKcos(j3array[0]);
02315 if( j3array[0] > IKPI )
02316 {
02317     j3array[0]-=IK2PI;
02318 }
02319 else if( j3array[0] < -IKPI )
02320 {    j3array[0]+=IK2PI;
02321 }
02322 j3valid[0] = true;
02323 for(int ij3 = 0; ij3 < 1; ++ij3)
02324 {
02325 if( !j3valid[ij3] )
02326 {
02327     continue;
02328 }
02329 _ij3[0] = ij3; _ij3[1] = -1;
02330 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02331 {
02332 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02333 {
02334     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02335 }
02336 }
02337 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02338 {
02339 IkReal evalcond[4];
02340 IkReal x843=IKsin(j3);
02341 IkReal x844=((IkReal(1.00000000000000))*(cj4));
02342 IkReal x845=((sj0)*(sj5));
02343 IkReal x846=((cj0)*(cj5));
02344 IkReal x847=((cj6)*(r01));
02345 IkReal x848=((r00)*(sj6));
02346 IkReal x849=((cj6)*(r11));
02347 IkReal x850=((cj5)*(sj0));
02348 IkReal x851=((cj6)*(sj4));
02349 IkReal x852=((sj4)*(sj6));
02350 IkReal x853=((cj4)*(cj5));
02351 IkReal x854=((cj6)*(r21));
02352 IkReal x855=((r20)*(sj6));
02353 IkReal x856=((r10)*(sj6));
02354 IkReal x857=((IkReal(1.00000000000000))*(IKcos(j3)));
02355 IkReal x858=((IkReal(1.00000000000000))*(cj0)*(sj5));
02356 evalcond[0]=((((sj5)*(x854)))+(((sj5)*(x855)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x843));
02357 evalcond[1]=((((r20)*(x851)))+(((x853)*(x854)))+(((cj4)*(r22)*(sj5)))+(((x853)*(x855)))+(((IkReal(-1.00000000000000))*(x857)))+(((IkReal(-1.00000000000000))*(r21)*(x852))));
02358 evalcond[2]=((((r12)*(x850)))+(((IkReal(-1.00000000000000))*(x848)*(x858)))+(((IkReal(-1.00000000000000))*(x845)*(x849)))+(((IkReal(-1.00000000000000))*(x857)))+(((IkReal(-1.00000000000000))*(x847)*(x858)))+(((IkReal(-1.00000000000000))*(x845)*(x856)))+(((r02)*(x846))));
02359 evalcond[3]=((((r11)*(sj0)*(x852)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x844)))+(((cj0)*(r01)*(x852)))+(((IkReal(-1.00000000000000))*(x843)))+(((IkReal(-1.00000000000000))*(x844)*(x849)*(x850)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x851)))+(((IkReal(-1.00000000000000))*(r12)*(x844)*(x845)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x851)))+(((IkReal(-1.00000000000000))*(x844)*(x846)*(x848)))+(((IkReal(-1.00000000000000))*(x844)*(x846)*(x847)))+(((IkReal(-1.00000000000000))*(x844)*(x850)*(x856))));
02360 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02361 {
02362 continue;
02363 }
02364 }
02365 
02366 {
02367 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02368 vinfos[0].jointtype = 1;
02369 vinfos[0].foffset = j0;
02370 vinfos[0].indices[0] = _ij0[0];
02371 vinfos[0].indices[1] = _ij0[1];
02372 vinfos[0].maxsolutions = _nj0;
02373 vinfos[1].jointtype = 1;
02374 vinfos[1].foffset = j1;
02375 vinfos[1].indices[0] = _ij1[0];
02376 vinfos[1].indices[1] = _ij1[1];
02377 vinfos[1].maxsolutions = _nj1;
02378 vinfos[2].jointtype = 1;
02379 vinfos[2].foffset = j2;
02380 vinfos[2].indices[0] = _ij2[0];
02381 vinfos[2].indices[1] = _ij2[1];
02382 vinfos[2].maxsolutions = _nj2;
02383 vinfos[3].jointtype = 1;
02384 vinfos[3].foffset = j3;
02385 vinfos[3].indices[0] = _ij3[0];
02386 vinfos[3].indices[1] = _ij3[1];
02387 vinfos[3].maxsolutions = _nj3;
02388 vinfos[4].jointtype = 1;
02389 vinfos[4].foffset = j4;
02390 vinfos[4].indices[0] = _ij4[0];
02391 vinfos[4].indices[1] = _ij4[1];
02392 vinfos[4].maxsolutions = _nj4;
02393 vinfos[5].jointtype = 1;
02394 vinfos[5].foffset = j5;
02395 vinfos[5].indices[0] = _ij5[0];
02396 vinfos[5].indices[1] = _ij5[1];
02397 vinfos[5].maxsolutions = _nj5;
02398 vinfos[6].jointtype = 1;
02399 vinfos[6].foffset = j6;
02400 vinfos[6].indices[0] = _ij6[0];
02401 vinfos[6].indices[1] = _ij6[1];
02402 vinfos[6].maxsolutions = _nj6;
02403 std::vector<int> vfree(0);
02404 solutions.AddSolution(vinfos,vfree);
02405 }
02406 }
02407 }
02408 
02409 } else
02410 {
02411 IkReal x859=((IkReal(1.00000000000000))*(cj0));
02412 IkReal x860=((cj4)*(sj6));
02413 IkReal x861=((sj0)*(sj4));
02414 IkReal x862=((cj5)*(sj6));
02415 IkReal x863=((sj4)*(sj5));
02416 IkReal x864=((r12)*(sj5));
02417 IkReal x865=((IkReal(0.374290000000000))*(cj5));
02418 IkReal x866=((r02)*(sj0));
02419 IkReal x867=((r20)*(sj4));
02420 IkReal x868=((IkReal(1.00000000000000))*(sj0));
02421 IkReal x869=((IkReal(1.00000000000000))*(cj5));
02422 IkReal x870=((cj0)*(r10));
02423 IkReal x871=((cj4)*(cj6));
02424 IkReal x872=((r00)*(sj0));
02425 IkReal x873=((cj6)*(r21));
02426 IkReal x874=((IkReal(0.374290000000000))*(sj5));
02427 IkReal x875=((cj0)*(r00));
02428 IkReal x876=((IkReal(0.0100000000000000))*(sj5));
02429 IkReal x877=((cj0)*(r02));
02430 IkReal x878=((cj5)*(sj4));
02431 IkReal x879=((cj6)*(r01));
02432 IkReal x880=((cj6)*(r11));
02433 IkReal x881=((r01)*(sj0));
02434 IkReal x882=((r10)*(sj0));
02435 IkReal x883=((IkReal(0.0100000000000000))*(cj5)*(cj6));
02436 IkReal x884=((sj6)*(x874));
02437 IkReal x885=((cj0)*(cj6)*(x874));
02438 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
02439 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x869)))+(((sj5)*(x873)))+(((r20)*(sj5)*(sj6))));
02440 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x863)))+(((x873)*(x878)))+(((x862)*(x867)))+(((IkReal(-1.00000000000000))*(r20)*(x871)))+(((r21)*(x860))));
02441 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x862)))+(((IkReal(-0.0100000000000000))*(cj5)*(x873)))+(((IkReal(-1.00000000000000))*(r22)*(x876)))+(((x873)*(x874)))+(((r20)*(x884)))+(((IkReal(-1.00000000000000))*(r22)*(x865)))+(pz));
02442 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x860)))+(((cj6)*(x867)))+(((cj5)*(r21)*(x871))));
02443 evalcond[5]=((((x860)*(x881)))+(((x870)*(x871)))+(((IkReal(-1.00000000000000))*(r12)*(x859)*(x863)))+(((IkReal(-1.00000000000000))*(r00)*(x868)*(x871)))+(((IkReal(-1.00000000000000))*(x859)*(x878)*(x880)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x859)*(x862)))+(((r02)*(sj5)*(x861)))+(((r00)*(x861)*(x862)))+(((cj5)*(x861)*(x879)))+(((IkReal(-1.00000000000000))*(r11)*(x859)*(x860))));
02444 evalcond[6]=((((IkReal(-1.00000000000000))*(x859)*(x878)*(x879)))+(((IkReal(-1.00000000000000))*(r10)*(x861)*(x862)))+(((IkReal(-1.00000000000000))*(x861)*(x864)))+(((IkReal(-1.00000000000000))*(x861)*(x869)*(x880)))+(((IkReal(-1.00000000000000))*(r02)*(x859)*(x863)))+(((x871)*(x882)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x859)*(x862)))+(((IkReal(-1.00000000000000))*(r01)*(x859)*(x860)))+(((x871)*(x875)))+(((IkReal(-1.00000000000000))*(r11)*(x860)*(x868))));
02445 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x879)))+(((IkReal(0.0100000000000000))*(cj0)*(x864)))+(((IkReal(-0.0100000000000000))*(x862)*(x872)))+(((IkReal(-1.00000000000000))*(x865)*(x866)))+(((IkReal(0.0100000000000000))*(x862)*(x870)))+(((sj0)*(x874)*(x879)))+(((x872)*(x884)))+(((cj0)*(r12)*(x865)))+(((IkReal(-1.00000000000000))*(cj0)*(x874)*(x880)))+(((IkReal(-1.00000000000000))*(py)*(x859)))+(((IkReal(-1.00000000000000))*(x870)*(x884)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x866)*(x876)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x880))));
02446 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(py)*(x868)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x879)))+(((IkReal(-1.00000000000000))*(x882)*(x884)))+(((r12)*(sj0)*(x865)))+(((IkReal(0.0100000000000000))*(sj0)*(x864)))+(((x876)*(x877)))+(((IkReal(0.0100000000000000))*(x862)*(x875)))+(((IkReal(-1.00000000000000))*(cj0)*(x874)*(x879)))+(((IkReal(-1.00000000000000))*(sj0)*(x874)*(x880)))+(((IkReal(-1.00000000000000))*(x875)*(x884)))+(((x865)*(x877)))+(((IkReal(0.0100000000000000))*(x862)*(x882)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x880)))+(((IkReal(-1.00000000000000))*(px)*(x859))));
02447 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
02448 {
02449 {
02450 IkReal j3array[1], cj3array[1], sj3array[1];
02451 bool j3valid[1]={false};
02452 _nj3 = 1;
02453 IkReal x886=((cj0)*(cj5));
02454 IkReal x887=((IkReal(1.00000000000000))*(cj0));
02455 IkReal x888=((cj6)*(r11));
02456 IkReal x889=((r10)*(sj6));
02457 IkReal x890=((cj5)*(sj0));
02458 IkReal x891=((r00)*(sj5)*(sj6));
02459 IkReal x892=((cj6)*(r01)*(sj5));
02460 IkReal x893=((IkReal(1.00000000000000))*(sj0)*(sj5));
02461 if( IKabs(((((r12)*(x886)))+(((IkReal(-1.00000000000000))*(r02)*(x890)))+(((sj0)*(x891)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x888)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x889)))+(((sj0)*(x892))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x887)*(x892)))+(((IkReal(-1.00000000000000))*(x887)*(x891)))+(((IkReal(-1.00000000000000))*(x888)*(x893)))+(((IkReal(-1.00000000000000))*(x889)*(x893)))+(((r02)*(x886)))+(((r12)*(x890))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r12)*(x886)))+(((IkReal(-1.00000000000000))*(r02)*(x890)))+(((sj0)*(x891)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x888)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x889)))+(((sj0)*(x892)))))+IKsqr(((((IkReal(-1.00000000000000))*(x887)*(x892)))+(((IkReal(-1.00000000000000))*(x887)*(x891)))+(((IkReal(-1.00000000000000))*(x888)*(x893)))+(((IkReal(-1.00000000000000))*(x889)*(x893)))+(((r02)*(x886)))+(((r12)*(x890)))))-1) <= IKFAST_SINCOS_THRESH )
02462     continue;
02463 j3array[0]=IKatan2(((((r12)*(x886)))+(((IkReal(-1.00000000000000))*(r02)*(x890)))+(((sj0)*(x891)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x888)))+(((IkReal(-1.00000000000000))*(sj5)*(x887)*(x889)))+(((sj0)*(x892)))), ((((IkReal(-1.00000000000000))*(x887)*(x892)))+(((IkReal(-1.00000000000000))*(x887)*(x891)))+(((IkReal(-1.00000000000000))*(x888)*(x893)))+(((IkReal(-1.00000000000000))*(x889)*(x893)))+(((r02)*(x886)))+(((r12)*(x890)))));
02464 sj3array[0]=IKsin(j3array[0]);
02465 cj3array[0]=IKcos(j3array[0]);
02466 if( j3array[0] > IKPI )
02467 {
02468     j3array[0]-=IK2PI;
02469 }
02470 else if( j3array[0] < -IKPI )
02471 {    j3array[0]+=IK2PI;
02472 }
02473 j3valid[0] = true;
02474 for(int ij3 = 0; ij3 < 1; ++ij3)
02475 {
02476 if( !j3valid[ij3] )
02477 {
02478     continue;
02479 }
02480 _ij3[0] = ij3; _ij3[1] = -1;
02481 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02482 {
02483 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02484 {
02485     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02486 }
02487 }
02488 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02489 {
02490 IkReal evalcond[4];
02491 IkReal x894=IKcos(j3);
02492 IkReal x895=((sj0)*(sj5));
02493 IkReal x896=((r00)*(sj6));
02494 IkReal x897=((cj6)*(sj0));
02495 IkReal x898=((IkReal(1.00000000000000))*(cj4));
02496 IkReal x899=((r00)*(sj4));
02497 IkReal x900=((cj0)*(cj5));
02498 IkReal x901=((cj5)*(sj0));
02499 IkReal x902=((cj6)*(r11));
02500 IkReal x903=((r10)*(sj6));
02501 IkReal x904=((cj0)*(sj5));
02502 IkReal x905=((r10)*(sj4));
02503 IkReal x906=((IkReal(1.00000000000000))*(IKsin(j3)));
02504 IkReal x907=((cj4)*(cj5)*(r01));
02505 IkReal x908=((IkReal(1.00000000000000))*(cj0)*(cj6));
02506 IkReal x909=((cj0)*(sj4)*(sj6));
02507 IkReal x910=((sj0)*(sj4)*(sj6));
02508 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x901)))+(((IkReal(-1.00000000000000))*(x903)*(x904)))+(((cj6)*(r01)*(x895)))+(((IkReal(-1.00000000000000))*(x902)*(x904)))+(((r12)*(x900)))+(((x895)*(x896)))+(((IkReal(-1.00000000000000))*(x906))));
02509 evalcond[1]=((((IkReal(-1.00000000000000))*(x895)*(x903)))+(((IkReal(-1.00000000000000))*(x896)*(x904)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x904)))+(((r02)*(x900)))+(((IkReal(-1.00000000000000))*(x894)))+(((IkReal(-1.00000000000000))*(x895)*(x902)))+(((r12)*(x901))));
02510 evalcond[2]=((((IkReal(-1.00000000000000))*(x905)*(x908)))+(((r11)*(x909)))+(((IkReal(-1.00000000000000))*(r12)*(x898)*(x904)))+(((IkReal(-1.00000000000000))*(r01)*(x910)))+(((x897)*(x907)))+(((IkReal(-1.00000000000000))*(x898)*(x900)*(x903)))+(((x897)*(x899)))+(((IkReal(-1.00000000000000))*(x898)*(x900)*(x902)))+(x894)+(((cj4)*(x896)*(x901)))+(((cj4)*(r02)*(x895))));
02511 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x897)*(x898)))+(((IkReal(-1.00000000000000))*(r12)*(x895)*(x898)))+(((IkReal(-1.00000000000000))*(r02)*(x898)*(x904)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x898)*(x900)))+(((IkReal(-1.00000000000000))*(x899)*(x908)))+(((r11)*(x910)))+(((IkReal(-1.00000000000000))*(x897)*(x905)))+(((IkReal(-1.00000000000000))*(x896)*(x898)*(x900)))+(((r01)*(x909)))+(((IkReal(-1.00000000000000))*(x898)*(x901)*(x903)))+(((IkReal(-1.00000000000000))*(x906))));
02512 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02513 {
02514 continue;
02515 }
02516 }
02517 
02518 {
02519 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02520 vinfos[0].jointtype = 1;
02521 vinfos[0].foffset = j0;
02522 vinfos[0].indices[0] = _ij0[0];
02523 vinfos[0].indices[1] = _ij0[1];
02524 vinfos[0].maxsolutions = _nj0;
02525 vinfos[1].jointtype = 1;
02526 vinfos[1].foffset = j1;
02527 vinfos[1].indices[0] = _ij1[0];
02528 vinfos[1].indices[1] = _ij1[1];
02529 vinfos[1].maxsolutions = _nj1;
02530 vinfos[2].jointtype = 1;
02531 vinfos[2].foffset = j2;
02532 vinfos[2].indices[0] = _ij2[0];
02533 vinfos[2].indices[1] = _ij2[1];
02534 vinfos[2].maxsolutions = _nj2;
02535 vinfos[3].jointtype = 1;
02536 vinfos[3].foffset = j3;
02537 vinfos[3].indices[0] = _ij3[0];
02538 vinfos[3].indices[1] = _ij3[1];
02539 vinfos[3].maxsolutions = _nj3;
02540 vinfos[4].jointtype = 1;
02541 vinfos[4].foffset = j4;
02542 vinfos[4].indices[0] = _ij4[0];
02543 vinfos[4].indices[1] = _ij4[1];
02544 vinfos[4].maxsolutions = _nj4;
02545 vinfos[5].jointtype = 1;
02546 vinfos[5].foffset = j5;
02547 vinfos[5].indices[0] = _ij5[0];
02548 vinfos[5].indices[1] = _ij5[1];
02549 vinfos[5].maxsolutions = _nj5;
02550 vinfos[6].jointtype = 1;
02551 vinfos[6].foffset = j6;
02552 vinfos[6].indices[0] = _ij6[0];
02553 vinfos[6].indices[1] = _ij6[1];
02554 vinfos[6].maxsolutions = _nj6;
02555 std::vector<int> vfree(0);
02556 solutions.AddSolution(vinfos,vfree);
02557 }
02558 }
02559 }
02560 
02561 } else
02562 {
02563 IkReal x911=((IkReal(1.00000000000000))*(cj0));
02564 IkReal x912=((cj4)*(sj6));
02565 IkReal x913=((sj0)*(sj4));
02566 IkReal x914=((cj5)*(sj6));
02567 IkReal x915=((sj4)*(sj5));
02568 IkReal x916=((r12)*(sj5));
02569 IkReal x917=((IkReal(0.374290000000000))*(cj5));
02570 IkReal x918=((r02)*(sj0));
02571 IkReal x919=((r20)*(sj4));
02572 IkReal x920=((IkReal(1.00000000000000))*(sj0));
02573 IkReal x921=((IkReal(1.00000000000000))*(cj5));
02574 IkReal x922=((cj0)*(r10));
02575 IkReal x923=((cj4)*(cj6));
02576 IkReal x924=((r00)*(sj0));
02577 IkReal x925=((cj6)*(r21));
02578 IkReal x926=((IkReal(0.374290000000000))*(sj5));
02579 IkReal x927=((cj0)*(r00));
02580 IkReal x928=((IkReal(0.0100000000000000))*(sj5));
02581 IkReal x929=((cj0)*(r02));
02582 IkReal x930=((cj5)*(sj4));
02583 IkReal x931=((cj6)*(r01));
02584 IkReal x932=((cj6)*(r11));
02585 IkReal x933=((r01)*(sj0));
02586 IkReal x934=((r10)*(sj0));
02587 IkReal x935=((IkReal(0.0100000000000000))*(cj5)*(cj6));
02588 IkReal x936=((sj6)*(x926));
02589 IkReal x937=((cj0)*(cj6)*(x926));
02590 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
02591 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x921)))+(((sj5)*(x925)))+(((r20)*(sj5)*(sj6))));
02592 evalcond[2]=((IkReal(1.00000000000000))+(((r21)*(x912)))+(((x914)*(x919)))+(((IkReal(-1.00000000000000))*(r20)*(x923)))+(((r22)*(x915)))+(((x925)*(x930))));
02593 evalcond[3]=((((x925)*(x926)))+(((IkReal(-1.00000000000000))*(r22)*(x917)))+(pz)+(((r20)*(x936)))+(((IkReal(-0.0100000000000000))*(r20)*(x914)))+(((IkReal(-0.0100000000000000))*(cj5)*(x925)))+(((IkReal(-1.00000000000000))*(r22)*(x928))));
02594 evalcond[4]=((((cj5)*(r21)*(x923)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x912)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x919))));
02595 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(x911)*(x912)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x911)*(x914)))+(((IkReal(-1.00000000000000))*(r00)*(x920)*(x923)))+(((IkReal(-1.00000000000000))*(r12)*(x911)*(x915)))+(((r02)*(sj5)*(x913)))+(((IkReal(-1.00000000000000))*(x911)*(x930)*(x932)))+(((cj5)*(x913)*(x931)))+(((x912)*(x933)))+(((r00)*(x913)*(x914)))+(((x922)*(x923))));
02596 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x911)*(x915)))+(((x923)*(x934)))+(((IkReal(-1.00000000000000))*(x911)*(x930)*(x931)))+(((IkReal(-1.00000000000000))*(r10)*(x913)*(x914)))+(((IkReal(-1.00000000000000))*(x913)*(x921)*(x932)))+(((IkReal(-1.00000000000000))*(x913)*(x916)))+(((IkReal(-1.00000000000000))*(r11)*(x912)*(x920)))+(((x923)*(x927)))+(((IkReal(-1.00000000000000))*(r01)*(x911)*(x912)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x911)*(x914))));
02597 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x911)))+(((IkReal(-0.0100000000000000))*(x914)*(x924)))+(((IkReal(-1.00000000000000))*(x918)*(x928)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x932)))+(((IkReal(0.0100000000000000))*(cj0)*(x916)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x931)))+(((IkReal(-1.00000000000000))*(x917)*(x918)))+(((sj0)*(x926)*(x931)))+(((IkReal(-1.00000000000000))*(x922)*(x936)))+(((IkReal(0.0100000000000000))*(x914)*(x922)))+(((cj0)*(r12)*(x917)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x926)*(x932)))+(((x924)*(x936))));
02598 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x932)))+(((IkReal(0.0100000000000000))*(x914)*(x927)))+(((IkReal(0.0100000000000000))*(x914)*(x934)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x931)))+(((x928)*(x929)))+(((IkReal(-1.00000000000000))*(sj0)*(x926)*(x932)))+(((IkReal(-1.00000000000000))*(py)*(x920)))+(((IkReal(-1.00000000000000))*(cj0)*(x926)*(x931)))+(((x917)*(x929)))+(((IkReal(-1.00000000000000))*(px)*(x911)))+(((IkReal(-1.00000000000000))*(x934)*(x936)))+(((IkReal(0.0100000000000000))*(sj0)*(x916)))+(((IkReal(-1.00000000000000))*(x927)*(x936)))+(((r12)*(sj0)*(x917))));
02599 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
02600 {
02601 {
02602 IkReal j3array[1], cj3array[1], sj3array[1];
02603 bool j3valid[1]={false};
02604 _nj3 = 1;
02605 IkReal x938=((cj5)*(r02));
02606 IkReal x939=((cj0)*(sj5));
02607 IkReal x940=((r10)*(sj6));
02608 IkReal x941=((IkReal(1.00000000000000))*(cj6));
02609 IkReal x942=((sj0)*(sj5));
02610 IkReal x943=((cj5)*(r12));
02611 IkReal x944=((IkReal(1.00000000000000))*(r00)*(sj6));
02612 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x943)))+(((IkReal(-1.00000000000000))*(r01)*(x941)*(x942)))+(((cj6)*(r11)*(x939)))+(((x939)*(x940)))+(((sj0)*(x938)))+(((IkReal(-1.00000000000000))*(x942)*(x944))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x940)*(x942)))+(((IkReal(-1.00000000000000))*(r01)*(x939)*(x941)))+(((sj0)*(x943)))+(((IkReal(-1.00000000000000))*(r11)*(x941)*(x942)))+(((cj0)*(x938)))+(((IkReal(-1.00000000000000))*(x939)*(x944))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x943)))+(((IkReal(-1.00000000000000))*(r01)*(x941)*(x942)))+(((cj6)*(r11)*(x939)))+(((x939)*(x940)))+(((sj0)*(x938)))+(((IkReal(-1.00000000000000))*(x942)*(x944)))))+IKsqr(((((IkReal(-1.00000000000000))*(x940)*(x942)))+(((IkReal(-1.00000000000000))*(r01)*(x939)*(x941)))+(((sj0)*(x943)))+(((IkReal(-1.00000000000000))*(r11)*(x941)*(x942)))+(((cj0)*(x938)))+(((IkReal(-1.00000000000000))*(x939)*(x944)))))-1) <= IKFAST_SINCOS_THRESH )
02613     continue;
02614 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x943)))+(((IkReal(-1.00000000000000))*(r01)*(x941)*(x942)))+(((cj6)*(r11)*(x939)))+(((x939)*(x940)))+(((sj0)*(x938)))+(((IkReal(-1.00000000000000))*(x942)*(x944)))), ((((IkReal(-1.00000000000000))*(x940)*(x942)))+(((IkReal(-1.00000000000000))*(r01)*(x939)*(x941)))+(((sj0)*(x943)))+(((IkReal(-1.00000000000000))*(r11)*(x941)*(x942)))+(((cj0)*(x938)))+(((IkReal(-1.00000000000000))*(x939)*(x944)))));
02615 sj3array[0]=IKsin(j3array[0]);
02616 cj3array[0]=IKcos(j3array[0]);
02617 if( j3array[0] > IKPI )
02618 {
02619     j3array[0]-=IK2PI;
02620 }
02621 else if( j3array[0] < -IKPI )
02622 {    j3array[0]+=IK2PI;
02623 }
02624 j3valid[0] = true;
02625 for(int ij3 = 0; ij3 < 1; ++ij3)
02626 {
02627 if( !j3valid[ij3] )
02628 {
02629     continue;
02630 }
02631 _ij3[0] = ij3; _ij3[1] = -1;
02632 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02633 {
02634 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02635 {
02636     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02637 }
02638 }
02639 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02640 {
02641 IkReal evalcond[4];
02642 IkReal x945=IKsin(j3);
02643 IkReal x946=((sj0)*(sj5));
02644 IkReal x947=((r00)*(sj6));
02645 IkReal x948=((IkReal(1.00000000000000))*(cj4));
02646 IkReal x949=((cj6)*(sj0));
02647 IkReal x950=((r00)*(sj4));
02648 IkReal x951=((cj0)*(cj5));
02649 IkReal x952=((cj6)*(r01));
02650 IkReal x953=((cj5)*(sj0));
02651 IkReal x954=((cj0)*(sj5));
02652 IkReal x955=((cj6)*(r11));
02653 IkReal x956=((r10)*(sj6));
02654 IkReal x957=((r10)*(sj4));
02655 IkReal x958=((IkReal(1.00000000000000))*(IKcos(j3)));
02656 IkReal x959=((cj0)*(sj4)*(sj6));
02657 IkReal x960=((sj0)*(sj4)*(sj6));
02658 IkReal x961=((IkReal(1.00000000000000))*(cj0)*(cj6));
02659 evalcond[0]=((((x946)*(x952)))+(((IkReal(-1.00000000000000))*(x954)*(x955)))+(((r12)*(x951)))+(((x946)*(x947)))+(x945)+(((IkReal(-1.00000000000000))*(r02)*(x953)))+(((IkReal(-1.00000000000000))*(x954)*(x956))));
02660 evalcond[1]=((((r02)*(x951)))+(((r12)*(x953)))+(((IkReal(-1.00000000000000))*(x946)*(x955)))+(((IkReal(-1.00000000000000))*(x947)*(x954)))+(((IkReal(-1.00000000000000))*(x946)*(x956)))+(((IkReal(-1.00000000000000))*(x958)))+(((IkReal(-1.00000000000000))*(x952)*(x954))));
02661 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x960)))+(((cj4)*(x947)*(x953)))+(((r11)*(x959)))+(((cj4)*(cj5)*(r01)*(x949)))+(((IkReal(-1.00000000000000))*(x957)*(x961)))+(((IkReal(-1.00000000000000))*(x948)*(x951)*(x955)))+(((x949)*(x950)))+(((IkReal(-1.00000000000000))*(r12)*(x948)*(x954)))+(((cj4)*(r02)*(x946)))+(((IkReal(-1.00000000000000))*(x948)*(x951)*(x956)))+(((IkReal(-1.00000000000000))*(x958))));
02662 evalcond[3]=((((IkReal(-1.00000000000000))*(x950)*(x961)))+(((IkReal(-1.00000000000000))*(x945)))+(((IkReal(-1.00000000000000))*(x949)*(x957)))+(((IkReal(-1.00000000000000))*(x948)*(x953)*(x956)))+(((IkReal(-1.00000000000000))*(x948)*(x951)*(x952)))+(((r01)*(x959)))+(((IkReal(-1.00000000000000))*(r12)*(x946)*(x948)))+(((r11)*(x960)))+(((IkReal(-1.00000000000000))*(x947)*(x948)*(x951)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x948)*(x949)))+(((IkReal(-1.00000000000000))*(r02)*(x948)*(x954))));
02663 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02664 {
02665 continue;
02666 }
02667 }
02668 
02669 {
02670 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02671 vinfos[0].jointtype = 1;
02672 vinfos[0].foffset = j0;
02673 vinfos[0].indices[0] = _ij0[0];
02674 vinfos[0].indices[1] = _ij0[1];
02675 vinfos[0].maxsolutions = _nj0;
02676 vinfos[1].jointtype = 1;
02677 vinfos[1].foffset = j1;
02678 vinfos[1].indices[0] = _ij1[0];
02679 vinfos[1].indices[1] = _ij1[1];
02680 vinfos[1].maxsolutions = _nj1;
02681 vinfos[2].jointtype = 1;
02682 vinfos[2].foffset = j2;
02683 vinfos[2].indices[0] = _ij2[0];
02684 vinfos[2].indices[1] = _ij2[1];
02685 vinfos[2].maxsolutions = _nj2;
02686 vinfos[3].jointtype = 1;
02687 vinfos[3].foffset = j3;
02688 vinfos[3].indices[0] = _ij3[0];
02689 vinfos[3].indices[1] = _ij3[1];
02690 vinfos[3].maxsolutions = _nj3;
02691 vinfos[4].jointtype = 1;
02692 vinfos[4].foffset = j4;
02693 vinfos[4].indices[0] = _ij4[0];
02694 vinfos[4].indices[1] = _ij4[1];
02695 vinfos[4].maxsolutions = _nj4;
02696 vinfos[5].jointtype = 1;
02697 vinfos[5].foffset = j5;
02698 vinfos[5].indices[0] = _ij5[0];
02699 vinfos[5].indices[1] = _ij5[1];
02700 vinfos[5].maxsolutions = _nj5;
02701 vinfos[6].jointtype = 1;
02702 vinfos[6].foffset = j6;
02703 vinfos[6].indices[0] = _ij6[0];
02704 vinfos[6].indices[1] = _ij6[1];
02705 vinfos[6].maxsolutions = _nj6;
02706 std::vector<int> vfree(0);
02707 solutions.AddSolution(vinfos,vfree);
02708 }
02709 }
02710 }
02711 
02712 } else
02713 {
02714 if( 1 )
02715 {
02716 continue;
02717 
02718 } else
02719 {
02720 }
02721 }
02722 }
02723 }
02724 }
02725 }
02726 
02727 } else
02728 {
02729 {
02730 IkReal j3array[1], cj3array[1], sj3array[1];
02731 bool j3valid[1]={false};
02732 _nj3 = 1;
02733 IkReal x962=((cj0)*(cj5));
02734 IkReal x963=((IkReal(1.00000000000000))*(cj0));
02735 IkReal x964=((cj6)*(r11));
02736 IkReal x965=((r10)*(sj6));
02737 IkReal x966=((cj5)*(sj0));
02738 IkReal x967=((r00)*(sj5)*(sj6));
02739 IkReal x968=((cj6)*(r01)*(sj5));
02740 IkReal x969=((IkReal(1.00000000000000))*(sj0)*(sj5));
02741 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x962)))+(((IkReal(-1.00000000000000))*(r02)*(x966)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x965)))+(((sj0)*(x967)))+(((sj0)*(x968)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x964))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x964)*(x969)))+(((IkReal(-1.00000000000000))*(x963)*(x968)))+(((IkReal(-1.00000000000000))*(x965)*(x969)))+(((r02)*(x962)))+(((r12)*(x966)))+(((IkReal(-1.00000000000000))*(x963)*(x967))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x962)))+(((IkReal(-1.00000000000000))*(r02)*(x966)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x965)))+(((sj0)*(x967)))+(((sj0)*(x968)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x964)))))))+IKsqr(((((IkReal(-1.00000000000000))*(x964)*(x969)))+(((IkReal(-1.00000000000000))*(x963)*(x968)))+(((IkReal(-1.00000000000000))*(x965)*(x969)))+(((r02)*(x962)))+(((r12)*(x966)))+(((IkReal(-1.00000000000000))*(x963)*(x967)))))-1) <= IKFAST_SINCOS_THRESH )
02742     continue;
02743 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x962)))+(((IkReal(-1.00000000000000))*(r02)*(x966)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x965)))+(((sj0)*(x967)))+(((sj0)*(x968)))+(((IkReal(-1.00000000000000))*(sj5)*(x963)*(x964)))))), ((((IkReal(-1.00000000000000))*(x964)*(x969)))+(((IkReal(-1.00000000000000))*(x963)*(x968)))+(((IkReal(-1.00000000000000))*(x965)*(x969)))+(((r02)*(x962)))+(((r12)*(x966)))+(((IkReal(-1.00000000000000))*(x963)*(x967)))));
02744 sj3array[0]=IKsin(j3array[0]);
02745 cj3array[0]=IKcos(j3array[0]);
02746 if( j3array[0] > IKPI )
02747 {
02748     j3array[0]-=IK2PI;
02749 }
02750 else if( j3array[0] < -IKPI )
02751 {    j3array[0]+=IK2PI;
02752 }
02753 j3valid[0] = true;
02754 for(int ij3 = 0; ij3 < 1; ++ij3)
02755 {
02756 if( !j3valid[ij3] )
02757 {
02758     continue;
02759 }
02760 _ij3[0] = ij3; _ij3[1] = -1;
02761 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02762 {
02763 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02764 {
02765     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02766 }
02767 }
02768 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02769 {
02770 IkReal evalcond[6];
02771 IkReal x970=IKsin(j3);
02772 IkReal x971=IKcos(j3);
02773 IkReal x972=((sj0)*(sj5));
02774 IkReal x973=((r00)*(sj6));
02775 IkReal x974=((IkReal(1.00000000000000))*(cj4));
02776 IkReal x975=((cj6)*(r01));
02777 IkReal x976=((cj0)*(cj5));
02778 IkReal x977=((cj5)*(sj0));
02779 IkReal x978=((cj6)*(r11));
02780 IkReal x979=((cj0)*(sj5));
02781 IkReal x980=((cj6)*(sj4));
02782 IkReal x981=((cj4)*(cj5));
02783 IkReal x982=((cj6)*(r21));
02784 IkReal x983=((r20)*(sj6));
02785 IkReal x984=((r10)*(sj6));
02786 IkReal x985=((IkReal(1.00000000000000))*(cj0));
02787 IkReal x986=((IkReal(1.00000000000000))*(x970));
02788 IkReal x987=((cj0)*(sj4)*(sj6));
02789 IkReal x988=((sj0)*(sj4)*(sj6));
02790 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x986)))+(((sj5)*(x982)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x983))));
02791 evalcond[1]=((((x981)*(x983)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x971)))+(((x981)*(x982)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x980))));
02792 evalcond[2]=((((IkReal(-1.00000000000000))*(x978)*(x979)))+(((x972)*(x975)))+(((IkReal(-1.00000000000000))*(sj2)*(x986)))+(((IkReal(-1.00000000000000))*(x979)*(x984)))+(((IkReal(-1.00000000000000))*(r02)*(x977)))+(((r12)*(x976)))+(((x972)*(x973))));
02793 evalcond[3]=((((IkReal(-1.00000000000000))*(x972)*(x978)))+(((IkReal(-1.00000000000000))*(x973)*(x979)))+(((r02)*(x976)))+(((IkReal(-1.00000000000000))*(x971)))+(((IkReal(-1.00000000000000))*(x972)*(x984)))+(((IkReal(-1.00000000000000))*(x975)*(x979)))+(((r12)*(x977))));
02794 evalcond[4]=((((r11)*(x987)))+(((IkReal(-1.00000000000000))*(r10)*(x980)*(x985)))+(((r00)*(sj0)*(x980)))+(((IkReal(-1.00000000000000))*(x974)*(x976)*(x978)))+(((cj4)*(r02)*(x972)))+(((cj4)*(x973)*(x977)))+(((IkReal(-1.00000000000000))*(r12)*(x974)*(x979)))+(((cj4)*(x975)*(x977)))+(((IkReal(-1.00000000000000))*(r01)*(x988)))+(((IkReal(-1.00000000000000))*(x974)*(x976)*(x984)))+(((sj2)*(x971))));
02795 evalcond[5]=((((IkReal(-1.00000000000000))*(x973)*(x974)*(x976)))+(((IkReal(-1.00000000000000))*(x974)*(x977)*(x978)))+(((IkReal(-1.00000000000000))*(x974)*(x977)*(x984)))+(((r01)*(x987)))+(((IkReal(-1.00000000000000))*(r00)*(x980)*(x985)))+(((IkReal(-1.00000000000000))*(r02)*(x974)*(x979)))+(((r11)*(x988)))+(((IkReal(-1.00000000000000))*(x986)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x980)))+(((IkReal(-1.00000000000000))*(x974)*(x975)*(x976)))+(((IkReal(-1.00000000000000))*(r12)*(x972)*(x974))));
02796 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
02797 {
02798 continue;
02799 }
02800 }
02801 
02802 {
02803 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02804 vinfos[0].jointtype = 1;
02805 vinfos[0].foffset = j0;
02806 vinfos[0].indices[0] = _ij0[0];
02807 vinfos[0].indices[1] = _ij0[1];
02808 vinfos[0].maxsolutions = _nj0;
02809 vinfos[1].jointtype = 1;
02810 vinfos[1].foffset = j1;
02811 vinfos[1].indices[0] = _ij1[0];
02812 vinfos[1].indices[1] = _ij1[1];
02813 vinfos[1].maxsolutions = _nj1;
02814 vinfos[2].jointtype = 1;
02815 vinfos[2].foffset = j2;
02816 vinfos[2].indices[0] = _ij2[0];
02817 vinfos[2].indices[1] = _ij2[1];
02818 vinfos[2].maxsolutions = _nj2;
02819 vinfos[3].jointtype = 1;
02820 vinfos[3].foffset = j3;
02821 vinfos[3].indices[0] = _ij3[0];
02822 vinfos[3].indices[1] = _ij3[1];
02823 vinfos[3].maxsolutions = _nj3;
02824 vinfos[4].jointtype = 1;
02825 vinfos[4].foffset = j4;
02826 vinfos[4].indices[0] = _ij4[0];
02827 vinfos[4].indices[1] = _ij4[1];
02828 vinfos[4].maxsolutions = _nj4;
02829 vinfos[5].jointtype = 1;
02830 vinfos[5].foffset = j5;
02831 vinfos[5].indices[0] = _ij5[0];
02832 vinfos[5].indices[1] = _ij5[1];
02833 vinfos[5].maxsolutions = _nj5;
02834 vinfos[6].jointtype = 1;
02835 vinfos[6].foffset = j6;
02836 vinfos[6].indices[0] = _ij6[0];
02837 vinfos[6].indices[1] = _ij6[1];
02838 vinfos[6].maxsolutions = _nj6;
02839 std::vector<int> vfree(0);
02840 solutions.AddSolution(vinfos,vfree);
02841 }
02842 }
02843 }
02844 
02845 }
02846 
02847 }
02848 
02849 } else
02850 {
02851 {
02852 IkReal j3array[1], cj3array[1], sj3array[1];
02853 bool j3valid[1]={false};
02854 _nj3 = 1;
02855 IkReal x989=((sj5)*(sj6));
02856 IkReal x990=((IkReal(1.00000000000000))*(cj6)*(sj5));
02857 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x989)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x989)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x989)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x990)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x990))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x989)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x989)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x989)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x990)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x990)))))-1) <= IKFAST_SINCOS_THRESH )
02858     continue;
02859 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x989)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x989)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x989)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x990)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x990)))));
02860 sj3array[0]=IKsin(j3array[0]);
02861 cj3array[0]=IKcos(j3array[0]);
02862 if( j3array[0] > IKPI )
02863 {
02864     j3array[0]-=IK2PI;
02865 }
02866 else if( j3array[0] < -IKPI )
02867 {    j3array[0]+=IK2PI;
02868 }
02869 j3valid[0] = true;
02870 for(int ij3 = 0; ij3 < 1; ++ij3)
02871 {
02872 if( !j3valid[ij3] )
02873 {
02874     continue;
02875 }
02876 _ij3[0] = ij3; _ij3[1] = -1;
02877 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02878 {
02879 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02880 {
02881     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02882 }
02883 }
02884 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02885 {
02886 IkReal evalcond[6];
02887 IkReal x991=IKsin(j3);
02888 IkReal x992=IKcos(j3);
02889 IkReal x993=((sj0)*(sj5));
02890 IkReal x994=((r00)*(sj6));
02891 IkReal x995=((IkReal(1.00000000000000))*(cj4));
02892 IkReal x996=((cj6)*(r01));
02893 IkReal x997=((cj0)*(cj5));
02894 IkReal x998=((cj5)*(sj0));
02895 IkReal x999=((cj6)*(r11));
02896 IkReal x1000=((cj0)*(sj5));
02897 IkReal x1001=((cj6)*(sj4));
02898 IkReal x1002=((cj4)*(cj5));
02899 IkReal x1003=((cj6)*(r21));
02900 IkReal x1004=((r20)*(sj6));
02901 IkReal x1005=((r10)*(sj6));
02902 IkReal x1006=((IkReal(1.00000000000000))*(cj0));
02903 IkReal x1007=((IkReal(1.00000000000000))*(x991));
02904 IkReal x1008=((cj0)*(sj4)*(sj6));
02905 IkReal x1009=((sj0)*(sj4)*(sj6));
02906 evalcond[0]=((((sj5)*(x1003)))+(((IkReal(-1.00000000000000))*(cj2)*(x1007)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1004))));
02907 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x1002)*(x1003)))+(((r20)*(x1001)))+(((cj4)*(r22)*(sj5)))+(((cj2)*(x992)))+(((x1002)*(x1004))));
02908 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x998)))+(((IkReal(-1.00000000000000))*(sj2)*(x1007)))+(((x993)*(x994)))+(((IkReal(-1.00000000000000))*(x1000)*(x999)))+(((r12)*(x997)))+(((IkReal(-1.00000000000000))*(x1000)*(x1005)))+(((x993)*(x996))));
02909 evalcond[3]=((((r02)*(x997)))+(((IkReal(-1.00000000000000))*(x992)))+(((IkReal(-1.00000000000000))*(x993)*(x999)))+(((IkReal(-1.00000000000000))*(x1005)*(x993)))+(((IkReal(-1.00000000000000))*(x1000)*(x994)))+(((r12)*(x998)))+(((IkReal(-1.00000000000000))*(x1000)*(x996))));
02910 evalcond[4]=((((cj4)*(r02)*(x993)))+(((sj2)*(x992)))+(((r00)*(sj0)*(x1001)))+(((IkReal(-1.00000000000000))*(r12)*(x1000)*(x995)))+(((IkReal(-1.00000000000000))*(x1005)*(x995)*(x997)))+(((IkReal(-1.00000000000000))*(x995)*(x997)*(x999)))+(((IkReal(-1.00000000000000))*(r10)*(x1001)*(x1006)))+(((r11)*(x1008)))+(((cj4)*(x994)*(x998)))+(((cj4)*(x996)*(x998)))+(((IkReal(-1.00000000000000))*(r01)*(x1009))));
02911 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x993)*(x995)))+(((IkReal(-1.00000000000000))*(x995)*(x998)*(x999)))+(((r01)*(x1008)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1001)))+(((IkReal(-1.00000000000000))*(x1007)))+(((IkReal(-1.00000000000000))*(r02)*(x1000)*(x995)))+(((IkReal(-1.00000000000000))*(r00)*(x1001)*(x1006)))+(((IkReal(-1.00000000000000))*(x995)*(x996)*(x997)))+(((IkReal(-1.00000000000000))*(x994)*(x995)*(x997)))+(((r11)*(x1009)))+(((IkReal(-1.00000000000000))*(x1005)*(x995)*(x998))));
02912 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
02913 {
02914 continue;
02915 }
02916 }
02917 
02918 {
02919 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
02920 vinfos[0].jointtype = 1;
02921 vinfos[0].foffset = j0;
02922 vinfos[0].indices[0] = _ij0[0];
02923 vinfos[0].indices[1] = _ij0[1];
02924 vinfos[0].maxsolutions = _nj0;
02925 vinfos[1].jointtype = 1;
02926 vinfos[1].foffset = j1;
02927 vinfos[1].indices[0] = _ij1[0];
02928 vinfos[1].indices[1] = _ij1[1];
02929 vinfos[1].maxsolutions = _nj1;
02930 vinfos[2].jointtype = 1;
02931 vinfos[2].foffset = j2;
02932 vinfos[2].indices[0] = _ij2[0];
02933 vinfos[2].indices[1] = _ij2[1];
02934 vinfos[2].maxsolutions = _nj2;
02935 vinfos[3].jointtype = 1;
02936 vinfos[3].foffset = j3;
02937 vinfos[3].indices[0] = _ij3[0];
02938 vinfos[3].indices[1] = _ij3[1];
02939 vinfos[3].maxsolutions = _nj3;
02940 vinfos[4].jointtype = 1;
02941 vinfos[4].foffset = j4;
02942 vinfos[4].indices[0] = _ij4[0];
02943 vinfos[4].indices[1] = _ij4[1];
02944 vinfos[4].maxsolutions = _nj4;
02945 vinfos[5].jointtype = 1;
02946 vinfos[5].foffset = j5;
02947 vinfos[5].indices[0] = _ij5[0];
02948 vinfos[5].indices[1] = _ij5[1];
02949 vinfos[5].maxsolutions = _nj5;
02950 vinfos[6].jointtype = 1;
02951 vinfos[6].foffset = j6;
02952 vinfos[6].indices[0] = _ij6[0];
02953 vinfos[6].indices[1] = _ij6[1];
02954 vinfos[6].maxsolutions = _nj6;
02955 std::vector<int> vfree(0);
02956 solutions.AddSolution(vinfos,vfree);
02957 }
02958 }
02959 }
02960 
02961 }
02962 
02963 }
02964 
02965 } else
02966 {
02967 {
02968 IkReal j3array[1], cj3array[1], sj3array[1];
02969 bool j3valid[1]={false};
02970 _nj3 = 1;
02971 IkReal x1010=((IkReal(1.00000000000000))*(cj4));
02972 IkReal x1011=((cj6)*(r21));
02973 IkReal x1012=((r20)*(sj6));
02974 if( IKabs(((gconst43)*(((((sj5)*(x1012)))+(((sj5)*(x1011)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1010)*(x1012)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1010)))+(((IkReal(-1.00000000000000))*(cj5)*(x1010)*(x1011)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
02975     continue;
02976 j3array[0]=IKatan2(((gconst43)*(((((sj5)*(x1012)))+(((sj5)*(x1011)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((gconst43)*(((((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1010)*(x1012)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1010)))+(((IkReal(-1.00000000000000))*(cj5)*(x1010)*(x1011)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
02977 sj3array[0]=IKsin(j3array[0]);
02978 cj3array[0]=IKcos(j3array[0]);
02979 if( j3array[0] > IKPI )
02980 {
02981     j3array[0]-=IK2PI;
02982 }
02983 else if( j3array[0] < -IKPI )
02984 {    j3array[0]+=IK2PI;
02985 }
02986 j3valid[0] = true;
02987 for(int ij3 = 0; ij3 < 1; ++ij3)
02988 {
02989 if( !j3valid[ij3] )
02990 {
02991     continue;
02992 }
02993 _ij3[0] = ij3; _ij3[1] = -1;
02994 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02995 {
02996 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02997 {
02998     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02999 }
03000 }
03001 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03002 {
03003 IkReal evalcond[6];
03004 IkReal x1013=IKsin(j3);
03005 IkReal x1014=IKcos(j3);
03006 IkReal x1015=((sj0)*(sj5));
03007 IkReal x1016=((r00)*(sj6));
03008 IkReal x1017=((IkReal(1.00000000000000))*(cj4));
03009 IkReal x1018=((cj6)*(r01));
03010 IkReal x1019=((cj0)*(cj5));
03011 IkReal x1020=((cj5)*(sj0));
03012 IkReal x1021=((cj6)*(r11));
03013 IkReal x1022=((cj0)*(sj5));
03014 IkReal x1023=((cj6)*(sj4));
03015 IkReal x1024=((cj4)*(cj5));
03016 IkReal x1025=((cj6)*(r21));
03017 IkReal x1026=((r20)*(sj6));
03018 IkReal x1027=((r10)*(sj6));
03019 IkReal x1028=((IkReal(1.00000000000000))*(cj0));
03020 IkReal x1029=((IkReal(1.00000000000000))*(x1013));
03021 IkReal x1030=((cj0)*(sj4)*(sj6));
03022 IkReal x1031=((sj0)*(sj4)*(sj6));
03023 evalcond[0]=((((sj5)*(x1025)))+(((IkReal(-1.00000000000000))*(cj2)*(x1029)))+(((sj5)*(x1026)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
03024 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x1023)))+(((x1024)*(x1025)))+(((x1024)*(x1026)))+(((cj4)*(r22)*(sj5)))+(((cj2)*(x1014))));
03025 evalcond[2]=((((IkReal(-1.00000000000000))*(x1021)*(x1022)))+(((r12)*(x1019)))+(((IkReal(-1.00000000000000))*(r02)*(x1020)))+(((x1015)*(x1016)))+(((IkReal(-1.00000000000000))*(sj2)*(x1029)))+(((x1015)*(x1018)))+(((IkReal(-1.00000000000000))*(x1022)*(x1027))));
03026 evalcond[3]=((((IkReal(-1.00000000000000))*(x1015)*(x1027)))+(((IkReal(-1.00000000000000))*(x1015)*(x1021)))+(((IkReal(-1.00000000000000))*(x1014)))+(((IkReal(-1.00000000000000))*(x1018)*(x1022)))+(((r12)*(x1020)))+(((r02)*(x1019)))+(((IkReal(-1.00000000000000))*(x1016)*(x1022))));
03027 evalcond[4]=((((r11)*(x1030)))+(((IkReal(-1.00000000000000))*(r01)*(x1031)))+(((IkReal(-1.00000000000000))*(r12)*(x1017)*(x1022)))+(((r00)*(sj0)*(x1023)))+(((IkReal(-1.00000000000000))*(r10)*(x1023)*(x1028)))+(((IkReal(-1.00000000000000))*(x1017)*(x1019)*(x1021)))+(((cj4)*(x1018)*(x1020)))+(((IkReal(-1.00000000000000))*(x1017)*(x1019)*(x1027)))+(((cj4)*(x1016)*(x1020)))+(((cj4)*(r02)*(x1015)))+(((sj2)*(x1014))));
03028 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x1017)*(x1022)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1023)))+(((IkReal(-1.00000000000000))*(x1017)*(x1018)*(x1019)))+(((IkReal(-1.00000000000000))*(x1017)*(x1020)*(x1027)))+(((r01)*(x1030)))+(((IkReal(-1.00000000000000))*(r12)*(x1015)*(x1017)))+(((IkReal(-1.00000000000000))*(r00)*(x1023)*(x1028)))+(((IkReal(-1.00000000000000))*(x1017)*(x1020)*(x1021)))+(((IkReal(-1.00000000000000))*(x1029)))+(((IkReal(-1.00000000000000))*(x1016)*(x1017)*(x1019)))+(((r11)*(x1031))));
03029 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
03030 {
03031 continue;
03032 }
03033 }
03034 
03035 {
03036 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03037 vinfos[0].jointtype = 1;
03038 vinfos[0].foffset = j0;
03039 vinfos[0].indices[0] = _ij0[0];
03040 vinfos[0].indices[1] = _ij0[1];
03041 vinfos[0].maxsolutions = _nj0;
03042 vinfos[1].jointtype = 1;
03043 vinfos[1].foffset = j1;
03044 vinfos[1].indices[0] = _ij1[0];
03045 vinfos[1].indices[1] = _ij1[1];
03046 vinfos[1].maxsolutions = _nj1;
03047 vinfos[2].jointtype = 1;
03048 vinfos[2].foffset = j2;
03049 vinfos[2].indices[0] = _ij2[0];
03050 vinfos[2].indices[1] = _ij2[1];
03051 vinfos[2].maxsolutions = _nj2;
03052 vinfos[3].jointtype = 1;
03053 vinfos[3].foffset = j3;
03054 vinfos[3].indices[0] = _ij3[0];
03055 vinfos[3].indices[1] = _ij3[1];
03056 vinfos[3].maxsolutions = _nj3;
03057 vinfos[4].jointtype = 1;
03058 vinfos[4].foffset = j4;
03059 vinfos[4].indices[0] = _ij4[0];
03060 vinfos[4].indices[1] = _ij4[1];
03061 vinfos[4].maxsolutions = _nj4;
03062 vinfos[5].jointtype = 1;
03063 vinfos[5].foffset = j5;
03064 vinfos[5].indices[0] = _ij5[0];
03065 vinfos[5].indices[1] = _ij5[1];
03066 vinfos[5].maxsolutions = _nj5;
03067 vinfos[6].jointtype = 1;
03068 vinfos[6].foffset = j6;
03069 vinfos[6].indices[0] = _ij6[0];
03070 vinfos[6].indices[1] = _ij6[1];
03071 vinfos[6].maxsolutions = _nj6;
03072 std::vector<int> vfree(0);
03073 solutions.AddSolution(vinfos,vfree);
03074 }
03075 }
03076 }
03077 
03078 }
03079 
03080 }
03081 }
03082 }
03083 
03084 }
03085 
03086 }
03087 
03088 } else
03089 {
03090 {
03091 IkReal j4array[1], cj4array[1], sj4array[1];
03092 bool j4valid[1]={false};
03093 _nj4 = 1;
03094 IkReal x1032=((r11)*(sj0));
03095 IkReal x1033=((cj0)*(r01));
03096 IkReal x1034=((cj0)*(sj2));
03097 IkReal x1035=((sj0)*(sj2));
03098 IkReal x1036=((cj5)*(sj6));
03099 IkReal x1037=((IkReal(1.00000000000000))*(sj2)*(sj6));
03100 IkReal x1038=((cj5)*(cj6)*(sj2));
03101 if( IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(x1032)*(x1037)))+(((cj6)*(r10)*(x1035)))+(((IkReal(-1.00000000000000))*(x1033)*(x1037)))+(((cj6)*(r00)*(x1034))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((r00)*(x1034)*(x1036)))+(((x1033)*(x1038)))+(((r02)*(sj5)*(x1034)))+(((r10)*(x1035)*(x1036)))+(((x1032)*(x1038)))+(((r12)*(sj5)*(x1035))))))) < IKFAST_ATAN2_MAGTHRESH )
03102     continue;
03103 j4array[0]=IKatan2(((gconst40)*(((((IkReal(-1.00000000000000))*(x1032)*(x1037)))+(((cj6)*(r10)*(x1035)))+(((IkReal(-1.00000000000000))*(x1033)*(x1037)))+(((cj6)*(r00)*(x1034)))))), ((gconst40)*(((((r00)*(x1034)*(x1036)))+(((x1033)*(x1038)))+(((r02)*(sj5)*(x1034)))+(((r10)*(x1035)*(x1036)))+(((x1032)*(x1038)))+(((r12)*(sj5)*(x1035)))))));
03104 sj4array[0]=IKsin(j4array[0]);
03105 cj4array[0]=IKcos(j4array[0]);
03106 if( j4array[0] > IKPI )
03107 {
03108     j4array[0]-=IK2PI;
03109 }
03110 else if( j4array[0] < -IKPI )
03111 {    j4array[0]+=IK2PI;
03112 }
03113 j4valid[0] = true;
03114 for(int ij4 = 0; ij4 < 1; ++ij4)
03115 {
03116 if( !j4valid[ij4] )
03117 {
03118     continue;
03119 }
03120 _ij4[0] = ij4; _ij4[1] = -1;
03121 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
03122 {
03123 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
03124 {
03125     j4valid[iij4]=false; _ij4[1] = iij4; break; 
03126 }
03127 }
03128 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
03129 {
03130 IkReal evalcond[3];
03131 IkReal x1039=IKsin(j4);
03132 IkReal x1040=IKcos(j4);
03133 IkReal x1041=((r00)*(sj6));
03134 IkReal x1042=((cj6)*(r01));
03135 IkReal x1043=((IkReal(1.00000000000000))*(cj0));
03136 IkReal x1044=((IkReal(1.00000000000000))*(sj0));
03137 IkReal x1045=((r10)*(sj6));
03138 IkReal x1046=((sj5)*(x1039));
03139 IkReal x1047=((IkReal(1.00000000000000))*(cj6)*(r11));
03140 IkReal x1048=((cj5)*(x1039));
03141 IkReal x1049=((cj6)*(x1040));
03142 IkReal x1050=((sj0)*(x1048));
03143 IkReal x1051=((r01)*(sj6)*(x1040));
03144 IkReal x1052=((r11)*(sj6)*(x1040));
03145 evalcond[0]=((((r22)*(x1046)))+(((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(r20)*(x1049)))+(((r20)*(sj6)*(x1048)))+(((r21)*(sj6)*(x1040)))+(((cj6)*(r21)*(x1048))));
03146 evalcond[1]=((((IkReal(-1.00000000000000))*(x1043)*(x1045)*(x1048)))+(((sj0)*(x1051)))+(((IkReal(-1.00000000000000))*(x1043)*(x1052)))+(((IkReal(-1.00000000000000))*(r12)*(x1043)*(x1046)))+(((cj0)*(r10)*(x1049)))+(((IkReal(-1.00000000000000))*(r00)*(x1044)*(x1049)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1043)*(x1048)))+(cj2)+(((x1042)*(x1050)))+(((x1041)*(x1050)))+(((r02)*(sj0)*(x1046))));
03147 evalcond[2]=((((IkReal(-1.00000000000000))*(x1044)*(x1052)))+(((IkReal(-1.00000000000000))*(x1041)*(x1043)*(x1048)))+(((IkReal(-1.00000000000000))*(x1044)*(x1045)*(x1048)))+(((IkReal(-1.00000000000000))*(r02)*(x1043)*(x1046)))+(((IkReal(-1.00000000000000))*(r12)*(x1044)*(x1046)))+(((IkReal(-1.00000000000000))*(x1042)*(x1043)*(x1048)))+(((r10)*(sj0)*(x1049)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1044)*(x1048)))+(((cj0)*(r00)*(x1049)))+(((IkReal(-1.00000000000000))*(x1043)*(x1051))));
03148 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
03149 {
03150 continue;
03151 }
03152 }
03153 
03154 {
03155 IkReal dummyeval[1];
03156 IkReal gconst43;
03157 gconst43=IKsign(cj2);
03158 dummyeval[0]=cj2;
03159 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03160 {
03161 {
03162 IkReal dummyeval[1];
03163 dummyeval[0]=cj2;
03164 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03165 {
03166 {
03167 IkReal dummyeval[1];
03168 dummyeval[0]=sj2;
03169 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03170 {
03171 {
03172 IkReal evalcond[9];
03173 IkReal x1053=((cj5)*(sj4));
03174 IkReal x1054=((IkReal(1.00000000000000))*(sj6));
03175 IkReal x1055=((r10)*(sj0));
03176 IkReal x1056=((sj4)*(sj5));
03177 IkReal x1057=((cj5)*(cj6));
03178 IkReal x1058=((r01)*(sj0));
03179 IkReal x1059=((IkReal(1.00000000000000))*(r02));
03180 IkReal x1060=((IkReal(0.374290000000000))*(cj0));
03181 IkReal x1061=((cj5)*(r12));
03182 IkReal x1062=((cj6)*(sj5));
03183 IkReal x1063=((cj0)*(r11));
03184 IkReal x1064=((cj5)*(sj0));
03185 IkReal x1065=((r20)*(sj6));
03186 IkReal x1066=((IkReal(1.00000000000000))*(sj0));
03187 IkReal x1067=((cj4)*(cj5));
03188 IkReal x1068=((IkReal(1.00000000000000))*(cj6));
03189 IkReal x1069=((IkReal(0.0100000000000000))*(sj5));
03190 IkReal x1070=((sj5)*(sj6));
03191 IkReal x1071=((cj0)*(r10));
03192 IkReal x1072=((cj4)*(cj6));
03193 IkReal x1073=((cj0)*(r01));
03194 IkReal x1074=((IkReal(1.00000000000000))*(cj4));
03195 IkReal x1075=((cj0)*(r00));
03196 IkReal x1076=((IkReal(0.374290000000000))*(sj0));
03197 IkReal x1077=((cj0)*(r12));
03198 IkReal x1078=((IkReal(0.374290000000000))*(sj5));
03199 IkReal x1079=((cj4)*(sj6));
03200 IkReal x1080=((IkReal(1.00000000000000))*(cj0));
03201 IkReal x1081=((r02)*(sj0));
03202 IkReal x1082=((IkReal(0.0100000000000000))*(cj5));
03203 IkReal x1083=((r11)*(sj0));
03204 IkReal x1084=((r00)*(sj0)*(sj6));
03205 IkReal x1085=((r00)*(x1072));
03206 IkReal x1086=((sj6)*(x1082));
03207 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
03208 evalcond[1]=((((x1053)*(x1065)))+(((r21)*(x1079)))+(((cj6)*(r21)*(x1053)))+(((r22)*(x1056)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x1068))));
03209 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x1069)))+(((x1065)*(x1078)))+(((IkReal(-0.0100000000000000))*(r21)*(x1057)))+(((IkReal(-1.00000000000000))*(x1065)*(x1082)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(0.374290000000000))*(r21)*(x1062))));
03210 evalcond[3]=((((IkReal(-1.00000000000000))*(x1062)*(x1063)))+(((IkReal(-1.00000000000000))*(sj5)*(x1054)*(x1071)))+(((IkReal(-1.00000000000000))*(x1059)*(x1064)))+(((x1058)*(x1062)))+(((r00)*(sj0)*(x1070)))+(((cj0)*(x1061))));
03211 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(x1054)*(x1063)))+(((cj6)*(x1053)*(x1058)))+(((IkReal(-1.00000000000000))*(x1056)*(x1077)))+(((IkReal(-1.00000000000000))*(x1066)*(x1085)))+(((x1071)*(x1072)))+(((x1053)*(x1084)))+(((IkReal(-1.00000000000000))*(x1053)*(x1063)*(x1068)))+(((x1058)*(x1079)))+(((IkReal(-1.00000000000000))*(x1053)*(x1054)*(x1071)))+(((x1056)*(x1081))));
03212 evalcond[5]=((((sj4)*(sj6)*(x1063)))+(((IkReal(-1.00000000000000))*(sj4)*(x1054)*(x1058)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x1068)*(x1071)))+(((IkReal(-1.00000000000000))*(sj5)*(x1074)*(x1077)))+(((cj4)*(x1057)*(x1058)))+(((IkReal(-1.00000000000000))*(x1057)*(x1063)*(x1074)))+(((IkReal(-1.00000000000000))*(x1054)*(x1067)*(x1071)))+(((cj4)*(sj5)*(x1081)))+(((r00)*(x1064)*(x1079))));
03213 evalcond[6]=((((x1072)*(x1075)))+(((IkReal(-1.00000000000000))*(cj4)*(x1054)*(x1073)))+(((x1055)*(x1072)))+(((IkReal(-1.00000000000000))*(x1053)*(x1068)*(x1073)))+(((IkReal(-1.00000000000000))*(cj0)*(x1056)*(x1059)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1053)*(x1066)))+(((IkReal(-1.00000000000000))*(cj4)*(x1054)*(x1083)))+(((IkReal(-1.00000000000000))*(x1053)*(x1054)*(x1075)))+(((IkReal(-1.00000000000000))*(x1053)*(x1054)*(x1055)))+(((IkReal(-1.00000000000000))*(r12)*(x1056)*(x1066))));
03214 evalcond[7]=((((IkReal(-1.00000000000000))*(py)*(x1080)))+(((IkReal(-0.0100000000000000))*(x1057)*(x1058)))+(((x1060)*(x1061)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x1064)))+(((IkReal(-1.00000000000000))*(r11)*(x1060)*(x1062)))+(((IkReal(-1.00000000000000))*(r10)*(x1060)*(x1070)))+(((x1071)*(x1086)))+(((IkReal(0.0100000000000000))*(x1057)*(x1063)))+(((x1069)*(x1077)))+(((IkReal(-0.374290000000000))*(r02)*(x1064)))+(((IkReal(0.374290000000000))*(x1058)*(x1062)))+(((r00)*(x1070)*(x1076)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x1069)*(x1081))));
03215 evalcond[8]=((IkReal(0.433420000000000))+(((x1061)*(x1076)))+(((IkReal(-0.374290000000000))*(x1055)*(x1070)))+(((IkReal(0.0100000000000000))*(x1057)*(x1073)))+(((IkReal(-1.00000000000000))*(r01)*(x1060)*(x1062)))+(((IkReal(-1.00000000000000))*(r00)*(x1060)*(x1070)))+(((IkReal(-1.00000000000000))*(px)*(x1080)))+(((r12)*(sj0)*(x1069)))+(((IkReal(-1.00000000000000))*(r11)*(x1062)*(x1076)))+(((cj0)*(r02)*(x1069)))+(((IkReal(-1.00000000000000))*(py)*(x1066)))+(((IkReal(0.0100000000000000))*(x1057)*(x1083)))+(((cj5)*(r02)*(x1060)))+(((x1055)*(x1086)))+(((x1075)*(x1086))));
03216 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
03217 {
03218 {
03219 IkReal j3array[1], cj3array[1], sj3array[1];
03220 bool j3valid[1]={false};
03221 _nj3 = 1;
03222 IkReal x1087=((IkReal(1.00000000000000))*(cj4));
03223 IkReal x1088=((cj6)*(r21));
03224 IkReal x1089=((r20)*(sj6));
03225 if( IKabs(((((sj5)*(x1089)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1088))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1087)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1089)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1088)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x1089)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1088)))))+IKsqr(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1087)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1089)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1088)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
03226     continue;
03227 j3array[0]=IKatan2(((((sj5)*(x1089)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1088)))), ((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1087)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1089)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1087)*(x1088)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
03228 sj3array[0]=IKsin(j3array[0]);
03229 cj3array[0]=IKcos(j3array[0]);
03230 if( j3array[0] > IKPI )
03231 {
03232     j3array[0]-=IK2PI;
03233 }
03234 else if( j3array[0] < -IKPI )
03235 {    j3array[0]+=IK2PI;
03236 }
03237 j3valid[0] = true;
03238 for(int ij3 = 0; ij3 < 1; ++ij3)
03239 {
03240 if( !j3valid[ij3] )
03241 {
03242     continue;
03243 }
03244 _ij3[0] = ij3; _ij3[1] = -1;
03245 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03246 {
03247 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03248 {
03249     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03250 }
03251 }
03252 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03253 {
03254 IkReal evalcond[4];
03255 IkReal x1090=IKcos(j3);
03256 IkReal x1091=((IkReal(1.00000000000000))*(cj4));
03257 IkReal x1092=((sj0)*(sj5));
03258 IkReal x1093=((cj0)*(cj5));
03259 IkReal x1094=((cj6)*(r01));
03260 IkReal x1095=((r00)*(sj6));
03261 IkReal x1096=((cj6)*(r11));
03262 IkReal x1097=((cj5)*(sj0));
03263 IkReal x1098=((cj6)*(sj4));
03264 IkReal x1099=((sj4)*(sj6));
03265 IkReal x1100=((cj4)*(cj5));
03266 IkReal x1101=((cj6)*(r21));
03267 IkReal x1102=((r20)*(sj6));
03268 IkReal x1103=((r10)*(sj6));
03269 IkReal x1104=((IkReal(1.00000000000000))*(IKsin(j3)));
03270 IkReal x1105=((IkReal(1.00000000000000))*(cj0)*(sj5));
03271 evalcond[0]=((((IkReal(-1.00000000000000))*(x1104)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1102)))+(((sj5)*(x1101))));
03272 evalcond[1]=((((r20)*(x1098)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x1099)))+(x1090)+(((x1100)*(x1101)))+(((x1100)*(x1102))));
03273 evalcond[2]=((((IkReal(-1.00000000000000))*(x1095)*(x1105)))+(((IkReal(-1.00000000000000))*(x1094)*(x1105)))+(((r02)*(x1093)))+(((IkReal(-1.00000000000000))*(x1092)*(x1103)))+(((IkReal(-1.00000000000000))*(x1092)*(x1096)))+(((r12)*(x1097)))+(((IkReal(-1.00000000000000))*(x1090))));
03274 evalcond[3]=((((IkReal(-1.00000000000000))*(x1091)*(x1093)*(x1095)))+(((IkReal(-1.00000000000000))*(x1104)))+(((IkReal(-1.00000000000000))*(r12)*(x1091)*(x1092)))+(((IkReal(-1.00000000000000))*(x1091)*(x1093)*(x1094)))+(((cj0)*(r01)*(x1099)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x1091)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1098)))+(((IkReal(-1.00000000000000))*(x1091)*(x1097)*(x1103)))+(((r11)*(sj0)*(x1099)))+(((IkReal(-1.00000000000000))*(x1091)*(x1096)*(x1097)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1098))));
03275 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03276 {
03277 continue;
03278 }
03279 }
03280 
03281 {
03282 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03283 vinfos[0].jointtype = 1;
03284 vinfos[0].foffset = j0;
03285 vinfos[0].indices[0] = _ij0[0];
03286 vinfos[0].indices[1] = _ij0[1];
03287 vinfos[0].maxsolutions = _nj0;
03288 vinfos[1].jointtype = 1;
03289 vinfos[1].foffset = j1;
03290 vinfos[1].indices[0] = _ij1[0];
03291 vinfos[1].indices[1] = _ij1[1];
03292 vinfos[1].maxsolutions = _nj1;
03293 vinfos[2].jointtype = 1;
03294 vinfos[2].foffset = j2;
03295 vinfos[2].indices[0] = _ij2[0];
03296 vinfos[2].indices[1] = _ij2[1];
03297 vinfos[2].maxsolutions = _nj2;
03298 vinfos[3].jointtype = 1;
03299 vinfos[3].foffset = j3;
03300 vinfos[3].indices[0] = _ij3[0];
03301 vinfos[3].indices[1] = _ij3[1];
03302 vinfos[3].maxsolutions = _nj3;
03303 vinfos[4].jointtype = 1;
03304 vinfos[4].foffset = j4;
03305 vinfos[4].indices[0] = _ij4[0];
03306 vinfos[4].indices[1] = _ij4[1];
03307 vinfos[4].maxsolutions = _nj4;
03308 vinfos[5].jointtype = 1;
03309 vinfos[5].foffset = j5;
03310 vinfos[5].indices[0] = _ij5[0];
03311 vinfos[5].indices[1] = _ij5[1];
03312 vinfos[5].maxsolutions = _nj5;
03313 vinfos[6].jointtype = 1;
03314 vinfos[6].foffset = j6;
03315 vinfos[6].indices[0] = _ij6[0];
03316 vinfos[6].indices[1] = _ij6[1];
03317 vinfos[6].maxsolutions = _nj6;
03318 std::vector<int> vfree(0);
03319 solutions.AddSolution(vinfos,vfree);
03320 }
03321 }
03322 }
03323 
03324 } else
03325 {
03326 IkReal x1106=((cj5)*(sj4));
03327 IkReal x1107=((IkReal(1.00000000000000))*(sj6));
03328 IkReal x1108=((r10)*(sj0));
03329 IkReal x1109=((sj4)*(sj5));
03330 IkReal x1110=((cj5)*(cj6));
03331 IkReal x1111=((r01)*(sj0));
03332 IkReal x1112=((IkReal(1.00000000000000))*(r02));
03333 IkReal x1113=((IkReal(0.374290000000000))*(cj0));
03334 IkReal x1114=((cj5)*(r12));
03335 IkReal x1115=((cj6)*(sj5));
03336 IkReal x1116=((cj0)*(r11));
03337 IkReal x1117=((cj5)*(sj0));
03338 IkReal x1118=((r20)*(sj6));
03339 IkReal x1119=((IkReal(1.00000000000000))*(sj0));
03340 IkReal x1120=((cj4)*(cj5));
03341 IkReal x1121=((IkReal(1.00000000000000))*(cj6));
03342 IkReal x1122=((IkReal(0.0100000000000000))*(sj5));
03343 IkReal x1123=((sj5)*(sj6));
03344 IkReal x1124=((cj0)*(r10));
03345 IkReal x1125=((cj4)*(cj6));
03346 IkReal x1126=((cj0)*(r01));
03347 IkReal x1127=((IkReal(1.00000000000000))*(cj4));
03348 IkReal x1128=((cj0)*(r00));
03349 IkReal x1129=((IkReal(0.374290000000000))*(sj0));
03350 IkReal x1130=((cj0)*(r12));
03351 IkReal x1131=((IkReal(0.374290000000000))*(sj5));
03352 IkReal x1132=((cj4)*(sj6));
03353 IkReal x1133=((IkReal(1.00000000000000))*(cj0));
03354 IkReal x1134=((r02)*(sj0));
03355 IkReal x1135=((IkReal(0.0100000000000000))*(cj5));
03356 IkReal x1136=((r11)*(sj0));
03357 IkReal x1137=((r00)*(sj0)*(sj6));
03358 IkReal x1138=((r00)*(x1125));
03359 IkReal x1139=((sj6)*(x1135));
03360 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
03361 evalcond[1]=((((r21)*(x1132)))+(((cj6)*(r21)*(x1106)))+(((x1106)*(x1118)))+(((r22)*(x1109)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x1121))));
03362 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x1115)))+(((IkReal(-0.0100000000000000))*(r21)*(x1110)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x1122)))+(((IkReal(-1.00000000000000))*(x1118)*(x1135)))+(((x1118)*(x1131))));
03363 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x1107)*(x1124)))+(((x1111)*(x1115)))+(((IkReal(-1.00000000000000))*(x1115)*(x1116)))+(((r00)*(sj0)*(x1123)))+(((cj0)*(x1114)))+(((IkReal(-1.00000000000000))*(x1112)*(x1117))));
03364 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1106)*(x1107)*(x1124)))+(((x1106)*(x1137)))+(((IkReal(-1.00000000000000))*(x1119)*(x1138)))+(((IkReal(-1.00000000000000))*(cj4)*(x1107)*(x1116)))+(((IkReal(-1.00000000000000))*(x1109)*(x1130)))+(((x1124)*(x1125)))+(((x1111)*(x1132)))+(((IkReal(-1.00000000000000))*(x1106)*(x1116)*(x1121)))+(((x1109)*(x1134)))+(((cj6)*(x1106)*(x1111))));
03365 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x1127)*(x1130)))+(((cj4)*(sj5)*(x1134)))+(((IkReal(-1.00000000000000))*(x1107)*(x1120)*(x1124)))+(((cj4)*(x1110)*(x1111)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((r00)*(x1117)*(x1132)))+(((sj4)*(sj6)*(x1116)))+(((IkReal(-1.00000000000000))*(sj4)*(x1107)*(x1111)))+(((IkReal(-1.00000000000000))*(sj4)*(x1121)*(x1124)))+(((IkReal(-1.00000000000000))*(x1110)*(x1116)*(x1127))));
03366 evalcond[6]=((((x1108)*(x1125)))+(((IkReal(-1.00000000000000))*(cj4)*(x1107)*(x1136)))+(((x1125)*(x1128)))+(((IkReal(-1.00000000000000))*(x1106)*(x1107)*(x1108)))+(((IkReal(-1.00000000000000))*(cj4)*(x1107)*(x1126)))+(((IkReal(-1.00000000000000))*(x1106)*(x1121)*(x1126)))+(((IkReal(-1.00000000000000))*(x1106)*(x1107)*(x1128)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1106)*(x1119)))+(((IkReal(-1.00000000000000))*(r12)*(x1109)*(x1119)))+(((IkReal(-1.00000000000000))*(cj0)*(x1109)*(x1112))));
03367 evalcond[7]=((((IkReal(-1.00000000000000))*(py)*(x1133)))+(((x1122)*(x1130)))+(((IkReal(-1.00000000000000))*(r11)*(x1113)*(x1115)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x1117)))+(((r00)*(x1123)*(x1129)))+(((IkReal(0.0100000000000000))*(x1110)*(x1116)))+(((IkReal(-1.00000000000000))*(r10)*(x1113)*(x1123)))+(((IkReal(-1.00000000000000))*(x1122)*(x1134)))+(((x1124)*(x1139)))+(((IkReal(0.374290000000000))*(x1111)*(x1115)))+(((px)*(sj0)))+(((x1113)*(x1114)))+(((IkReal(-0.0100000000000000))*(x1110)*(x1111)))+(((IkReal(-0.374290000000000))*(r02)*(x1117))));
03368 evalcond[8]=((IkReal(0.433420000000000))+(((r12)*(sj0)*(x1122)))+(((x1114)*(x1129)))+(((IkReal(0.0100000000000000))*(x1110)*(x1136)))+(((x1128)*(x1139)))+(((IkReal(-0.374290000000000))*(x1108)*(x1123)))+(((IkReal(-1.00000000000000))*(r00)*(x1113)*(x1123)))+(((IkReal(-1.00000000000000))*(px)*(x1133)))+(((IkReal(-1.00000000000000))*(r11)*(x1115)*(x1129)))+(((IkReal(-1.00000000000000))*(py)*(x1119)))+(((cj0)*(r02)*(x1122)))+(((IkReal(-1.00000000000000))*(r01)*(x1113)*(x1115)))+(((x1108)*(x1139)))+(((cj5)*(r02)*(x1113)))+(((IkReal(0.0100000000000000))*(x1110)*(x1126))));
03369 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
03370 {
03371 {
03372 IkReal j3array[1], cj3array[1], sj3array[1];
03373 bool j3valid[1]={false};
03374 _nj3 = 1;
03375 IkReal x1140=((IkReal(1.00000000000000))*(r21));
03376 IkReal x1141=((cj4)*(cj5));
03377 IkReal x1142=((r20)*(sj6));
03378 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x1142)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1140)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r20)*(sj4)))+(((x1141)*(x1142)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x1141)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1140))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x1142)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1140)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r20)*(sj4)))+(((x1141)*(x1142)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x1141)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1140)))))-1) <= IKFAST_SINCOS_THRESH )
03379     continue;
03380 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x1142)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1140)))+(((cj5)*(r22)))), ((((cj6)*(r20)*(sj4)))+(((x1141)*(x1142)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x1141)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1140)))));
03381 sj3array[0]=IKsin(j3array[0]);
03382 cj3array[0]=IKcos(j3array[0]);
03383 if( j3array[0] > IKPI )
03384 {
03385     j3array[0]-=IK2PI;
03386 }
03387 else if( j3array[0] < -IKPI )
03388 {    j3array[0]+=IK2PI;
03389 }
03390 j3valid[0] = true;
03391 for(int ij3 = 0; ij3 < 1; ++ij3)
03392 {
03393 if( !j3valid[ij3] )
03394 {
03395     continue;
03396 }
03397 _ij3[0] = ij3; _ij3[1] = -1;
03398 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03399 {
03400 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03401 {
03402     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03403 }
03404 }
03405 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03406 {
03407 IkReal evalcond[4];
03408 IkReal x1143=IKsin(j3);
03409 IkReal x1144=((IkReal(1.00000000000000))*(cj4));
03410 IkReal x1145=((sj0)*(sj5));
03411 IkReal x1146=((cj0)*(cj5));
03412 IkReal x1147=((cj6)*(r01));
03413 IkReal x1148=((r00)*(sj6));
03414 IkReal x1149=((cj6)*(r11));
03415 IkReal x1150=((cj5)*(sj0));
03416 IkReal x1151=((cj6)*(sj4));
03417 IkReal x1152=((sj4)*(sj6));
03418 IkReal x1153=((cj4)*(cj5));
03419 IkReal x1154=((cj6)*(r21));
03420 IkReal x1155=((r20)*(sj6));
03421 IkReal x1156=((r10)*(sj6));
03422 IkReal x1157=((IkReal(1.00000000000000))*(IKcos(j3)));
03423 IkReal x1158=((IkReal(1.00000000000000))*(cj0)*(sj5));
03424 evalcond[0]=((x1143)+(((sj5)*(x1154)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1155))));
03425 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x1152)))+(((cj4)*(r22)*(sj5)))+(((x1153)*(x1154)))+(((x1153)*(x1155)))+(((r20)*(x1151)))+(((IkReal(-1.00000000000000))*(x1157))));
03426 evalcond[2]=((((r02)*(x1146)))+(((IkReal(-1.00000000000000))*(x1145)*(x1149)))+(((IkReal(-1.00000000000000))*(x1148)*(x1158)))+(((IkReal(-1.00000000000000))*(x1145)*(x1156)))+(((r12)*(x1150)))+(((IkReal(-1.00000000000000))*(x1147)*(x1158)))+(((IkReal(-1.00000000000000))*(x1157))));
03427 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x1144)*(x1145)))+(((IkReal(-1.00000000000000))*(x1144)*(x1146)*(x1148)))+(((IkReal(-1.00000000000000))*(x1144)*(x1150)*(x1156)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1151)))+(((IkReal(-1.00000000000000))*(x1144)*(x1149)*(x1150)))+(((r11)*(sj0)*(x1152)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x1144)))+(((IkReal(-1.00000000000000))*(x1143)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1151)))+(((cj0)*(r01)*(x1152)))+(((IkReal(-1.00000000000000))*(x1144)*(x1146)*(x1147))));
03428 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03429 {
03430 continue;
03431 }
03432 }
03433 
03434 {
03435 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03436 vinfos[0].jointtype = 1;
03437 vinfos[0].foffset = j0;
03438 vinfos[0].indices[0] = _ij0[0];
03439 vinfos[0].indices[1] = _ij0[1];
03440 vinfos[0].maxsolutions = _nj0;
03441 vinfos[1].jointtype = 1;
03442 vinfos[1].foffset = j1;
03443 vinfos[1].indices[0] = _ij1[0];
03444 vinfos[1].indices[1] = _ij1[1];
03445 vinfos[1].maxsolutions = _nj1;
03446 vinfos[2].jointtype = 1;
03447 vinfos[2].foffset = j2;
03448 vinfos[2].indices[0] = _ij2[0];
03449 vinfos[2].indices[1] = _ij2[1];
03450 vinfos[2].maxsolutions = _nj2;
03451 vinfos[3].jointtype = 1;
03452 vinfos[3].foffset = j3;
03453 vinfos[3].indices[0] = _ij3[0];
03454 vinfos[3].indices[1] = _ij3[1];
03455 vinfos[3].maxsolutions = _nj3;
03456 vinfos[4].jointtype = 1;
03457 vinfos[4].foffset = j4;
03458 vinfos[4].indices[0] = _ij4[0];
03459 vinfos[4].indices[1] = _ij4[1];
03460 vinfos[4].maxsolutions = _nj4;
03461 vinfos[5].jointtype = 1;
03462 vinfos[5].foffset = j5;
03463 vinfos[5].indices[0] = _ij5[0];
03464 vinfos[5].indices[1] = _ij5[1];
03465 vinfos[5].maxsolutions = _nj5;
03466 vinfos[6].jointtype = 1;
03467 vinfos[6].foffset = j6;
03468 vinfos[6].indices[0] = _ij6[0];
03469 vinfos[6].indices[1] = _ij6[1];
03470 vinfos[6].maxsolutions = _nj6;
03471 std::vector<int> vfree(0);
03472 solutions.AddSolution(vinfos,vfree);
03473 }
03474 }
03475 }
03476 
03477 } else
03478 {
03479 IkReal x1159=((IkReal(1.00000000000000))*(cj0));
03480 IkReal x1160=((cj4)*(sj6));
03481 IkReal x1161=((sj0)*(sj4));
03482 IkReal x1162=((cj5)*(sj6));
03483 IkReal x1163=((sj4)*(sj5));
03484 IkReal x1164=((r12)*(sj5));
03485 IkReal x1165=((IkReal(0.374290000000000))*(cj5));
03486 IkReal x1166=((r02)*(sj0));
03487 IkReal x1167=((r20)*(sj4));
03488 IkReal x1168=((IkReal(1.00000000000000))*(sj0));
03489 IkReal x1169=((IkReal(1.00000000000000))*(cj5));
03490 IkReal x1170=((cj0)*(r10));
03491 IkReal x1171=((cj4)*(cj6));
03492 IkReal x1172=((r00)*(sj0));
03493 IkReal x1173=((cj6)*(r21));
03494 IkReal x1174=((IkReal(0.374290000000000))*(sj5));
03495 IkReal x1175=((cj0)*(r00));
03496 IkReal x1176=((IkReal(0.0100000000000000))*(sj5));
03497 IkReal x1177=((cj0)*(r02));
03498 IkReal x1178=((cj5)*(sj4));
03499 IkReal x1179=((cj6)*(r01));
03500 IkReal x1180=((cj6)*(r11));
03501 IkReal x1181=((r01)*(sj0));
03502 IkReal x1182=((r10)*(sj0));
03503 IkReal x1183=((IkReal(0.0100000000000000))*(cj5)*(cj6));
03504 IkReal x1184=((sj6)*(x1174));
03505 IkReal x1185=((cj0)*(cj6)*(x1174));
03506 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
03507 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x1169)))+(((sj5)*(x1173)))+(((r20)*(sj5)*(sj6))));
03508 evalcond[2]=((IkReal(-1.00000000000000))+(((x1173)*(x1178)))+(((x1162)*(x1167)))+(((IkReal(-1.00000000000000))*(r20)*(x1171)))+(((r22)*(x1163)))+(((r21)*(x1160))));
03509 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x1176)))+(((IkReal(-0.0100000000000000))*(r20)*(x1162)))+(((r20)*(x1184)))+(pz)+(((IkReal(-0.0100000000000000))*(cj5)*(x1173)))+(((x1173)*(x1174)))+(((IkReal(-1.00000000000000))*(r22)*(x1165))));
03510 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x1160)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x1167)))+(((cj5)*(r21)*(x1171))));
03511 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(x1159)*(x1160)))+(((x1160)*(x1181)))+(((cj5)*(x1161)*(x1179)))+(((IkReal(-1.00000000000000))*(r00)*(x1168)*(x1171)))+(((r00)*(x1161)*(x1162)))+(((IkReal(-1.00000000000000))*(x1159)*(x1178)*(x1180)))+(((IkReal(-1.00000000000000))*(r12)*(x1159)*(x1163)))+(((r02)*(sj5)*(x1161)))+(((x1170)*(x1171)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x1159)*(x1162))));
03512 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(x1161)*(x1162)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x1159)*(x1162)))+(((IkReal(-1.00000000000000))*(r01)*(x1159)*(x1160)))+(((IkReal(-1.00000000000000))*(x1161)*(x1169)*(x1180)))+(((x1171)*(x1175)))+(((IkReal(-1.00000000000000))*(x1161)*(x1164)))+(((x1171)*(x1182)))+(((IkReal(-1.00000000000000))*(x1159)*(x1178)*(x1179)))+(((IkReal(-1.00000000000000))*(r11)*(x1160)*(x1168)))+(((IkReal(-1.00000000000000))*(r02)*(x1159)*(x1163))));
03513 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x1159)))+(((IkReal(-1.00000000000000))*(x1166)*(x1176)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1180)))+(((IkReal(0.0100000000000000))*(cj0)*(x1164)))+(((sj0)*(x1174)*(x1179)))+(((IkReal(0.0100000000000000))*(x1162)*(x1170)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x1179)))+(((IkReal(-1.00000000000000))*(x1165)*(x1166)))+(((x1172)*(x1184)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x1174)*(x1180)))+(((cj0)*(r12)*(x1165)))+(((IkReal(-1.00000000000000))*(x1170)*(x1184)))+(((IkReal(-0.0100000000000000))*(x1162)*(x1172))));
03514 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x1180)))+(((IkReal(-1.00000000000000))*(x1175)*(x1184)))+(((IkReal(-1.00000000000000))*(cj0)*(x1174)*(x1179)))+(((IkReal(0.0100000000000000))*(x1162)*(x1175)))+(((IkReal(-1.00000000000000))*(x1182)*(x1184)))+(((IkReal(0.0100000000000000))*(x1162)*(x1182)))+(((x1176)*(x1177)))+(((r12)*(sj0)*(x1165)))+(((IkReal(-1.00000000000000))*(px)*(x1159)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1179)))+(((x1165)*(x1177)))+(((IkReal(-1.00000000000000))*(py)*(x1168)))+(((IkReal(0.0100000000000000))*(sj0)*(x1164)))+(((IkReal(-1.00000000000000))*(sj0)*(x1174)*(x1180))));
03515 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
03516 {
03517 {
03518 IkReal j3array[1], cj3array[1], sj3array[1];
03519 bool j3valid[1]={false};
03520 _nj3 = 1;
03521 IkReal x1186=((cj0)*(cj5));
03522 IkReal x1187=((IkReal(1.00000000000000))*(cj0));
03523 IkReal x1188=((cj6)*(r11));
03524 IkReal x1189=((r10)*(sj6));
03525 IkReal x1190=((cj5)*(sj0));
03526 IkReal x1191=((r00)*(sj5)*(sj6));
03527 IkReal x1192=((cj6)*(r01)*(sj5));
03528 IkReal x1193=((IkReal(1.00000000000000))*(sj0)*(sj5));
03529 if( IKabs(((((sj0)*(x1192)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1188)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1189)))+(((IkReal(-1.00000000000000))*(r02)*(x1190)))+(((sj0)*(x1191)))+(((r12)*(x1186))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x1189)*(x1193)))+(((r02)*(x1186)))+(((IkReal(-1.00000000000000))*(x1188)*(x1193)))+(((IkReal(-1.00000000000000))*(x1187)*(x1191)))+(((r12)*(x1190)))+(((IkReal(-1.00000000000000))*(x1187)*(x1192))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x1192)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1188)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1189)))+(((IkReal(-1.00000000000000))*(r02)*(x1190)))+(((sj0)*(x1191)))+(((r12)*(x1186)))))+IKsqr(((((IkReal(-1.00000000000000))*(x1189)*(x1193)))+(((r02)*(x1186)))+(((IkReal(-1.00000000000000))*(x1188)*(x1193)))+(((IkReal(-1.00000000000000))*(x1187)*(x1191)))+(((r12)*(x1190)))+(((IkReal(-1.00000000000000))*(x1187)*(x1192)))))-1) <= IKFAST_SINCOS_THRESH )
03530     continue;
03531 j3array[0]=IKatan2(((((sj0)*(x1192)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1188)))+(((IkReal(-1.00000000000000))*(sj5)*(x1187)*(x1189)))+(((IkReal(-1.00000000000000))*(r02)*(x1190)))+(((sj0)*(x1191)))+(((r12)*(x1186)))), ((((IkReal(-1.00000000000000))*(x1189)*(x1193)))+(((r02)*(x1186)))+(((IkReal(-1.00000000000000))*(x1188)*(x1193)))+(((IkReal(-1.00000000000000))*(x1187)*(x1191)))+(((r12)*(x1190)))+(((IkReal(-1.00000000000000))*(x1187)*(x1192)))));
03532 sj3array[0]=IKsin(j3array[0]);
03533 cj3array[0]=IKcos(j3array[0]);
03534 if( j3array[0] > IKPI )
03535 {
03536     j3array[0]-=IK2PI;
03537 }
03538 else if( j3array[0] < -IKPI )
03539 {    j3array[0]+=IK2PI;
03540 }
03541 j3valid[0] = true;
03542 for(int ij3 = 0; ij3 < 1; ++ij3)
03543 {
03544 if( !j3valid[ij3] )
03545 {
03546     continue;
03547 }
03548 _ij3[0] = ij3; _ij3[1] = -1;
03549 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03550 {
03551 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03552 {
03553     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03554 }
03555 }
03556 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03557 {
03558 IkReal evalcond[4];
03559 IkReal x1194=IKcos(j3);
03560 IkReal x1195=((sj0)*(sj5));
03561 IkReal x1196=((r00)*(sj6));
03562 IkReal x1197=((cj6)*(sj0));
03563 IkReal x1198=((IkReal(1.00000000000000))*(cj4));
03564 IkReal x1199=((r00)*(sj4));
03565 IkReal x1200=((cj0)*(cj5));
03566 IkReal x1201=((cj5)*(sj0));
03567 IkReal x1202=((cj6)*(r11));
03568 IkReal x1203=((r10)*(sj6));
03569 IkReal x1204=((cj0)*(sj5));
03570 IkReal x1205=((r10)*(sj4));
03571 IkReal x1206=((IkReal(1.00000000000000))*(IKsin(j3)));
03572 IkReal x1207=((cj4)*(cj5)*(r01));
03573 IkReal x1208=((IkReal(1.00000000000000))*(cj0)*(cj6));
03574 IkReal x1209=((cj0)*(sj4)*(sj6));
03575 IkReal x1210=((sj0)*(sj4)*(sj6));
03576 evalcond[0]=((((IkReal(-1.00000000000000))*(x1203)*(x1204)))+(((x1195)*(x1196)))+(((r12)*(x1200)))+(((cj6)*(r01)*(x1195)))+(((IkReal(-1.00000000000000))*(x1206)))+(((IkReal(-1.00000000000000))*(x1202)*(x1204)))+(((IkReal(-1.00000000000000))*(r02)*(x1201))));
03577 evalcond[1]=((((IkReal(-1.00000000000000))*(x1195)*(x1202)))+(((IkReal(-1.00000000000000))*(x1194)))+(((r02)*(x1200)))+(((IkReal(-1.00000000000000))*(x1195)*(x1203)))+(((IkReal(-1.00000000000000))*(x1196)*(x1204)))+(((r12)*(x1201)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x1204))));
03578 evalcond[2]=((((IkReal(-1.00000000000000))*(x1198)*(x1200)*(x1203)))+(((IkReal(-1.00000000000000))*(x1205)*(x1208)))+(((IkReal(-1.00000000000000))*(r12)*(x1198)*(x1204)))+(((r11)*(x1209)))+(((IkReal(-1.00000000000000))*(x1198)*(x1200)*(x1202)))+(((cj4)*(r02)*(x1195)))+(x1194)+(((x1197)*(x1207)))+(((IkReal(-1.00000000000000))*(r01)*(x1210)))+(((cj4)*(x1196)*(x1201)))+(((x1197)*(x1199))));
03579 evalcond[3]=((((IkReal(-1.00000000000000))*(r02)*(x1198)*(x1204)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1197)*(x1198)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x1198)*(x1200)))+(((IkReal(-1.00000000000000))*(x1196)*(x1198)*(x1200)))+(((IkReal(-1.00000000000000))*(x1197)*(x1205)))+(((IkReal(-1.00000000000000))*(x1199)*(x1208)))+(((r01)*(x1209)))+(((IkReal(-1.00000000000000))*(x1198)*(x1201)*(x1203)))+(((IkReal(-1.00000000000000))*(x1206)))+(((IkReal(-1.00000000000000))*(r12)*(x1195)*(x1198)))+(((r11)*(x1210))));
03580 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03581 {
03582 continue;
03583 }
03584 }
03585 
03586 {
03587 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03588 vinfos[0].jointtype = 1;
03589 vinfos[0].foffset = j0;
03590 vinfos[0].indices[0] = _ij0[0];
03591 vinfos[0].indices[1] = _ij0[1];
03592 vinfos[0].maxsolutions = _nj0;
03593 vinfos[1].jointtype = 1;
03594 vinfos[1].foffset = j1;
03595 vinfos[1].indices[0] = _ij1[0];
03596 vinfos[1].indices[1] = _ij1[1];
03597 vinfos[1].maxsolutions = _nj1;
03598 vinfos[2].jointtype = 1;
03599 vinfos[2].foffset = j2;
03600 vinfos[2].indices[0] = _ij2[0];
03601 vinfos[2].indices[1] = _ij2[1];
03602 vinfos[2].maxsolutions = _nj2;
03603 vinfos[3].jointtype = 1;
03604 vinfos[3].foffset = j3;
03605 vinfos[3].indices[0] = _ij3[0];
03606 vinfos[3].indices[1] = _ij3[1];
03607 vinfos[3].maxsolutions = _nj3;
03608 vinfos[4].jointtype = 1;
03609 vinfos[4].foffset = j4;
03610 vinfos[4].indices[0] = _ij4[0];
03611 vinfos[4].indices[1] = _ij4[1];
03612 vinfos[4].maxsolutions = _nj4;
03613 vinfos[5].jointtype = 1;
03614 vinfos[5].foffset = j5;
03615 vinfos[5].indices[0] = _ij5[0];
03616 vinfos[5].indices[1] = _ij5[1];
03617 vinfos[5].maxsolutions = _nj5;
03618 vinfos[6].jointtype = 1;
03619 vinfos[6].foffset = j6;
03620 vinfos[6].indices[0] = _ij6[0];
03621 vinfos[6].indices[1] = _ij6[1];
03622 vinfos[6].maxsolutions = _nj6;
03623 std::vector<int> vfree(0);
03624 solutions.AddSolution(vinfos,vfree);
03625 }
03626 }
03627 }
03628 
03629 } else
03630 {
03631 IkReal x1211=((IkReal(1.00000000000000))*(cj0));
03632 IkReal x1212=((cj4)*(sj6));
03633 IkReal x1213=((sj0)*(sj4));
03634 IkReal x1214=((cj5)*(sj6));
03635 IkReal x1215=((sj4)*(sj5));
03636 IkReal x1216=((r12)*(sj5));
03637 IkReal x1217=((IkReal(0.374290000000000))*(cj5));
03638 IkReal x1218=((r02)*(sj0));
03639 IkReal x1219=((r20)*(sj4));
03640 IkReal x1220=((IkReal(1.00000000000000))*(sj0));
03641 IkReal x1221=((IkReal(1.00000000000000))*(cj5));
03642 IkReal x1222=((cj0)*(r10));
03643 IkReal x1223=((cj4)*(cj6));
03644 IkReal x1224=((r00)*(sj0));
03645 IkReal x1225=((cj6)*(r21));
03646 IkReal x1226=((IkReal(0.374290000000000))*(sj5));
03647 IkReal x1227=((cj0)*(r00));
03648 IkReal x1228=((IkReal(0.0100000000000000))*(sj5));
03649 IkReal x1229=((cj0)*(r02));
03650 IkReal x1230=((cj5)*(sj4));
03651 IkReal x1231=((cj6)*(r01));
03652 IkReal x1232=((cj6)*(r11));
03653 IkReal x1233=((r01)*(sj0));
03654 IkReal x1234=((r10)*(sj0));
03655 IkReal x1235=((IkReal(0.0100000000000000))*(cj5)*(cj6));
03656 IkReal x1236=((sj6)*(x1226));
03657 IkReal x1237=((cj0)*(cj6)*(x1226));
03658 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
03659 evalcond[1]=((((sj5)*(x1225)))+(((IkReal(-1.00000000000000))*(r22)*(x1221)))+(((r20)*(sj5)*(sj6))));
03660 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x1223)))+(((x1225)*(x1230)))+(((r21)*(x1212)))+(((r22)*(x1215)))+(((x1214)*(x1219))));
03661 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x1217)))+(((IkReal(-0.0100000000000000))*(r20)*(x1214)))+(((r20)*(x1236)))+(((IkReal(-1.00000000000000))*(r22)*(x1228)))+(((x1225)*(x1226)))+(pz)+(((IkReal(-0.0100000000000000))*(cj5)*(x1225))));
03662 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x1219)))+(((cj5)*(r20)*(x1212)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x1223))));
03663 evalcond[5]=((((r00)*(x1213)*(x1214)))+(((IkReal(-1.00000000000000))*(r12)*(x1211)*(x1215)))+(((IkReal(-1.00000000000000))*(x1211)*(x1230)*(x1232)))+(((IkReal(-1.00000000000000))*(r00)*(x1220)*(x1223)))+(((r02)*(sj5)*(x1213)))+(((x1212)*(x1233)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x1211)*(x1214)))+(((cj5)*(x1213)*(x1231)))+(((IkReal(-1.00000000000000))*(r11)*(x1211)*(x1212)))+(((x1222)*(x1223))));
03664 evalcond[6]=((((IkReal(-1.00000000000000))*(x1211)*(x1230)*(x1231)))+(((IkReal(-1.00000000000000))*(r11)*(x1212)*(x1220)))+(((x1223)*(x1227)))+(((x1223)*(x1234)))+(((IkReal(-1.00000000000000))*(x1213)*(x1216)))+(((IkReal(-1.00000000000000))*(r02)*(x1211)*(x1215)))+(((IkReal(-1.00000000000000))*(r10)*(x1213)*(x1214)))+(((IkReal(-1.00000000000000))*(x1213)*(x1221)*(x1232)))+(((IkReal(-1.00000000000000))*(r01)*(x1211)*(x1212)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x1211)*(x1214))));
03665 evalcond[7]=((IkReal(-0.0690000000000000))+(((cj0)*(r12)*(x1217)))+(((IkReal(-1.00000000000000))*(cj0)*(x1226)*(x1232)))+(((x1224)*(x1236)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1232)))+(((IkReal(0.0100000000000000))*(cj0)*(x1216)))+(((IkReal(-1.00000000000000))*(py)*(x1211)))+(((IkReal(-1.00000000000000))*(x1217)*(x1218)))+(((IkReal(-0.0100000000000000))*(x1214)*(x1224)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x1231)))+(((IkReal(-1.00000000000000))*(x1218)*(x1228)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(x1214)*(x1222)))+(((IkReal(-1.00000000000000))*(x1222)*(x1236)))+(((sj0)*(x1226)*(x1231))));
03666 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x1226)*(x1231)))+(((IkReal(-1.00000000000000))*(sj0)*(x1226)*(x1232)))+(((IkReal(-1.00000000000000))*(x1227)*(x1236)))+(((IkReal(0.0100000000000000))*(sj0)*(x1216)))+(((IkReal(0.0100000000000000))*(x1214)*(x1234)))+(((IkReal(-1.00000000000000))*(py)*(x1220)))+(((x1217)*(x1229)))+(((IkReal(-1.00000000000000))*(px)*(x1211)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1231)))+(((IkReal(0.0100000000000000))*(x1214)*(x1227)))+(((IkReal(-1.00000000000000))*(x1234)*(x1236)))+(((x1228)*(x1229)))+(((r12)*(sj0)*(x1217)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x1232))));
03667 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
03668 {
03669 {
03670 IkReal j3array[1], cj3array[1], sj3array[1];
03671 bool j3valid[1]={false};
03672 _nj3 = 1;
03673 IkReal x1238=((cj5)*(r02));
03674 IkReal x1239=((cj0)*(sj5));
03675 IkReal x1240=((r10)*(sj6));
03676 IkReal x1241=((IkReal(1.00000000000000))*(cj6));
03677 IkReal x1242=((sj0)*(sj5));
03678 IkReal x1243=((cj5)*(r12));
03679 IkReal x1244=((IkReal(1.00000000000000))*(r00)*(sj6));
03680 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x1243)))+(((IkReal(-1.00000000000000))*(r01)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1242)*(x1244)))+(((x1239)*(x1240)))+(((cj6)*(r11)*(x1239)))+(((sj0)*(x1238))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x1240)*(x1242)))+(((IkReal(-1.00000000000000))*(r01)*(x1239)*(x1241)))+(((IkReal(-1.00000000000000))*(r11)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1239)*(x1244)))+(((sj0)*(x1243)))+(((cj0)*(x1238))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x1243)))+(((IkReal(-1.00000000000000))*(r01)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1242)*(x1244)))+(((x1239)*(x1240)))+(((cj6)*(r11)*(x1239)))+(((sj0)*(x1238)))))+IKsqr(((((IkReal(-1.00000000000000))*(x1240)*(x1242)))+(((IkReal(-1.00000000000000))*(r01)*(x1239)*(x1241)))+(((IkReal(-1.00000000000000))*(r11)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1239)*(x1244)))+(((sj0)*(x1243)))+(((cj0)*(x1238)))))-1) <= IKFAST_SINCOS_THRESH )
03681     continue;
03682 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x1243)))+(((IkReal(-1.00000000000000))*(r01)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1242)*(x1244)))+(((x1239)*(x1240)))+(((cj6)*(r11)*(x1239)))+(((sj0)*(x1238)))), ((((IkReal(-1.00000000000000))*(x1240)*(x1242)))+(((IkReal(-1.00000000000000))*(r01)*(x1239)*(x1241)))+(((IkReal(-1.00000000000000))*(r11)*(x1241)*(x1242)))+(((IkReal(-1.00000000000000))*(x1239)*(x1244)))+(((sj0)*(x1243)))+(((cj0)*(x1238)))));
03683 sj3array[0]=IKsin(j3array[0]);
03684 cj3array[0]=IKcos(j3array[0]);
03685 if( j3array[0] > IKPI )
03686 {
03687     j3array[0]-=IK2PI;
03688 }
03689 else if( j3array[0] < -IKPI )
03690 {    j3array[0]+=IK2PI;
03691 }
03692 j3valid[0] = true;
03693 for(int ij3 = 0; ij3 < 1; ++ij3)
03694 {
03695 if( !j3valid[ij3] )
03696 {
03697     continue;
03698 }
03699 _ij3[0] = ij3; _ij3[1] = -1;
03700 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03701 {
03702 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03703 {
03704     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03705 }
03706 }
03707 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03708 {
03709 IkReal evalcond[4];
03710 IkReal x1245=IKsin(j3);
03711 IkReal x1246=((sj0)*(sj5));
03712 IkReal x1247=((r00)*(sj6));
03713 IkReal x1248=((IkReal(1.00000000000000))*(cj4));
03714 IkReal x1249=((cj6)*(sj0));
03715 IkReal x1250=((r00)*(sj4));
03716 IkReal x1251=((cj0)*(cj5));
03717 IkReal x1252=((cj6)*(r01));
03718 IkReal x1253=((cj5)*(sj0));
03719 IkReal x1254=((cj0)*(sj5));
03720 IkReal x1255=((cj6)*(r11));
03721 IkReal x1256=((r10)*(sj6));
03722 IkReal x1257=((r10)*(sj4));
03723 IkReal x1258=((IkReal(1.00000000000000))*(IKcos(j3)));
03724 IkReal x1259=((cj0)*(sj4)*(sj6));
03725 IkReal x1260=((sj0)*(sj4)*(sj6));
03726 IkReal x1261=((IkReal(1.00000000000000))*(cj0)*(cj6));
03727 evalcond[0]=((((x1246)*(x1252)))+(((r12)*(x1251)))+(((IkReal(-1.00000000000000))*(x1254)*(x1255)))+(((IkReal(-1.00000000000000))*(r02)*(x1253)))+(x1245)+(((IkReal(-1.00000000000000))*(x1254)*(x1256)))+(((x1246)*(x1247))));
03728 evalcond[1]=((((IkReal(-1.00000000000000))*(x1252)*(x1254)))+(((IkReal(-1.00000000000000))*(x1246)*(x1256)))+(((r12)*(x1253)))+(((IkReal(-1.00000000000000))*(x1247)*(x1254)))+(((IkReal(-1.00000000000000))*(x1246)*(x1255)))+(((r02)*(x1251)))+(((IkReal(-1.00000000000000))*(x1258))));
03729 evalcond[2]=((((IkReal(-1.00000000000000))*(x1257)*(x1261)))+(((IkReal(-1.00000000000000))*(r01)*(x1260)))+(((x1249)*(x1250)))+(((IkReal(-1.00000000000000))*(r12)*(x1248)*(x1254)))+(((IkReal(-1.00000000000000))*(x1248)*(x1251)*(x1255)))+(((cj4)*(x1247)*(x1253)))+(((cj4)*(r02)*(x1246)))+(((cj4)*(cj5)*(r01)*(x1249)))+(((IkReal(-1.00000000000000))*(x1248)*(x1251)*(x1256)))+(((r11)*(x1259)))+(((IkReal(-1.00000000000000))*(x1258))));
03730 evalcond[3]=((((r01)*(x1259)))+(((r11)*(x1260)))+(((IkReal(-1.00000000000000))*(x1250)*(x1261)))+(((IkReal(-1.00000000000000))*(x1245)))+(((IkReal(-1.00000000000000))*(x1247)*(x1248)*(x1251)))+(((IkReal(-1.00000000000000))*(r12)*(x1246)*(x1248)))+(((IkReal(-1.00000000000000))*(x1248)*(x1251)*(x1252)))+(((IkReal(-1.00000000000000))*(x1249)*(x1257)))+(((IkReal(-1.00000000000000))*(x1248)*(x1253)*(x1256)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1248)*(x1249)))+(((IkReal(-1.00000000000000))*(r02)*(x1248)*(x1254))));
03731 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03732 {
03733 continue;
03734 }
03735 }
03736 
03737 {
03738 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03739 vinfos[0].jointtype = 1;
03740 vinfos[0].foffset = j0;
03741 vinfos[0].indices[0] = _ij0[0];
03742 vinfos[0].indices[1] = _ij0[1];
03743 vinfos[0].maxsolutions = _nj0;
03744 vinfos[1].jointtype = 1;
03745 vinfos[1].foffset = j1;
03746 vinfos[1].indices[0] = _ij1[0];
03747 vinfos[1].indices[1] = _ij1[1];
03748 vinfos[1].maxsolutions = _nj1;
03749 vinfos[2].jointtype = 1;
03750 vinfos[2].foffset = j2;
03751 vinfos[2].indices[0] = _ij2[0];
03752 vinfos[2].indices[1] = _ij2[1];
03753 vinfos[2].maxsolutions = _nj2;
03754 vinfos[3].jointtype = 1;
03755 vinfos[3].foffset = j3;
03756 vinfos[3].indices[0] = _ij3[0];
03757 vinfos[3].indices[1] = _ij3[1];
03758 vinfos[3].maxsolutions = _nj3;
03759 vinfos[4].jointtype = 1;
03760 vinfos[4].foffset = j4;
03761 vinfos[4].indices[0] = _ij4[0];
03762 vinfos[4].indices[1] = _ij4[1];
03763 vinfos[4].maxsolutions = _nj4;
03764 vinfos[5].jointtype = 1;
03765 vinfos[5].foffset = j5;
03766 vinfos[5].indices[0] = _ij5[0];
03767 vinfos[5].indices[1] = _ij5[1];
03768 vinfos[5].maxsolutions = _nj5;
03769 vinfos[6].jointtype = 1;
03770 vinfos[6].foffset = j6;
03771 vinfos[6].indices[0] = _ij6[0];
03772 vinfos[6].indices[1] = _ij6[1];
03773 vinfos[6].maxsolutions = _nj6;
03774 std::vector<int> vfree(0);
03775 solutions.AddSolution(vinfos,vfree);
03776 }
03777 }
03778 }
03779 
03780 } else
03781 {
03782 if( 1 )
03783 {
03784 continue;
03785 
03786 } else
03787 {
03788 }
03789 }
03790 }
03791 }
03792 }
03793 }
03794 
03795 } else
03796 {
03797 {
03798 IkReal j3array[1], cj3array[1], sj3array[1];
03799 bool j3valid[1]={false};
03800 _nj3 = 1;
03801 IkReal x1262=((cj0)*(cj5));
03802 IkReal x1263=((IkReal(1.00000000000000))*(cj0));
03803 IkReal x1264=((cj6)*(r11));
03804 IkReal x1265=((r10)*(sj6));
03805 IkReal x1266=((cj5)*(sj0));
03806 IkReal x1267=((r00)*(sj5)*(sj6));
03807 IkReal x1268=((cj6)*(r01)*(sj5));
03808 IkReal x1269=((IkReal(1.00000000000000))*(sj0)*(sj5));
03809 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x1262)))+(((IkReal(-1.00000000000000))*(r02)*(x1266)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1265)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1264)))+(((sj0)*(x1268)))+(((sj0)*(x1267))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x1264)*(x1269)))+(((IkReal(-1.00000000000000))*(x1265)*(x1269)))+(((IkReal(-1.00000000000000))*(x1263)*(x1267)))+(((r12)*(x1266)))+(((IkReal(-1.00000000000000))*(x1263)*(x1268)))+(((r02)*(x1262))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x1262)))+(((IkReal(-1.00000000000000))*(r02)*(x1266)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1265)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1264)))+(((sj0)*(x1268)))+(((sj0)*(x1267)))))))+IKsqr(((((IkReal(-1.00000000000000))*(x1264)*(x1269)))+(((IkReal(-1.00000000000000))*(x1265)*(x1269)))+(((IkReal(-1.00000000000000))*(x1263)*(x1267)))+(((r12)*(x1266)))+(((IkReal(-1.00000000000000))*(x1263)*(x1268)))+(((r02)*(x1262)))))-1) <= IKFAST_SINCOS_THRESH )
03810     continue;
03811 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x1262)))+(((IkReal(-1.00000000000000))*(r02)*(x1266)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1265)))+(((IkReal(-1.00000000000000))*(sj5)*(x1263)*(x1264)))+(((sj0)*(x1268)))+(((sj0)*(x1267)))))), ((((IkReal(-1.00000000000000))*(x1264)*(x1269)))+(((IkReal(-1.00000000000000))*(x1265)*(x1269)))+(((IkReal(-1.00000000000000))*(x1263)*(x1267)))+(((r12)*(x1266)))+(((IkReal(-1.00000000000000))*(x1263)*(x1268)))+(((r02)*(x1262)))));
03812 sj3array[0]=IKsin(j3array[0]);
03813 cj3array[0]=IKcos(j3array[0]);
03814 if( j3array[0] > IKPI )
03815 {
03816     j3array[0]-=IK2PI;
03817 }
03818 else if( j3array[0] < -IKPI )
03819 {    j3array[0]+=IK2PI;
03820 }
03821 j3valid[0] = true;
03822 for(int ij3 = 0; ij3 < 1; ++ij3)
03823 {
03824 if( !j3valid[ij3] )
03825 {
03826     continue;
03827 }
03828 _ij3[0] = ij3; _ij3[1] = -1;
03829 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03830 {
03831 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03832 {
03833     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03834 }
03835 }
03836 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03837 {
03838 IkReal evalcond[6];
03839 IkReal x1270=IKsin(j3);
03840 IkReal x1271=IKcos(j3);
03841 IkReal x1272=((sj0)*(sj5));
03842 IkReal x1273=((r00)*(sj6));
03843 IkReal x1274=((IkReal(1.00000000000000))*(cj4));
03844 IkReal x1275=((cj6)*(r01));
03845 IkReal x1276=((cj0)*(cj5));
03846 IkReal x1277=((cj5)*(sj0));
03847 IkReal x1278=((cj6)*(r11));
03848 IkReal x1279=((cj0)*(sj5));
03849 IkReal x1280=((cj6)*(sj4));
03850 IkReal x1281=((cj4)*(cj5));
03851 IkReal x1282=((cj6)*(r21));
03852 IkReal x1283=((r20)*(sj6));
03853 IkReal x1284=((r10)*(sj6));
03854 IkReal x1285=((IkReal(1.00000000000000))*(cj0));
03855 IkReal x1286=((IkReal(1.00000000000000))*(x1270));
03856 IkReal x1287=((cj0)*(sj4)*(sj6));
03857 IkReal x1288=((sj0)*(sj4)*(sj6));
03858 evalcond[0]=((((sj5)*(x1282)))+(((sj5)*(x1283)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x1286))));
03859 evalcond[1]=((((cj2)*(x1271)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x1281)*(x1283)))+(((x1281)*(x1282)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x1280))));
03860 evalcond[2]=((((r12)*(x1276)))+(((x1272)*(x1275)))+(((IkReal(-1.00000000000000))*(x1279)*(x1284)))+(((IkReal(-1.00000000000000))*(sj2)*(x1286)))+(((x1272)*(x1273)))+(((IkReal(-1.00000000000000))*(x1278)*(x1279)))+(((IkReal(-1.00000000000000))*(r02)*(x1277))));
03861 evalcond[3]=((((r12)*(x1277)))+(((IkReal(-1.00000000000000))*(x1272)*(x1284)))+(((IkReal(-1.00000000000000))*(x1275)*(x1279)))+(((IkReal(-1.00000000000000))*(x1271)))+(((r02)*(x1276)))+(((IkReal(-1.00000000000000))*(x1272)*(x1278)))+(((IkReal(-1.00000000000000))*(x1273)*(x1279))));
03862 evalcond[4]=((((IkReal(-1.00000000000000))*(x1274)*(x1276)*(x1278)))+(((IkReal(-1.00000000000000))*(r01)*(x1288)))+(((cj4)*(x1275)*(x1277)))+(((cj4)*(x1273)*(x1277)))+(((r00)*(sj0)*(x1280)))+(((IkReal(-1.00000000000000))*(r10)*(x1280)*(x1285)))+(((r11)*(x1287)))+(((IkReal(-1.00000000000000))*(r12)*(x1274)*(x1279)))+(((cj4)*(r02)*(x1272)))+(((sj2)*(x1271)))+(((IkReal(-1.00000000000000))*(x1274)*(x1276)*(x1284))));
03863 evalcond[5]=((((IkReal(-1.00000000000000))*(x1286)))+(((IkReal(-1.00000000000000))*(x1274)*(x1277)*(x1278)))+(((IkReal(-1.00000000000000))*(x1273)*(x1274)*(x1276)))+(((r11)*(x1288)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1280)))+(((r01)*(x1287)))+(((IkReal(-1.00000000000000))*(x1274)*(x1277)*(x1284)))+(((IkReal(-1.00000000000000))*(r02)*(x1274)*(x1279)))+(((IkReal(-1.00000000000000))*(x1274)*(x1275)*(x1276)))+(((IkReal(-1.00000000000000))*(r00)*(x1280)*(x1285)))+(((IkReal(-1.00000000000000))*(r12)*(x1272)*(x1274))));
03864 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
03865 {
03866 continue;
03867 }
03868 }
03869 
03870 {
03871 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03872 vinfos[0].jointtype = 1;
03873 vinfos[0].foffset = j0;
03874 vinfos[0].indices[0] = _ij0[0];
03875 vinfos[0].indices[1] = _ij0[1];
03876 vinfos[0].maxsolutions = _nj0;
03877 vinfos[1].jointtype = 1;
03878 vinfos[1].foffset = j1;
03879 vinfos[1].indices[0] = _ij1[0];
03880 vinfos[1].indices[1] = _ij1[1];
03881 vinfos[1].maxsolutions = _nj1;
03882 vinfos[2].jointtype = 1;
03883 vinfos[2].foffset = j2;
03884 vinfos[2].indices[0] = _ij2[0];
03885 vinfos[2].indices[1] = _ij2[1];
03886 vinfos[2].maxsolutions = _nj2;
03887 vinfos[3].jointtype = 1;
03888 vinfos[3].foffset = j3;
03889 vinfos[3].indices[0] = _ij3[0];
03890 vinfos[3].indices[1] = _ij3[1];
03891 vinfos[3].maxsolutions = _nj3;
03892 vinfos[4].jointtype = 1;
03893 vinfos[4].foffset = j4;
03894 vinfos[4].indices[0] = _ij4[0];
03895 vinfos[4].indices[1] = _ij4[1];
03896 vinfos[4].maxsolutions = _nj4;
03897 vinfos[5].jointtype = 1;
03898 vinfos[5].foffset = j5;
03899 vinfos[5].indices[0] = _ij5[0];
03900 vinfos[5].indices[1] = _ij5[1];
03901 vinfos[5].maxsolutions = _nj5;
03902 vinfos[6].jointtype = 1;
03903 vinfos[6].foffset = j6;
03904 vinfos[6].indices[0] = _ij6[0];
03905 vinfos[6].indices[1] = _ij6[1];
03906 vinfos[6].maxsolutions = _nj6;
03907 std::vector<int> vfree(0);
03908 solutions.AddSolution(vinfos,vfree);
03909 }
03910 }
03911 }
03912 
03913 }
03914 
03915 }
03916 
03917 } else
03918 {
03919 {
03920 IkReal j3array[1], cj3array[1], sj3array[1];
03921 bool j3valid[1]={false};
03922 _nj3 = 1;
03923 IkReal x1289=((sj5)*(sj6));
03924 IkReal x1290=((IkReal(1.00000000000000))*(cj6)*(sj5));
03925 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x1289)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1289)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1290)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1289)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1290))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x1289)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1289)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1290)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1289)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1290)))))-1) <= IKFAST_SINCOS_THRESH )
03926     continue;
03927 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x1289)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1289)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1290)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1289)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1290)))));
03928 sj3array[0]=IKsin(j3array[0]);
03929 cj3array[0]=IKcos(j3array[0]);
03930 if( j3array[0] > IKPI )
03931 {
03932     j3array[0]-=IK2PI;
03933 }
03934 else if( j3array[0] < -IKPI )
03935 {    j3array[0]+=IK2PI;
03936 }
03937 j3valid[0] = true;
03938 for(int ij3 = 0; ij3 < 1; ++ij3)
03939 {
03940 if( !j3valid[ij3] )
03941 {
03942     continue;
03943 }
03944 _ij3[0] = ij3; _ij3[1] = -1;
03945 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03946 {
03947 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03948 {
03949     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03950 }
03951 }
03952 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03953 {
03954 IkReal evalcond[6];
03955 IkReal x1291=IKsin(j3);
03956 IkReal x1292=IKcos(j3);
03957 IkReal x1293=((sj0)*(sj5));
03958 IkReal x1294=((r00)*(sj6));
03959 IkReal x1295=((IkReal(1.00000000000000))*(cj4));
03960 IkReal x1296=((cj6)*(r01));
03961 IkReal x1297=((cj0)*(cj5));
03962 IkReal x1298=((cj5)*(sj0));
03963 IkReal x1299=((cj6)*(r11));
03964 IkReal x1300=((cj0)*(sj5));
03965 IkReal x1301=((cj6)*(sj4));
03966 IkReal x1302=((cj4)*(cj5));
03967 IkReal x1303=((cj6)*(r21));
03968 IkReal x1304=((r20)*(sj6));
03969 IkReal x1305=((r10)*(sj6));
03970 IkReal x1306=((IkReal(1.00000000000000))*(cj0));
03971 IkReal x1307=((IkReal(1.00000000000000))*(x1291));
03972 IkReal x1308=((cj0)*(sj4)*(sj6));
03973 IkReal x1309=((sj0)*(sj4)*(sj6));
03974 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x1307)))+(((sj5)*(x1304)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1303))));
03975 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x1302)*(x1303)))+(((r20)*(x1301)))+(((cj2)*(x1292)))+(((x1302)*(x1304))));
03976 evalcond[2]=((((IkReal(-1.00000000000000))*(x1300)*(x1305)))+(((r12)*(x1297)))+(((IkReal(-1.00000000000000))*(sj2)*(x1307)))+(((IkReal(-1.00000000000000))*(r02)*(x1298)))+(((x1293)*(x1294)))+(((IkReal(-1.00000000000000))*(x1299)*(x1300)))+(((x1293)*(x1296))));
03977 evalcond[3]=((((IkReal(-1.00000000000000))*(x1292)))+(((IkReal(-1.00000000000000))*(x1293)*(x1305)))+(((IkReal(-1.00000000000000))*(x1293)*(x1299)))+(((IkReal(-1.00000000000000))*(x1296)*(x1300)))+(((r12)*(x1298)))+(((IkReal(-1.00000000000000))*(x1294)*(x1300)))+(((r02)*(x1297))));
03978 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x1301)*(x1306)))+(((cj4)*(r02)*(x1293)))+(((IkReal(-1.00000000000000))*(x1295)*(x1297)*(x1305)))+(((r00)*(sj0)*(x1301)))+(((IkReal(-1.00000000000000))*(x1295)*(x1297)*(x1299)))+(((cj4)*(x1296)*(x1298)))+(((IkReal(-1.00000000000000))*(r12)*(x1295)*(x1300)))+(((r11)*(x1308)))+(((cj4)*(x1294)*(x1298)))+(((sj2)*(x1292)))+(((IkReal(-1.00000000000000))*(r01)*(x1309))));
03979 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x1295)*(x1300)))+(((IkReal(-1.00000000000000))*(x1295)*(x1298)*(x1299)))+(((IkReal(-1.00000000000000))*(x1295)*(x1298)*(x1305)))+(((IkReal(-1.00000000000000))*(r00)*(x1301)*(x1306)))+(((IkReal(-1.00000000000000))*(r12)*(x1293)*(x1295)))+(((IkReal(-1.00000000000000))*(x1294)*(x1295)*(x1297)))+(((IkReal(-1.00000000000000))*(x1295)*(x1296)*(x1297)))+(((IkReal(-1.00000000000000))*(x1307)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1301)))+(((r11)*(x1309)))+(((r01)*(x1308))));
03980 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
03981 {
03982 continue;
03983 }
03984 }
03985 
03986 {
03987 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
03988 vinfos[0].jointtype = 1;
03989 vinfos[0].foffset = j0;
03990 vinfos[0].indices[0] = _ij0[0];
03991 vinfos[0].indices[1] = _ij0[1];
03992 vinfos[0].maxsolutions = _nj0;
03993 vinfos[1].jointtype = 1;
03994 vinfos[1].foffset = j1;
03995 vinfos[1].indices[0] = _ij1[0];
03996 vinfos[1].indices[1] = _ij1[1];
03997 vinfos[1].maxsolutions = _nj1;
03998 vinfos[2].jointtype = 1;
03999 vinfos[2].foffset = j2;
04000 vinfos[2].indices[0] = _ij2[0];
04001 vinfos[2].indices[1] = _ij2[1];
04002 vinfos[2].maxsolutions = _nj2;
04003 vinfos[3].jointtype = 1;
04004 vinfos[3].foffset = j3;
04005 vinfos[3].indices[0] = _ij3[0];
04006 vinfos[3].indices[1] = _ij3[1];
04007 vinfos[3].maxsolutions = _nj3;
04008 vinfos[4].jointtype = 1;
04009 vinfos[4].foffset = j4;
04010 vinfos[4].indices[0] = _ij4[0];
04011 vinfos[4].indices[1] = _ij4[1];
04012 vinfos[4].maxsolutions = _nj4;
04013 vinfos[5].jointtype = 1;
04014 vinfos[5].foffset = j5;
04015 vinfos[5].indices[0] = _ij5[0];
04016 vinfos[5].indices[1] = _ij5[1];
04017 vinfos[5].maxsolutions = _nj5;
04018 vinfos[6].jointtype = 1;
04019 vinfos[6].foffset = j6;
04020 vinfos[6].indices[0] = _ij6[0];
04021 vinfos[6].indices[1] = _ij6[1];
04022 vinfos[6].maxsolutions = _nj6;
04023 std::vector<int> vfree(0);
04024 solutions.AddSolution(vinfos,vfree);
04025 }
04026 }
04027 }
04028 
04029 }
04030 
04031 }
04032 
04033 } else
04034 {
04035 {
04036 IkReal j3array[1], cj3array[1], sj3array[1];
04037 bool j3valid[1]={false};
04038 _nj3 = 1;
04039 IkReal x1310=((IkReal(1.00000000000000))*(cj4));
04040 IkReal x1311=((cj6)*(r21));
04041 IkReal x1312=((r20)*(sj6));
04042 if( IKabs(((gconst43)*(((((sj5)*(x1311)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1312))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((IkReal(-1.00000000000000))*(cj5)*(x1310)*(x1312)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1310)*(x1311)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1310)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
04043     continue;
04044 j3array[0]=IKatan2(((gconst43)*(((((sj5)*(x1311)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1312)))))), ((gconst43)*(((((IkReal(-1.00000000000000))*(cj5)*(x1310)*(x1312)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x1310)*(x1311)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1310)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
04045 sj3array[0]=IKsin(j3array[0]);
04046 cj3array[0]=IKcos(j3array[0]);
04047 if( j3array[0] > IKPI )
04048 {
04049     j3array[0]-=IK2PI;
04050 }
04051 else if( j3array[0] < -IKPI )
04052 {    j3array[0]+=IK2PI;
04053 }
04054 j3valid[0] = true;
04055 for(int ij3 = 0; ij3 < 1; ++ij3)
04056 {
04057 if( !j3valid[ij3] )
04058 {
04059     continue;
04060 }
04061 _ij3[0] = ij3; _ij3[1] = -1;
04062 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
04063 {
04064 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
04065 {
04066     j3valid[iij3]=false; _ij3[1] = iij3; break; 
04067 }
04068 }
04069 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
04070 {
04071 IkReal evalcond[6];
04072 IkReal x1313=IKsin(j3);
04073 IkReal x1314=IKcos(j3);
04074 IkReal x1315=((sj0)*(sj5));
04075 IkReal x1316=((r00)*(sj6));
04076 IkReal x1317=((IkReal(1.00000000000000))*(cj4));
04077 IkReal x1318=((cj6)*(r01));
04078 IkReal x1319=((cj0)*(cj5));
04079 IkReal x1320=((cj5)*(sj0));
04080 IkReal x1321=((cj6)*(r11));
04081 IkReal x1322=((cj0)*(sj5));
04082 IkReal x1323=((cj6)*(sj4));
04083 IkReal x1324=((cj4)*(cj5));
04084 IkReal x1325=((cj6)*(r21));
04085 IkReal x1326=((r20)*(sj6));
04086 IkReal x1327=((r10)*(sj6));
04087 IkReal x1328=((IkReal(1.00000000000000))*(cj0));
04088 IkReal x1329=((IkReal(1.00000000000000))*(x1313));
04089 IkReal x1330=((cj0)*(sj4)*(sj6));
04090 IkReal x1331=((sj0)*(sj4)*(sj6));
04091 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x1325)))+(((sj5)*(x1326)))+(((IkReal(-1.00000000000000))*(cj2)*(x1329))));
04092 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x1324)*(x1325)))+(((r20)*(x1323)))+(((cj2)*(x1314)))+(((cj4)*(r22)*(sj5)))+(((x1324)*(x1326))));
04093 evalcond[2]=((((x1315)*(x1318)))+(((r12)*(x1319)))+(((IkReal(-1.00000000000000))*(x1321)*(x1322)))+(((IkReal(-1.00000000000000))*(sj2)*(x1329)))+(((IkReal(-1.00000000000000))*(x1322)*(x1327)))+(((x1315)*(x1316)))+(((IkReal(-1.00000000000000))*(r02)*(x1320))));
04094 evalcond[3]=((((IkReal(-1.00000000000000))*(x1316)*(x1322)))+(((IkReal(-1.00000000000000))*(x1315)*(x1321)))+(((r12)*(x1320)))+(((IkReal(-1.00000000000000))*(x1314)))+(((IkReal(-1.00000000000000))*(x1318)*(x1322)))+(((IkReal(-1.00000000000000))*(x1315)*(x1327)))+(((r02)*(x1319))));
04095 evalcond[4]=((((cj4)*(r02)*(x1315)))+(((IkReal(-1.00000000000000))*(x1317)*(x1319)*(x1321)))+(((cj4)*(x1316)*(x1320)))+(((r11)*(x1330)))+(((IkReal(-1.00000000000000))*(r12)*(x1317)*(x1322)))+(((IkReal(-1.00000000000000))*(x1317)*(x1319)*(x1327)))+(((cj4)*(x1318)*(x1320)))+(((sj2)*(x1314)))+(((IkReal(-1.00000000000000))*(r01)*(x1331)))+(((IkReal(-1.00000000000000))*(r10)*(x1323)*(x1328)))+(((r00)*(sj0)*(x1323))));
04096 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1323)))+(((IkReal(-1.00000000000000))*(x1317)*(x1320)*(x1327)))+(((IkReal(-1.00000000000000))*(r12)*(x1315)*(x1317)))+(((r11)*(x1331)))+(((IkReal(-1.00000000000000))*(x1317)*(x1320)*(x1321)))+(((r01)*(x1330)))+(((IkReal(-1.00000000000000))*(r02)*(x1317)*(x1322)))+(((IkReal(-1.00000000000000))*(r00)*(x1323)*(x1328)))+(((IkReal(-1.00000000000000))*(x1316)*(x1317)*(x1319)))+(((IkReal(-1.00000000000000))*(x1329)))+(((IkReal(-1.00000000000000))*(x1317)*(x1318)*(x1319))));
04097 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
04098 {
04099 continue;
04100 }
04101 }
04102 
04103 {
04104 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
04105 vinfos[0].jointtype = 1;
04106 vinfos[0].foffset = j0;
04107 vinfos[0].indices[0] = _ij0[0];
04108 vinfos[0].indices[1] = _ij0[1];
04109 vinfos[0].maxsolutions = _nj0;
04110 vinfos[1].jointtype = 1;
04111 vinfos[1].foffset = j1;
04112 vinfos[1].indices[0] = _ij1[0];
04113 vinfos[1].indices[1] = _ij1[1];
04114 vinfos[1].maxsolutions = _nj1;
04115 vinfos[2].jointtype = 1;
04116 vinfos[2].foffset = j2;
04117 vinfos[2].indices[0] = _ij2[0];
04118 vinfos[2].indices[1] = _ij2[1];
04119 vinfos[2].maxsolutions = _nj2;
04120 vinfos[3].jointtype = 1;
04121 vinfos[3].foffset = j3;
04122 vinfos[3].indices[0] = _ij3[0];
04123 vinfos[3].indices[1] = _ij3[1];
04124 vinfos[3].maxsolutions = _nj3;
04125 vinfos[4].jointtype = 1;
04126 vinfos[4].foffset = j4;
04127 vinfos[4].indices[0] = _ij4[0];
04128 vinfos[4].indices[1] = _ij4[1];
04129 vinfos[4].maxsolutions = _nj4;
04130 vinfos[5].jointtype = 1;
04131 vinfos[5].foffset = j5;
04132 vinfos[5].indices[0] = _ij5[0];
04133 vinfos[5].indices[1] = _ij5[1];
04134 vinfos[5].maxsolutions = _nj5;
04135 vinfos[6].jointtype = 1;
04136 vinfos[6].foffset = j6;
04137 vinfos[6].indices[0] = _ij6[0];
04138 vinfos[6].indices[1] = _ij6[1];
04139 vinfos[6].maxsolutions = _nj6;
04140 std::vector<int> vfree(0);
04141 solutions.AddSolution(vinfos,vfree);
04142 }
04143 }
04144 }
04145 
04146 }
04147 
04148 }
04149 }
04150 }
04151 
04152 }
04153 
04154 }
04155 }
04156 }
04157 
04158 } else
04159 {
04160 IkReal x1332=((cj0)*(cj5));
04161 IkReal x1333=((IkReal(0.374290000000000))*(sj0));
04162 IkReal x1334=((cj6)*(r11));
04163 IkReal x1335=((IkReal(0.0100000000000000))*(sj6));
04164 IkReal x1336=((cj6)*(r01));
04165 IkReal x1337=((IkReal(0.0100000000000000))*(sj0));
04166 IkReal x1338=((cj0)*(sj5));
04167 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
04168 evalcond[1]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(sj5)*(x1333)*(x1334)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((cj5)*(x1334)*(x1337)))+(((r00)*(x1332)*(x1335)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(sj6)*(x1333)))+(((IkReal(-0.374290000000000))*(x1336)*(x1338)))+(((IkReal(0.0100000000000000))*(x1332)*(x1336)))+(((cj5)*(r12)*(x1333)))+(((r12)*(sj5)*(x1337)))+(((IkReal(-0.374290000000000))*(r00)*(sj6)*(x1338)))+(((IkReal(0.0100000000000000))*(r02)*(x1338)))+(((IkReal(-1.00000000000000))*(py)*(sj0)))+(((IkReal(0.374290000000000))*(r02)*(x1332)))+(((cj5)*(r10)*(sj0)*(x1335))));
04169 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  )
04170 {
04171 {
04172 IkReal j2array[1], cj2array[1], sj2array[1];
04173 bool j2valid[1]={false};
04174 _nj2 = 1;
04175 IkReal x1339=((cj0)*(r11));
04176 IkReal x1340=((r01)*(sj0));
04177 IkReal x1341=((r20)*(sj6));
04178 IkReal x1342=((IkReal(0.144927536231884))*(cj5));
04179 IkReal x1343=((IkReal(5.42449275362319))*(cj5));
04180 IkReal x1344=((IkReal(5.42449275362319))*(sj5));
04181 IkReal x1345=((IkReal(0.144927536231884))*(sj5));
04182 IkReal x1346=((cj0)*(r12));
04183 IkReal x1347=((r02)*(sj0));
04184 IkReal x1348=((cj6)*(x1344));
04185 IkReal x1349=((cj0)*(r10)*(sj6));
04186 IkReal x1350=((r00)*(sj0)*(sj6));
04187 if( IKabs(((((x1344)*(x1349)))+(((x1342)*(x1350)))+(((x1345)*(x1347)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-1.00000000000000))*(x1344)*(x1350)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((cj6)*(x1340)*(x1342)))+(((IkReal(-1.00000000000000))*(x1342)*(x1349)))+(((IkReal(-1.00000000000000))*(cj6)*(x1339)*(x1342)))+(((IkReal(-1.00000000000000))*(x1345)*(x1346)))+(((x1339)*(x1348)))+(((x1343)*(x1347)))+(((IkReal(-1.00000000000000))*(x1343)*(x1346)))+(((IkReal(-1.00000000000000))*(x1340)*(x1348))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x1341)*(x1344)))+(((IkReal(-1.00000000000000))*(r22)*(x1343)))+(((IkReal(14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x1342)))+(((r21)*(x1348)))+(((IkReal(-1.00000000000000))*(x1341)*(x1342)))+(((IkReal(-1.00000000000000))*(r22)*(x1345))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x1344)*(x1349)))+(((x1342)*(x1350)))+(((x1345)*(x1347)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-1.00000000000000))*(x1344)*(x1350)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((cj6)*(x1340)*(x1342)))+(((IkReal(-1.00000000000000))*(x1342)*(x1349)))+(((IkReal(-1.00000000000000))*(cj6)*(x1339)*(x1342)))+(((IkReal(-1.00000000000000))*(x1345)*(x1346)))+(((x1339)*(x1348)))+(((x1343)*(x1347)))+(((IkReal(-1.00000000000000))*(x1343)*(x1346)))+(((IkReal(-1.00000000000000))*(x1340)*(x1348)))))+IKsqr(((((x1341)*(x1344)))+(((IkReal(-1.00000000000000))*(r22)*(x1343)))+(((IkReal(14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x1342)))+(((r21)*(x1348)))+(((IkReal(-1.00000000000000))*(x1341)*(x1342)))+(((IkReal(-1.00000000000000))*(r22)*(x1345)))))-1) <= IKFAST_SINCOS_THRESH )
04188     continue;
04189 j2array[0]=IKatan2(((((x1344)*(x1349)))+(((x1342)*(x1350)))+(((x1345)*(x1347)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-1.00000000000000))*(x1344)*(x1350)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((cj6)*(x1340)*(x1342)))+(((IkReal(-1.00000000000000))*(x1342)*(x1349)))+(((IkReal(-1.00000000000000))*(cj6)*(x1339)*(x1342)))+(((IkReal(-1.00000000000000))*(x1345)*(x1346)))+(((x1339)*(x1348)))+(((x1343)*(x1347)))+(((IkReal(-1.00000000000000))*(x1343)*(x1346)))+(((IkReal(-1.00000000000000))*(x1340)*(x1348)))), ((((x1341)*(x1344)))+(((IkReal(-1.00000000000000))*(r22)*(x1343)))+(((IkReal(14.4927536231884))*(pz)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x1342)))+(((r21)*(x1348)))+(((IkReal(-1.00000000000000))*(x1341)*(x1342)))+(((IkReal(-1.00000000000000))*(r22)*(x1345)))));
04190 sj2array[0]=IKsin(j2array[0]);
04191 cj2array[0]=IKcos(j2array[0]);
04192 if( j2array[0] > IKPI )
04193 {
04194     j2array[0]-=IK2PI;
04195 }
04196 else if( j2array[0] < -IKPI )
04197 {    j2array[0]+=IK2PI;
04198 }
04199 j2valid[0] = true;
04200 for(int ij2 = 0; ij2 < 1; ++ij2)
04201 {
04202 if( !j2valid[ij2] )
04203 {
04204     continue;
04205 }
04206 _ij2[0] = ij2; _ij2[1] = -1;
04207 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
04208 {
04209 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
04210 {
04211     j2valid[iij2]=false; _ij2[1] = iij2; break; 
04212 }
04213 }
04214 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
04215 {
04216 IkReal evalcond[2];
04217 IkReal x1351=((cj6)*(r11));
04218 IkReal x1352=((IkReal(0.374290000000000))*(sj0));
04219 IkReal x1353=((IkReal(0.0100000000000000))*(cj5));
04220 IkReal x1354=((cj6)*(r21));
04221 IkReal x1355=((r10)*(sj6));
04222 IkReal x1356=((IkReal(0.374290000000000))*(sj5));
04223 IkReal x1357=((IkReal(0.0100000000000000))*(sj5));
04224 IkReal x1358=((cj6)*(r01));
04225 IkReal x1359=((r20)*(sj6));
04226 IkReal x1360=((IkReal(0.374290000000000))*(cj5));
04227 IkReal x1361=((cj0)*(r12));
04228 IkReal x1362=((r00)*(sj6));
04229 IkReal x1363=((cj0)*(x1356));
04230 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x1360)))+(((IkReal(-0.0690000000000000))*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(x1353)*(x1359)))+(((x1356)*(x1359)))+(((IkReal(-1.00000000000000))*(r22)*(x1357)))+(((IkReal(-1.00000000000000))*(x1353)*(x1354)))+(pz)+(((x1354)*(x1356))));
04231 evalcond[1]=((((cj0)*(x1351)*(x1353)))+(((IkReal(-1.00000000000000))*(x1355)*(x1363)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x1352)))+(((IkReal(-1.00000000000000))*(cj0)*(py)))+(((cj0)*(x1353)*(x1355)))+(((IkReal(-1.00000000000000))*(sj0)*(x1353)*(x1358)))+(((IkReal(-1.00000000000000))*(sj0)*(x1353)*(x1362)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1357)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((sj5)*(x1352)*(x1358)))+(((x1357)*(x1361)))+(((x1360)*(x1361)))+(((sj5)*(x1352)*(x1362)))+(((IkReal(-1.00000000000000))*(x1351)*(x1363)))+(((px)*(sj0))));
04232 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04233 {
04234 continue;
04235 }
04236 }
04237 
04238 {
04239 IkReal dummyeval[1];
04240 IkReal gconst53;
04241 IkReal x1364=(cj6)*(cj6);
04242 IkReal x1365=(sj6)*(sj6);
04243 IkReal x1366=((sj5)*(sj6));
04244 IkReal x1367=((IkReal(1.00000000000000))*(cj0));
04245 IkReal x1368=((cj6)*(sj5));
04246 IkReal x1369=((r20)*(sj0));
04247 IkReal x1370=((cj0)*(r20));
04248 IkReal x1371=((r00)*(r21));
04249 IkReal x1372=((r22)*(sj0));
04250 IkReal x1373=((IkReal(1.00000000000000))*(r21)*(sj0));
04251 IkReal x1374=((cj5)*(x1365));
04252 IkReal x1375=((cj5)*(x1364));
04253 gconst53=IKsign(((((r11)*(x1369)*(x1375)))+(((IkReal(-1.00000000000000))*(x1367)*(x1371)*(x1375)))+(((cj0)*(r01)*(r22)*(x1366)))+(((IkReal(-1.00000000000000))*(r10)*(x1373)*(x1374)))+(((r01)*(x1370)*(x1374)))+(((r01)*(x1370)*(x1375)))+(((r11)*(x1366)*(x1372)))+(((r11)*(x1369)*(x1374)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x1367)*(x1368)))+(((IkReal(-1.00000000000000))*(r10)*(x1373)*(x1375)))+(((r12)*(x1368)*(x1369)))+(((r02)*(x1368)*(x1370)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x1366)*(x1367)))+(((IkReal(-1.00000000000000))*(r12)*(x1366)*(x1373)))+(((IkReal(-1.00000000000000))*(r10)*(x1368)*(x1372)))+(((IkReal(-1.00000000000000))*(x1367)*(x1371)*(x1374)))));
04254 IkReal x1376=(cj6)*(cj6);
04255 IkReal x1377=(sj6)*(sj6);
04256 IkReal x1378=((sj5)*(sj6));
04257 IkReal x1379=((IkReal(1.00000000000000))*(cj0));
04258 IkReal x1380=((cj6)*(sj5));
04259 IkReal x1381=((r20)*(sj0));
04260 IkReal x1382=((cj0)*(r20));
04261 IkReal x1383=((r00)*(r21));
04262 IkReal x1384=((r22)*(sj0));
04263 IkReal x1385=((IkReal(1.00000000000000))*(r21)*(sj0));
04264 IkReal x1386=((cj5)*(x1377));
04265 IkReal x1387=((cj5)*(x1376));
04266 dummyeval[0]=((((r01)*(x1382)*(x1386)))+(((IkReal(-1.00000000000000))*(r10)*(x1385)*(x1387)))+(((r02)*(x1380)*(x1382)))+(((IkReal(-1.00000000000000))*(x1379)*(x1383)*(x1387)))+(((cj0)*(r01)*(r22)*(x1378)))+(((r11)*(x1381)*(x1386)))+(((r11)*(x1381)*(x1387)))+(((IkReal(-1.00000000000000))*(r10)*(x1385)*(x1386)))+(((r11)*(x1378)*(x1384)))+(((IkReal(-1.00000000000000))*(r12)*(x1378)*(x1385)))+(((IkReal(-1.00000000000000))*(r10)*(x1380)*(x1384)))+(((r12)*(x1380)*(x1381)))+(((IkReal(-1.00000000000000))*(x1379)*(x1383)*(x1386)))+(((r01)*(x1382)*(x1387)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x1379)*(x1380)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x1378)*(x1379))));
04267 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04268 {
04269 {
04270 IkReal dummyeval[1];
04271 IkReal gconst52;
04272 IkReal x1388=(cj6)*(cj6);
04273 IkReal x1389=(sj6)*(sj6);
04274 IkReal x1390=((IkReal(1.00000000000000))*(r01));
04275 IkReal x1391=((sj0)*(sj5));
04276 IkReal x1392=((cj6)*(r22));
04277 IkReal x1393=((r21)*(sj6));
04278 IkReal x1394=((r00)*(r21));
04279 IkReal x1395=((cj0)*(sj5));
04280 IkReal x1396=((cj6)*(r20));
04281 IkReal x1397=((r22)*(sj6));
04282 IkReal x1398=((cj0)*(cj5));
04283 IkReal x1399=((IkReal(1.00000000000000))*(r10));
04284 IkReal x1400=((cj5)*(sj0));
04285 IkReal x1401=((r20)*(x1389));
04286 IkReal x1402=((x1388)*(x1400));
04287 gconst52=IKsign(((((r11)*(x1395)*(x1397)))+(((r11)*(x1398)*(x1401)))+(((IkReal(-1.00000000000000))*(r12)*(x1393)*(x1395)))+(((IkReal(-1.00000000000000))*(x1390)*(x1391)*(x1397)))+(((r00)*(x1391)*(x1392)))+(((r12)*(x1395)*(x1396)))+(((r02)*(x1391)*(x1393)))+(((x1394)*(x1402)))+(((IkReal(-1.00000000000000))*(x1390)*(x1400)*(x1401)))+(((IkReal(-1.00000000000000))*(r02)*(x1391)*(x1396)))+(((IkReal(-1.00000000000000))*(r21)*(x1388)*(x1398)*(x1399)))+(((IkReal(-1.00000000000000))*(x1392)*(x1395)*(x1399)))+(((IkReal(-1.00000000000000))*(r20)*(x1390)*(x1402)))+(((x1389)*(x1394)*(x1400)))+(((r11)*(r20)*(x1388)*(x1398)))+(((IkReal(-1.00000000000000))*(r21)*(x1389)*(x1398)*(x1399)))));
04288 IkReal x1403=(cj6)*(cj6);
04289 IkReal x1404=(sj6)*(sj6);
04290 IkReal x1405=((IkReal(1.00000000000000))*(r01));
04291 IkReal x1406=((sj0)*(sj5));
04292 IkReal x1407=((cj6)*(r22));
04293 IkReal x1408=((r21)*(sj6));
04294 IkReal x1409=((r00)*(r21));
04295 IkReal x1410=((cj0)*(sj5));
04296 IkReal x1411=((cj6)*(r20));
04297 IkReal x1412=((r22)*(sj6));
04298 IkReal x1413=((cj0)*(cj5));
04299 IkReal x1414=((IkReal(1.00000000000000))*(r10));
04300 IkReal x1415=((cj5)*(sj0));
04301 IkReal x1416=((r20)*(x1404));
04302 IkReal x1417=((x1403)*(x1415));
04303 dummyeval[0]=((((r11)*(r20)*(x1403)*(x1413)))+(((IkReal(-1.00000000000000))*(r12)*(x1408)*(x1410)))+(((IkReal(-1.00000000000000))*(x1407)*(x1410)*(x1414)))+(((r12)*(x1410)*(x1411)))+(((IkReal(-1.00000000000000))*(r21)*(x1403)*(x1413)*(x1414)))+(((x1404)*(x1409)*(x1415)))+(((r11)*(x1413)*(x1416)))+(((r02)*(x1406)*(x1408)))+(((IkReal(-1.00000000000000))*(r20)*(x1405)*(x1417)))+(((r00)*(x1406)*(x1407)))+(((IkReal(-1.00000000000000))*(r21)*(x1404)*(x1413)*(x1414)))+(((IkReal(-1.00000000000000))*(x1405)*(x1406)*(x1412)))+(((IkReal(-1.00000000000000))*(x1405)*(x1415)*(x1416)))+(((x1409)*(x1417)))+(((r11)*(x1410)*(x1412)))+(((IkReal(-1.00000000000000))*(r02)*(x1406)*(x1411))));
04304 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04305 {
04306 {
04307 IkReal dummyeval[1];
04308 dummyeval[0]=cj2;
04309 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04310 {
04311 {
04312 IkReal evalcond[5];
04313 IkReal x1418=((cj5)*(r22));
04314 IkReal x1419=((IkReal(0.374290000000000))*(sj5));
04315 IkReal x1420=((cj0)*(sj6));
04316 IkReal x1421=((cj6)*(r21));
04317 IkReal x1422=((IkReal(0.0100000000000000))*(sj5));
04318 IkReal x1423=((cj0)*(r02));
04319 IkReal x1424=((IkReal(0.0100000000000000))*(cj5));
04320 IkReal x1425=((IkReal(1.00000000000000))*(py));
04321 IkReal x1426=((r01)*(sj0));
04322 IkReal x1427=((r20)*(sj6));
04323 IkReal x1428=((r11)*(sj0));
04324 IkReal x1429=((IkReal(0.374290000000000))*(cj5));
04325 IkReal x1430=((cj0)*(r12));
04326 IkReal x1431=((sj0)*(x1429));
04327 IkReal x1432=((cj6)*(x1424));
04328 IkReal x1433=((r10)*(sj0)*(sj6));
04329 IkReal x1434=((r00)*(sj0)*(sj6));
04330 IkReal x1435=((cj0)*(cj6)*(x1419));
04331 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
04332 evalcond[1]=((((sj5)*(x1421)))+(((sj5)*(x1427)))+(((IkReal(-1.00000000000000))*(x1418))));
04333 evalcond[2]=((((IkReal(-1.00000000000000))*(x1424)*(x1427)))+(((IkReal(-1.00000000000000))*(r22)*(x1422)))+(((IkReal(-1.00000000000000))*(x1421)*(x1424)))+(((x1419)*(x1421)))+(pz)+(((IkReal(-0.374290000000000))*(x1418)))+(((x1419)*(x1427))));
04334 evalcond[3]=((IkReal(0.0690000000000000))+(((cj0)*(r11)*(x1432)))+(((IkReal(-1.00000000000000))*(r11)*(x1435)))+(((IkReal(-1.00000000000000))*(cj0)*(x1425)))+(((r10)*(x1420)*(x1424)))+(((cj6)*(x1419)*(x1426)))+(((IkReal(-1.00000000000000))*(x1426)*(x1432)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1422)))+(((x1422)*(x1430)))+(((IkReal(-1.00000000000000))*(x1424)*(x1434)))+(((x1429)*(x1430)))+(((IkReal(-1.00000000000000))*(r02)*(x1431)))+(((px)*(sj0)))+(((x1419)*(x1434)))+(((IkReal(-1.00000000000000))*(r10)*(x1419)*(x1420))));
04335 evalcond[4]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x1424)*(x1433)))+(((x1422)*(x1423)))+(((x1428)*(x1432)))+(((r12)*(sj0)*(x1422)))+(((x1423)*(x1429)))+(((IkReal(-1.00000000000000))*(r00)*(x1419)*(x1420)))+(((IkReal(-1.00000000000000))*(sj0)*(x1425)))+(((r00)*(x1420)*(x1424)))+(((cj0)*(r01)*(x1432)))+(((r12)*(x1431)))+(((IkReal(-1.00000000000000))*(cj6)*(x1419)*(x1428)))+(((IkReal(-1.00000000000000))*(r01)*(x1435)))+(((IkReal(-1.00000000000000))*(x1419)*(x1433))));
04336 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
04337 {
04338 {
04339 IkReal j3array[1], cj3array[1], sj3array[1];
04340 bool j3valid[1]={false};
04341 _nj3 = 1;
04342 IkReal x1436=((sj0)*(sj5));
04343 IkReal x1437=((r00)*(sj6));
04344 IkReal x1438=((IkReal(1.00000000000000))*(cj5));
04345 IkReal x1439=((cj6)*(r11));
04346 IkReal x1440=((cj6)*(r01));
04347 IkReal x1441=((r10)*(sj6));
04348 IkReal x1442=((cj0)*(sj5));
04349 if( IKabs(((((x1436)*(x1440)))+(((x1436)*(x1437)))+(((IkReal(-1.00000000000000))*(x1441)*(x1442)))+(((IkReal(-1.00000000000000))*(x1439)*(x1442)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1438))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x1440)*(x1442)))+(((x1436)*(x1439)))+(((x1437)*(x1442)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1438)))+(((x1436)*(x1441)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1438))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x1436)*(x1440)))+(((x1436)*(x1437)))+(((IkReal(-1.00000000000000))*(x1441)*(x1442)))+(((IkReal(-1.00000000000000))*(x1439)*(x1442)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1438)))))+IKsqr(((((x1440)*(x1442)))+(((x1436)*(x1439)))+(((x1437)*(x1442)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1438)))+(((x1436)*(x1441)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1438)))))-1) <= IKFAST_SINCOS_THRESH )
04350     continue;
04351 j3array[0]=IKatan2(((((x1436)*(x1440)))+(((x1436)*(x1437)))+(((IkReal(-1.00000000000000))*(x1441)*(x1442)))+(((IkReal(-1.00000000000000))*(x1439)*(x1442)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1438)))), ((((x1440)*(x1442)))+(((x1436)*(x1439)))+(((x1437)*(x1442)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1438)))+(((x1436)*(x1441)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1438)))));
04352 sj3array[0]=IKsin(j3array[0]);
04353 cj3array[0]=IKcos(j3array[0]);
04354 if( j3array[0] > IKPI )
04355 {
04356     j3array[0]-=IK2PI;
04357 }
04358 else if( j3array[0] < -IKPI )
04359 {    j3array[0]+=IK2PI;
04360 }
04361 j3valid[0] = true;
04362 for(int ij3 = 0; ij3 < 1; ++ij3)
04363 {
04364 if( !j3valid[ij3] )
04365 {
04366     continue;
04367 }
04368 _ij3[0] = ij3; _ij3[1] = -1;
04369 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
04370 {
04371 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
04372 {
04373     j3valid[iij3]=false; _ij3[1] = iij3; break; 
04374 }
04375 }
04376 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
04377 {
04378 IkReal evalcond[2];
04379 IkReal x1443=((cj0)*(cj5));
04380 IkReal x1444=((IkReal(1.00000000000000))*(cj0));
04381 IkReal x1445=((cj6)*(r11));
04382 IkReal x1446=((r10)*(sj6));
04383 IkReal x1447=((cj5)*(sj0));
04384 IkReal x1448=((r00)*(sj5)*(sj6));
04385 IkReal x1449=((cj6)*(r01)*(sj5));
04386 IkReal x1450=((IkReal(1.00000000000000))*(sj0)*(sj5));
04387 evalcond[0]=((((IkReal(-1.00000000000000))*(sj5)*(x1444)*(x1445)))+(((IkReal(-1.00000000000000))*(r02)*(x1447)))+(((r12)*(x1443)))+(((sj0)*(x1448)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((sj0)*(x1449)))+(((IkReal(-1.00000000000000))*(sj5)*(x1444)*(x1446))));
04388 evalcond[1]=((((IkReal(-1.00000000000000))*(x1446)*(x1450)))+(((r12)*(x1447)))+(((IkReal(-1.00000000000000))*(x1445)*(x1450)))+(((IkReal(-1.00000000000000))*(x1444)*(x1448)))+(IKcos(j3))+(((r02)*(x1443)))+(((IkReal(-1.00000000000000))*(x1444)*(x1449))));
04389 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04390 {
04391 continue;
04392 }
04393 }
04394 
04395 {
04396 IkReal dummyeval[1];
04397 IkReal gconst59;
04398 IkReal x1451=(r21)*(r21);
04399 IkReal x1452=(cj5)*(cj5);
04400 IkReal x1453=(sj6)*(sj6);
04401 IkReal x1454=(cj6)*(cj6);
04402 IkReal x1455=(r20)*(r20);
04403 IkReal x1456=((cj6)*(r21));
04404 IkReal x1457=((IkReal(2.00000000000000))*(r20)*(sj6));
04405 IkReal x1458=((cj5)*(r22)*(sj5));
04406 IkReal x1459=((IkReal(1.00000000000000))*(x1453));
04407 IkReal x1460=((IkReal(1.00000000000000))*(x1454));
04408 gconst59=IKsign(((((x1456)*(x1457)))+(((IkReal(-1.00000000000000))*(x1455)*(x1460)))+(((IkReal(-1.00000000000000))*(x1457)*(x1458)))+(((IkReal(-1.00000000000000))*(x1451)*(x1452)*(x1460)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x1452)*(x1456)*(x1457)))+(((IkReal(-2.00000000000000))*(x1456)*(x1458)))+(((IkReal(-1.00000000000000))*(x1451)*(x1459)))+(((IkReal(-1.00000000000000))*(x1452)*(x1455)*(x1459)))));
04409 IkReal x1461=(r21)*(r21);
04410 IkReal x1462=(cj5)*(cj5);
04411 IkReal x1463=(sj6)*(sj6);
04412 IkReal x1464=(cj6)*(cj6);
04413 IkReal x1465=(r20)*(r20);
04414 IkReal x1466=((cj6)*(r21));
04415 IkReal x1467=((IkReal(2.00000000000000))*(r20)*(sj6));
04416 IkReal x1468=((cj5)*(r22)*(sj5));
04417 IkReal x1469=((IkReal(1.00000000000000))*(x1463));
04418 IkReal x1470=((IkReal(1.00000000000000))*(x1464));
04419 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1462)*(x1466)*(x1467)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x1461)*(x1462)*(x1470)))+(((IkReal(-2.00000000000000))*(x1466)*(x1468)))+(((IkReal(-1.00000000000000))*(x1462)*(x1465)*(x1469)))+(((IkReal(-1.00000000000000))*(x1467)*(x1468)))+(((IkReal(-1.00000000000000))*(x1465)*(x1470)))+(((IkReal(-1.00000000000000))*(x1461)*(x1469)))+(((x1466)*(x1467))));
04420 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04421 {
04422 {
04423 IkReal dummyeval[1];
04424 IkReal gconst60;
04425 IkReal x1471=(cj6)*(cj6);
04426 IkReal x1472=(sj6)*(sj6);
04427 IkReal x1473=((IkReal(1.00000000000000))*(r01));
04428 IkReal x1474=((sj0)*(sj5));
04429 IkReal x1475=((cj6)*(r22));
04430 IkReal x1476=((r21)*(sj6));
04431 IkReal x1477=((r00)*(r21));
04432 IkReal x1478=((cj0)*(sj5));
04433 IkReal x1479=((cj6)*(r20));
04434 IkReal x1480=((r22)*(sj6));
04435 IkReal x1481=((cj0)*(cj5));
04436 IkReal x1482=((IkReal(1.00000000000000))*(r10));
04437 IkReal x1483=((cj5)*(sj0));
04438 IkReal x1484=((r20)*(x1472));
04439 IkReal x1485=((x1471)*(x1483));
04440 gconst60=IKsign(((((IkReal(-1.00000000000000))*(r12)*(x1476)*(x1478)))+(((IkReal(-1.00000000000000))*(r02)*(x1474)*(x1479)))+(((IkReal(-1.00000000000000))*(x1473)*(x1483)*(x1484)))+(((r02)*(x1474)*(x1476)))+(((IkReal(-1.00000000000000))*(r20)*(x1473)*(x1485)))+(((r11)*(x1478)*(x1480)))+(((r11)*(x1481)*(x1484)))+(((IkReal(-1.00000000000000))*(r21)*(x1472)*(x1481)*(x1482)))+(((r00)*(x1474)*(x1475)))+(((IkReal(-1.00000000000000))*(r21)*(x1471)*(x1481)*(x1482)))+(((x1472)*(x1477)*(x1483)))+(((r12)*(x1478)*(x1479)))+(((r11)*(r20)*(x1471)*(x1481)))+(((IkReal(-1.00000000000000))*(x1475)*(x1478)*(x1482)))+(((IkReal(-1.00000000000000))*(x1473)*(x1474)*(x1480)))+(((x1477)*(x1485)))));
04441 IkReal x1486=(cj6)*(cj6);
04442 IkReal x1487=(sj6)*(sj6);
04443 IkReal x1488=((IkReal(1.00000000000000))*(r01));
04444 IkReal x1489=((sj0)*(sj5));
04445 IkReal x1490=((cj6)*(r22));
04446 IkReal x1491=((r21)*(sj6));
04447 IkReal x1492=((r00)*(r21));
04448 IkReal x1493=((cj0)*(sj5));
04449 IkReal x1494=((cj6)*(r20));
04450 IkReal x1495=((r22)*(sj6));
04451 IkReal x1496=((cj0)*(cj5));
04452 IkReal x1497=((IkReal(1.00000000000000))*(r10));
04453 IkReal x1498=((cj5)*(sj0));
04454 IkReal x1499=((r20)*(x1487));
04455 IkReal x1500=((x1486)*(x1498));
04456 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1488)*(x1489)*(x1495)))+(((IkReal(-1.00000000000000))*(r12)*(x1491)*(x1493)))+(((IkReal(-1.00000000000000))*(x1490)*(x1493)*(x1497)))+(((r12)*(x1493)*(x1494)))+(((r11)*(x1493)*(x1495)))+(((r11)*(r20)*(x1486)*(x1496)))+(((IkReal(-1.00000000000000))*(r20)*(x1488)*(x1500)))+(((IkReal(-1.00000000000000))*(x1488)*(x1498)*(x1499)))+(((x1492)*(x1500)))+(((x1487)*(x1492)*(x1498)))+(((IkReal(-1.00000000000000))*(r21)*(x1486)*(x1496)*(x1497)))+(((r11)*(x1496)*(x1499)))+(((IkReal(-1.00000000000000))*(r02)*(x1489)*(x1494)))+(((r02)*(x1489)*(x1491)))+(((IkReal(-1.00000000000000))*(r21)*(x1487)*(x1496)*(x1497)))+(((r00)*(x1489)*(x1490))));
04457 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04458 {
04459 continue;
04460 
04461 } else
04462 {
04463 {
04464 IkReal j4array[1], cj4array[1], sj4array[1];
04465 bool j4valid[1]={false};
04466 _nj4 = 1;
04467 IkReal x1501=((sj0)*(sj6));
04468 IkReal x1502=((cj0)*(r10));
04469 IkReal x1503=((IkReal(1.00000000000000))*(cj5));
04470 IkReal x1504=((cj6)*(sj0));
04471 IkReal x1505=((cj0)*(r11));
04472 if( IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(sj6)*(x1505)))+(((r01)*(x1501)))+(((cj6)*(x1502)))+(((IkReal(-1.00000000000000))*(r00)*(x1504))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((cj5)*(sj6)*(x1502)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x1505)))+(((IkReal(-1.00000000000000))*(r00)*(x1501)*(x1503)))+(((IkReal(-1.00000000000000))*(r01)*(x1503)*(x1504))))))) < IKFAST_ATAN2_MAGTHRESH )
04473     continue;
04474 j4array[0]=IKatan2(((gconst60)*(((((IkReal(-1.00000000000000))*(sj6)*(x1505)))+(((r01)*(x1501)))+(((cj6)*(x1502)))+(((IkReal(-1.00000000000000))*(r00)*(x1504)))))), ((gconst60)*(((((cj5)*(sj6)*(x1502)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x1505)))+(((IkReal(-1.00000000000000))*(r00)*(x1501)*(x1503)))+(((IkReal(-1.00000000000000))*(r01)*(x1503)*(x1504)))))));
04475 sj4array[0]=IKsin(j4array[0]);
04476 cj4array[0]=IKcos(j4array[0]);
04477 if( j4array[0] > IKPI )
04478 {
04479     j4array[0]-=IK2PI;
04480 }
04481 else if( j4array[0] < -IKPI )
04482 {    j4array[0]+=IK2PI;
04483 }
04484 j4valid[0] = true;
04485 for(int ij4 = 0; ij4 < 1; ++ij4)
04486 {
04487 if( !j4valid[ij4] )
04488 {
04489     continue;
04490 }
04491 _ij4[0] = ij4; _ij4[1] = -1;
04492 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
04493 {
04494 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
04495 {
04496     j4valid[iij4]=false; _ij4[1] = iij4; break; 
04497 }
04498 }
04499 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
04500 {
04501 IkReal evalcond[6];
04502 IkReal x1506=IKsin(j4);
04503 IkReal x1507=IKcos(j4);
04504 IkReal x1508=((r22)*(sj5));
04505 IkReal x1509=((IkReal(1.00000000000000))*(cj6));
04506 IkReal x1510=((IkReal(1.00000000000000))*(cj0));
04507 IkReal x1511=((cj5)*(r11));
04508 IkReal x1512=((cj5)*(cj6));
04509 IkReal x1513=((r11)*(sj6));
04510 IkReal x1514=((IkReal(1.00000000000000))*(sj6));
04511 IkReal x1515=((cj6)*(r00));
04512 IkReal x1516=((r12)*(sj5));
04513 IkReal x1517=((r02)*(sj5));
04514 IkReal x1518=((cj6)*(r10));
04515 IkReal x1519=((cj5)*(sj6));
04516 IkReal x1520=((cj5)*(r01));
04517 IkReal x1521=((sj0)*(x1506));
04518 IkReal x1522=((r00)*(x1519));
04519 IkReal x1523=((cj0)*(x1506));
04520 IkReal x1524=((sj0)*(x1507));
04521 IkReal x1525=((r20)*(x1507));
04522 IkReal x1526=((cj0)*(x1507));
04523 IkReal x1527=((r21)*(x1506));
04524 IkReal x1528=((r21)*(x1507));
04525 IkReal x1529=((r20)*(x1506));
04526 IkReal x1530=((x1507)*(x1516));
04527 IkReal x1531=((r01)*(sj6)*(x1507));
04528 IkReal x1532=((cj5)*(r10)*(x1514));
04529 evalcond[0]=((IkReal(1.00000000000000))+(((x1506)*(x1508)))+(((IkReal(-1.00000000000000))*(x1509)*(x1525)))+(((sj6)*(x1528)))+(((x1519)*(x1529)))+(((x1512)*(x1527))));
04530 evalcond[1]=((((IkReal(-1.00000000000000))*(x1514)*(x1527)))+(((x1507)*(x1508)))+(((x1512)*(x1528)))+(((cj6)*(x1529)))+(((x1519)*(x1525))));
04531 evalcond[2]=((((IkReal(-1.00000000000000))*(x1506)*(x1510)*(x1516)))+(((IkReal(-1.00000000000000))*(r00)*(x1509)*(x1524)))+(((IkReal(-1.00000000000000))*(x1507)*(x1510)*(x1513)))+(((x1518)*(x1526)))+(((x1517)*(x1521)))+(((r01)*(x1512)*(x1521)))+(((r01)*(sj6)*(x1524)))+(((x1521)*(x1522)))+(((IkReal(-1.00000000000000))*(x1509)*(x1511)*(x1523)))+(((IkReal(-1.00000000000000))*(r10)*(x1506)*(x1510)*(x1519))));
04532 evalcond[3]=((((x1517)*(x1524)))+(((IkReal(-1.00000000000000))*(x1510)*(x1530)))+(((IkReal(-1.00000000000000))*(r10)*(x1507)*(x1510)*(x1519)))+(cj3)+(((r01)*(x1512)*(x1524)))+(((x1515)*(x1521)))+(((x1513)*(x1523)))+(((IkReal(-1.00000000000000))*(x1509)*(x1511)*(x1526)))+(((x1522)*(x1524)))+(((IkReal(-1.00000000000000))*(r10)*(x1509)*(x1523)))+(((IkReal(-1.00000000000000))*(r01)*(x1514)*(x1521))));
04533 evalcond[4]=((((IkReal(-1.00000000000000))*(x1506)*(x1510)*(x1517)))+(((IkReal(-1.00000000000000))*(x1509)*(x1511)*(x1521)))+(((IkReal(-1.00000000000000))*(x1506)*(x1510)*(x1522)))+(((x1518)*(x1524)))+(((IkReal(-1.00000000000000))*(x1510)*(x1531)))+(((IkReal(-1.00000000000000))*(x1521)*(x1532)))+(((IkReal(-1.00000000000000))*(x1516)*(x1521)))+(((IkReal(-1.00000000000000))*(x1509)*(x1520)*(x1523)))+(((IkReal(-1.00000000000000))*(x1513)*(x1524)))+(((x1515)*(x1526))));
04534 evalcond[5]=((((IkReal(-1.00000000000000))*(x1509)*(x1511)*(x1524)))+(((r01)*(sj6)*(x1523)))+(((IkReal(-1.00000000000000))*(x1516)*(x1524)))+(sj3)+(((IkReal(-1.00000000000000))*(x1507)*(x1510)*(x1522)))+(((IkReal(-1.00000000000000))*(x1509)*(x1520)*(x1526)))+(((IkReal(-1.00000000000000))*(x1507)*(x1510)*(x1517)))+(((IkReal(-1.00000000000000))*(r00)*(x1509)*(x1523)))+(((IkReal(-1.00000000000000))*(x1524)*(x1532)))+(((x1513)*(x1521)))+(((IkReal(-1.00000000000000))*(r10)*(x1509)*(x1521))));
04535 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
04536 {
04537 continue;
04538 }
04539 }
04540 
04541 {
04542 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
04543 vinfos[0].jointtype = 1;
04544 vinfos[0].foffset = j0;
04545 vinfos[0].indices[0] = _ij0[0];
04546 vinfos[0].indices[1] = _ij0[1];
04547 vinfos[0].maxsolutions = _nj0;
04548 vinfos[1].jointtype = 1;
04549 vinfos[1].foffset = j1;
04550 vinfos[1].indices[0] = _ij1[0];
04551 vinfos[1].indices[1] = _ij1[1];
04552 vinfos[1].maxsolutions = _nj1;
04553 vinfos[2].jointtype = 1;
04554 vinfos[2].foffset = j2;
04555 vinfos[2].indices[0] = _ij2[0];
04556 vinfos[2].indices[1] = _ij2[1];
04557 vinfos[2].maxsolutions = _nj2;
04558 vinfos[3].jointtype = 1;
04559 vinfos[3].foffset = j3;
04560 vinfos[3].indices[0] = _ij3[0];
04561 vinfos[3].indices[1] = _ij3[1];
04562 vinfos[3].maxsolutions = _nj3;
04563 vinfos[4].jointtype = 1;
04564 vinfos[4].foffset = j4;
04565 vinfos[4].indices[0] = _ij4[0];
04566 vinfos[4].indices[1] = _ij4[1];
04567 vinfos[4].maxsolutions = _nj4;
04568 vinfos[5].jointtype = 1;
04569 vinfos[5].foffset = j5;
04570 vinfos[5].indices[0] = _ij5[0];
04571 vinfos[5].indices[1] = _ij5[1];
04572 vinfos[5].maxsolutions = _nj5;
04573 vinfos[6].jointtype = 1;
04574 vinfos[6].foffset = j6;
04575 vinfos[6].indices[0] = _ij6[0];
04576 vinfos[6].indices[1] = _ij6[1];
04577 vinfos[6].maxsolutions = _nj6;
04578 std::vector<int> vfree(0);
04579 solutions.AddSolution(vinfos,vfree);
04580 }
04581 }
04582 }
04583 
04584 }
04585 
04586 }
04587 
04588 } else
04589 {
04590 {
04591 IkReal j4array[1], cj4array[1], sj4array[1];
04592 bool j4valid[1]={false};
04593 _nj4 = 1;
04594 if( IKabs(((gconst59)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
04595     continue;
04596 j4array[0]=IKatan2(((gconst59)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst59)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
04597 sj4array[0]=IKsin(j4array[0]);
04598 cj4array[0]=IKcos(j4array[0]);
04599 if( j4array[0] > IKPI )
04600 {
04601     j4array[0]-=IK2PI;
04602 }
04603 else if( j4array[0] < -IKPI )
04604 {    j4array[0]+=IK2PI;
04605 }
04606 j4valid[0] = true;
04607 for(int ij4 = 0; ij4 < 1; ++ij4)
04608 {
04609 if( !j4valid[ij4] )
04610 {
04611     continue;
04612 }
04613 _ij4[0] = ij4; _ij4[1] = -1;
04614 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
04615 {
04616 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
04617 {
04618     j4valid[iij4]=false; _ij4[1] = iij4; break; 
04619 }
04620 }
04621 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
04622 {
04623 IkReal evalcond[6];
04624 IkReal x1533=IKsin(j4);
04625 IkReal x1534=IKcos(j4);
04626 IkReal x1535=((r22)*(sj5));
04627 IkReal x1536=((IkReal(1.00000000000000))*(cj6));
04628 IkReal x1537=((IkReal(1.00000000000000))*(cj0));
04629 IkReal x1538=((cj5)*(r11));
04630 IkReal x1539=((cj5)*(cj6));
04631 IkReal x1540=((r11)*(sj6));
04632 IkReal x1541=((IkReal(1.00000000000000))*(sj6));
04633 IkReal x1542=((cj6)*(r00));
04634 IkReal x1543=((r12)*(sj5));
04635 IkReal x1544=((r02)*(sj5));
04636 IkReal x1545=((cj6)*(r10));
04637 IkReal x1546=((cj5)*(sj6));
04638 IkReal x1547=((cj5)*(r01));
04639 IkReal x1548=((sj0)*(x1533));
04640 IkReal x1549=((r00)*(x1546));
04641 IkReal x1550=((cj0)*(x1533));
04642 IkReal x1551=((sj0)*(x1534));
04643 IkReal x1552=((r20)*(x1534));
04644 IkReal x1553=((cj0)*(x1534));
04645 IkReal x1554=((r21)*(x1533));
04646 IkReal x1555=((r21)*(x1534));
04647 IkReal x1556=((r20)*(x1533));
04648 IkReal x1557=((x1534)*(x1543));
04649 IkReal x1558=((r01)*(sj6)*(x1534));
04650 IkReal x1559=((cj5)*(r10)*(x1541));
04651 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1536)*(x1552)))+(((x1546)*(x1556)))+(((x1533)*(x1535)))+(((x1539)*(x1554)))+(((sj6)*(x1555))));
04652 evalcond[1]=((((cj6)*(x1556)))+(((x1534)*(x1535)))+(((x1546)*(x1552)))+(((x1539)*(x1555)))+(((IkReal(-1.00000000000000))*(x1541)*(x1554))));
04653 evalcond[2]=((((IkReal(-1.00000000000000))*(x1536)*(x1538)*(x1550)))+(((IkReal(-1.00000000000000))*(x1533)*(x1537)*(x1543)))+(((x1544)*(x1548)))+(((IkReal(-1.00000000000000))*(r10)*(x1533)*(x1537)*(x1546)))+(((IkReal(-1.00000000000000))*(x1534)*(x1537)*(x1540)))+(((r01)*(sj6)*(x1551)))+(((x1548)*(x1549)))+(((r01)*(x1539)*(x1548)))+(((x1545)*(x1553)))+(((IkReal(-1.00000000000000))*(r00)*(x1536)*(x1551))));
04654 evalcond[3]=((((x1540)*(x1550)))+(((x1542)*(x1548)))+(((IkReal(-1.00000000000000))*(r10)*(x1536)*(x1550)))+(((r01)*(x1539)*(x1551)))+(((x1544)*(x1551)))+(((IkReal(-1.00000000000000))*(x1537)*(x1557)))+(((IkReal(-1.00000000000000))*(r01)*(x1541)*(x1548)))+(((IkReal(-1.00000000000000))*(r10)*(x1534)*(x1537)*(x1546)))+(cj3)+(((x1549)*(x1551)))+(((IkReal(-1.00000000000000))*(x1536)*(x1538)*(x1553))));
04655 evalcond[4]=((((IkReal(-1.00000000000000))*(x1540)*(x1551)))+(((x1542)*(x1553)))+(((IkReal(-1.00000000000000))*(x1536)*(x1538)*(x1548)))+(((IkReal(-1.00000000000000))*(x1533)*(x1537)*(x1544)))+(((IkReal(-1.00000000000000))*(x1533)*(x1537)*(x1549)))+(((IkReal(-1.00000000000000))*(x1536)*(x1547)*(x1550)))+(((IkReal(-1.00000000000000))*(x1543)*(x1548)))+(((IkReal(-1.00000000000000))*(x1548)*(x1559)))+(((x1545)*(x1551)))+(((IkReal(-1.00000000000000))*(x1537)*(x1558))));
04656 evalcond[5]=((((IkReal(-1.00000000000000))*(x1536)*(x1547)*(x1553)))+(((x1540)*(x1548)))+(((r01)*(sj6)*(x1550)))+(((IkReal(-1.00000000000000))*(r00)*(x1536)*(x1550)))+(sj3)+(((IkReal(-1.00000000000000))*(x1536)*(x1538)*(x1551)))+(((IkReal(-1.00000000000000))*(r10)*(x1536)*(x1548)))+(((IkReal(-1.00000000000000))*(x1551)*(x1559)))+(((IkReal(-1.00000000000000))*(x1534)*(x1537)*(x1544)))+(((IkReal(-1.00000000000000))*(x1534)*(x1537)*(x1549)))+(((IkReal(-1.00000000000000))*(x1543)*(x1551))));
04657 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
04658 {
04659 continue;
04660 }
04661 }
04662 
04663 {
04664 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
04665 vinfos[0].jointtype = 1;
04666 vinfos[0].foffset = j0;
04667 vinfos[0].indices[0] = _ij0[0];
04668 vinfos[0].indices[1] = _ij0[1];
04669 vinfos[0].maxsolutions = _nj0;
04670 vinfos[1].jointtype = 1;
04671 vinfos[1].foffset = j1;
04672 vinfos[1].indices[0] = _ij1[0];
04673 vinfos[1].indices[1] = _ij1[1];
04674 vinfos[1].maxsolutions = _nj1;
04675 vinfos[2].jointtype = 1;
04676 vinfos[2].foffset = j2;
04677 vinfos[2].indices[0] = _ij2[0];
04678 vinfos[2].indices[1] = _ij2[1];
04679 vinfos[2].maxsolutions = _nj2;
04680 vinfos[3].jointtype = 1;
04681 vinfos[3].foffset = j3;
04682 vinfos[3].indices[0] = _ij3[0];
04683 vinfos[3].indices[1] = _ij3[1];
04684 vinfos[3].maxsolutions = _nj3;
04685 vinfos[4].jointtype = 1;
04686 vinfos[4].foffset = j4;
04687 vinfos[4].indices[0] = _ij4[0];
04688 vinfos[4].indices[1] = _ij4[1];
04689 vinfos[4].maxsolutions = _nj4;
04690 vinfos[5].jointtype = 1;
04691 vinfos[5].foffset = j5;
04692 vinfos[5].indices[0] = _ij5[0];
04693 vinfos[5].indices[1] = _ij5[1];
04694 vinfos[5].maxsolutions = _nj5;
04695 vinfos[6].jointtype = 1;
04696 vinfos[6].foffset = j6;
04697 vinfos[6].indices[0] = _ij6[0];
04698 vinfos[6].indices[1] = _ij6[1];
04699 vinfos[6].maxsolutions = _nj6;
04700 std::vector<int> vfree(0);
04701 solutions.AddSolution(vinfos,vfree);
04702 }
04703 }
04704 }
04705 
04706 }
04707 
04708 }
04709 }
04710 }
04711 
04712 } else
04713 {
04714 IkReal x1560=((cj5)*(r22));
04715 IkReal x1561=((IkReal(0.374290000000000))*(sj5));
04716 IkReal x1562=((cj0)*(sj6));
04717 IkReal x1563=((cj6)*(r21));
04718 IkReal x1564=((IkReal(0.0100000000000000))*(sj5));
04719 IkReal x1565=((cj0)*(r02));
04720 IkReal x1566=((IkReal(0.0100000000000000))*(cj5));
04721 IkReal x1567=((IkReal(1.00000000000000))*(py));
04722 IkReal x1568=((r01)*(sj0));
04723 IkReal x1569=((r20)*(sj6));
04724 IkReal x1570=((r11)*(sj0));
04725 IkReal x1571=((IkReal(0.374290000000000))*(cj5));
04726 IkReal x1572=((cj0)*(r12));
04727 IkReal x1573=((sj0)*(x1571));
04728 IkReal x1574=((cj6)*(x1566));
04729 IkReal x1575=((r10)*(sj0)*(sj6));
04730 IkReal x1576=((r00)*(sj0)*(sj6));
04731 IkReal x1577=((cj0)*(cj6)*(x1561));
04732 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
04733 evalcond[1]=((((IkReal(-1.00000000000000))*(x1560)))+(((sj5)*(x1569)))+(((sj5)*(x1563))));
04734 evalcond[2]=((((IkReal(-1.00000000000000))*(x1566)*(x1569)))+(((x1561)*(x1563)))+(((IkReal(-1.00000000000000))*(r22)*(x1564)))+(pz)+(((x1561)*(x1569)))+(((IkReal(-1.00000000000000))*(x1563)*(x1566)))+(((IkReal(-0.374290000000000))*(x1560))));
04735 evalcond[3]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x1566)*(x1576)))+(((IkReal(-1.00000000000000))*(r11)*(x1577)))+(((x1571)*(x1572)))+(((r10)*(x1562)*(x1566)))+(((x1561)*(x1576)))+(((IkReal(-1.00000000000000))*(cj0)*(x1567)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1564)))+(((cj6)*(x1561)*(x1568)))+(((IkReal(-1.00000000000000))*(x1568)*(x1574)))+(((px)*(sj0)))+(((cj0)*(r11)*(x1574)))+(((x1564)*(x1572)))+(((IkReal(-1.00000000000000))*(r02)*(x1573)))+(((IkReal(-1.00000000000000))*(r10)*(x1561)*(x1562))));
04736 evalcond[4]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(r00)*(x1561)*(x1562)))+(((cj0)*(r01)*(x1574)))+(((x1565)*(x1571)))+(((IkReal(-1.00000000000000))*(sj0)*(x1567)))+(((x1570)*(x1574)))+(((r12)*(sj0)*(x1564)))+(((x1564)*(x1565)))+(((r12)*(x1573)))+(((IkReal(-1.00000000000000))*(x1561)*(x1575)))+(((IkReal(-1.00000000000000))*(cj6)*(x1561)*(x1570)))+(((r00)*(x1562)*(x1566)))+(((x1566)*(x1575)))+(((IkReal(-1.00000000000000))*(r01)*(x1577))));
04737 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
04738 {
04739 {
04740 IkReal j3array[1], cj3array[1], sj3array[1];
04741 bool j3valid[1]={false};
04742 _nj3 = 1;
04743 IkReal x1578=((IkReal(1.00000000000000))*(cj5));
04744 IkReal x1579=((r10)*(sj5)*(sj6));
04745 IkReal x1580=((cj6)*(sj0)*(sj5));
04746 IkReal x1581=((r00)*(sj5)*(sj6));
04747 IkReal x1582=((cj0)*(cj6)*(sj5));
04748 if( IKabs(((((cj0)*(x1579)))+(((IkReal(-1.00000000000000))*(sj0)*(x1581)))+(((IkReal(-1.00000000000000))*(r01)*(x1580)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x1582)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x1578))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1578)))+(((sj0)*(x1579)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1578)))+(((r11)*(x1580)))+(((r01)*(x1582)))+(((cj0)*(x1581))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(x1579)))+(((IkReal(-1.00000000000000))*(sj0)*(x1581)))+(((IkReal(-1.00000000000000))*(r01)*(x1580)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x1582)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x1578)))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1578)))+(((sj0)*(x1579)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1578)))+(((r11)*(x1580)))+(((r01)*(x1582)))+(((cj0)*(x1581)))))-1) <= IKFAST_SINCOS_THRESH )
04749     continue;
04750 j3array[0]=IKatan2(((((cj0)*(x1579)))+(((IkReal(-1.00000000000000))*(sj0)*(x1581)))+(((IkReal(-1.00000000000000))*(r01)*(x1580)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x1582)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x1578)))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1578)))+(((sj0)*(x1579)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1578)))+(((r11)*(x1580)))+(((r01)*(x1582)))+(((cj0)*(x1581)))));
04751 sj3array[0]=IKsin(j3array[0]);
04752 cj3array[0]=IKcos(j3array[0]);
04753 if( j3array[0] > IKPI )
04754 {
04755     j3array[0]-=IK2PI;
04756 }
04757 else if( j3array[0] < -IKPI )
04758 {    j3array[0]+=IK2PI;
04759 }
04760 j3valid[0] = true;
04761 for(int ij3 = 0; ij3 < 1; ++ij3)
04762 {
04763 if( !j3valid[ij3] )
04764 {
04765     continue;
04766 }
04767 _ij3[0] = ij3; _ij3[1] = -1;
04768 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
04769 {
04770 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
04771 {
04772     j3valid[iij3]=false; _ij3[1] = iij3; break; 
04773 }
04774 }
04775 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
04776 {
04777 IkReal evalcond[2];
04778 IkReal x1583=((cj0)*(cj5));
04779 IkReal x1584=((IkReal(1.00000000000000))*(cj0));
04780 IkReal x1585=((cj6)*(r11));
04781 IkReal x1586=((r10)*(sj6));
04782 IkReal x1587=((cj5)*(sj0));
04783 IkReal x1588=((r00)*(sj5)*(sj6));
04784 IkReal x1589=((cj6)*(r01)*(sj5));
04785 IkReal x1590=((IkReal(1.00000000000000))*(sj0)*(sj5));
04786 evalcond[0]=((((IkReal(-1.00000000000000))*(sj5)*(x1584)*(x1585)))+(((IkReal(-1.00000000000000))*(r02)*(x1587)))+(((r12)*(x1583)))+(((sj0)*(x1588)))+(IKsin(j3))+(((sj0)*(x1589)))+(((IkReal(-1.00000000000000))*(sj5)*(x1584)*(x1586))));
04787 evalcond[1]=((((IkReal(-1.00000000000000))*(x1584)*(x1589)))+(((r02)*(x1583)))+(((IkReal(-1.00000000000000))*(x1585)*(x1590)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x1586)*(x1590)))+(((IkReal(-1.00000000000000))*(x1584)*(x1588)))+(((r12)*(x1587))));
04788 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04789 {
04790 continue;
04791 }
04792 }
04793 
04794 {
04795 IkReal dummyeval[1];
04796 IkReal gconst63;
04797 IkReal x1591=(cj5)*(cj5);
04798 IkReal x1592=(r20)*(r20);
04799 IkReal x1593=(sj6)*(sj6);
04800 IkReal x1594=(cj6)*(cj6);
04801 IkReal x1595=(r21)*(r21);
04802 IkReal x1596=((cj6)*(r21));
04803 IkReal x1597=((IkReal(2.00000000000000))*(r20)*(sj6));
04804 IkReal x1598=((cj5)*(r22)*(sj5));
04805 gconst63=IKsign(((((x1592)*(x1594)))+(((x1593)*(x1595)))+(((IkReal(-1.00000000000000))*(x1596)*(x1597)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x1591)*(x1594)*(x1595)))+(((x1591)*(x1592)*(x1593)))+(((IkReal(2.00000000000000))*(x1596)*(x1598)))+(((x1597)*(x1598)))+(((x1591)*(x1596)*(x1597)))));
04806 IkReal x1599=(cj5)*(cj5);
04807 IkReal x1600=(r20)*(r20);
04808 IkReal x1601=(sj6)*(sj6);
04809 IkReal x1602=(cj6)*(cj6);
04810 IkReal x1603=(r21)*(r21);
04811 IkReal x1604=((cj6)*(r21));
04812 IkReal x1605=((IkReal(2.00000000000000))*(r20)*(sj6));
04813 IkReal x1606=((cj5)*(r22)*(sj5));
04814 dummyeval[0]=((((x1601)*(x1603)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x1600)*(x1602)))+(((IkReal(2.00000000000000))*(x1604)*(x1606)))+(((x1605)*(x1606)))+(((x1599)*(x1604)*(x1605)))+(((x1599)*(x1600)*(x1601)))+(((x1599)*(x1602)*(x1603)))+(((IkReal(-1.00000000000000))*(x1604)*(x1605))));
04815 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04816 {
04817 {
04818 IkReal dummyeval[1];
04819 IkReal gconst64;
04820 IkReal x1607=(cj6)*(cj6);
04821 IkReal x1608=(sj6)*(sj6);
04822 IkReal x1609=((IkReal(1.00000000000000))*(r21));
04823 IkReal x1610=((cj6)*(r20));
04824 IkReal x1611=((r22)*(sj5));
04825 IkReal x1612=((r01)*(sj0));
04826 IkReal x1613=((r00)*(sj0));
04827 IkReal x1614=((cj0)*(r10));
04828 IkReal x1615=((r02)*(sj0)*(sj5));
04829 IkReal x1616=((cj5)*(x1607));
04830 IkReal x1617=((cj0)*(r12)*(sj5));
04831 IkReal x1618=((IkReal(1.00000000000000))*(cj0)*(r11));
04832 IkReal x1619=((cj5)*(x1608));
04833 IkReal x1620=((r20)*(x1619));
04834 gconst64=IKsign(((((IkReal(-1.00000000000000))*(x1609)*(x1613)*(x1619)))+(((cj6)*(x1611)*(x1614)))+(((r21)*(x1614)*(x1619)))+(((IkReal(-1.00000000000000))*(x1609)*(x1613)*(x1616)))+(((IkReal(-1.00000000000000))*(x1610)*(x1617)))+(((IkReal(-1.00000000000000))*(r20)*(x1616)*(x1618)))+(((IkReal(-1.00000000000000))*(x1618)*(x1620)))+(((IkReal(-1.00000000000000))*(cj6)*(x1611)*(x1613)))+(((sj6)*(x1611)*(x1612)))+(((r21)*(x1614)*(x1616)))+(((r21)*(sj6)*(x1617)))+(((IkReal(-1.00000000000000))*(sj6)*(x1611)*(x1618)))+(((IkReal(-1.00000000000000))*(sj6)*(x1609)*(x1615)))+(((r20)*(x1612)*(x1616)))+(((x1610)*(x1615)))+(((x1612)*(x1620)))));
04835 IkReal x1621=(cj6)*(cj6);
04836 IkReal x1622=(sj6)*(sj6);
04837 IkReal x1623=((IkReal(1.00000000000000))*(r21));
04838 IkReal x1624=((cj6)*(r20));
04839 IkReal x1625=((r22)*(sj5));
04840 IkReal x1626=((r01)*(sj0));
04841 IkReal x1627=((r00)*(sj0));
04842 IkReal x1628=((cj0)*(r10));
04843 IkReal x1629=((r02)*(sj0)*(sj5));
04844 IkReal x1630=((cj5)*(x1621));
04845 IkReal x1631=((cj0)*(r12)*(sj5));
04846 IkReal x1632=((IkReal(1.00000000000000))*(cj0)*(r11));
04847 IkReal x1633=((cj5)*(x1622));
04848 IkReal x1634=((r20)*(x1633));
04849 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1623)*(x1627)*(x1630)))+(((IkReal(-1.00000000000000))*(r20)*(x1630)*(x1632)))+(((sj6)*(x1625)*(x1626)))+(((IkReal(-1.00000000000000))*(x1624)*(x1631)))+(((IkReal(-1.00000000000000))*(sj6)*(x1625)*(x1632)))+(((r21)*(x1628)*(x1633)))+(((x1626)*(x1634)))+(((IkReal(-1.00000000000000))*(x1632)*(x1634)))+(((cj6)*(x1625)*(x1628)))+(((x1624)*(x1629)))+(((r21)*(sj6)*(x1631)))+(((r20)*(x1626)*(x1630)))+(((r21)*(x1628)*(x1630)))+(((IkReal(-1.00000000000000))*(cj6)*(x1625)*(x1627)))+(((IkReal(-1.00000000000000))*(x1623)*(x1627)*(x1633)))+(((IkReal(-1.00000000000000))*(sj6)*(x1623)*(x1629))));
04850 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04851 {
04852 continue;
04853 
04854 } else
04855 {
04856 {
04857 IkReal j4array[1], cj4array[1], sj4array[1];
04858 bool j4valid[1]={false};
04859 _nj4 = 1;
04860 IkReal x1635=((sj0)*(sj6));
04861 IkReal x1636=((cj0)*(r10));
04862 IkReal x1637=((IkReal(1.00000000000000))*(cj5));
04863 IkReal x1638=((cj6)*(sj0));
04864 IkReal x1639=((cj0)*(r11));
04865 if( IKabs(((gconst64)*(((((IkReal(-1.00000000000000))*(sj6)*(x1639)))+(((cj6)*(x1636)))+(((IkReal(-1.00000000000000))*(r00)*(x1638)))+(((r01)*(x1635))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst64)*(((((cj5)*(cj6)*(x1639)))+(((cj5)*(sj6)*(x1636)))+(((IkReal(-1.00000000000000))*(r01)*(x1637)*(x1638)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x1635)*(x1637)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
04866     continue;
04867 j4array[0]=IKatan2(((gconst64)*(((((IkReal(-1.00000000000000))*(sj6)*(x1639)))+(((cj6)*(x1636)))+(((IkReal(-1.00000000000000))*(r00)*(x1638)))+(((r01)*(x1635)))))), ((gconst64)*(((((cj5)*(cj6)*(x1639)))+(((cj5)*(sj6)*(x1636)))+(((IkReal(-1.00000000000000))*(r01)*(x1637)*(x1638)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x1635)*(x1637)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))))));
04868 sj4array[0]=IKsin(j4array[0]);
04869 cj4array[0]=IKcos(j4array[0]);
04870 if( j4array[0] > IKPI )
04871 {
04872     j4array[0]-=IK2PI;
04873 }
04874 else if( j4array[0] < -IKPI )
04875 {    j4array[0]+=IK2PI;
04876 }
04877 j4valid[0] = true;
04878 for(int ij4 = 0; ij4 < 1; ++ij4)
04879 {
04880 if( !j4valid[ij4] )
04881 {
04882     continue;
04883 }
04884 _ij4[0] = ij4; _ij4[1] = -1;
04885 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
04886 {
04887 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
04888 {
04889     j4valid[iij4]=false; _ij4[1] = iij4; break; 
04890 }
04891 }
04892 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
04893 {
04894 IkReal evalcond[6];
04895 IkReal x1640=IKsin(j4);
04896 IkReal x1641=IKcos(j4);
04897 IkReal x1642=((r22)*(sj5));
04898 IkReal x1643=((IkReal(1.00000000000000))*(cj6));
04899 IkReal x1644=((IkReal(1.00000000000000))*(cj0));
04900 IkReal x1645=((cj5)*(r11));
04901 IkReal x1646=((cj5)*(cj6));
04902 IkReal x1647=((r11)*(sj6));
04903 IkReal x1648=((IkReal(1.00000000000000))*(sj6));
04904 IkReal x1649=((cj6)*(r00));
04905 IkReal x1650=((r12)*(sj5));
04906 IkReal x1651=((r02)*(sj5));
04907 IkReal x1652=((cj6)*(r10));
04908 IkReal x1653=((cj5)*(sj6));
04909 IkReal x1654=((cj5)*(r01));
04910 IkReal x1655=((sj0)*(x1640));
04911 IkReal x1656=((r00)*(x1653));
04912 IkReal x1657=((cj0)*(x1640));
04913 IkReal x1658=((sj0)*(x1641));
04914 IkReal x1659=((r20)*(x1641));
04915 IkReal x1660=((cj0)*(x1641));
04916 IkReal x1661=((r21)*(x1640));
04917 IkReal x1662=((r21)*(x1641));
04918 IkReal x1663=((r20)*(x1640));
04919 IkReal x1664=((x1641)*(x1650));
04920 IkReal x1665=((r01)*(sj6)*(x1641));
04921 IkReal x1666=((cj5)*(r10)*(x1648));
04922 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1643)*(x1659)))+(((x1646)*(x1661)))+(((x1640)*(x1642)))+(((sj6)*(x1662)))+(((x1653)*(x1663))));
04923 evalcond[1]=((((IkReal(-1.00000000000000))*(x1648)*(x1661)))+(((x1641)*(x1642)))+(((x1653)*(x1659)))+(((x1646)*(x1662)))+(((cj6)*(x1663))));
04924 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x1640)*(x1644)*(x1653)))+(((r01)*(sj6)*(x1658)))+(((x1651)*(x1655)))+(((r01)*(x1646)*(x1655)))+(((x1652)*(x1660)))+(((IkReal(-1.00000000000000))*(x1640)*(x1644)*(x1650)))+(((IkReal(-1.00000000000000))*(x1643)*(x1645)*(x1657)))+(((IkReal(-1.00000000000000))*(x1641)*(x1644)*(x1647)))+(((x1655)*(x1656)))+(((IkReal(-1.00000000000000))*(r00)*(x1643)*(x1658))));
04925 evalcond[3]=((((x1649)*(x1655)))+(((x1656)*(x1658)))+(((IkReal(-1.00000000000000))*(r01)*(x1648)*(x1655)))+(((IkReal(-1.00000000000000))*(r10)*(x1641)*(x1644)*(x1653)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1644)*(x1664)))+(((x1651)*(x1658)))+(((x1647)*(x1657)))+(((r01)*(x1646)*(x1658)))+(((IkReal(-1.00000000000000))*(r10)*(x1643)*(x1657)))+(((IkReal(-1.00000000000000))*(x1643)*(x1645)*(x1660))));
04926 evalcond[4]=((((IkReal(-1.00000000000000))*(x1644)*(x1665)))+(((IkReal(-1.00000000000000))*(x1640)*(x1644)*(x1656)))+(((IkReal(-1.00000000000000))*(x1643)*(x1654)*(x1657)))+(((IkReal(-1.00000000000000))*(x1643)*(x1645)*(x1655)))+(((IkReal(-1.00000000000000))*(x1655)*(x1666)))+(((x1649)*(x1660)))+(((x1652)*(x1658)))+(((IkReal(-1.00000000000000))*(x1640)*(x1644)*(x1651)))+(((IkReal(-1.00000000000000))*(x1650)*(x1655)))+(((IkReal(-1.00000000000000))*(x1647)*(x1658))));
04927 evalcond[5]=((((IkReal(-1.00000000000000))*(x1643)*(x1645)*(x1658)))+(sj3)+(((x1647)*(x1655)))+(((IkReal(-1.00000000000000))*(x1658)*(x1666)))+(((IkReal(-1.00000000000000))*(x1641)*(x1644)*(x1651)))+(((IkReal(-1.00000000000000))*(r00)*(x1643)*(x1657)))+(((IkReal(-1.00000000000000))*(r10)*(x1643)*(x1655)))+(((IkReal(-1.00000000000000))*(x1641)*(x1644)*(x1656)))+(((IkReal(-1.00000000000000))*(x1650)*(x1658)))+(((IkReal(-1.00000000000000))*(x1643)*(x1654)*(x1660)))+(((r01)*(sj6)*(x1657))));
04928 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
04929 {
04930 continue;
04931 }
04932 }
04933 
04934 {
04935 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
04936 vinfos[0].jointtype = 1;
04937 vinfos[0].foffset = j0;
04938 vinfos[0].indices[0] = _ij0[0];
04939 vinfos[0].indices[1] = _ij0[1];
04940 vinfos[0].maxsolutions = _nj0;
04941 vinfos[1].jointtype = 1;
04942 vinfos[1].foffset = j1;
04943 vinfos[1].indices[0] = _ij1[0];
04944 vinfos[1].indices[1] = _ij1[1];
04945 vinfos[1].maxsolutions = _nj1;
04946 vinfos[2].jointtype = 1;
04947 vinfos[2].foffset = j2;
04948 vinfos[2].indices[0] = _ij2[0];
04949 vinfos[2].indices[1] = _ij2[1];
04950 vinfos[2].maxsolutions = _nj2;
04951 vinfos[3].jointtype = 1;
04952 vinfos[3].foffset = j3;
04953 vinfos[3].indices[0] = _ij3[0];
04954 vinfos[3].indices[1] = _ij3[1];
04955 vinfos[3].maxsolutions = _nj3;
04956 vinfos[4].jointtype = 1;
04957 vinfos[4].foffset = j4;
04958 vinfos[4].indices[0] = _ij4[0];
04959 vinfos[4].indices[1] = _ij4[1];
04960 vinfos[4].maxsolutions = _nj4;
04961 vinfos[5].jointtype = 1;
04962 vinfos[5].foffset = j5;
04963 vinfos[5].indices[0] = _ij5[0];
04964 vinfos[5].indices[1] = _ij5[1];
04965 vinfos[5].maxsolutions = _nj5;
04966 vinfos[6].jointtype = 1;
04967 vinfos[6].foffset = j6;
04968 vinfos[6].indices[0] = _ij6[0];
04969 vinfos[6].indices[1] = _ij6[1];
04970 vinfos[6].maxsolutions = _nj6;
04971 std::vector<int> vfree(0);
04972 solutions.AddSolution(vinfos,vfree);
04973 }
04974 }
04975 }
04976 
04977 }
04978 
04979 }
04980 
04981 } else
04982 {
04983 {
04984 IkReal j4array[1], cj4array[1], sj4array[1];
04985 bool j4valid[1]={false};
04986 _nj4 = 1;
04987 if( IKabs(((gconst63)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst63)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
04988     continue;
04989 j4array[0]=IKatan2(((gconst63)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst63)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
04990 sj4array[0]=IKsin(j4array[0]);
04991 cj4array[0]=IKcos(j4array[0]);
04992 if( j4array[0] > IKPI )
04993 {
04994     j4array[0]-=IK2PI;
04995 }
04996 else if( j4array[0] < -IKPI )
04997 {    j4array[0]+=IK2PI;
04998 }
04999 j4valid[0] = true;
05000 for(int ij4 = 0; ij4 < 1; ++ij4)
05001 {
05002 if( !j4valid[ij4] )
05003 {
05004     continue;
05005 }
05006 _ij4[0] = ij4; _ij4[1] = -1;
05007 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
05008 {
05009 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
05010 {
05011     j4valid[iij4]=false; _ij4[1] = iij4; break; 
05012 }
05013 }
05014 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
05015 {
05016 IkReal evalcond[6];
05017 IkReal x1667=IKsin(j4);
05018 IkReal x1668=IKcos(j4);
05019 IkReal x1669=((r22)*(sj5));
05020 IkReal x1670=((IkReal(1.00000000000000))*(cj6));
05021 IkReal x1671=((IkReal(1.00000000000000))*(cj0));
05022 IkReal x1672=((cj5)*(r11));
05023 IkReal x1673=((cj5)*(cj6));
05024 IkReal x1674=((r11)*(sj6));
05025 IkReal x1675=((IkReal(1.00000000000000))*(sj6));
05026 IkReal x1676=((cj6)*(r00));
05027 IkReal x1677=((r12)*(sj5));
05028 IkReal x1678=((r02)*(sj5));
05029 IkReal x1679=((cj6)*(r10));
05030 IkReal x1680=((cj5)*(sj6));
05031 IkReal x1681=((cj5)*(r01));
05032 IkReal x1682=((sj0)*(x1667));
05033 IkReal x1683=((r00)*(x1680));
05034 IkReal x1684=((cj0)*(x1667));
05035 IkReal x1685=((sj0)*(x1668));
05036 IkReal x1686=((r20)*(x1668));
05037 IkReal x1687=((cj0)*(x1668));
05038 IkReal x1688=((r21)*(x1667));
05039 IkReal x1689=((r21)*(x1668));
05040 IkReal x1690=((r20)*(x1667));
05041 IkReal x1691=((x1668)*(x1677));
05042 IkReal x1692=((r01)*(sj6)*(x1668));
05043 IkReal x1693=((cj5)*(r10)*(x1675));
05044 evalcond[0]=((IkReal(-1.00000000000000))+(((x1680)*(x1690)))+(((x1667)*(x1669)))+(((sj6)*(x1689)))+(((IkReal(-1.00000000000000))*(x1670)*(x1686)))+(((x1673)*(x1688))));
05045 evalcond[1]=((((cj6)*(x1690)))+(((x1668)*(x1669)))+(((x1673)*(x1689)))+(((IkReal(-1.00000000000000))*(x1675)*(x1688)))+(((x1680)*(x1686))));
05046 evalcond[2]=((((r01)*(sj6)*(x1685)))+(((x1682)*(x1683)))+(((x1679)*(x1687)))+(((x1678)*(x1682)))+(((IkReal(-1.00000000000000))*(x1668)*(x1671)*(x1674)))+(((IkReal(-1.00000000000000))*(r10)*(x1667)*(x1671)*(x1680)))+(((IkReal(-1.00000000000000))*(x1667)*(x1671)*(x1677)))+(((IkReal(-1.00000000000000))*(x1670)*(x1672)*(x1684)))+(((r01)*(x1673)*(x1682)))+(((IkReal(-1.00000000000000))*(r00)*(x1670)*(x1685))));
05047 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x1675)*(x1682)))+(((IkReal(-1.00000000000000))*(x1671)*(x1691)))+(((IkReal(-1.00000000000000))*(r10)*(x1670)*(x1684)))+(((IkReal(-1.00000000000000))*(r10)*(x1668)*(x1671)*(x1680)))+(((r01)*(x1673)*(x1685)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1670)*(x1672)*(x1687)))+(((x1676)*(x1682)))+(((x1683)*(x1685)))+(((x1674)*(x1684)))+(((x1678)*(x1685))));
05048 evalcond[4]=((((x1676)*(x1687)))+(((IkReal(-1.00000000000000))*(x1667)*(x1671)*(x1683)))+(((IkReal(-1.00000000000000))*(x1670)*(x1681)*(x1684)))+(((IkReal(-1.00000000000000))*(x1670)*(x1672)*(x1682)))+(((IkReal(-1.00000000000000))*(x1667)*(x1671)*(x1678)))+(((IkReal(-1.00000000000000))*(x1677)*(x1682)))+(((IkReal(-1.00000000000000))*(x1682)*(x1693)))+(((IkReal(-1.00000000000000))*(x1671)*(x1692)))+(((IkReal(-1.00000000000000))*(x1674)*(x1685)))+(((x1679)*(x1685))));
05049 evalcond[5]=((((IkReal(-1.00000000000000))*(x1685)*(x1693)))+(((IkReal(-1.00000000000000))*(x1677)*(x1685)))+(((IkReal(-1.00000000000000))*(r10)*(x1670)*(x1682)))+(((IkReal(-1.00000000000000))*(x1670)*(x1672)*(x1685)))+(sj3)+(((x1674)*(x1682)))+(((IkReal(-1.00000000000000))*(x1670)*(x1681)*(x1687)))+(((IkReal(-1.00000000000000))*(x1668)*(x1671)*(x1678)))+(((r01)*(sj6)*(x1684)))+(((IkReal(-1.00000000000000))*(r00)*(x1670)*(x1684)))+(((IkReal(-1.00000000000000))*(x1668)*(x1671)*(x1683))));
05050 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
05051 {
05052 continue;
05053 }
05054 }
05055 
05056 {
05057 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05058 vinfos[0].jointtype = 1;
05059 vinfos[0].foffset = j0;
05060 vinfos[0].indices[0] = _ij0[0];
05061 vinfos[0].indices[1] = _ij0[1];
05062 vinfos[0].maxsolutions = _nj0;
05063 vinfos[1].jointtype = 1;
05064 vinfos[1].foffset = j1;
05065 vinfos[1].indices[0] = _ij1[0];
05066 vinfos[1].indices[1] = _ij1[1];
05067 vinfos[1].maxsolutions = _nj1;
05068 vinfos[2].jointtype = 1;
05069 vinfos[2].foffset = j2;
05070 vinfos[2].indices[0] = _ij2[0];
05071 vinfos[2].indices[1] = _ij2[1];
05072 vinfos[2].maxsolutions = _nj2;
05073 vinfos[3].jointtype = 1;
05074 vinfos[3].foffset = j3;
05075 vinfos[3].indices[0] = _ij3[0];
05076 vinfos[3].indices[1] = _ij3[1];
05077 vinfos[3].maxsolutions = _nj3;
05078 vinfos[4].jointtype = 1;
05079 vinfos[4].foffset = j4;
05080 vinfos[4].indices[0] = _ij4[0];
05081 vinfos[4].indices[1] = _ij4[1];
05082 vinfos[4].maxsolutions = _nj4;
05083 vinfos[5].jointtype = 1;
05084 vinfos[5].foffset = j5;
05085 vinfos[5].indices[0] = _ij5[0];
05086 vinfos[5].indices[1] = _ij5[1];
05087 vinfos[5].maxsolutions = _nj5;
05088 vinfos[6].jointtype = 1;
05089 vinfos[6].foffset = j6;
05090 vinfos[6].indices[0] = _ij6[0];
05091 vinfos[6].indices[1] = _ij6[1];
05092 vinfos[6].maxsolutions = _nj6;
05093 std::vector<int> vfree(0);
05094 solutions.AddSolution(vinfos,vfree);
05095 }
05096 }
05097 }
05098 
05099 }
05100 
05101 }
05102 }
05103 }
05104 
05105 } else
05106 {
05107 if( 1 )
05108 {
05109 continue;
05110 
05111 } else
05112 {
05113 }
05114 }
05115 }
05116 }
05117 
05118 } else
05119 {
05120 {
05121 IkReal j3array[1], cj3array[1], sj3array[1];
05122 bool j3valid[1]={false};
05123 _nj3 = 1;
05124 IkReal x1694=((cj6)*(sj5));
05125 IkReal x1695=((IkReal(1.00000000000000))*(cj5));
05126 IkReal x1696=((sj5)*(sj6));
05127 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x1696)))+(((IkReal(-1.00000000000000))*(r21)*(x1694)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(r00)*(x1696)))+(((r10)*(sj0)*(x1696)))+(((cj0)*(r01)*(x1694)))+(((r11)*(sj0)*(x1694)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1695)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1695))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x1696)))+(((IkReal(-1.00000000000000))*(r21)*(x1694)))+(((cj5)*(r22)))))))+IKsqr(((((cj0)*(r00)*(x1696)))+(((r10)*(sj0)*(x1696)))+(((cj0)*(r01)*(x1694)))+(((r11)*(sj0)*(x1694)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1695)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1695)))))-1) <= IKFAST_SINCOS_THRESH )
05128     continue;
05129 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x1696)))+(((IkReal(-1.00000000000000))*(r21)*(x1694)))+(((cj5)*(r22)))))), ((((cj0)*(r00)*(x1696)))+(((r10)*(sj0)*(x1696)))+(((cj0)*(r01)*(x1694)))+(((r11)*(sj0)*(x1694)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1695)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1695)))));
05130 sj3array[0]=IKsin(j3array[0]);
05131 cj3array[0]=IKcos(j3array[0]);
05132 if( j3array[0] > IKPI )
05133 {
05134     j3array[0]-=IK2PI;
05135 }
05136 else if( j3array[0] < -IKPI )
05137 {    j3array[0]+=IK2PI;
05138 }
05139 j3valid[0] = true;
05140 for(int ij3 = 0; ij3 < 1; ++ij3)
05141 {
05142 if( !j3valid[ij3] )
05143 {
05144     continue;
05145 }
05146 _ij3[0] = ij3; _ij3[1] = -1;
05147 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
05148 {
05149 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
05150 {
05151     j3valid[iij3]=false; _ij3[1] = iij3; break; 
05152 }
05153 }
05154 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
05155 {
05156 IkReal evalcond[3];
05157 IkReal x1697=IKsin(j3);
05158 IkReal x1698=((sj5)*(sj6));
05159 IkReal x1699=((cj0)*(cj5));
05160 IkReal x1700=((IkReal(1.00000000000000))*(cj0));
05161 IkReal x1701=((IkReal(1.00000000000000))*(sj0));
05162 IkReal x1702=((cj6)*(r01)*(sj5));
05163 IkReal x1703=((cj6)*(r11)*(sj5));
05164 evalcond[0]=((((cj2)*(x1697)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x1698))));
05165 evalcond[1]=((((r12)*(x1699)))+(((IkReal(-1.00000000000000))*(x1700)*(x1703)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x1701)))+(((sj0)*(x1702)))+(((r00)*(sj0)*(x1698)))+(((IkReal(-1.00000000000000))*(sj2)*(x1697)))+(((IkReal(-1.00000000000000))*(r10)*(x1698)*(x1700))));
05166 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x1698)*(x1700)))+(((r02)*(x1699)))+(((IkReal(-1.00000000000000))*(x1700)*(x1702)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(x1698)*(x1701)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x1701)*(x1703))));
05167 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
05168 {
05169 continue;
05170 }
05171 }
05172 
05173 {
05174 IkReal dummyeval[1];
05175 IkReal gconst54;
05176 IkReal x1704=(r21)*(r21);
05177 IkReal x1705=(cj5)*(cj5);
05178 IkReal x1706=(sj6)*(sj6);
05179 IkReal x1707=(cj6)*(cj6);
05180 IkReal x1708=(r20)*(r20);
05181 IkReal x1709=((cj6)*(r21));
05182 IkReal x1710=((IkReal(2.00000000000000))*(r20)*(sj6));
05183 IkReal x1711=((cj5)*(r22)*(sj5));
05184 IkReal x1712=((IkReal(1.00000000000000))*(x1706));
05185 IkReal x1713=((IkReal(1.00000000000000))*(x1707));
05186 gconst54=IKsign(((((IkReal(-1.00000000000000))*(x1708)*(x1713)))+(((IkReal(-2.00000000000000))*(x1709)*(x1711)))+(((x1709)*(x1710)))+(((IkReal(-1.00000000000000))*(x1704)*(x1712)))+(((IkReal(-1.00000000000000))*(x1704)*(x1705)*(x1713)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x1705)*(x1709)*(x1710)))+(((IkReal(-1.00000000000000))*(x1710)*(x1711)))+(((IkReal(-1.00000000000000))*(x1705)*(x1708)*(x1712)))));
05187 IkReal x1714=(r21)*(r21);
05188 IkReal x1715=(cj5)*(cj5);
05189 IkReal x1716=(sj6)*(sj6);
05190 IkReal x1717=(cj6)*(cj6);
05191 IkReal x1718=(r20)*(r20);
05192 IkReal x1719=((cj6)*(r21));
05193 IkReal x1720=((IkReal(2.00000000000000))*(r20)*(sj6));
05194 IkReal x1721=((cj5)*(r22)*(sj5));
05195 IkReal x1722=((IkReal(1.00000000000000))*(x1716));
05196 IkReal x1723=((IkReal(1.00000000000000))*(x1717));
05197 dummyeval[0]=((((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x1714)*(x1722)))+(((IkReal(-1.00000000000000))*(x1715)*(x1719)*(x1720)))+(((x1719)*(x1720)))+(((IkReal(-1.00000000000000))*(x1720)*(x1721)))+(((IkReal(-2.00000000000000))*(x1719)*(x1721)))+(((IkReal(-1.00000000000000))*(x1718)*(x1723)))+(((IkReal(-1.00000000000000))*(x1715)*(x1718)*(x1722)))+(((IkReal(-1.00000000000000))*(x1714)*(x1715)*(x1723))));
05198 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05199 {
05200 {
05201 IkReal dummyeval[1];
05202 IkReal gconst55;
05203 IkReal x1724=(cj6)*(cj6);
05204 IkReal x1725=(sj6)*(sj6);
05205 IkReal x1726=((IkReal(1.00000000000000))*(r01));
05206 IkReal x1727=((sj0)*(sj5));
05207 IkReal x1728=((cj6)*(r22));
05208 IkReal x1729=((r21)*(sj6));
05209 IkReal x1730=((r00)*(r21));
05210 IkReal x1731=((cj0)*(sj5));
05211 IkReal x1732=((cj6)*(r20));
05212 IkReal x1733=((r22)*(sj6));
05213 IkReal x1734=((cj0)*(cj5));
05214 IkReal x1735=((IkReal(1.00000000000000))*(r10));
05215 IkReal x1736=((cj5)*(sj0));
05216 IkReal x1737=((r20)*(x1725));
05217 IkReal x1738=((x1724)*(x1736));
05218 gconst55=IKsign(((((x1725)*(x1730)*(x1736)))+(((r11)*(r20)*(x1724)*(x1734)))+(((IkReal(-1.00000000000000))*(r02)*(x1727)*(x1732)))+(((IkReal(-1.00000000000000))*(r20)*(x1726)*(x1738)))+(((r02)*(x1727)*(x1729)))+(((IkReal(-1.00000000000000))*(x1728)*(x1731)*(x1735)))+(((IkReal(-1.00000000000000))*(r12)*(x1729)*(x1731)))+(((IkReal(-1.00000000000000))*(x1726)*(x1736)*(x1737)))+(((x1730)*(x1738)))+(((r11)*(x1734)*(x1737)))+(((IkReal(-1.00000000000000))*(r21)*(x1725)*(x1734)*(x1735)))+(((IkReal(-1.00000000000000))*(r21)*(x1724)*(x1734)*(x1735)))+(((r00)*(x1727)*(x1728)))+(((r11)*(x1731)*(x1733)))+(((IkReal(-1.00000000000000))*(x1726)*(x1727)*(x1733)))+(((r12)*(x1731)*(x1732)))));
05219 IkReal x1739=(cj6)*(cj6);
05220 IkReal x1740=(sj6)*(sj6);
05221 IkReal x1741=((IkReal(1.00000000000000))*(r01));
05222 IkReal x1742=((sj0)*(sj5));
05223 IkReal x1743=((cj6)*(r22));
05224 IkReal x1744=((r21)*(sj6));
05225 IkReal x1745=((r00)*(r21));
05226 IkReal x1746=((cj0)*(sj5));
05227 IkReal x1747=((cj6)*(r20));
05228 IkReal x1748=((r22)*(sj6));
05229 IkReal x1749=((cj0)*(cj5));
05230 IkReal x1750=((IkReal(1.00000000000000))*(r10));
05231 IkReal x1751=((cj5)*(sj0));
05232 IkReal x1752=((r20)*(x1740));
05233 IkReal x1753=((x1739)*(x1751));
05234 dummyeval[0]=((((IkReal(-1.00000000000000))*(r20)*(x1741)*(x1753)))+(((IkReal(-1.00000000000000))*(r21)*(x1740)*(x1749)*(x1750)))+(((IkReal(-1.00000000000000))*(r21)*(x1739)*(x1749)*(x1750)))+(((r00)*(x1742)*(x1743)))+(((x1740)*(x1745)*(x1751)))+(((r11)*(x1749)*(x1752)))+(((r12)*(x1746)*(x1747)))+(((x1745)*(x1753)))+(((r02)*(x1742)*(x1744)))+(((IkReal(-1.00000000000000))*(r12)*(x1744)*(x1746)))+(((IkReal(-1.00000000000000))*(r02)*(x1742)*(x1747)))+(((IkReal(-1.00000000000000))*(x1741)*(x1751)*(x1752)))+(((IkReal(-1.00000000000000))*(x1741)*(x1742)*(x1748)))+(((IkReal(-1.00000000000000))*(x1743)*(x1746)*(x1750)))+(((r11)*(r20)*(x1739)*(x1749)))+(((r11)*(x1746)*(x1748))));
05235 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05236 {
05237 continue;
05238 
05239 } else
05240 {
05241 {
05242 IkReal j4array[1], cj4array[1], sj4array[1];
05243 bool j4valid[1]={false};
05244 _nj4 = 1;
05245 IkReal x1754=((cj5)*(sj6));
05246 IkReal x1755=((cj2)*(r20));
05247 IkReal x1756=((IkReal(1.00000000000000))*(sj6));
05248 IkReal x1757=((cj2)*(r21));
05249 IkReal x1758=((cj0)*(sj2));
05250 IkReal x1759=((cj5)*(cj6));
05251 IkReal x1760=((IkReal(1.00000000000000))*(sj0)*(sj2));
05252 IkReal x1761=((r10)*(x1758));
05253 if( IKabs(((gconst55)*(((((IkReal(-1.00000000000000))*(r11)*(x1756)*(x1758)))+(((r01)*(sj0)*(sj2)*(sj6)))+(((cj6)*(x1761)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x1760)))+(((IkReal(-1.00000000000000))*(x1756)*(x1757)))+(((cj6)*(x1755))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x1754)*(x1760)))+(((IkReal(-1.00000000000000))*(r01)*(x1759)*(x1760)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x1760)))+(((x1754)*(x1755)))+(((x1754)*(x1761)))+(((r12)*(sj5)*(x1758)))+(((x1757)*(x1759)))+(((r11)*(x1758)*(x1759))))))) < IKFAST_ATAN2_MAGTHRESH )
05254     continue;
05255 j4array[0]=IKatan2(((gconst55)*(((((IkReal(-1.00000000000000))*(r11)*(x1756)*(x1758)))+(((r01)*(sj0)*(sj2)*(sj6)))+(((cj6)*(x1761)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x1760)))+(((IkReal(-1.00000000000000))*(x1756)*(x1757)))+(((cj6)*(x1755)))))), ((gconst55)*(((((cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x1754)*(x1760)))+(((IkReal(-1.00000000000000))*(r01)*(x1759)*(x1760)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x1760)))+(((x1754)*(x1755)))+(((x1754)*(x1761)))+(((r12)*(sj5)*(x1758)))+(((x1757)*(x1759)))+(((r11)*(x1758)*(x1759)))))));
05256 sj4array[0]=IKsin(j4array[0]);
05257 cj4array[0]=IKcos(j4array[0]);
05258 if( j4array[0] > IKPI )
05259 {
05260     j4array[0]-=IK2PI;
05261 }
05262 else if( j4array[0] < -IKPI )
05263 {    j4array[0]+=IK2PI;
05264 }
05265 j4valid[0] = true;
05266 for(int ij4 = 0; ij4 < 1; ++ij4)
05267 {
05268 if( !j4valid[ij4] )
05269 {
05270     continue;
05271 }
05272 _ij4[0] = ij4; _ij4[1] = -1;
05273 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
05274 {
05275 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
05276 {
05277     j4valid[iij4]=false; _ij4[1] = iij4; break; 
05278 }
05279 }
05280 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
05281 {
05282 IkReal evalcond[6];
05283 IkReal x1762=IKsin(j4);
05284 IkReal x1763=IKcos(j4);
05285 IkReal x1764=((r00)*(sj6));
05286 IkReal x1765=((IkReal(1.00000000000000))*(r12));
05287 IkReal x1766=((IkReal(1.00000000000000))*(cj6));
05288 IkReal x1767=((cj6)*(r01));
05289 IkReal x1768=((cj0)*(r11));
05290 IkReal x1769=((r01)*(sj6));
05291 IkReal x1770=((IkReal(1.00000000000000))*(cj5));
05292 IkReal x1771=((cj5)*(r11));
05293 IkReal x1772=((cj0)*(r01));
05294 IkReal x1773=((r02)*(sj5));
05295 IkReal x1774=((cj6)*(r10));
05296 IkReal x1775=((sj5)*(x1762));
05297 IkReal x1776=((cj0)*(x1763));
05298 IkReal x1777=((sj6)*(x1762));
05299 IkReal x1778=((sj0)*(x1763));
05300 IkReal x1779=((r10)*(x1762));
05301 IkReal x1780=((IkReal(1.00000000000000))*(r10)*(sj6));
05302 IkReal x1781=((cj5)*(x1762));
05303 IkReal x1782=((IkReal(1.00000000000000))*(r11)*(sj6));
05304 IkReal x1783=((r00)*(x1762));
05305 IkReal x1784=((r20)*(x1763));
05306 IkReal x1785=((r21)*(x1763));
05307 IkReal x1786=((sj0)*(x1781));
05308 evalcond[0]=((((sj6)*(x1785)))+(sj2)+(((cj5)*(r20)*(x1777)))+(((r22)*(x1775)))+(((IkReal(-1.00000000000000))*(x1766)*(x1784)))+(((cj6)*(r21)*(x1781))));
05309 evalcond[1]=((((cj5)*(cj6)*(x1785)))+(((cj6)*(r20)*(x1762)))+(((r22)*(sj5)*(x1763)))+(((cj5)*(sj6)*(x1784)))+(((IkReal(-1.00000000000000))*(r21)*(x1777)))+(((IkReal(-1.00000000000000))*(cj2)*(cj3))));
05310 evalcond[2]=((((x1769)*(x1778)))+(((IkReal(-1.00000000000000))*(x1766)*(x1768)*(x1781)))+(((IkReal(-1.00000000000000))*(sj6)*(x1763)*(x1768)))+(((x1767)*(x1786)))+(cj2)+(((x1774)*(x1776)))+(((x1764)*(x1786)))+(((sj0)*(x1762)*(x1773)))+(((IkReal(-1.00000000000000))*(r00)*(x1766)*(x1778)))+(((IkReal(-1.00000000000000))*(cj0)*(x1765)*(x1775)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x1770)*(x1777))));
05311 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj6)*(x1770)*(x1776)))+(((x1768)*(x1777)))+(((IkReal(-1.00000000000000))*(cj5)*(x1763)*(x1766)*(x1768)))+(((cj5)*(x1764)*(x1778)))+(((cj6)*(sj0)*(x1783)))+(((cj5)*(x1767)*(x1778)))+(((IkReal(-1.00000000000000))*(sj0)*(x1762)*(x1769)))+(((x1773)*(x1778)))+(((IkReal(-1.00000000000000))*(cj0)*(x1766)*(x1779)))+(((IkReal(-1.00000000000000))*(sj5)*(x1765)*(x1776)))+(((cj3)*(sj2))));
05312 evalcond[4]=((((IkReal(-1.00000000000000))*(x1778)*(x1782)))+(((cj6)*(r00)*(x1776)))+(((IkReal(-1.00000000000000))*(cj0)*(x1762)*(x1764)*(x1770)))+(((IkReal(-1.00000000000000))*(x1769)*(x1776)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1770)*(x1777)))+(((IkReal(-1.00000000000000))*(sj0)*(x1765)*(x1775)))+(((IkReal(-1.00000000000000))*(cj0)*(x1762)*(x1773)))+(((x1774)*(x1778)))+(((IkReal(-1.00000000000000))*(x1766)*(x1772)*(x1781)))+(((IkReal(-1.00000000000000))*(sj0)*(x1762)*(x1766)*(x1771))));
05313 evalcond[5]=((((IkReal(-1.00000000000000))*(x1773)*(x1776)))+(((IkReal(-1.00000000000000))*(sj5)*(x1765)*(x1778)))+(sj3)+(((IkReal(-1.00000000000000))*(cj0)*(x1766)*(x1783)))+(((r11)*(sj0)*(x1777)))+(((IkReal(-1.00000000000000))*(x1766)*(x1771)*(x1778)))+(((IkReal(-1.00000000000000))*(cj5)*(x1763)*(x1766)*(x1772)))+(((cj0)*(x1762)*(x1769)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x1770)*(x1778)))+(((IkReal(-1.00000000000000))*(x1764)*(x1770)*(x1776)))+(((IkReal(-1.00000000000000))*(sj0)*(x1766)*(x1779))));
05314 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
05315 {
05316 continue;
05317 }
05318 }
05319 
05320 {
05321 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05322 vinfos[0].jointtype = 1;
05323 vinfos[0].foffset = j0;
05324 vinfos[0].indices[0] = _ij0[0];
05325 vinfos[0].indices[1] = _ij0[1];
05326 vinfos[0].maxsolutions = _nj0;
05327 vinfos[1].jointtype = 1;
05328 vinfos[1].foffset = j1;
05329 vinfos[1].indices[0] = _ij1[0];
05330 vinfos[1].indices[1] = _ij1[1];
05331 vinfos[1].maxsolutions = _nj1;
05332 vinfos[2].jointtype = 1;
05333 vinfos[2].foffset = j2;
05334 vinfos[2].indices[0] = _ij2[0];
05335 vinfos[2].indices[1] = _ij2[1];
05336 vinfos[2].maxsolutions = _nj2;
05337 vinfos[3].jointtype = 1;
05338 vinfos[3].foffset = j3;
05339 vinfos[3].indices[0] = _ij3[0];
05340 vinfos[3].indices[1] = _ij3[1];
05341 vinfos[3].maxsolutions = _nj3;
05342 vinfos[4].jointtype = 1;
05343 vinfos[4].foffset = j4;
05344 vinfos[4].indices[0] = _ij4[0];
05345 vinfos[4].indices[1] = _ij4[1];
05346 vinfos[4].maxsolutions = _nj4;
05347 vinfos[5].jointtype = 1;
05348 vinfos[5].foffset = j5;
05349 vinfos[5].indices[0] = _ij5[0];
05350 vinfos[5].indices[1] = _ij5[1];
05351 vinfos[5].maxsolutions = _nj5;
05352 vinfos[6].jointtype = 1;
05353 vinfos[6].foffset = j6;
05354 vinfos[6].indices[0] = _ij6[0];
05355 vinfos[6].indices[1] = _ij6[1];
05356 vinfos[6].maxsolutions = _nj6;
05357 std::vector<int> vfree(0);
05358 solutions.AddSolution(vinfos,vfree);
05359 }
05360 }
05361 }
05362 
05363 }
05364 
05365 }
05366 
05367 } else
05368 {
05369 {
05370 IkReal j4array[1], cj4array[1], sj4array[1];
05371 bool j4valid[1]={false};
05372 _nj4 = 1;
05373 IkReal x1787=((cj6)*(r20));
05374 IkReal x1788=((r22)*(sj5));
05375 IkReal x1789=((r21)*(sj2));
05376 IkReal x1790=((cj5)*(cj6));
05377 IkReal x1791=((cj5)*(r20)*(sj6));
05378 IkReal x1792=((IkReal(1.00000000000000))*(cj2)*(cj3));
05379 if( IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(x1787)*(x1792)))+(((cj2)*(cj3)*(r21)*(sj6)))+(((sj2)*(x1788)))+(((sj2)*(x1791)))+(((x1789)*(x1790))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(r21)*(x1790)*(x1792)))+(((IkReal(-1.00000000000000))*(sj2)*(x1787)))+(((IkReal(-1.00000000000000))*(x1788)*(x1792)))+(((sj6)*(x1789)))+(((IkReal(-1.00000000000000))*(x1791)*(x1792))))))) < IKFAST_ATAN2_MAGTHRESH )
05380     continue;
05381 j4array[0]=IKatan2(((gconst54)*(((((IkReal(-1.00000000000000))*(x1787)*(x1792)))+(((cj2)*(cj3)*(r21)*(sj6)))+(((sj2)*(x1788)))+(((sj2)*(x1791)))+(((x1789)*(x1790)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(r21)*(x1790)*(x1792)))+(((IkReal(-1.00000000000000))*(sj2)*(x1787)))+(((IkReal(-1.00000000000000))*(x1788)*(x1792)))+(((sj6)*(x1789)))+(((IkReal(-1.00000000000000))*(x1791)*(x1792)))))));
05382 sj4array[0]=IKsin(j4array[0]);
05383 cj4array[0]=IKcos(j4array[0]);
05384 if( j4array[0] > IKPI )
05385 {
05386     j4array[0]-=IK2PI;
05387 }
05388 else if( j4array[0] < -IKPI )
05389 {    j4array[0]+=IK2PI;
05390 }
05391 j4valid[0] = true;
05392 for(int ij4 = 0; ij4 < 1; ++ij4)
05393 {
05394 if( !j4valid[ij4] )
05395 {
05396     continue;
05397 }
05398 _ij4[0] = ij4; _ij4[1] = -1;
05399 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
05400 {
05401 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
05402 {
05403     j4valid[iij4]=false; _ij4[1] = iij4; break; 
05404 }
05405 }
05406 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
05407 {
05408 IkReal evalcond[6];
05409 IkReal x1793=IKsin(j4);
05410 IkReal x1794=IKcos(j4);
05411 IkReal x1795=((r00)*(sj6));
05412 IkReal x1796=((IkReal(1.00000000000000))*(r12));
05413 IkReal x1797=((IkReal(1.00000000000000))*(cj6));
05414 IkReal x1798=((cj6)*(r01));
05415 IkReal x1799=((cj0)*(r11));
05416 IkReal x1800=((r01)*(sj6));
05417 IkReal x1801=((IkReal(1.00000000000000))*(cj5));
05418 IkReal x1802=((cj5)*(r11));
05419 IkReal x1803=((cj0)*(r01));
05420 IkReal x1804=((r02)*(sj5));
05421 IkReal x1805=((cj6)*(r10));
05422 IkReal x1806=((sj5)*(x1793));
05423 IkReal x1807=((cj0)*(x1794));
05424 IkReal x1808=((sj6)*(x1793));
05425 IkReal x1809=((sj0)*(x1794));
05426 IkReal x1810=((r10)*(x1793));
05427 IkReal x1811=((IkReal(1.00000000000000))*(r10)*(sj6));
05428 IkReal x1812=((cj5)*(x1793));
05429 IkReal x1813=((IkReal(1.00000000000000))*(r11)*(sj6));
05430 IkReal x1814=((r00)*(x1793));
05431 IkReal x1815=((r20)*(x1794));
05432 IkReal x1816=((r21)*(x1794));
05433 IkReal x1817=((sj0)*(x1812));
05434 evalcond[0]=((((r22)*(x1806)))+(((sj6)*(x1816)))+(sj2)+(((cj6)*(r21)*(x1812)))+(((cj5)*(r20)*(x1808)))+(((IkReal(-1.00000000000000))*(x1797)*(x1815))));
05435 evalcond[1]=((((r22)*(sj5)*(x1794)))+(((cj6)*(r20)*(x1793)))+(((cj5)*(cj6)*(x1816)))+(((cj5)*(sj6)*(x1815)))+(((IkReal(-1.00000000000000))*(r21)*(x1808)))+(((IkReal(-1.00000000000000))*(cj2)*(cj3))));
05436 evalcond[2]=((((IkReal(-1.00000000000000))*(x1797)*(x1799)*(x1812)))+(((sj0)*(x1793)*(x1804)))+(((x1800)*(x1809)))+(((IkReal(-1.00000000000000))*(cj0)*(x1796)*(x1806)))+(((x1795)*(x1817)))+(cj2)+(((x1805)*(x1807)))+(((x1798)*(x1817)))+(((IkReal(-1.00000000000000))*(sj6)*(x1794)*(x1799)))+(((IkReal(-1.00000000000000))*(r00)*(x1797)*(x1809)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x1801)*(x1808))));
05437 evalcond[3]=((((cj6)*(sj0)*(x1814)))+(((x1799)*(x1808)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x1801)*(x1807)))+(((IkReal(-1.00000000000000))*(sj0)*(x1793)*(x1800)))+(((x1804)*(x1809)))+(((cj3)*(sj2)))+(((cj5)*(x1798)*(x1809)))+(((cj5)*(x1795)*(x1809)))+(((IkReal(-1.00000000000000))*(cj0)*(x1797)*(x1810)))+(((IkReal(-1.00000000000000))*(sj5)*(x1796)*(x1807)))+(((IkReal(-1.00000000000000))*(cj5)*(x1794)*(x1797)*(x1799))));
05438 evalcond[4]=((((x1805)*(x1809)))+(((IkReal(-1.00000000000000))*(x1809)*(x1813)))+(((IkReal(-1.00000000000000))*(x1797)*(x1803)*(x1812)))+(((IkReal(-1.00000000000000))*(cj0)*(x1793)*(x1804)))+(((IkReal(-1.00000000000000))*(sj0)*(x1796)*(x1806)))+(((IkReal(-1.00000000000000))*(cj0)*(x1793)*(x1795)*(x1801)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1801)*(x1808)))+(((IkReal(-1.00000000000000))*(sj0)*(x1793)*(x1797)*(x1802)))+(((IkReal(-1.00000000000000))*(x1800)*(x1807)))+(((cj6)*(r00)*(x1807))));
05439 evalcond[5]=((((IkReal(-1.00000000000000))*(x1804)*(x1807)))+(((IkReal(-1.00000000000000))*(x1797)*(x1802)*(x1809)))+(((cj0)*(x1793)*(x1800)))+(sj3)+(((IkReal(-1.00000000000000))*(cj5)*(x1794)*(x1797)*(x1803)))+(((IkReal(-1.00000000000000))*(sj0)*(x1797)*(x1810)))+(((IkReal(-1.00000000000000))*(cj0)*(x1797)*(x1814)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x1801)*(x1809)))+(((IkReal(-1.00000000000000))*(sj5)*(x1796)*(x1809)))+(((r11)*(sj0)*(x1808)))+(((IkReal(-1.00000000000000))*(x1795)*(x1801)*(x1807))));
05440 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
05441 {
05442 continue;
05443 }
05444 }
05445 
05446 {
05447 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05448 vinfos[0].jointtype = 1;
05449 vinfos[0].foffset = j0;
05450 vinfos[0].indices[0] = _ij0[0];
05451 vinfos[0].indices[1] = _ij0[1];
05452 vinfos[0].maxsolutions = _nj0;
05453 vinfos[1].jointtype = 1;
05454 vinfos[1].foffset = j1;
05455 vinfos[1].indices[0] = _ij1[0];
05456 vinfos[1].indices[1] = _ij1[1];
05457 vinfos[1].maxsolutions = _nj1;
05458 vinfos[2].jointtype = 1;
05459 vinfos[2].foffset = j2;
05460 vinfos[2].indices[0] = _ij2[0];
05461 vinfos[2].indices[1] = _ij2[1];
05462 vinfos[2].maxsolutions = _nj2;
05463 vinfos[3].jointtype = 1;
05464 vinfos[3].foffset = j3;
05465 vinfos[3].indices[0] = _ij3[0];
05466 vinfos[3].indices[1] = _ij3[1];
05467 vinfos[3].maxsolutions = _nj3;
05468 vinfos[4].jointtype = 1;
05469 vinfos[4].foffset = j4;
05470 vinfos[4].indices[0] = _ij4[0];
05471 vinfos[4].indices[1] = _ij4[1];
05472 vinfos[4].maxsolutions = _nj4;
05473 vinfos[5].jointtype = 1;
05474 vinfos[5].foffset = j5;
05475 vinfos[5].indices[0] = _ij5[0];
05476 vinfos[5].indices[1] = _ij5[1];
05477 vinfos[5].maxsolutions = _nj5;
05478 vinfos[6].jointtype = 1;
05479 vinfos[6].foffset = j6;
05480 vinfos[6].indices[0] = _ij6[0];
05481 vinfos[6].indices[1] = _ij6[1];
05482 vinfos[6].maxsolutions = _nj6;
05483 std::vector<int> vfree(0);
05484 solutions.AddSolution(vinfos,vfree);
05485 }
05486 }
05487 }
05488 
05489 }
05490 
05491 }
05492 }
05493 }
05494 
05495 }
05496 
05497 }
05498 
05499 } else
05500 {
05501 {
05502 IkReal j4array[1], cj4array[1], sj4array[1];
05503 bool j4valid[1]={false};
05504 _nj4 = 1;
05505 IkReal x1818=((cj5)*(sj6));
05506 IkReal x1819=((cj2)*(r20));
05507 IkReal x1820=((IkReal(1.00000000000000))*(sj6));
05508 IkReal x1821=((cj2)*(r21));
05509 IkReal x1822=((cj5)*(cj6));
05510 IkReal x1823=((IkReal(1.00000000000000))*(sj0)*(sj2));
05511 IkReal x1824=((cj0)*(r10)*(sj2));
05512 IkReal x1825=((cj0)*(r11)*(sj2));
05513 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x1820)*(x1821)))+(((r01)*(sj0)*(sj2)*(sj6)))+(((IkReal(-1.00000000000000))*(x1820)*(x1825)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x1823)))+(((cj6)*(x1824)))+(((cj6)*(x1819))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((x1818)*(x1824)))+(((cj2)*(r22)*(sj5)))+(((cj0)*(r12)*(sj2)*(sj5)))+(((x1821)*(x1822)))+(((IkReal(-1.00000000000000))*(r01)*(x1822)*(x1823)))+(((x1818)*(x1819)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x1823)))+(((x1822)*(x1825)))+(((IkReal(-1.00000000000000))*(r00)*(x1818)*(x1823))))))) < IKFAST_ATAN2_MAGTHRESH )
05514     continue;
05515 j4array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(x1820)*(x1821)))+(((r01)*(sj0)*(sj2)*(sj6)))+(((IkReal(-1.00000000000000))*(x1820)*(x1825)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x1823)))+(((cj6)*(x1824)))+(((cj6)*(x1819)))))), ((gconst52)*(((((x1818)*(x1824)))+(((cj2)*(r22)*(sj5)))+(((cj0)*(r12)*(sj2)*(sj5)))+(((x1821)*(x1822)))+(((IkReal(-1.00000000000000))*(r01)*(x1822)*(x1823)))+(((x1818)*(x1819)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x1823)))+(((x1822)*(x1825)))+(((IkReal(-1.00000000000000))*(r00)*(x1818)*(x1823)))))));
05516 sj4array[0]=IKsin(j4array[0]);
05517 cj4array[0]=IKcos(j4array[0]);
05518 if( j4array[0] > IKPI )
05519 {
05520     j4array[0]-=IK2PI;
05521 }
05522 else if( j4array[0] < -IKPI )
05523 {    j4array[0]+=IK2PI;
05524 }
05525 j4valid[0] = true;
05526 for(int ij4 = 0; ij4 < 1; ++ij4)
05527 {
05528 if( !j4valid[ij4] )
05529 {
05530     continue;
05531 }
05532 _ij4[0] = ij4; _ij4[1] = -1;
05533 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
05534 {
05535 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
05536 {
05537     j4valid[iij4]=false; _ij4[1] = iij4; break; 
05538 }
05539 }
05540 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
05541 {
05542 IkReal evalcond[3];
05543 IkReal x1826=IKsin(j4);
05544 IkReal x1827=IKcos(j4);
05545 IkReal x1828=((r00)*(sj6));
05546 IkReal x1829=((cj6)*(r01));
05547 IkReal x1830=((IkReal(1.00000000000000))*(cj0));
05548 IkReal x1831=((IkReal(1.00000000000000))*(sj0));
05549 IkReal x1832=((r10)*(sj6));
05550 IkReal x1833=((sj5)*(x1826));
05551 IkReal x1834=((IkReal(1.00000000000000))*(cj6)*(r11));
05552 IkReal x1835=((cj5)*(x1826));
05553 IkReal x1836=((cj6)*(x1827));
05554 IkReal x1837=((sj0)*(x1835));
05555 IkReal x1838=((r01)*(sj6)*(x1827));
05556 IkReal x1839=((r11)*(sj6)*(x1827));
05557 evalcond[0]=((sj2)+(((r22)*(x1833)))+(((r20)*(sj6)*(x1835)))+(((r21)*(sj6)*(x1827)))+(((IkReal(-1.00000000000000))*(r20)*(x1836)))+(((cj6)*(r21)*(x1835))));
05558 evalcond[1]=((((IkReal(-1.00000000000000))*(x1830)*(x1839)))+(((cj0)*(r10)*(x1836)))+(((r02)*(sj0)*(x1833)))+(((IkReal(-1.00000000000000))*(r12)*(x1830)*(x1833)))+(cj2)+(((IkReal(-1.00000000000000))*(x1830)*(x1832)*(x1835)))+(((sj0)*(x1838)))+(((x1828)*(x1837)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1830)*(x1835)))+(((IkReal(-1.00000000000000))*(r00)*(x1831)*(x1836)))+(((x1829)*(x1837))));
05559 evalcond[2]=((((IkReal(-1.00000000000000))*(x1831)*(x1839)))+(((IkReal(-1.00000000000000))*(r02)*(x1830)*(x1833)))+(((IkReal(-1.00000000000000))*(x1829)*(x1830)*(x1835)))+(((r10)*(sj0)*(x1836)))+(((IkReal(-1.00000000000000))*(r12)*(x1831)*(x1833)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1831)*(x1835)))+(((IkReal(-1.00000000000000))*(x1830)*(x1838)))+(((IkReal(-1.00000000000000))*(x1831)*(x1832)*(x1835)))+(((IkReal(-1.00000000000000))*(x1828)*(x1830)*(x1835)))+(((cj0)*(r00)*(x1836))));
05560 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
05561 {
05562 continue;
05563 }
05564 }
05565 
05566 {
05567 IkReal dummyeval[1];
05568 IkReal gconst56;
05569 gconst56=IKsign(cj2);
05570 dummyeval[0]=cj2;
05571 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05572 {
05573 {
05574 IkReal dummyeval[1];
05575 dummyeval[0]=cj2;
05576 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05577 {
05578 {
05579 IkReal dummyeval[1];
05580 dummyeval[0]=sj2;
05581 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05582 {
05583 {
05584 IkReal evalcond[9];
05585 IkReal x1840=((cj5)*(sj4));
05586 IkReal x1841=((IkReal(1.00000000000000))*(sj6));
05587 IkReal x1842=((r10)*(sj0));
05588 IkReal x1843=((sj4)*(sj5));
05589 IkReal x1844=((cj5)*(cj6));
05590 IkReal x1845=((r01)*(sj0));
05591 IkReal x1846=((IkReal(1.00000000000000))*(r02));
05592 IkReal x1847=((IkReal(0.374290000000000))*(cj0));
05593 IkReal x1848=((cj5)*(r12));
05594 IkReal x1849=((cj6)*(sj5));
05595 IkReal x1850=((cj0)*(r11));
05596 IkReal x1851=((cj5)*(sj0));
05597 IkReal x1852=((r20)*(sj6));
05598 IkReal x1853=((IkReal(1.00000000000000))*(sj0));
05599 IkReal x1854=((cj4)*(cj5));
05600 IkReal x1855=((IkReal(1.00000000000000))*(cj6));
05601 IkReal x1856=((IkReal(0.0100000000000000))*(sj5));
05602 IkReal x1857=((sj5)*(sj6));
05603 IkReal x1858=((cj0)*(r10));
05604 IkReal x1859=((cj4)*(cj6));
05605 IkReal x1860=((cj0)*(r01));
05606 IkReal x1861=((IkReal(1.00000000000000))*(cj4));
05607 IkReal x1862=((cj0)*(r00));
05608 IkReal x1863=((IkReal(0.374290000000000))*(sj0));
05609 IkReal x1864=((cj0)*(r12));
05610 IkReal x1865=((IkReal(0.374290000000000))*(sj5));
05611 IkReal x1866=((cj4)*(sj6));
05612 IkReal x1867=((IkReal(1.00000000000000))*(cj0));
05613 IkReal x1868=((r02)*(sj0));
05614 IkReal x1869=((IkReal(0.0100000000000000))*(cj5));
05615 IkReal x1870=((r11)*(sj0));
05616 IkReal x1871=((r00)*(sj0)*(sj6));
05617 IkReal x1872=((r00)*(x1859));
05618 IkReal x1873=((sj6)*(x1869));
05619 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
05620 evalcond[1]=((((r21)*(x1866)))+(((cj6)*(r21)*(x1840)))+(((x1840)*(x1852)))+(((r22)*(x1843)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x1855))));
05621 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x1852)*(x1869)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x1844)))+(((x1852)*(x1865)))+(pz)+(((IkReal(0.374290000000000))*(r21)*(x1849)))+(((IkReal(-1.00000000000000))*(r22)*(x1856))));
05622 evalcond[3]=((((IkReal(-1.00000000000000))*(x1846)*(x1851)))+(((x1845)*(x1849)))+(((cj0)*(x1848)))+(((IkReal(-1.00000000000000))*(x1849)*(x1850)))+(((r00)*(sj0)*(x1857)))+(((IkReal(-1.00000000000000))*(sj5)*(x1841)*(x1858))));
05623 evalcond[4]=((IkReal(1.00000000000000))+(((x1845)*(x1866)))+(((IkReal(-1.00000000000000))*(x1853)*(x1872)))+(((IkReal(-1.00000000000000))*(x1840)*(x1850)*(x1855)))+(((x1840)*(x1871)))+(((x1858)*(x1859)))+(((IkReal(-1.00000000000000))*(x1840)*(x1841)*(x1858)))+(((IkReal(-1.00000000000000))*(cj4)*(x1841)*(x1850)))+(((x1843)*(x1868)))+(((cj6)*(x1840)*(x1845)))+(((IkReal(-1.00000000000000))*(x1843)*(x1864))));
05624 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x1841)*(x1845)))+(((r00)*(x1851)*(x1866)))+(((IkReal(-1.00000000000000))*(sj4)*(x1855)*(x1858)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(sj5)*(x1868)))+(((IkReal(-1.00000000000000))*(x1841)*(x1854)*(x1858)))+(((IkReal(-1.00000000000000))*(sj5)*(x1861)*(x1864)))+(((cj4)*(x1844)*(x1845)))+(((sj4)*(sj6)*(x1850)))+(((IkReal(-1.00000000000000))*(x1844)*(x1850)*(x1861))));
05625 evalcond[6]=((((IkReal(-1.00000000000000))*(x1840)*(x1841)*(x1862)))+(((IkReal(-1.00000000000000))*(cj0)*(x1843)*(x1846)))+(((IkReal(-1.00000000000000))*(x1840)*(x1855)*(x1860)))+(((x1859)*(x1862)))+(((IkReal(-1.00000000000000))*(x1840)*(x1841)*(x1842)))+(((IkReal(-1.00000000000000))*(cj4)*(x1841)*(x1870)))+(((x1842)*(x1859)))+(((IkReal(-1.00000000000000))*(cj4)*(x1841)*(x1860)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1840)*(x1853)))+(((IkReal(-1.00000000000000))*(r12)*(x1843)*(x1853))));
05626 evalcond[7]=((((IkReal(0.0100000000000000))*(x1844)*(x1850)))+(((IkReal(-0.0100000000000000))*(x1844)*(x1845)))+(((IkReal(-0.374290000000000))*(r02)*(x1851)))+(((x1847)*(x1848)))+(((r00)*(x1857)*(x1863)))+(((IkReal(-1.00000000000000))*(r11)*(x1847)*(x1849)))+(((x1856)*(x1864)))+(((IkReal(0.374290000000000))*(x1845)*(x1849)))+(((IkReal(-1.00000000000000))*(py)*(x1867)))+(((IkReal(-1.00000000000000))*(r10)*(x1847)*(x1857)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x1851)))+(((IkReal(-1.00000000000000))*(x1856)*(x1868)))+(((px)*(sj0)))+(((x1858)*(x1873))));
05627 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(py)*(x1853)))+(((r12)*(sj0)*(x1856)))+(((cj0)*(r02)*(x1856)))+(((IkReal(0.0100000000000000))*(x1844)*(x1870)))+(((IkReal(-1.00000000000000))*(px)*(x1867)))+(((IkReal(0.0100000000000000))*(x1844)*(x1860)))+(((x1862)*(x1873)))+(((IkReal(-1.00000000000000))*(r01)*(x1847)*(x1849)))+(((cj5)*(r02)*(x1847)))+(((IkReal(-0.374290000000000))*(x1842)*(x1857)))+(((IkReal(-1.00000000000000))*(r00)*(x1847)*(x1857)))+(((x1842)*(x1873)))+(((x1848)*(x1863)))+(((IkReal(-1.00000000000000))*(r11)*(x1849)*(x1863))));
05628 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
05629 {
05630 {
05631 IkReal j3array[1], cj3array[1], sj3array[1];
05632 bool j3valid[1]={false};
05633 _nj3 = 1;
05634 IkReal x1874=((IkReal(1.00000000000000))*(r21));
05635 IkReal x1875=((cj4)*(cj5));
05636 IkReal x1876=((r20)*(sj6));
05637 if( IKabs(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1874)))+(((IkReal(-1.00000000000000))*(sj5)*(x1876)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r20)*(sj4)))+(((cj6)*(r21)*(x1875)))+(((cj4)*(r22)*(sj5)))+(((x1875)*(x1876)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1874))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1874)))+(((IkReal(-1.00000000000000))*(sj5)*(x1876)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r20)*(sj4)))+(((cj6)*(r21)*(x1875)))+(((cj4)*(r22)*(sj5)))+(((x1875)*(x1876)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1874)))))-1) <= IKFAST_SINCOS_THRESH )
05638     continue;
05639 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x1874)))+(((IkReal(-1.00000000000000))*(sj5)*(x1876)))+(((cj5)*(r22)))), ((((cj6)*(r20)*(sj4)))+(((cj6)*(r21)*(x1875)))+(((cj4)*(r22)*(sj5)))+(((x1875)*(x1876)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x1874)))));
05640 sj3array[0]=IKsin(j3array[0]);
05641 cj3array[0]=IKcos(j3array[0]);
05642 if( j3array[0] > IKPI )
05643 {
05644     j3array[0]-=IK2PI;
05645 }
05646 else if( j3array[0] < -IKPI )
05647 {    j3array[0]+=IK2PI;
05648 }
05649 j3valid[0] = true;
05650 for(int ij3 = 0; ij3 < 1; ++ij3)
05651 {
05652 if( !j3valid[ij3] )
05653 {
05654     continue;
05655 }
05656 _ij3[0] = ij3; _ij3[1] = -1;
05657 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
05658 {
05659 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
05660 {
05661     j3valid[iij3]=false; _ij3[1] = iij3; break; 
05662 }
05663 }
05664 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
05665 {
05666 IkReal evalcond[4];
05667 IkReal x1877=IKcos(j3);
05668 IkReal x1878=IKsin(j3);
05669 IkReal x1879=((IkReal(1.00000000000000))*(cj4));
05670 IkReal x1880=((sj0)*(sj5));
05671 IkReal x1881=((cj0)*(cj5));
05672 IkReal x1882=((cj6)*(r01));
05673 IkReal x1883=((r00)*(sj6));
05674 IkReal x1884=((cj6)*(r11));
05675 IkReal x1885=((cj5)*(sj0));
05676 IkReal x1886=((cj6)*(sj4));
05677 IkReal x1887=((sj4)*(sj6));
05678 IkReal x1888=((cj4)*(cj5));
05679 IkReal x1889=((cj6)*(r21));
05680 IkReal x1890=((r20)*(sj6));
05681 IkReal x1891=((r10)*(sj6));
05682 IkReal x1892=((IkReal(1.00000000000000))*(cj0)*(sj5));
05683 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x1878)+(((sj5)*(x1889)))+(((sj5)*(x1890))));
05684 evalcond[1]=((((x1888)*(x1889)))+(((x1888)*(x1890)))+(((IkReal(-1.00000000000000))*(r21)*(x1887)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x1886)))+(((IkReal(-1.00000000000000))*(x1877))));
05685 evalcond[2]=((((IkReal(-1.00000000000000))*(x1880)*(x1891)))+(((r12)*(x1885)))+(((r02)*(x1881)))+(((IkReal(-1.00000000000000))*(x1883)*(x1892)))+(x1877)+(((IkReal(-1.00000000000000))*(x1880)*(x1884)))+(((IkReal(-1.00000000000000))*(x1882)*(x1892))));
05686 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1886)))+(((r11)*(sj0)*(x1887)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1886)))+(((IkReal(-1.00000000000000))*(x1879)*(x1881)*(x1882)))+(((IkReal(-1.00000000000000))*(x1879)*(x1881)*(x1883)))+(((IkReal(-1.00000000000000))*(r12)*(x1879)*(x1880)))+(((IkReal(-1.00000000000000))*(x1879)*(x1885)*(x1891)))+(x1878)+(((cj0)*(r01)*(x1887)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x1879)))+(((IkReal(-1.00000000000000))*(x1879)*(x1884)*(x1885))));
05687 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05688 {
05689 continue;
05690 }
05691 }
05692 
05693 {
05694 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05695 vinfos[0].jointtype = 1;
05696 vinfos[0].foffset = j0;
05697 vinfos[0].indices[0] = _ij0[0];
05698 vinfos[0].indices[1] = _ij0[1];
05699 vinfos[0].maxsolutions = _nj0;
05700 vinfos[1].jointtype = 1;
05701 vinfos[1].foffset = j1;
05702 vinfos[1].indices[0] = _ij1[0];
05703 vinfos[1].indices[1] = _ij1[1];
05704 vinfos[1].maxsolutions = _nj1;
05705 vinfos[2].jointtype = 1;
05706 vinfos[2].foffset = j2;
05707 vinfos[2].indices[0] = _ij2[0];
05708 vinfos[2].indices[1] = _ij2[1];
05709 vinfos[2].maxsolutions = _nj2;
05710 vinfos[3].jointtype = 1;
05711 vinfos[3].foffset = j3;
05712 vinfos[3].indices[0] = _ij3[0];
05713 vinfos[3].indices[1] = _ij3[1];
05714 vinfos[3].maxsolutions = _nj3;
05715 vinfos[4].jointtype = 1;
05716 vinfos[4].foffset = j4;
05717 vinfos[4].indices[0] = _ij4[0];
05718 vinfos[4].indices[1] = _ij4[1];
05719 vinfos[4].maxsolutions = _nj4;
05720 vinfos[5].jointtype = 1;
05721 vinfos[5].foffset = j5;
05722 vinfos[5].indices[0] = _ij5[0];
05723 vinfos[5].indices[1] = _ij5[1];
05724 vinfos[5].maxsolutions = _nj5;
05725 vinfos[6].jointtype = 1;
05726 vinfos[6].foffset = j6;
05727 vinfos[6].indices[0] = _ij6[0];
05728 vinfos[6].indices[1] = _ij6[1];
05729 vinfos[6].maxsolutions = _nj6;
05730 std::vector<int> vfree(0);
05731 solutions.AddSolution(vinfos,vfree);
05732 }
05733 }
05734 }
05735 
05736 } else
05737 {
05738 IkReal x1893=((cj5)*(sj4));
05739 IkReal x1894=((IkReal(1.00000000000000))*(sj6));
05740 IkReal x1895=((r10)*(sj0));
05741 IkReal x1896=((sj4)*(sj5));
05742 IkReal x1897=((cj5)*(cj6));
05743 IkReal x1898=((r01)*(sj0));
05744 IkReal x1899=((IkReal(1.00000000000000))*(r02));
05745 IkReal x1900=((IkReal(0.374290000000000))*(cj0));
05746 IkReal x1901=((cj5)*(r12));
05747 IkReal x1902=((cj6)*(sj5));
05748 IkReal x1903=((cj0)*(r11));
05749 IkReal x1904=((cj5)*(sj0));
05750 IkReal x1905=((r20)*(sj6));
05751 IkReal x1906=((IkReal(1.00000000000000))*(sj0));
05752 IkReal x1907=((cj4)*(cj5));
05753 IkReal x1908=((IkReal(1.00000000000000))*(cj6));
05754 IkReal x1909=((IkReal(0.0100000000000000))*(sj5));
05755 IkReal x1910=((sj5)*(sj6));
05756 IkReal x1911=((cj0)*(r10));
05757 IkReal x1912=((cj4)*(cj6));
05758 IkReal x1913=((cj0)*(r01));
05759 IkReal x1914=((IkReal(1.00000000000000))*(cj4));
05760 IkReal x1915=((cj0)*(r00));
05761 IkReal x1916=((IkReal(0.374290000000000))*(sj0));
05762 IkReal x1917=((cj0)*(r12));
05763 IkReal x1918=((IkReal(0.374290000000000))*(sj5));
05764 IkReal x1919=((cj4)*(sj6));
05765 IkReal x1920=((IkReal(1.00000000000000))*(cj0));
05766 IkReal x1921=((r02)*(sj0));
05767 IkReal x1922=((IkReal(0.0100000000000000))*(cj5));
05768 IkReal x1923=((r11)*(sj0));
05769 IkReal x1924=((r00)*(sj0)*(sj6));
05770 IkReal x1925=((r00)*(x1912));
05771 IkReal x1926=((sj6)*(x1922));
05772 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
05773 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(r20)*(x1908)))+(((r21)*(x1919)))+(((r22)*(x1896)))+(((x1893)*(x1905)))+(((cj6)*(r21)*(x1893))));
05774 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x1902)))+(((IkReal(-1.00000000000000))*(r22)*(x1909)))+(((IkReal(-0.0100000000000000))*(r21)*(x1897)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x1905)*(x1918)))+(((IkReal(-1.00000000000000))*(x1905)*(x1922)))+(pz));
05775 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x1894)*(x1911)))+(((r00)*(sj0)*(x1910)))+(((cj0)*(x1901)))+(((x1898)*(x1902)))+(((IkReal(-1.00000000000000))*(x1899)*(x1904)))+(((IkReal(-1.00000000000000))*(x1902)*(x1903))));
05776 evalcond[4]=((IkReal(-1.00000000000000))+(((cj6)*(x1893)*(x1898)))+(((IkReal(-1.00000000000000))*(x1893)*(x1894)*(x1911)))+(((IkReal(-1.00000000000000))*(x1896)*(x1917)))+(((x1893)*(x1924)))+(((IkReal(-1.00000000000000))*(cj4)*(x1894)*(x1903)))+(((x1911)*(x1912)))+(((IkReal(-1.00000000000000))*(x1906)*(x1925)))+(((x1898)*(x1919)))+(((IkReal(-1.00000000000000))*(x1893)*(x1903)*(x1908)))+(((x1896)*(x1921))));
05777 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x1894)*(x1898)))+(((cj4)*(sj5)*(x1921)))+(((cj4)*(x1897)*(x1898)))+(((r00)*(x1904)*(x1919)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((sj4)*(sj6)*(x1903)))+(((IkReal(-1.00000000000000))*(sj5)*(x1914)*(x1917)))+(((IkReal(-1.00000000000000))*(x1897)*(x1903)*(x1914)))+(((IkReal(-1.00000000000000))*(x1894)*(x1907)*(x1911)))+(((IkReal(-1.00000000000000))*(sj4)*(x1908)*(x1911))));
05778 evalcond[6]=((((x1912)*(x1915)))+(((IkReal(-1.00000000000000))*(x1893)*(x1894)*(x1915)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x1893)*(x1906)))+(((IkReal(-1.00000000000000))*(cj0)*(x1896)*(x1899)))+(((IkReal(-1.00000000000000))*(cj4)*(x1894)*(x1923)))+(((IkReal(-1.00000000000000))*(x1893)*(x1894)*(x1895)))+(((IkReal(-1.00000000000000))*(cj4)*(x1894)*(x1913)))+(((IkReal(-1.00000000000000))*(r12)*(x1896)*(x1906)))+(((IkReal(-1.00000000000000))*(x1893)*(x1908)*(x1913)))+(((x1895)*(x1912))));
05779 evalcond[7]=((((IkReal(0.0100000000000000))*(x1897)*(x1903)))+(((x1900)*(x1901)))+(((IkReal(-0.374290000000000))*(r02)*(x1904)))+(((IkReal(-0.0100000000000000))*(x1897)*(x1898)))+(((IkReal(-1.00000000000000))*(x1909)*(x1921)))+(((IkReal(-1.00000000000000))*(py)*(x1920)))+(((x1911)*(x1926)))+(((r00)*(x1910)*(x1916)))+(((IkReal(-1.00000000000000))*(r11)*(x1900)*(x1902)))+(((x1909)*(x1917)))+(((IkReal(-1.00000000000000))*(r10)*(x1900)*(x1910)))+(((IkReal(0.374290000000000))*(x1898)*(x1902)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x1904))));
05780 evalcond[8]=((IkReal(-0.295420000000000))+(((cj0)*(r02)*(x1909)))+(((IkReal(-1.00000000000000))*(py)*(x1906)))+(((IkReal(-1.00000000000000))*(r00)*(x1900)*(x1910)))+(((x1901)*(x1916)))+(((x1895)*(x1926)))+(((IkReal(-1.00000000000000))*(px)*(x1920)))+(((IkReal(-1.00000000000000))*(r11)*(x1902)*(x1916)))+(((r12)*(sj0)*(x1909)))+(((x1915)*(x1926)))+(((cj5)*(r02)*(x1900)))+(((IkReal(-1.00000000000000))*(r01)*(x1900)*(x1902)))+(((IkReal(-0.374290000000000))*(x1895)*(x1910)))+(((IkReal(0.0100000000000000))*(x1897)*(x1913)))+(((IkReal(0.0100000000000000))*(x1897)*(x1923))));
05781 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
05782 {
05783 {
05784 IkReal j3array[1], cj3array[1], sj3array[1];
05785 bool j3valid[1]={false};
05786 _nj3 = 1;
05787 IkReal x1927=((IkReal(1.00000000000000))*(cj4));
05788 IkReal x1928=((cj6)*(r21));
05789 IkReal x1929=((r20)*(sj6));
05790 if( IKabs(((((sj5)*(x1929)))+(((sj5)*(x1928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1928)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1927)))+(((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1929)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x1929)))+(((sj5)*(x1928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1928)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1927)))+(((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1929)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
05791     continue;
05792 j3array[0]=IKatan2(((((sj5)*(x1929)))+(((sj5)*(x1928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1928)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x1927)))+(((IkReal(-1.00000000000000))*(cj5)*(x1927)*(x1929)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
05793 sj3array[0]=IKsin(j3array[0]);
05794 cj3array[0]=IKcos(j3array[0]);
05795 if( j3array[0] > IKPI )
05796 {
05797     j3array[0]-=IK2PI;
05798 }
05799 else if( j3array[0] < -IKPI )
05800 {    j3array[0]+=IK2PI;
05801 }
05802 j3valid[0] = true;
05803 for(int ij3 = 0; ij3 < 1; ++ij3)
05804 {
05805 if( !j3valid[ij3] )
05806 {
05807     continue;
05808 }
05809 _ij3[0] = ij3; _ij3[1] = -1;
05810 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
05811 {
05812 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
05813 {
05814     j3valid[iij3]=false; _ij3[1] = iij3; break; 
05815 }
05816 }
05817 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
05818 {
05819 IkReal evalcond[4];
05820 IkReal x1930=IKcos(j3);
05821 IkReal x1931=IKsin(j3);
05822 IkReal x1932=((IkReal(1.00000000000000))*(cj4));
05823 IkReal x1933=((sj0)*(sj5));
05824 IkReal x1934=((cj0)*(cj5));
05825 IkReal x1935=((cj6)*(r01));
05826 IkReal x1936=((r00)*(sj6));
05827 IkReal x1937=((cj6)*(r11));
05828 IkReal x1938=((cj5)*(sj0));
05829 IkReal x1939=((cj6)*(sj4));
05830 IkReal x1940=((sj4)*(sj6));
05831 IkReal x1941=((cj4)*(cj5));
05832 IkReal x1942=((cj6)*(r21));
05833 IkReal x1943=((r20)*(sj6));
05834 IkReal x1944=((r10)*(sj6));
05835 IkReal x1945=((IkReal(1.00000000000000))*(cj0)*(sj5));
05836 evalcond[0]=((((sj5)*(x1943)))+(((IkReal(-1.00000000000000))*(x1931)))+(((sj5)*(x1942)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
05837 evalcond[1]=((x1930)+(((IkReal(-1.00000000000000))*(r21)*(x1940)))+(((x1941)*(x1943)))+(((r20)*(x1939)))+(((cj4)*(r22)*(sj5)))+(((x1941)*(x1942))));
05838 evalcond[2]=((x1930)+(((r02)*(x1934)))+(((IkReal(-1.00000000000000))*(x1936)*(x1945)))+(((r12)*(x1938)))+(((IkReal(-1.00000000000000))*(x1935)*(x1945)))+(((IkReal(-1.00000000000000))*(x1933)*(x1937)))+(((IkReal(-1.00000000000000))*(x1933)*(x1944))));
05839 evalcond[3]=((x1931)+(((IkReal(-1.00000000000000))*(r12)*(x1932)*(x1933)))+(((IkReal(-1.00000000000000))*(x1932)*(x1934)*(x1936)))+(((IkReal(-1.00000000000000))*(x1932)*(x1938)*(x1944)))+(((cj0)*(r01)*(x1940)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x1932)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1939)))+(((r11)*(sj0)*(x1940)))+(((IkReal(-1.00000000000000))*(x1932)*(x1934)*(x1935)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1939)))+(((IkReal(-1.00000000000000))*(x1932)*(x1937)*(x1938))));
05840 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05841 {
05842 continue;
05843 }
05844 }
05845 
05846 {
05847 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05848 vinfos[0].jointtype = 1;
05849 vinfos[0].foffset = j0;
05850 vinfos[0].indices[0] = _ij0[0];
05851 vinfos[0].indices[1] = _ij0[1];
05852 vinfos[0].maxsolutions = _nj0;
05853 vinfos[1].jointtype = 1;
05854 vinfos[1].foffset = j1;
05855 vinfos[1].indices[0] = _ij1[0];
05856 vinfos[1].indices[1] = _ij1[1];
05857 vinfos[1].maxsolutions = _nj1;
05858 vinfos[2].jointtype = 1;
05859 vinfos[2].foffset = j2;
05860 vinfos[2].indices[0] = _ij2[0];
05861 vinfos[2].indices[1] = _ij2[1];
05862 vinfos[2].maxsolutions = _nj2;
05863 vinfos[3].jointtype = 1;
05864 vinfos[3].foffset = j3;
05865 vinfos[3].indices[0] = _ij3[0];
05866 vinfos[3].indices[1] = _ij3[1];
05867 vinfos[3].maxsolutions = _nj3;
05868 vinfos[4].jointtype = 1;
05869 vinfos[4].foffset = j4;
05870 vinfos[4].indices[0] = _ij4[0];
05871 vinfos[4].indices[1] = _ij4[1];
05872 vinfos[4].maxsolutions = _nj4;
05873 vinfos[5].jointtype = 1;
05874 vinfos[5].foffset = j5;
05875 vinfos[5].indices[0] = _ij5[0];
05876 vinfos[5].indices[1] = _ij5[1];
05877 vinfos[5].maxsolutions = _nj5;
05878 vinfos[6].jointtype = 1;
05879 vinfos[6].foffset = j6;
05880 vinfos[6].indices[0] = _ij6[0];
05881 vinfos[6].indices[1] = _ij6[1];
05882 vinfos[6].maxsolutions = _nj6;
05883 std::vector<int> vfree(0);
05884 solutions.AddSolution(vinfos,vfree);
05885 }
05886 }
05887 }
05888 
05889 } else
05890 {
05891 IkReal x1946=((IkReal(1.00000000000000))*(cj0));
05892 IkReal x1947=((cj4)*(sj6));
05893 IkReal x1948=((sj0)*(sj4));
05894 IkReal x1949=((cj5)*(sj6));
05895 IkReal x1950=((sj4)*(sj5));
05896 IkReal x1951=((r12)*(sj5));
05897 IkReal x1952=((IkReal(0.374290000000000))*(cj5));
05898 IkReal x1953=((r02)*(sj0));
05899 IkReal x1954=((r20)*(sj4));
05900 IkReal x1955=((IkReal(1.00000000000000))*(sj0));
05901 IkReal x1956=((IkReal(1.00000000000000))*(cj5));
05902 IkReal x1957=((cj0)*(r10));
05903 IkReal x1958=((cj4)*(cj6));
05904 IkReal x1959=((r00)*(sj0));
05905 IkReal x1960=((cj6)*(r21));
05906 IkReal x1961=((IkReal(0.374290000000000))*(sj5));
05907 IkReal x1962=((cj0)*(r00));
05908 IkReal x1963=((IkReal(0.0100000000000000))*(sj5));
05909 IkReal x1964=((cj0)*(r02));
05910 IkReal x1965=((cj5)*(sj4));
05911 IkReal x1966=((cj6)*(r01));
05912 IkReal x1967=((cj6)*(r11));
05913 IkReal x1968=((r01)*(sj0));
05914 IkReal x1969=((r10)*(sj0));
05915 IkReal x1970=((IkReal(0.0100000000000000))*(cj5)*(cj6));
05916 IkReal x1971=((sj6)*(x1961));
05917 IkReal x1972=((cj0)*(cj6)*(x1961));
05918 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
05919 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x1956)))+(((sj5)*(x1960)))+(((r20)*(sj5)*(sj6))));
05920 evalcond[2]=((IkReal(1.00000000000000))+(((r21)*(x1947)))+(((x1949)*(x1954)))+(((x1960)*(x1965)))+(((IkReal(-1.00000000000000))*(r20)*(x1958)))+(((r22)*(x1950))));
05921 evalcond[3]=((((r20)*(x1971)))+(((IkReal(-0.0100000000000000))*(r20)*(x1949)))+(((IkReal(-1.00000000000000))*(r22)*(x1963)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x1952)))+(((x1960)*(x1961)))+(((IkReal(-0.0100000000000000))*(cj5)*(x1960))));
05922 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x1947)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x1958)))+(((cj6)*(x1954))));
05923 evalcond[5]=((((cj5)*(x1948)*(x1966)))+(((x1957)*(x1958)))+(((x1947)*(x1968)))+(((r00)*(x1948)*(x1949)))+(((IkReal(-1.00000000000000))*(r11)*(x1946)*(x1947)))+(((IkReal(-1.00000000000000))*(x1946)*(x1965)*(x1967)))+(((r02)*(sj5)*(x1948)))+(((IkReal(-1.00000000000000))*(r12)*(x1946)*(x1950)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x1946)*(x1949)))+(((IkReal(-1.00000000000000))*(r00)*(x1955)*(x1958))));
05924 evalcond[6]=((((x1958)*(x1969)))+(((IkReal(-1.00000000000000))*(x1946)*(x1965)*(x1966)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x1946)*(x1949)))+(((IkReal(-1.00000000000000))*(r11)*(x1947)*(x1955)))+(((IkReal(-1.00000000000000))*(r02)*(x1946)*(x1950)))+(((IkReal(-1.00000000000000))*(r10)*(x1948)*(x1949)))+(((IkReal(-1.00000000000000))*(r01)*(x1946)*(x1947)))+(((IkReal(-1.00000000000000))*(x1948)*(x1951)))+(((IkReal(-1.00000000000000))*(x1948)*(x1956)*(x1967)))+(((x1958)*(x1962))));
05925 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x1961)*(x1967)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x1966)))+(((IkReal(-0.0100000000000000))*(x1949)*(x1959)))+(((cj0)*(r12)*(x1952)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1967)))+(((IkReal(-1.00000000000000))*(x1953)*(x1963)))+(((IkReal(-1.00000000000000))*(x1957)*(x1971)))+(((IkReal(-1.00000000000000))*(x1952)*(x1953)))+(((IkReal(0.0100000000000000))*(x1949)*(x1957)))+(((IkReal(0.0100000000000000))*(cj0)*(x1951)))+(((px)*(sj0)))+(((x1959)*(x1971)))+(((IkReal(-1.00000000000000))*(py)*(x1946)))+(((sj0)*(x1961)*(x1966))));
05926 evalcond[8]=((IkReal(-0.295420000000000))+(((r12)*(sj0)*(x1952)))+(((x1963)*(x1964)))+(((IkReal(0.0100000000000000))*(sj0)*(x1951)))+(((IkReal(-1.00000000000000))*(px)*(x1946)))+(((IkReal(-1.00000000000000))*(sj0)*(x1961)*(x1967)))+(((IkReal(0.0100000000000000))*(x1949)*(x1969)))+(((IkReal(-1.00000000000000))*(cj0)*(x1961)*(x1966)))+(((IkReal(-1.00000000000000))*(x1969)*(x1971)))+(((IkReal(-1.00000000000000))*(py)*(x1955)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x1966)))+(((IkReal(-1.00000000000000))*(x1962)*(x1971)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x1967)))+(((IkReal(0.0100000000000000))*(x1949)*(x1962)))+(((x1952)*(x1964))));
05927 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
05928 {
05929 {
05930 IkReal j3array[1], cj3array[1], sj3array[1];
05931 bool j3valid[1]={false};
05932 _nj3 = 1;
05933 IkReal x1973=((sj0)*(sj5));
05934 IkReal x1974=((r00)*(sj6));
05935 IkReal x1975=((IkReal(1.00000000000000))*(cj5));
05936 IkReal x1976=((cj6)*(r11));
05937 IkReal x1977=((cj6)*(r01));
05938 IkReal x1978=((r10)*(sj6));
05939 IkReal x1979=((cj0)*(sj5));
05940 if( IKabs(((((IkReal(-1.00000000000000))*(x1978)*(x1979)))+(((IkReal(-1.00000000000000))*(x1976)*(x1979)))+(((x1973)*(x1974)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1975)))+(((cj0)*(cj5)*(r12)))+(((x1973)*(x1977))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1975)))+(((x1974)*(x1979)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1975)))+(((x1973)*(x1976)))+(((x1973)*(x1978)))+(((x1977)*(x1979))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x1978)*(x1979)))+(((IkReal(-1.00000000000000))*(x1976)*(x1979)))+(((x1973)*(x1974)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1975)))+(((cj0)*(cj5)*(r12)))+(((x1973)*(x1977)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1975)))+(((x1974)*(x1979)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1975)))+(((x1973)*(x1976)))+(((x1973)*(x1978)))+(((x1977)*(x1979)))))-1) <= IKFAST_SINCOS_THRESH )
05941     continue;
05942 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x1978)*(x1979)))+(((IkReal(-1.00000000000000))*(x1976)*(x1979)))+(((x1973)*(x1974)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1975)))+(((cj0)*(cj5)*(r12)))+(((x1973)*(x1977)))), ((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1975)))+(((x1974)*(x1979)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1975)))+(((x1973)*(x1976)))+(((x1973)*(x1978)))+(((x1977)*(x1979)))));
05943 sj3array[0]=IKsin(j3array[0]);
05944 cj3array[0]=IKcos(j3array[0]);
05945 if( j3array[0] > IKPI )
05946 {
05947     j3array[0]-=IK2PI;
05948 }
05949 else if( j3array[0] < -IKPI )
05950 {    j3array[0]+=IK2PI;
05951 }
05952 j3valid[0] = true;
05953 for(int ij3 = 0; ij3 < 1; ++ij3)
05954 {
05955 if( !j3valid[ij3] )
05956 {
05957     continue;
05958 }
05959 _ij3[0] = ij3; _ij3[1] = -1;
05960 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
05961 {
05962 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
05963 {
05964     j3valid[iij3]=false; _ij3[1] = iij3; break; 
05965 }
05966 }
05967 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
05968 {
05969 IkReal evalcond[4];
05970 IkReal x1980=IKcos(j3);
05971 IkReal x1981=IKsin(j3);
05972 IkReal x1982=((sj0)*(sj5));
05973 IkReal x1983=((r00)*(sj6));
05974 IkReal x1984=((cj6)*(sj0));
05975 IkReal x1985=((IkReal(1.00000000000000))*(cj4));
05976 IkReal x1986=((r00)*(sj4));
05977 IkReal x1987=((cj0)*(cj5));
05978 IkReal x1988=((cj5)*(sj0));
05979 IkReal x1989=((cj6)*(r11));
05980 IkReal x1990=((r10)*(sj6));
05981 IkReal x1991=((cj0)*(sj5));
05982 IkReal x1992=((r10)*(sj4));
05983 IkReal x1993=((cj4)*(cj5)*(r01));
05984 IkReal x1994=((IkReal(1.00000000000000))*(cj0)*(cj6));
05985 IkReal x1995=((cj0)*(sj4)*(sj6));
05986 IkReal x1996=((sj0)*(sj4)*(sj6));
05987 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x1988)))+(((x1982)*(x1983)))+(((cj6)*(r01)*(x1982)))+(((IkReal(-1.00000000000000))*(x1989)*(x1991)))+(((IkReal(-1.00000000000000))*(x1981)))+(((IkReal(-1.00000000000000))*(x1990)*(x1991)))+(((r12)*(x1987))));
05988 evalcond[1]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x1991)))+(x1980)+(((r12)*(x1988)))+(((IkReal(-1.00000000000000))*(x1982)*(x1989)))+(((IkReal(-1.00000000000000))*(x1983)*(x1991)))+(((r02)*(x1987)))+(((IkReal(-1.00000000000000))*(x1982)*(x1990))));
05989 evalcond[2]=((((cj4)*(x1983)*(x1988)))+(x1980)+(((r11)*(x1995)))+(((IkReal(-1.00000000000000))*(x1992)*(x1994)))+(((cj4)*(r02)*(x1982)))+(((x1984)*(x1993)))+(((IkReal(-1.00000000000000))*(r12)*(x1985)*(x1991)))+(((IkReal(-1.00000000000000))*(x1985)*(x1987)*(x1990)))+(((IkReal(-1.00000000000000))*(r01)*(x1996)))+(((IkReal(-1.00000000000000))*(x1985)*(x1987)*(x1989)))+(((x1984)*(x1986))));
05990 evalcond[3]=((((IkReal(-1.00000000000000))*(x1984)*(x1992)))+(x1981)+(((IkReal(-1.00000000000000))*(r02)*(x1985)*(x1991)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x1985)*(x1987)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1984)*(x1985)))+(((IkReal(-1.00000000000000))*(x1986)*(x1994)))+(((IkReal(-1.00000000000000))*(x1983)*(x1985)*(x1987)))+(((r01)*(x1995)))+(((r11)*(x1996)))+(((IkReal(-1.00000000000000))*(x1985)*(x1988)*(x1990)))+(((IkReal(-1.00000000000000))*(r12)*(x1982)*(x1985))));
05991 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05992 {
05993 continue;
05994 }
05995 }
05996 
05997 {
05998 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
05999 vinfos[0].jointtype = 1;
06000 vinfos[0].foffset = j0;
06001 vinfos[0].indices[0] = _ij0[0];
06002 vinfos[0].indices[1] = _ij0[1];
06003 vinfos[0].maxsolutions = _nj0;
06004 vinfos[1].jointtype = 1;
06005 vinfos[1].foffset = j1;
06006 vinfos[1].indices[0] = _ij1[0];
06007 vinfos[1].indices[1] = _ij1[1];
06008 vinfos[1].maxsolutions = _nj1;
06009 vinfos[2].jointtype = 1;
06010 vinfos[2].foffset = j2;
06011 vinfos[2].indices[0] = _ij2[0];
06012 vinfos[2].indices[1] = _ij2[1];
06013 vinfos[2].maxsolutions = _nj2;
06014 vinfos[3].jointtype = 1;
06015 vinfos[3].foffset = j3;
06016 vinfos[3].indices[0] = _ij3[0];
06017 vinfos[3].indices[1] = _ij3[1];
06018 vinfos[3].maxsolutions = _nj3;
06019 vinfos[4].jointtype = 1;
06020 vinfos[4].foffset = j4;
06021 vinfos[4].indices[0] = _ij4[0];
06022 vinfos[4].indices[1] = _ij4[1];
06023 vinfos[4].maxsolutions = _nj4;
06024 vinfos[5].jointtype = 1;
06025 vinfos[5].foffset = j5;
06026 vinfos[5].indices[0] = _ij5[0];
06027 vinfos[5].indices[1] = _ij5[1];
06028 vinfos[5].maxsolutions = _nj5;
06029 vinfos[6].jointtype = 1;
06030 vinfos[6].foffset = j6;
06031 vinfos[6].indices[0] = _ij6[0];
06032 vinfos[6].indices[1] = _ij6[1];
06033 vinfos[6].maxsolutions = _nj6;
06034 std::vector<int> vfree(0);
06035 solutions.AddSolution(vinfos,vfree);
06036 }
06037 }
06038 }
06039 
06040 } else
06041 {
06042 IkReal x1997=((IkReal(1.00000000000000))*(cj0));
06043 IkReal x1998=((cj4)*(sj6));
06044 IkReal x1999=((sj0)*(sj4));
06045 IkReal x2000=((cj5)*(sj6));
06046 IkReal x2001=((sj4)*(sj5));
06047 IkReal x2002=((r12)*(sj5));
06048 IkReal x2003=((IkReal(0.374290000000000))*(cj5));
06049 IkReal x2004=((r02)*(sj0));
06050 IkReal x2005=((r20)*(sj4));
06051 IkReal x2006=((IkReal(1.00000000000000))*(sj0));
06052 IkReal x2007=((IkReal(1.00000000000000))*(cj5));
06053 IkReal x2008=((cj0)*(r10));
06054 IkReal x2009=((cj4)*(cj6));
06055 IkReal x2010=((r00)*(sj0));
06056 IkReal x2011=((cj6)*(r21));
06057 IkReal x2012=((IkReal(0.374290000000000))*(sj5));
06058 IkReal x2013=((cj0)*(r00));
06059 IkReal x2014=((IkReal(0.0100000000000000))*(sj5));
06060 IkReal x2015=((cj0)*(r02));
06061 IkReal x2016=((cj5)*(sj4));
06062 IkReal x2017=((cj6)*(r01));
06063 IkReal x2018=((cj6)*(r11));
06064 IkReal x2019=((r01)*(sj0));
06065 IkReal x2020=((r10)*(sj0));
06066 IkReal x2021=((IkReal(0.0100000000000000))*(cj5)*(cj6));
06067 IkReal x2022=((sj6)*(x2012));
06068 IkReal x2023=((cj0)*(cj6)*(x2012));
06069 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
06070 evalcond[1]=((((sj5)*(x2011)))+(((IkReal(-1.00000000000000))*(r22)*(x2007)))+(((r20)*(sj5)*(sj6))));
06071 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x2001)))+(((r21)*(x1998)))+(((x2000)*(x2005)))+(((IkReal(-1.00000000000000))*(r20)*(x2009)))+(((x2011)*(x2016))));
06072 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x2011)))+(((x2011)*(x2012)))+(((IkReal(-1.00000000000000))*(r22)*(x2003)))+(((IkReal(-0.0100000000000000))*(r20)*(x2000)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x2014)))+(((r20)*(x2022))));
06073 evalcond[4]=((((cj5)*(r21)*(x2009)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x2005)))+(((cj5)*(r20)*(x1998))));
06074 evalcond[5]=((((r02)*(sj5)*(x1999)))+(((x1998)*(x2019)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x1997)*(x2000)))+(((x2008)*(x2009)))+(((r00)*(x1999)*(x2000)))+(((IkReal(-1.00000000000000))*(r00)*(x2006)*(x2009)))+(((IkReal(-1.00000000000000))*(x1997)*(x2016)*(x2018)))+(((IkReal(-1.00000000000000))*(r11)*(x1997)*(x1998)))+(((IkReal(-1.00000000000000))*(r12)*(x1997)*(x2001)))+(((cj5)*(x1999)*(x2017))));
06075 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x1997)*(x1998)))+(((IkReal(-1.00000000000000))*(x1999)*(x2002)))+(((x2009)*(x2020)))+(((x2009)*(x2013)))+(((IkReal(-1.00000000000000))*(r10)*(x1999)*(x2000)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x1997)*(x2000)))+(((IkReal(-1.00000000000000))*(r02)*(x1997)*(x2001)))+(((IkReal(-1.00000000000000))*(x1999)*(x2007)*(x2018)))+(((IkReal(-1.00000000000000))*(x1997)*(x2016)*(x2017)))+(((IkReal(-1.00000000000000))*(r11)*(x1998)*(x2006))));
06076 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x2008)*(x2022)))+(((IkReal(-1.00000000000000))*(cj0)*(x2012)*(x2018)))+(((IkReal(-1.00000000000000))*(x2004)*(x2014)))+(((x2010)*(x2022)))+(((IkReal(-1.00000000000000))*(py)*(x1997)))+(((IkReal(0.0100000000000000))*(cj0)*(x2002)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x2017)))+(((IkReal(-0.0100000000000000))*(x2000)*(x2010)))+(((IkReal(-1.00000000000000))*(x2003)*(x2004)))+(((cj0)*(r12)*(x2003)))+(((px)*(sj0)))+(((sj0)*(x2012)*(x2017)))+(((IkReal(0.0100000000000000))*(x2000)*(x2008)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2018))));
06077 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(sj0)*(x2002)))+(((r12)*(sj0)*(x2003)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x2018)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2017)))+(((x2014)*(x2015)))+(((IkReal(-1.00000000000000))*(sj0)*(x2012)*(x2018)))+(((IkReal(0.0100000000000000))*(x2000)*(x2013)))+(((IkReal(-1.00000000000000))*(cj0)*(x2012)*(x2017)))+(((IkReal(-1.00000000000000))*(x2020)*(x2022)))+(((IkReal(-1.00000000000000))*(py)*(x2006)))+(((IkReal(-1.00000000000000))*(x2013)*(x2022)))+(((IkReal(-1.00000000000000))*(px)*(x1997)))+(((IkReal(0.0100000000000000))*(x2000)*(x2020)))+(((x2003)*(x2015))));
06078 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
06079 {
06080 {
06081 IkReal j3array[1], cj3array[1], sj3array[1];
06082 bool j3valid[1]={false};
06083 _nj3 = 1;
06084 IkReal x2024=((IkReal(1.00000000000000))*(cj5));
06085 IkReal x2025=((r10)*(sj5)*(sj6));
06086 IkReal x2026=((cj6)*(sj0)*(sj5));
06087 IkReal x2027=((r00)*(sj5)*(sj6));
06088 IkReal x2028=((cj0)*(cj6)*(sj5));
06089 if( IKabs(((((IkReal(-1.00000000000000))*(r01)*(x2026)))+(((r11)*(x2028)))+(((cj0)*(x2025)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2024)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x2027))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(x2027)))+(((sj0)*(x2025)))+(((r01)*(x2028)))+(((r11)*(x2026)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2024)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2024))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x2026)))+(((r11)*(x2028)))+(((cj0)*(x2025)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2024)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x2027)))))+IKsqr(((((cj0)*(x2027)))+(((sj0)*(x2025)))+(((r01)*(x2028)))+(((r11)*(x2026)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2024)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2024)))))-1) <= IKFAST_SINCOS_THRESH )
06090     continue;
06091 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r01)*(x2026)))+(((r11)*(x2028)))+(((cj0)*(x2025)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2024)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x2027)))), ((((cj0)*(x2027)))+(((sj0)*(x2025)))+(((r01)*(x2028)))+(((r11)*(x2026)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2024)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2024)))));
06092 sj3array[0]=IKsin(j3array[0]);
06093 cj3array[0]=IKcos(j3array[0]);
06094 if( j3array[0] > IKPI )
06095 {
06096     j3array[0]-=IK2PI;
06097 }
06098 else if( j3array[0] < -IKPI )
06099 {    j3array[0]+=IK2PI;
06100 }
06101 j3valid[0] = true;
06102 for(int ij3 = 0; ij3 < 1; ++ij3)
06103 {
06104 if( !j3valid[ij3] )
06105 {
06106     continue;
06107 }
06108 _ij3[0] = ij3; _ij3[1] = -1;
06109 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06110 {
06111 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06112 {
06113     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06114 }
06115 }
06116 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06117 {
06118 IkReal evalcond[4];
06119 IkReal x2029=IKcos(j3);
06120 IkReal x2030=IKsin(j3);
06121 IkReal x2031=((sj0)*(sj5));
06122 IkReal x2032=((r00)*(sj6));
06123 IkReal x2033=((IkReal(1.00000000000000))*(cj4));
06124 IkReal x2034=((cj6)*(sj0));
06125 IkReal x2035=((r00)*(sj4));
06126 IkReal x2036=((cj0)*(cj5));
06127 IkReal x2037=((cj6)*(r01));
06128 IkReal x2038=((cj5)*(sj0));
06129 IkReal x2039=((cj0)*(sj5));
06130 IkReal x2040=((cj6)*(r11));
06131 IkReal x2041=((r10)*(sj6));
06132 IkReal x2042=((r10)*(sj4));
06133 IkReal x2043=((cj0)*(sj4)*(sj6));
06134 IkReal x2044=((sj0)*(sj4)*(sj6));
06135 IkReal x2045=((IkReal(1.00000000000000))*(cj0)*(cj6));
06136 evalcond[0]=((x2030)+(((x2031)*(x2032)))+(((IkReal(-1.00000000000000))*(r02)*(x2038)))+(((IkReal(-1.00000000000000))*(x2039)*(x2040)))+(((r12)*(x2036)))+(((x2031)*(x2037)))+(((IkReal(-1.00000000000000))*(x2039)*(x2041))));
06137 evalcond[1]=((x2029)+(((IkReal(-1.00000000000000))*(x2032)*(x2039)))+(((r02)*(x2036)))+(((IkReal(-1.00000000000000))*(x2031)*(x2041)))+(((IkReal(-1.00000000000000))*(x2037)*(x2039)))+(((r12)*(x2038)))+(((IkReal(-1.00000000000000))*(x2031)*(x2040))));
06138 evalcond[2]=((((IkReal(-1.00000000000000))*(x2029)))+(((cj4)*(x2032)*(x2038)))+(((IkReal(-1.00000000000000))*(x2033)*(x2036)*(x2041)))+(((IkReal(-1.00000000000000))*(r12)*(x2033)*(x2039)))+(((IkReal(-1.00000000000000))*(x2042)*(x2045)))+(((IkReal(-1.00000000000000))*(x2033)*(x2036)*(x2040)))+(((IkReal(-1.00000000000000))*(r01)*(x2044)))+(((r11)*(x2043)))+(((cj4)*(cj5)*(r01)*(x2034)))+(((cj4)*(r02)*(x2031)))+(((x2034)*(x2035))));
06139 evalcond[3]=((x2030)+(((r01)*(x2043)))+(((IkReal(-1.00000000000000))*(r02)*(x2033)*(x2039)))+(((r11)*(x2044)))+(((IkReal(-1.00000000000000))*(x2034)*(x2042)))+(((IkReal(-1.00000000000000))*(r12)*(x2031)*(x2033)))+(((IkReal(-1.00000000000000))*(x2032)*(x2033)*(x2036)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2033)*(x2034)))+(((IkReal(-1.00000000000000))*(x2033)*(x2038)*(x2041)))+(((IkReal(-1.00000000000000))*(x2033)*(x2036)*(x2037)))+(((IkReal(-1.00000000000000))*(x2035)*(x2045))));
06140 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06141 {
06142 continue;
06143 }
06144 }
06145 
06146 {
06147 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06148 vinfos[0].jointtype = 1;
06149 vinfos[0].foffset = j0;
06150 vinfos[0].indices[0] = _ij0[0];
06151 vinfos[0].indices[1] = _ij0[1];
06152 vinfos[0].maxsolutions = _nj0;
06153 vinfos[1].jointtype = 1;
06154 vinfos[1].foffset = j1;
06155 vinfos[1].indices[0] = _ij1[0];
06156 vinfos[1].indices[1] = _ij1[1];
06157 vinfos[1].maxsolutions = _nj1;
06158 vinfos[2].jointtype = 1;
06159 vinfos[2].foffset = j2;
06160 vinfos[2].indices[0] = _ij2[0];
06161 vinfos[2].indices[1] = _ij2[1];
06162 vinfos[2].maxsolutions = _nj2;
06163 vinfos[3].jointtype = 1;
06164 vinfos[3].foffset = j3;
06165 vinfos[3].indices[0] = _ij3[0];
06166 vinfos[3].indices[1] = _ij3[1];
06167 vinfos[3].maxsolutions = _nj3;
06168 vinfos[4].jointtype = 1;
06169 vinfos[4].foffset = j4;
06170 vinfos[4].indices[0] = _ij4[0];
06171 vinfos[4].indices[1] = _ij4[1];
06172 vinfos[4].maxsolutions = _nj4;
06173 vinfos[5].jointtype = 1;
06174 vinfos[5].foffset = j5;
06175 vinfos[5].indices[0] = _ij5[0];
06176 vinfos[5].indices[1] = _ij5[1];
06177 vinfos[5].maxsolutions = _nj5;
06178 vinfos[6].jointtype = 1;
06179 vinfos[6].foffset = j6;
06180 vinfos[6].indices[0] = _ij6[0];
06181 vinfos[6].indices[1] = _ij6[1];
06182 vinfos[6].maxsolutions = _nj6;
06183 std::vector<int> vfree(0);
06184 solutions.AddSolution(vinfos,vfree);
06185 }
06186 }
06187 }
06188 
06189 } else
06190 {
06191 if( 1 )
06192 {
06193 continue;
06194 
06195 } else
06196 {
06197 }
06198 }
06199 }
06200 }
06201 }
06202 }
06203 
06204 } else
06205 {
06206 {
06207 IkReal j3array[1], cj3array[1], sj3array[1];
06208 bool j3valid[1]={false};
06209 _nj3 = 1;
06210 IkReal x2046=((sj0)*(sj5));
06211 IkReal x2047=((r00)*(sj6));
06212 IkReal x2048=((IkReal(1.00000000000000))*(cj5));
06213 IkReal x2049=((cj6)*(r11));
06214 IkReal x2050=((cj6)*(r01));
06215 IkReal x2051=((cj0)*(sj5));
06216 IkReal x2052=((r10)*(sj6));
06217 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x2049)*(x2051)))+(((x2046)*(x2047)))+(((x2046)*(x2050)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2048)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2051)*(x2052))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2048)))+(((x2046)*(x2052)))+(((x2050)*(x2051)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2048)))+(((x2046)*(x2049)))+(((x2047)*(x2051))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x2049)*(x2051)))+(((x2046)*(x2047)))+(((x2046)*(x2050)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2048)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2051)*(x2052)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2048)))+(((x2046)*(x2052)))+(((x2050)*(x2051)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2048)))+(((x2046)*(x2049)))+(((x2047)*(x2051)))))-1) <= IKFAST_SINCOS_THRESH )
06218     continue;
06219 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x2049)*(x2051)))+(((x2046)*(x2047)))+(((x2046)*(x2050)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2048)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2051)*(x2052)))))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2048)))+(((x2046)*(x2052)))+(((x2050)*(x2051)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2048)))+(((x2046)*(x2049)))+(((x2047)*(x2051)))));
06220 sj3array[0]=IKsin(j3array[0]);
06221 cj3array[0]=IKcos(j3array[0]);
06222 if( j3array[0] > IKPI )
06223 {
06224     j3array[0]-=IK2PI;
06225 }
06226 else if( j3array[0] < -IKPI )
06227 {    j3array[0]+=IK2PI;
06228 }
06229 j3valid[0] = true;
06230 for(int ij3 = 0; ij3 < 1; ++ij3)
06231 {
06232 if( !j3valid[ij3] )
06233 {
06234     continue;
06235 }
06236 _ij3[0] = ij3; _ij3[1] = -1;
06237 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06238 {
06239 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06240 {
06241     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06242 }
06243 }
06244 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06245 {
06246 IkReal evalcond[6];
06247 IkReal x2053=IKsin(j3);
06248 IkReal x2054=IKcos(j3);
06249 IkReal x2055=((sj0)*(sj5));
06250 IkReal x2056=((r00)*(sj6));
06251 IkReal x2057=((IkReal(1.00000000000000))*(cj4));
06252 IkReal x2058=((cj6)*(r01));
06253 IkReal x2059=((cj0)*(cj5));
06254 IkReal x2060=((cj5)*(sj0));
06255 IkReal x2061=((cj6)*(r11));
06256 IkReal x2062=((cj6)*(sj4));
06257 IkReal x2063=((cj0)*(sj5));
06258 IkReal x2064=((cj4)*(cj5));
06259 IkReal x2065=((cj6)*(r21));
06260 IkReal x2066=((r20)*(sj6));
06261 IkReal x2067=((r10)*(sj6));
06262 IkReal x2068=((IkReal(1.00000000000000))*(cj0));
06263 IkReal x2069=((cj0)*(sj4)*(sj6));
06264 IkReal x2070=((sj0)*(sj4)*(sj6));
06265 evalcond[0]=((((sj5)*(x2066)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x2053)))+(((sj5)*(x2065))));
06266 evalcond[1]=((((r20)*(x2062)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x2064)*(x2066)))+(((IkReal(-1.00000000000000))*(cj2)*(x2054)))+(((cj4)*(r22)*(sj5)))+(((x2064)*(x2065))));
06267 evalcond[2]=((((x2055)*(x2056)))+(((IkReal(-1.00000000000000))*(x2063)*(x2067)))+(((IkReal(-1.00000000000000))*(r02)*(x2060)))+(((IkReal(-1.00000000000000))*(sj2)*(x2053)))+(((x2055)*(x2058)))+(((r12)*(x2059)))+(((IkReal(-1.00000000000000))*(x2061)*(x2063))));
06268 evalcond[3]=((((IkReal(-1.00000000000000))*(x2055)*(x2061)))+(((r02)*(x2059)))+(((IkReal(-1.00000000000000))*(x2058)*(x2063)))+(x2054)+(((IkReal(-1.00000000000000))*(x2056)*(x2063)))+(((r12)*(x2060)))+(((IkReal(-1.00000000000000))*(x2055)*(x2067))));
06269 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x2070)))+(((IkReal(-1.00000000000000))*(r12)*(x2057)*(x2063)))+(((r00)*(sj0)*(x2062)))+(((cj4)*(r02)*(x2055)))+(((IkReal(-1.00000000000000))*(r10)*(x2062)*(x2068)))+(((IkReal(-1.00000000000000))*(x2057)*(x2059)*(x2061)))+(((r11)*(x2069)))+(((cj4)*(x2058)*(x2060)))+(((IkReal(-1.00000000000000))*(x2057)*(x2059)*(x2067)))+(((cj4)*(x2056)*(x2060)))+(((sj2)*(x2054))));
06270 evalcond[5]=((((IkReal(-1.00000000000000))*(x2057)*(x2058)*(x2059)))+(((IkReal(-1.00000000000000))*(x2057)*(x2060)*(x2061)))+(x2053)+(((IkReal(-1.00000000000000))*(r12)*(x2055)*(x2057)))+(((r01)*(x2069)))+(((IkReal(-1.00000000000000))*(r00)*(x2062)*(x2068)))+(((r11)*(x2070)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2062)))+(((IkReal(-1.00000000000000))*(x2057)*(x2060)*(x2067)))+(((IkReal(-1.00000000000000))*(x2056)*(x2057)*(x2059)))+(((IkReal(-1.00000000000000))*(r02)*(x2057)*(x2063))));
06271 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
06272 {
06273 continue;
06274 }
06275 }
06276 
06277 {
06278 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06279 vinfos[0].jointtype = 1;
06280 vinfos[0].foffset = j0;
06281 vinfos[0].indices[0] = _ij0[0];
06282 vinfos[0].indices[1] = _ij0[1];
06283 vinfos[0].maxsolutions = _nj0;
06284 vinfos[1].jointtype = 1;
06285 vinfos[1].foffset = j1;
06286 vinfos[1].indices[0] = _ij1[0];
06287 vinfos[1].indices[1] = _ij1[1];
06288 vinfos[1].maxsolutions = _nj1;
06289 vinfos[2].jointtype = 1;
06290 vinfos[2].foffset = j2;
06291 vinfos[2].indices[0] = _ij2[0];
06292 vinfos[2].indices[1] = _ij2[1];
06293 vinfos[2].maxsolutions = _nj2;
06294 vinfos[3].jointtype = 1;
06295 vinfos[3].foffset = j3;
06296 vinfos[3].indices[0] = _ij3[0];
06297 vinfos[3].indices[1] = _ij3[1];
06298 vinfos[3].maxsolutions = _nj3;
06299 vinfos[4].jointtype = 1;
06300 vinfos[4].foffset = j4;
06301 vinfos[4].indices[0] = _ij4[0];
06302 vinfos[4].indices[1] = _ij4[1];
06303 vinfos[4].maxsolutions = _nj4;
06304 vinfos[5].jointtype = 1;
06305 vinfos[5].foffset = j5;
06306 vinfos[5].indices[0] = _ij5[0];
06307 vinfos[5].indices[1] = _ij5[1];
06308 vinfos[5].maxsolutions = _nj5;
06309 vinfos[6].jointtype = 1;
06310 vinfos[6].foffset = j6;
06311 vinfos[6].indices[0] = _ij6[0];
06312 vinfos[6].indices[1] = _ij6[1];
06313 vinfos[6].maxsolutions = _nj6;
06314 std::vector<int> vfree(0);
06315 solutions.AddSolution(vinfos,vfree);
06316 }
06317 }
06318 }
06319 
06320 }
06321 
06322 }
06323 
06324 } else
06325 {
06326 {
06327 IkReal j3array[1], cj3array[1], sj3array[1];
06328 bool j3valid[1]={false};
06329 _nj3 = 1;
06330 IkReal x2071=((cj6)*(sj5));
06331 IkReal x2072=((IkReal(1.00000000000000))*(cj5));
06332 IkReal x2073=((sj5)*(sj6));
06333 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2071)))+(((IkReal(-1.00000000000000))*(r20)*(x2073)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r11)*(sj0)*(x2071)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2072)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2072)))+(((cj0)*(r01)*(x2071)))+(((cj0)*(r00)*(x2073)))+(((r10)*(sj0)*(x2073))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2071)))+(((IkReal(-1.00000000000000))*(r20)*(x2073)))+(((cj5)*(r22)))))))+IKsqr(((((r11)*(sj0)*(x2071)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2072)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2072)))+(((cj0)*(r01)*(x2071)))+(((cj0)*(r00)*(x2073)))+(((r10)*(sj0)*(x2073)))))-1) <= IKFAST_SINCOS_THRESH )
06334     continue;
06335 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2071)))+(((IkReal(-1.00000000000000))*(r20)*(x2073)))+(((cj5)*(r22)))))), ((((r11)*(sj0)*(x2071)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2072)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2072)))+(((cj0)*(r01)*(x2071)))+(((cj0)*(r00)*(x2073)))+(((r10)*(sj0)*(x2073)))));
06336 sj3array[0]=IKsin(j3array[0]);
06337 cj3array[0]=IKcos(j3array[0]);
06338 if( j3array[0] > IKPI )
06339 {
06340     j3array[0]-=IK2PI;
06341 }
06342 else if( j3array[0] < -IKPI )
06343 {    j3array[0]+=IK2PI;
06344 }
06345 j3valid[0] = true;
06346 for(int ij3 = 0; ij3 < 1; ++ij3)
06347 {
06348 if( !j3valid[ij3] )
06349 {
06350     continue;
06351 }
06352 _ij3[0] = ij3; _ij3[1] = -1;
06353 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06354 {
06355 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06356 {
06357     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06358 }
06359 }
06360 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06361 {
06362 IkReal evalcond[6];
06363 IkReal x2074=IKsin(j3);
06364 IkReal x2075=IKcos(j3);
06365 IkReal x2076=((sj0)*(sj5));
06366 IkReal x2077=((r00)*(sj6));
06367 IkReal x2078=((IkReal(1.00000000000000))*(cj4));
06368 IkReal x2079=((cj6)*(r01));
06369 IkReal x2080=((cj0)*(cj5));
06370 IkReal x2081=((cj5)*(sj0));
06371 IkReal x2082=((cj6)*(r11));
06372 IkReal x2083=((cj6)*(sj4));
06373 IkReal x2084=((cj0)*(sj5));
06374 IkReal x2085=((cj4)*(cj5));
06375 IkReal x2086=((cj6)*(r21));
06376 IkReal x2087=((r20)*(sj6));
06377 IkReal x2088=((r10)*(sj6));
06378 IkReal x2089=((IkReal(1.00000000000000))*(cj0));
06379 IkReal x2090=((cj0)*(sj4)*(sj6));
06380 IkReal x2091=((sj0)*(sj4)*(sj6));
06381 evalcond[0]=((((sj5)*(x2087)))+(((cj2)*(x2074)))+(((sj5)*(x2086)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
06382 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x2075)))+(((x2085)*(x2087)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x2085)*(x2086)))+(((r20)*(x2083))));
06383 evalcond[2]=((((IkReal(-1.00000000000000))*(x2084)*(x2088)))+(((IkReal(-1.00000000000000))*(sj2)*(x2074)))+(((x2076)*(x2079)))+(((IkReal(-1.00000000000000))*(x2082)*(x2084)))+(((x2076)*(x2077)))+(((r12)*(x2080)))+(((IkReal(-1.00000000000000))*(r02)*(x2081))));
06384 evalcond[3]=((x2075)+(((IkReal(-1.00000000000000))*(x2076)*(x2082)))+(((r12)*(x2081)))+(((r02)*(x2080)))+(((IkReal(-1.00000000000000))*(x2077)*(x2084)))+(((IkReal(-1.00000000000000))*(x2076)*(x2088)))+(((IkReal(-1.00000000000000))*(x2079)*(x2084))));
06385 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x2083)*(x2089)))+(((IkReal(-1.00000000000000))*(x2078)*(x2080)*(x2082)))+(((r00)*(sj0)*(x2083)))+(((IkReal(-1.00000000000000))*(r12)*(x2078)*(x2084)))+(((cj4)*(r02)*(x2076)))+(((r11)*(x2090)))+(((sj2)*(x2075)))+(((IkReal(-1.00000000000000))*(x2078)*(x2080)*(x2088)))+(((cj4)*(x2077)*(x2081)))+(((cj4)*(x2079)*(x2081)))+(((IkReal(-1.00000000000000))*(r01)*(x2091))));
06386 evalcond[5]=((x2074)+(((r01)*(x2090)))+(((IkReal(-1.00000000000000))*(x2078)*(x2079)*(x2080)))+(((IkReal(-1.00000000000000))*(x2078)*(x2081)*(x2082)))+(((IkReal(-1.00000000000000))*(x2077)*(x2078)*(x2080)))+(((IkReal(-1.00000000000000))*(r12)*(x2076)*(x2078)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2083)))+(((r11)*(x2091)))+(((IkReal(-1.00000000000000))*(r00)*(x2083)*(x2089)))+(((IkReal(-1.00000000000000))*(r02)*(x2078)*(x2084)))+(((IkReal(-1.00000000000000))*(x2078)*(x2081)*(x2088))));
06387 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
06388 {
06389 continue;
06390 }
06391 }
06392 
06393 {
06394 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06395 vinfos[0].jointtype = 1;
06396 vinfos[0].foffset = j0;
06397 vinfos[0].indices[0] = _ij0[0];
06398 vinfos[0].indices[1] = _ij0[1];
06399 vinfos[0].maxsolutions = _nj0;
06400 vinfos[1].jointtype = 1;
06401 vinfos[1].foffset = j1;
06402 vinfos[1].indices[0] = _ij1[0];
06403 vinfos[1].indices[1] = _ij1[1];
06404 vinfos[1].maxsolutions = _nj1;
06405 vinfos[2].jointtype = 1;
06406 vinfos[2].foffset = j2;
06407 vinfos[2].indices[0] = _ij2[0];
06408 vinfos[2].indices[1] = _ij2[1];
06409 vinfos[2].maxsolutions = _nj2;
06410 vinfos[3].jointtype = 1;
06411 vinfos[3].foffset = j3;
06412 vinfos[3].indices[0] = _ij3[0];
06413 vinfos[3].indices[1] = _ij3[1];
06414 vinfos[3].maxsolutions = _nj3;
06415 vinfos[4].jointtype = 1;
06416 vinfos[4].foffset = j4;
06417 vinfos[4].indices[0] = _ij4[0];
06418 vinfos[4].indices[1] = _ij4[1];
06419 vinfos[4].maxsolutions = _nj4;
06420 vinfos[5].jointtype = 1;
06421 vinfos[5].foffset = j5;
06422 vinfos[5].indices[0] = _ij5[0];
06423 vinfos[5].indices[1] = _ij5[1];
06424 vinfos[5].maxsolutions = _nj5;
06425 vinfos[6].jointtype = 1;
06426 vinfos[6].foffset = j6;
06427 vinfos[6].indices[0] = _ij6[0];
06428 vinfos[6].indices[1] = _ij6[1];
06429 vinfos[6].maxsolutions = _nj6;
06430 std::vector<int> vfree(0);
06431 solutions.AddSolution(vinfos,vfree);
06432 }
06433 }
06434 }
06435 
06436 }
06437 
06438 }
06439 
06440 } else
06441 {
06442 {
06443 IkReal j3array[1], cj3array[1], sj3array[1];
06444 bool j3valid[1]={false};
06445 _nj3 = 1;
06446 IkReal x2092=((IkReal(1.00000000000000))*(r21));
06447 IkReal x2093=((cj4)*(cj5));
06448 IkReal x2094=((r20)*(sj6));
06449 if( IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2092)))+(((IkReal(-1.00000000000000))*(sj5)*(x2094)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((x2093)*(x2094)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2092)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x2093))))))) < IKFAST_ATAN2_MAGTHRESH )
06450     continue;
06451 j3array[0]=IKatan2(((gconst56)*(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2092)))+(((IkReal(-1.00000000000000))*(sj5)*(x2094)))+(((cj5)*(r22)))))), ((gconst56)*(((((x2093)*(x2094)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2092)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x2093)))))));
06452 sj3array[0]=IKsin(j3array[0]);
06453 cj3array[0]=IKcos(j3array[0]);
06454 if( j3array[0] > IKPI )
06455 {
06456     j3array[0]-=IK2PI;
06457 }
06458 else if( j3array[0] < -IKPI )
06459 {    j3array[0]+=IK2PI;
06460 }
06461 j3valid[0] = true;
06462 for(int ij3 = 0; ij3 < 1; ++ij3)
06463 {
06464 if( !j3valid[ij3] )
06465 {
06466     continue;
06467 }
06468 _ij3[0] = ij3; _ij3[1] = -1;
06469 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06470 {
06471 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06472 {
06473     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06474 }
06475 }
06476 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06477 {
06478 IkReal evalcond[6];
06479 IkReal x2095=IKsin(j3);
06480 IkReal x2096=IKcos(j3);
06481 IkReal x2097=((sj0)*(sj5));
06482 IkReal x2098=((r00)*(sj6));
06483 IkReal x2099=((IkReal(1.00000000000000))*(cj4));
06484 IkReal x2100=((cj6)*(r01));
06485 IkReal x2101=((cj0)*(cj5));
06486 IkReal x2102=((cj5)*(sj0));
06487 IkReal x2103=((cj6)*(r11));
06488 IkReal x2104=((cj6)*(sj4));
06489 IkReal x2105=((cj0)*(sj5));
06490 IkReal x2106=((cj4)*(cj5));
06491 IkReal x2107=((cj6)*(r21));
06492 IkReal x2108=((r20)*(sj6));
06493 IkReal x2109=((r10)*(sj6));
06494 IkReal x2110=((IkReal(1.00000000000000))*(cj0));
06495 IkReal x2111=((cj0)*(sj4)*(sj6));
06496 IkReal x2112=((sj0)*(sj4)*(sj6));
06497 evalcond[0]=((((sj5)*(x2108)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x2095)))+(((sj5)*(x2107))));
06498 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x2096)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x2106)*(x2108)))+(((cj4)*(r22)*(sj5)))+(((x2106)*(x2107)))+(((r20)*(x2104))));
06499 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x2095)))+(((IkReal(-1.00000000000000))*(x2103)*(x2105)))+(((IkReal(-1.00000000000000))*(x2105)*(x2109)))+(((x2097)*(x2098)))+(((r12)*(x2101)))+(((x2097)*(x2100)))+(((IkReal(-1.00000000000000))*(r02)*(x2102))));
06500 evalcond[3]=((x2096)+(((IkReal(-1.00000000000000))*(x2098)*(x2105)))+(((IkReal(-1.00000000000000))*(x2100)*(x2105)))+(((r12)*(x2102)))+(((r02)*(x2101)))+(((IkReal(-1.00000000000000))*(x2097)*(x2103)))+(((IkReal(-1.00000000000000))*(x2097)*(x2109))));
06501 evalcond[4]=((((IkReal(-1.00000000000000))*(x2099)*(x2101)*(x2103)))+(((IkReal(-1.00000000000000))*(r10)*(x2104)*(x2110)))+(((sj2)*(x2096)))+(((cj4)*(r02)*(x2097)))+(((cj4)*(x2100)*(x2102)))+(((cj4)*(x2098)*(x2102)))+(((IkReal(-1.00000000000000))*(r12)*(x2099)*(x2105)))+(((IkReal(-1.00000000000000))*(x2099)*(x2101)*(x2109)))+(((IkReal(-1.00000000000000))*(r01)*(x2112)))+(((r11)*(x2111)))+(((r00)*(sj0)*(x2104))));
06502 evalcond[5]=((((IkReal(-1.00000000000000))*(x2099)*(x2100)*(x2101)))+(((IkReal(-1.00000000000000))*(r00)*(x2104)*(x2110)))+(((r01)*(x2111)))+(((IkReal(-1.00000000000000))*(x2098)*(x2099)*(x2101)))+(x2095)+(((r11)*(x2112)))+(((IkReal(-1.00000000000000))*(r12)*(x2097)*(x2099)))+(((IkReal(-1.00000000000000))*(r02)*(x2099)*(x2105)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2104)))+(((IkReal(-1.00000000000000))*(x2099)*(x2102)*(x2109)))+(((IkReal(-1.00000000000000))*(x2099)*(x2102)*(x2103))));
06503 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
06504 {
06505 continue;
06506 }
06507 }
06508 
06509 {
06510 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06511 vinfos[0].jointtype = 1;
06512 vinfos[0].foffset = j0;
06513 vinfos[0].indices[0] = _ij0[0];
06514 vinfos[0].indices[1] = _ij0[1];
06515 vinfos[0].maxsolutions = _nj0;
06516 vinfos[1].jointtype = 1;
06517 vinfos[1].foffset = j1;
06518 vinfos[1].indices[0] = _ij1[0];
06519 vinfos[1].indices[1] = _ij1[1];
06520 vinfos[1].maxsolutions = _nj1;
06521 vinfos[2].jointtype = 1;
06522 vinfos[2].foffset = j2;
06523 vinfos[2].indices[0] = _ij2[0];
06524 vinfos[2].indices[1] = _ij2[1];
06525 vinfos[2].maxsolutions = _nj2;
06526 vinfos[3].jointtype = 1;
06527 vinfos[3].foffset = j3;
06528 vinfos[3].indices[0] = _ij3[0];
06529 vinfos[3].indices[1] = _ij3[1];
06530 vinfos[3].maxsolutions = _nj3;
06531 vinfos[4].jointtype = 1;
06532 vinfos[4].foffset = j4;
06533 vinfos[4].indices[0] = _ij4[0];
06534 vinfos[4].indices[1] = _ij4[1];
06535 vinfos[4].maxsolutions = _nj4;
06536 vinfos[5].jointtype = 1;
06537 vinfos[5].foffset = j5;
06538 vinfos[5].indices[0] = _ij5[0];
06539 vinfos[5].indices[1] = _ij5[1];
06540 vinfos[5].maxsolutions = _nj5;
06541 vinfos[6].jointtype = 1;
06542 vinfos[6].foffset = j6;
06543 vinfos[6].indices[0] = _ij6[0];
06544 vinfos[6].indices[1] = _ij6[1];
06545 vinfos[6].maxsolutions = _nj6;
06546 std::vector<int> vfree(0);
06547 solutions.AddSolution(vinfos,vfree);
06548 }
06549 }
06550 }
06551 
06552 }
06553 
06554 }
06555 }
06556 }
06557 
06558 }
06559 
06560 }
06561 
06562 } else
06563 {
06564 {
06565 IkReal j4array[1], cj4array[1], sj4array[1];
06566 bool j4valid[1]={false};
06567 _nj4 = 1;
06568 IkReal x2113=((r11)*(sj0));
06569 IkReal x2114=((cj0)*(r01));
06570 IkReal x2115=((cj0)*(sj2));
06571 IkReal x2116=((sj0)*(sj2));
06572 IkReal x2117=((cj5)*(sj6));
06573 IkReal x2118=((IkReal(1.00000000000000))*(sj2)*(sj6));
06574 IkReal x2119=((cj5)*(cj6)*(sj2));
06575 if( IKabs(((gconst53)*(((((cj6)*(r00)*(x2115)))+(((IkReal(-1.00000000000000))*(x2114)*(x2118)))+(((cj6)*(r10)*(x2116)))+(((IkReal(-1.00000000000000))*(x2113)*(x2118))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((x2114)*(x2119)))+(((r02)*(sj5)*(x2115)))+(((r00)*(x2115)*(x2117)))+(((r10)*(x2116)*(x2117)))+(((x2113)*(x2119)))+(((r12)*(sj5)*(x2116))))))) < IKFAST_ATAN2_MAGTHRESH )
06576     continue;
06577 j4array[0]=IKatan2(((gconst53)*(((((cj6)*(r00)*(x2115)))+(((IkReal(-1.00000000000000))*(x2114)*(x2118)))+(((cj6)*(r10)*(x2116)))+(((IkReal(-1.00000000000000))*(x2113)*(x2118)))))), ((gconst53)*(((((x2114)*(x2119)))+(((r02)*(sj5)*(x2115)))+(((r00)*(x2115)*(x2117)))+(((r10)*(x2116)*(x2117)))+(((x2113)*(x2119)))+(((r12)*(sj5)*(x2116)))))));
06578 sj4array[0]=IKsin(j4array[0]);
06579 cj4array[0]=IKcos(j4array[0]);
06580 if( j4array[0] > IKPI )
06581 {
06582     j4array[0]-=IK2PI;
06583 }
06584 else if( j4array[0] < -IKPI )
06585 {    j4array[0]+=IK2PI;
06586 }
06587 j4valid[0] = true;
06588 for(int ij4 = 0; ij4 < 1; ++ij4)
06589 {
06590 if( !j4valid[ij4] )
06591 {
06592     continue;
06593 }
06594 _ij4[0] = ij4; _ij4[1] = -1;
06595 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
06596 {
06597 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
06598 {
06599     j4valid[iij4]=false; _ij4[1] = iij4; break; 
06600 }
06601 }
06602 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
06603 {
06604 IkReal evalcond[3];
06605 IkReal x2120=IKsin(j4);
06606 IkReal x2121=IKcos(j4);
06607 IkReal x2122=((r00)*(sj6));
06608 IkReal x2123=((cj6)*(r01));
06609 IkReal x2124=((IkReal(1.00000000000000))*(cj0));
06610 IkReal x2125=((IkReal(1.00000000000000))*(sj0));
06611 IkReal x2126=((r10)*(sj6));
06612 IkReal x2127=((sj5)*(x2120));
06613 IkReal x2128=((IkReal(1.00000000000000))*(cj6)*(r11));
06614 IkReal x2129=((cj5)*(x2120));
06615 IkReal x2130=((cj6)*(x2121));
06616 IkReal x2131=((sj0)*(x2129));
06617 IkReal x2132=((r01)*(sj6)*(x2121));
06618 IkReal x2133=((r11)*(sj6)*(x2121));
06619 evalcond[0]=((sj2)+(((cj6)*(r21)*(x2129)))+(((IkReal(-1.00000000000000))*(r20)*(x2130)))+(((r21)*(sj6)*(x2121)))+(((r20)*(sj6)*(x2129)))+(((r22)*(x2127))));
06620 evalcond[1]=((((sj0)*(x2132)))+(((x2123)*(x2131)))+(((IkReal(-1.00000000000000))*(r12)*(x2124)*(x2127)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2124)*(x2129)))+(((IkReal(-1.00000000000000))*(r00)*(x2125)*(x2130)))+(((IkReal(-1.00000000000000))*(x2124)*(x2126)*(x2129)))+(((cj0)*(r10)*(x2130)))+(cj2)+(((r02)*(sj0)*(x2127)))+(((IkReal(-1.00000000000000))*(x2124)*(x2133)))+(((x2122)*(x2131))));
06621 evalcond[2]=((((IkReal(-1.00000000000000))*(x2125)*(x2133)))+(((IkReal(-1.00000000000000))*(x2125)*(x2126)*(x2129)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2125)*(x2129)))+(((IkReal(-1.00000000000000))*(x2123)*(x2124)*(x2129)))+(((IkReal(-1.00000000000000))*(x2124)*(x2132)))+(((IkReal(-1.00000000000000))*(r12)*(x2125)*(x2127)))+(((IkReal(-1.00000000000000))*(r02)*(x2124)*(x2127)))+(((IkReal(-1.00000000000000))*(x2122)*(x2124)*(x2129)))+(((r10)*(sj0)*(x2130)))+(((cj0)*(r00)*(x2130))));
06622 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
06623 {
06624 continue;
06625 }
06626 }
06627 
06628 {
06629 IkReal dummyeval[1];
06630 IkReal gconst56;
06631 gconst56=IKsign(cj2);
06632 dummyeval[0]=cj2;
06633 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06634 {
06635 {
06636 IkReal dummyeval[1];
06637 dummyeval[0]=cj2;
06638 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06639 {
06640 {
06641 IkReal dummyeval[1];
06642 dummyeval[0]=sj2;
06643 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06644 {
06645 {
06646 IkReal evalcond[9];
06647 IkReal x2134=((cj5)*(sj4));
06648 IkReal x2135=((IkReal(1.00000000000000))*(sj6));
06649 IkReal x2136=((r10)*(sj0));
06650 IkReal x2137=((sj4)*(sj5));
06651 IkReal x2138=((cj5)*(cj6));
06652 IkReal x2139=((r01)*(sj0));
06653 IkReal x2140=((IkReal(1.00000000000000))*(r02));
06654 IkReal x2141=((IkReal(0.374290000000000))*(cj0));
06655 IkReal x2142=((cj5)*(r12));
06656 IkReal x2143=((cj6)*(sj5));
06657 IkReal x2144=((cj0)*(r11));
06658 IkReal x2145=((cj5)*(sj0));
06659 IkReal x2146=((r20)*(sj6));
06660 IkReal x2147=((IkReal(1.00000000000000))*(sj0));
06661 IkReal x2148=((cj4)*(cj5));
06662 IkReal x2149=((IkReal(1.00000000000000))*(cj6));
06663 IkReal x2150=((IkReal(0.0100000000000000))*(sj5));
06664 IkReal x2151=((sj5)*(sj6));
06665 IkReal x2152=((cj0)*(r10));
06666 IkReal x2153=((cj4)*(cj6));
06667 IkReal x2154=((cj0)*(r01));
06668 IkReal x2155=((IkReal(1.00000000000000))*(cj4));
06669 IkReal x2156=((cj0)*(r00));
06670 IkReal x2157=((IkReal(0.374290000000000))*(sj0));
06671 IkReal x2158=((cj0)*(r12));
06672 IkReal x2159=((IkReal(0.374290000000000))*(sj5));
06673 IkReal x2160=((cj4)*(sj6));
06674 IkReal x2161=((IkReal(1.00000000000000))*(cj0));
06675 IkReal x2162=((r02)*(sj0));
06676 IkReal x2163=((IkReal(0.0100000000000000))*(cj5));
06677 IkReal x2164=((r11)*(sj0));
06678 IkReal x2165=((r00)*(sj0)*(sj6));
06679 IkReal x2166=((r00)*(x2153));
06680 IkReal x2167=((sj6)*(x2163));
06681 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
06682 evalcond[1]=((((r22)*(x2137)))+(((x2134)*(x2146)))+(((cj6)*(r21)*(x2134)))+(((r21)*(x2160)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x2149))));
06683 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(0.374290000000000))*(r21)*(x2143)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x2150)))+(((x2146)*(x2159)))+(((IkReal(-1.00000000000000))*(x2146)*(x2163)))+(((IkReal(-0.0100000000000000))*(r21)*(x2138))));
06684 evalcond[3]=((((IkReal(-1.00000000000000))*(x2143)*(x2144)))+(((r00)*(sj0)*(x2151)))+(((IkReal(-1.00000000000000))*(x2140)*(x2145)))+(((x2139)*(x2143)))+(((cj0)*(x2142)))+(((IkReal(-1.00000000000000))*(sj5)*(x2135)*(x2152))));
06685 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2147)*(x2166)))+(((IkReal(-1.00000000000000))*(cj4)*(x2135)*(x2144)))+(((IkReal(-1.00000000000000))*(x2134)*(x2144)*(x2149)))+(((IkReal(-1.00000000000000))*(x2137)*(x2158)))+(((x2139)*(x2160)))+(((cj6)*(x2134)*(x2139)))+(((x2134)*(x2165)))+(((x2152)*(x2153)))+(((x2137)*(x2162)))+(((IkReal(-1.00000000000000))*(x2134)*(x2135)*(x2152))));
06686 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x2135)*(x2139)))+(((sj4)*(sj6)*(x2144)))+(((cj4)*(sj5)*(x2162)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x2135)*(x2148)*(x2152)))+(((IkReal(-1.00000000000000))*(sj4)*(x2149)*(x2152)))+(((IkReal(-1.00000000000000))*(x2138)*(x2144)*(x2155)))+(((cj4)*(x2138)*(x2139)))+(((r00)*(x2145)*(x2160)))+(((IkReal(-1.00000000000000))*(sj5)*(x2155)*(x2158))));
06687 evalcond[6]=((((IkReal(-1.00000000000000))*(x2134)*(x2135)*(x2136)))+(((IkReal(-1.00000000000000))*(r12)*(x2137)*(x2147)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2134)*(x2147)))+(((x2136)*(x2153)))+(((x2153)*(x2156)))+(((IkReal(-1.00000000000000))*(cj4)*(x2135)*(x2154)))+(((IkReal(-1.00000000000000))*(x2134)*(x2135)*(x2156)))+(((IkReal(-1.00000000000000))*(cj0)*(x2137)*(x2140)))+(((IkReal(-1.00000000000000))*(x2134)*(x2149)*(x2154)))+(((IkReal(-1.00000000000000))*(cj4)*(x2135)*(x2164))));
06688 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x2141)*(x2143)))+(((IkReal(-0.374290000000000))*(r02)*(x2145)))+(((IkReal(0.374290000000000))*(x2139)*(x2143)))+(((x2152)*(x2167)))+(((IkReal(0.0100000000000000))*(x2138)*(x2144)))+(((x2150)*(x2158)))+(((IkReal(-1.00000000000000))*(py)*(x2161)))+(((IkReal(-1.00000000000000))*(r10)*(x2141)*(x2151)))+(((IkReal(-0.0100000000000000))*(x2138)*(x2139)))+(((x2141)*(x2142)))+(((px)*(sj0)))+(((r00)*(x2151)*(x2157)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x2145)))+(((IkReal(-1.00000000000000))*(x2150)*(x2162))));
06689 evalcond[8]=((IkReal(-0.295420000000000))+(((x2136)*(x2167)))+(((cj5)*(r02)*(x2141)))+(((IkReal(-1.00000000000000))*(py)*(x2147)))+(((IkReal(0.0100000000000000))*(x2138)*(x2164)))+(((r12)*(sj0)*(x2150)))+(((IkReal(0.0100000000000000))*(x2138)*(x2154)))+(((IkReal(-1.00000000000000))*(r01)*(x2141)*(x2143)))+(((x2142)*(x2157)))+(((IkReal(-1.00000000000000))*(r00)*(x2141)*(x2151)))+(((IkReal(-1.00000000000000))*(r11)*(x2143)*(x2157)))+(((IkReal(-0.374290000000000))*(x2136)*(x2151)))+(((cj0)*(r02)*(x2150)))+(((x2156)*(x2167)))+(((IkReal(-1.00000000000000))*(px)*(x2161))));
06690 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
06691 {
06692 {
06693 IkReal j3array[1], cj3array[1], sj3array[1];
06694 bool j3valid[1]={false};
06695 _nj3 = 1;
06696 IkReal x2168=((IkReal(1.00000000000000))*(r21));
06697 IkReal x2169=((cj4)*(cj5));
06698 IkReal x2170=((r20)*(sj6));
06699 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x2170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2168))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2168)))+(((cj4)*(r22)*(sj5)))+(((x2169)*(x2170)))+(((cj6)*(r21)*(x2169))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x2170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2168)))))+IKsqr(((((cj6)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2168)))+(((cj4)*(r22)*(sj5)))+(((x2169)*(x2170)))+(((cj6)*(r21)*(x2169)))))-1) <= IKFAST_SINCOS_THRESH )
06700     continue;
06701 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x2170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2168)))), ((((cj6)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2168)))+(((cj4)*(r22)*(sj5)))+(((x2169)*(x2170)))+(((cj6)*(r21)*(x2169)))));
06702 sj3array[0]=IKsin(j3array[0]);
06703 cj3array[0]=IKcos(j3array[0]);
06704 if( j3array[0] > IKPI )
06705 {
06706     j3array[0]-=IK2PI;
06707 }
06708 else if( j3array[0] < -IKPI )
06709 {    j3array[0]+=IK2PI;
06710 }
06711 j3valid[0] = true;
06712 for(int ij3 = 0; ij3 < 1; ++ij3)
06713 {
06714 if( !j3valid[ij3] )
06715 {
06716     continue;
06717 }
06718 _ij3[0] = ij3; _ij3[1] = -1;
06719 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06720 {
06721 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06722 {
06723     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06724 }
06725 }
06726 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06727 {
06728 IkReal evalcond[4];
06729 IkReal x2171=IKcos(j3);
06730 IkReal x2172=IKsin(j3);
06731 IkReal x2173=((IkReal(1.00000000000000))*(cj4));
06732 IkReal x2174=((sj0)*(sj5));
06733 IkReal x2175=((cj0)*(cj5));
06734 IkReal x2176=((cj6)*(r01));
06735 IkReal x2177=((r00)*(sj6));
06736 IkReal x2178=((cj6)*(r11));
06737 IkReal x2179=((cj5)*(sj0));
06738 IkReal x2180=((cj6)*(sj4));
06739 IkReal x2181=((sj4)*(sj6));
06740 IkReal x2182=((cj4)*(cj5));
06741 IkReal x2183=((cj6)*(r21));
06742 IkReal x2184=((r20)*(sj6));
06743 IkReal x2185=((r10)*(sj6));
06744 IkReal x2186=((IkReal(1.00000000000000))*(cj0)*(sj5));
06745 evalcond[0]=((x2172)+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x2184)))+(((sj5)*(x2183))));
06746 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x2181)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x2171)))+(((x2182)*(x2183)))+(((x2182)*(x2184)))+(((r20)*(x2180))));
06747 evalcond[2]=((x2171)+(((IkReal(-1.00000000000000))*(x2176)*(x2186)))+(((r02)*(x2175)))+(((IkReal(-1.00000000000000))*(x2174)*(x2185)))+(((IkReal(-1.00000000000000))*(x2174)*(x2178)))+(((r12)*(x2179)))+(((IkReal(-1.00000000000000))*(x2177)*(x2186))));
06748 evalcond[3]=((((cj0)*(r01)*(x2181)))+(x2172)+(((r11)*(sj0)*(x2181)))+(((IkReal(-1.00000000000000))*(x2173)*(x2179)*(x2185)))+(((IkReal(-1.00000000000000))*(x2173)*(x2175)*(x2177)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x2180)))+(((IkReal(-1.00000000000000))*(x2173)*(x2178)*(x2179)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x2173)))+(((IkReal(-1.00000000000000))*(r12)*(x2173)*(x2174)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2180)))+(((IkReal(-1.00000000000000))*(x2173)*(x2175)*(x2176))));
06749 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06750 {
06751 continue;
06752 }
06753 }
06754 
06755 {
06756 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06757 vinfos[0].jointtype = 1;
06758 vinfos[0].foffset = j0;
06759 vinfos[0].indices[0] = _ij0[0];
06760 vinfos[0].indices[1] = _ij0[1];
06761 vinfos[0].maxsolutions = _nj0;
06762 vinfos[1].jointtype = 1;
06763 vinfos[1].foffset = j1;
06764 vinfos[1].indices[0] = _ij1[0];
06765 vinfos[1].indices[1] = _ij1[1];
06766 vinfos[1].maxsolutions = _nj1;
06767 vinfos[2].jointtype = 1;
06768 vinfos[2].foffset = j2;
06769 vinfos[2].indices[0] = _ij2[0];
06770 vinfos[2].indices[1] = _ij2[1];
06771 vinfos[2].maxsolutions = _nj2;
06772 vinfos[3].jointtype = 1;
06773 vinfos[3].foffset = j3;
06774 vinfos[3].indices[0] = _ij3[0];
06775 vinfos[3].indices[1] = _ij3[1];
06776 vinfos[3].maxsolutions = _nj3;
06777 vinfos[4].jointtype = 1;
06778 vinfos[4].foffset = j4;
06779 vinfos[4].indices[0] = _ij4[0];
06780 vinfos[4].indices[1] = _ij4[1];
06781 vinfos[4].maxsolutions = _nj4;
06782 vinfos[5].jointtype = 1;
06783 vinfos[5].foffset = j5;
06784 vinfos[5].indices[0] = _ij5[0];
06785 vinfos[5].indices[1] = _ij5[1];
06786 vinfos[5].maxsolutions = _nj5;
06787 vinfos[6].jointtype = 1;
06788 vinfos[6].foffset = j6;
06789 vinfos[6].indices[0] = _ij6[0];
06790 vinfos[6].indices[1] = _ij6[1];
06791 vinfos[6].maxsolutions = _nj6;
06792 std::vector<int> vfree(0);
06793 solutions.AddSolution(vinfos,vfree);
06794 }
06795 }
06796 }
06797 
06798 } else
06799 {
06800 IkReal x2187=((cj5)*(sj4));
06801 IkReal x2188=((IkReal(1.00000000000000))*(sj6));
06802 IkReal x2189=((r10)*(sj0));
06803 IkReal x2190=((sj4)*(sj5));
06804 IkReal x2191=((cj5)*(cj6));
06805 IkReal x2192=((r01)*(sj0));
06806 IkReal x2193=((IkReal(1.00000000000000))*(r02));
06807 IkReal x2194=((IkReal(0.374290000000000))*(cj0));
06808 IkReal x2195=((cj5)*(r12));
06809 IkReal x2196=((cj6)*(sj5));
06810 IkReal x2197=((cj0)*(r11));
06811 IkReal x2198=((cj5)*(sj0));
06812 IkReal x2199=((r20)*(sj6));
06813 IkReal x2200=((IkReal(1.00000000000000))*(sj0));
06814 IkReal x2201=((cj4)*(cj5));
06815 IkReal x2202=((IkReal(1.00000000000000))*(cj6));
06816 IkReal x2203=((IkReal(0.0100000000000000))*(sj5));
06817 IkReal x2204=((sj5)*(sj6));
06818 IkReal x2205=((cj0)*(r10));
06819 IkReal x2206=((cj4)*(cj6));
06820 IkReal x2207=((cj0)*(r01));
06821 IkReal x2208=((IkReal(1.00000000000000))*(cj4));
06822 IkReal x2209=((cj0)*(r00));
06823 IkReal x2210=((IkReal(0.374290000000000))*(sj0));
06824 IkReal x2211=((cj0)*(r12));
06825 IkReal x2212=((IkReal(0.374290000000000))*(sj5));
06826 IkReal x2213=((cj4)*(sj6));
06827 IkReal x2214=((IkReal(1.00000000000000))*(cj0));
06828 IkReal x2215=((r02)*(sj0));
06829 IkReal x2216=((IkReal(0.0100000000000000))*(cj5));
06830 IkReal x2217=((r11)*(sj0));
06831 IkReal x2218=((r00)*(sj0)*(sj6));
06832 IkReal x2219=((r00)*(x2206));
06833 IkReal x2220=((sj6)*(x2216));
06834 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
06835 evalcond[1]=((((r22)*(x2190)))+(((r21)*(x2213)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x2202)))+(((x2187)*(x2199)))+(((cj6)*(r21)*(x2187))));
06836 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x2203)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x2191)))+(((IkReal(0.374290000000000))*(r21)*(x2196)))+(((IkReal(-1.00000000000000))*(x2199)*(x2216)))+(((x2199)*(x2212)))+(pz));
06837 evalcond[3]=((((cj0)*(x2195)))+(((IkReal(-1.00000000000000))*(x2196)*(x2197)))+(((r00)*(sj0)*(x2204)))+(((x2192)*(x2196)))+(((IkReal(-1.00000000000000))*(x2193)*(x2198)))+(((IkReal(-1.00000000000000))*(sj5)*(x2188)*(x2205))));
06838 evalcond[4]=((IkReal(-1.00000000000000))+(((x2192)*(x2213)))+(((IkReal(-1.00000000000000))*(x2187)*(x2197)*(x2202)))+(((IkReal(-1.00000000000000))*(x2190)*(x2211)))+(((IkReal(-1.00000000000000))*(x2200)*(x2219)))+(((x2187)*(x2218)))+(((IkReal(-1.00000000000000))*(cj4)*(x2188)*(x2197)))+(((x2190)*(x2215)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2205)))+(((cj6)*(x2187)*(x2192)))+(((x2205)*(x2206))));
06839 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x2202)*(x2205)))+(((IkReal(-1.00000000000000))*(x2191)*(x2197)*(x2208)))+(((sj4)*(sj6)*(x2197)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x2188)*(x2192)))+(((cj4)*(x2191)*(x2192)))+(((cj4)*(sj5)*(x2215)))+(((r00)*(x2198)*(x2213)))+(((IkReal(-1.00000000000000))*(x2188)*(x2201)*(x2205)))+(((IkReal(-1.00000000000000))*(sj5)*(x2208)*(x2211))));
06840 evalcond[6]=((((x2189)*(x2206)))+(((IkReal(-1.00000000000000))*(cj4)*(x2188)*(x2217)))+(((IkReal(-1.00000000000000))*(cj0)*(x2190)*(x2193)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2187)*(x2200)))+(((x2206)*(x2209)))+(((IkReal(-1.00000000000000))*(cj4)*(x2188)*(x2207)))+(((IkReal(-1.00000000000000))*(x2187)*(x2202)*(x2207)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2209)))+(((IkReal(-1.00000000000000))*(r12)*(x2190)*(x2200)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2189))));
06841 evalcond[7]=((((x2205)*(x2220)))+(((IkReal(-0.374290000000000))*(r02)*(x2198)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x2198)))+(((IkReal(-1.00000000000000))*(r11)*(x2194)*(x2196)))+(((x2203)*(x2211)))+(((IkReal(0.0100000000000000))*(x2191)*(x2197)))+(((IkReal(-1.00000000000000))*(r10)*(x2194)*(x2204)))+(((IkReal(-1.00000000000000))*(py)*(x2214)))+(((IkReal(-0.0100000000000000))*(x2191)*(x2192)))+(((IkReal(0.374290000000000))*(x2192)*(x2196)))+(((r00)*(x2204)*(x2210)))+(((IkReal(-1.00000000000000))*(x2203)*(x2215)))+(((px)*(sj0)))+(((x2194)*(x2195))));
06842 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(r00)*(x2194)*(x2204)))+(((cj5)*(r02)*(x2194)))+(((cj0)*(r02)*(x2203)))+(((r12)*(sj0)*(x2203)))+(((IkReal(-0.374290000000000))*(x2189)*(x2204)))+(((x2195)*(x2210)))+(((x2209)*(x2220)))+(((IkReal(-1.00000000000000))*(r01)*(x2194)*(x2196)))+(((IkReal(0.0100000000000000))*(x2191)*(x2217)))+(((IkReal(-1.00000000000000))*(r11)*(x2196)*(x2210)))+(((IkReal(0.0100000000000000))*(x2191)*(x2207)))+(((IkReal(-1.00000000000000))*(py)*(x2200)))+(((x2189)*(x2220)))+(((IkReal(-1.00000000000000))*(px)*(x2214))));
06843 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
06844 {
06845 {
06846 IkReal j3array[1], cj3array[1], sj3array[1];
06847 bool j3valid[1]={false};
06848 _nj3 = 1;
06849 IkReal x2221=((IkReal(1.00000000000000))*(cj4));
06850 IkReal x2222=((cj6)*(r21));
06851 IkReal x2223=((r20)*(sj6));
06852 if( IKabs(((((sj5)*(x2223)))+(((sj5)*(x2222)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2223)))+(((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2222)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2221)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x2223)))+(((sj5)*(x2222)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2223)))+(((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2222)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2221)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
06853     continue;
06854 j3array[0]=IKatan2(((((sj5)*(x2223)))+(((sj5)*(x2222)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2223)))+(((IkReal(-1.00000000000000))*(cj5)*(x2221)*(x2222)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2221)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
06855 sj3array[0]=IKsin(j3array[0]);
06856 cj3array[0]=IKcos(j3array[0]);
06857 if( j3array[0] > IKPI )
06858 {
06859     j3array[0]-=IK2PI;
06860 }
06861 else if( j3array[0] < -IKPI )
06862 {    j3array[0]+=IK2PI;
06863 }
06864 j3valid[0] = true;
06865 for(int ij3 = 0; ij3 < 1; ++ij3)
06866 {
06867 if( !j3valid[ij3] )
06868 {
06869     continue;
06870 }
06871 _ij3[0] = ij3; _ij3[1] = -1;
06872 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
06873 {
06874 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
06875 {
06876     j3valid[iij3]=false; _ij3[1] = iij3; break; 
06877 }
06878 }
06879 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
06880 {
06881 IkReal evalcond[4];
06882 IkReal x2224=IKcos(j3);
06883 IkReal x2225=IKsin(j3);
06884 IkReal x2226=((IkReal(1.00000000000000))*(cj4));
06885 IkReal x2227=((sj0)*(sj5));
06886 IkReal x2228=((cj0)*(cj5));
06887 IkReal x2229=((cj6)*(r01));
06888 IkReal x2230=((r00)*(sj6));
06889 IkReal x2231=((cj6)*(r11));
06890 IkReal x2232=((cj5)*(sj0));
06891 IkReal x2233=((cj6)*(sj4));
06892 IkReal x2234=((sj4)*(sj6));
06893 IkReal x2235=((cj4)*(cj5));
06894 IkReal x2236=((cj6)*(r21));
06895 IkReal x2237=((r20)*(sj6));
06896 IkReal x2238=((r10)*(sj6));
06897 IkReal x2239=((IkReal(1.00000000000000))*(cj0)*(sj5));
06898 evalcond[0]=((((sj5)*(x2236)))+(((sj5)*(x2237)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x2225))));
06899 evalcond[1]=((x2224)+(((r20)*(x2233)))+(((IkReal(-1.00000000000000))*(r21)*(x2234)))+(((x2235)*(x2237)))+(((cj4)*(r22)*(sj5)))+(((x2235)*(x2236))));
06900 evalcond[2]=((x2224)+(((IkReal(-1.00000000000000))*(x2230)*(x2239)))+(((IkReal(-1.00000000000000))*(x2227)*(x2238)))+(((IkReal(-1.00000000000000))*(x2227)*(x2231)))+(((IkReal(-1.00000000000000))*(x2229)*(x2239)))+(((r12)*(x2232)))+(((r02)*(x2228))));
06901 evalcond[3]=((x2225)+(((IkReal(-1.00000000000000))*(x2226)*(x2228)*(x2229)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x2226)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2233)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x2233)))+(((IkReal(-1.00000000000000))*(x2226)*(x2228)*(x2230)))+(((IkReal(-1.00000000000000))*(x2226)*(x2232)*(x2238)))+(((IkReal(-1.00000000000000))*(r12)*(x2226)*(x2227)))+(((IkReal(-1.00000000000000))*(x2226)*(x2231)*(x2232)))+(((cj0)*(r01)*(x2234)))+(((r11)*(sj0)*(x2234))));
06902 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06903 {
06904 continue;
06905 }
06906 }
06907 
06908 {
06909 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
06910 vinfos[0].jointtype = 1;
06911 vinfos[0].foffset = j0;
06912 vinfos[0].indices[0] = _ij0[0];
06913 vinfos[0].indices[1] = _ij0[1];
06914 vinfos[0].maxsolutions = _nj0;
06915 vinfos[1].jointtype = 1;
06916 vinfos[1].foffset = j1;
06917 vinfos[1].indices[0] = _ij1[0];
06918 vinfos[1].indices[1] = _ij1[1];
06919 vinfos[1].maxsolutions = _nj1;
06920 vinfos[2].jointtype = 1;
06921 vinfos[2].foffset = j2;
06922 vinfos[2].indices[0] = _ij2[0];
06923 vinfos[2].indices[1] = _ij2[1];
06924 vinfos[2].maxsolutions = _nj2;
06925 vinfos[3].jointtype = 1;
06926 vinfos[3].foffset = j3;
06927 vinfos[3].indices[0] = _ij3[0];
06928 vinfos[3].indices[1] = _ij3[1];
06929 vinfos[3].maxsolutions = _nj3;
06930 vinfos[4].jointtype = 1;
06931 vinfos[4].foffset = j4;
06932 vinfos[4].indices[0] = _ij4[0];
06933 vinfos[4].indices[1] = _ij4[1];
06934 vinfos[4].maxsolutions = _nj4;
06935 vinfos[5].jointtype = 1;
06936 vinfos[5].foffset = j5;
06937 vinfos[5].indices[0] = _ij5[0];
06938 vinfos[5].indices[1] = _ij5[1];
06939 vinfos[5].maxsolutions = _nj5;
06940 vinfos[6].jointtype = 1;
06941 vinfos[6].foffset = j6;
06942 vinfos[6].indices[0] = _ij6[0];
06943 vinfos[6].indices[1] = _ij6[1];
06944 vinfos[6].maxsolutions = _nj6;
06945 std::vector<int> vfree(0);
06946 solutions.AddSolution(vinfos,vfree);
06947 }
06948 }
06949 }
06950 
06951 } else
06952 {
06953 IkReal x2240=((IkReal(1.00000000000000))*(cj0));
06954 IkReal x2241=((cj4)*(sj6));
06955 IkReal x2242=((sj0)*(sj4));
06956 IkReal x2243=((cj5)*(sj6));
06957 IkReal x2244=((sj4)*(sj5));
06958 IkReal x2245=((r12)*(sj5));
06959 IkReal x2246=((IkReal(0.374290000000000))*(cj5));
06960 IkReal x2247=((r02)*(sj0));
06961 IkReal x2248=((r20)*(sj4));
06962 IkReal x2249=((IkReal(1.00000000000000))*(sj0));
06963 IkReal x2250=((IkReal(1.00000000000000))*(cj5));
06964 IkReal x2251=((cj0)*(r10));
06965 IkReal x2252=((cj4)*(cj6));
06966 IkReal x2253=((r00)*(sj0));
06967 IkReal x2254=((cj6)*(r21));
06968 IkReal x2255=((IkReal(0.374290000000000))*(sj5));
06969 IkReal x2256=((cj0)*(r00));
06970 IkReal x2257=((IkReal(0.0100000000000000))*(sj5));
06971 IkReal x2258=((cj0)*(r02));
06972 IkReal x2259=((cj5)*(sj4));
06973 IkReal x2260=((cj6)*(r01));
06974 IkReal x2261=((cj6)*(r11));
06975 IkReal x2262=((r01)*(sj0));
06976 IkReal x2263=((r10)*(sj0));
06977 IkReal x2264=((IkReal(0.0100000000000000))*(cj5)*(cj6));
06978 IkReal x2265=((sj6)*(x2255));
06979 IkReal x2266=((cj0)*(cj6)*(x2255));
06980 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
06981 evalcond[1]=((((sj5)*(x2254)))+(((IkReal(-1.00000000000000))*(r22)*(x2250)))+(((r20)*(sj5)*(sj6))));
06982 evalcond[2]=((IkReal(1.00000000000000))+(((x2254)*(x2259)))+(((IkReal(-1.00000000000000))*(r20)*(x2252)))+(((x2243)*(x2248)))+(((r21)*(x2241)))+(((r22)*(x2244))));
06983 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x2254)))+(((IkReal(-0.0100000000000000))*(r20)*(x2243)))+(((IkReal(-1.00000000000000))*(r22)*(x2246)))+(((r20)*(x2265)))+(((x2254)*(x2255)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x2257))));
06984 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x2248)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x2241)))+(((cj5)*(r21)*(x2252))));
06985 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(x2240)*(x2241)))+(((x2241)*(x2262)))+(((r02)*(sj5)*(x2242)))+(((IkReal(-1.00000000000000))*(r12)*(x2240)*(x2244)))+(((IkReal(-1.00000000000000))*(r00)*(x2249)*(x2252)))+(((x2251)*(x2252)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x2240)*(x2243)))+(((IkReal(-1.00000000000000))*(x2240)*(x2259)*(x2261)))+(((r00)*(x2242)*(x2243)))+(((cj5)*(x2242)*(x2260))));
06986 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x2240)*(x2241)))+(((IkReal(-1.00000000000000))*(r11)*(x2241)*(x2249)))+(((x2252)*(x2256)))+(((IkReal(-1.00000000000000))*(x2240)*(x2259)*(x2260)))+(((IkReal(-1.00000000000000))*(r10)*(x2242)*(x2243)))+(((IkReal(-1.00000000000000))*(x2242)*(x2245)))+(((x2252)*(x2263)))+(((IkReal(-1.00000000000000))*(r02)*(x2240)*(x2244)))+(((IkReal(-1.00000000000000))*(x2242)*(x2250)*(x2261)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x2240)*(x2243))));
06987 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x2255)*(x2261)))+(((IkReal(-1.00000000000000))*(x2246)*(x2247)))+(((IkReal(0.0100000000000000))*(x2243)*(x2251)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x2260)))+(((IkReal(-1.00000000000000))*(x2251)*(x2265)))+(((cj0)*(r12)*(x2246)))+(((IkReal(-1.00000000000000))*(x2247)*(x2257)))+(((IkReal(-0.0100000000000000))*(x2243)*(x2253)))+(((IkReal(0.0100000000000000))*(cj0)*(x2245)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2261)))+(((sj0)*(x2255)*(x2260)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x2240)))+(((x2253)*(x2265))));
06988 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2260)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x2261)))+(((IkReal(0.0100000000000000))*(sj0)*(x2245)))+(((IkReal(-1.00000000000000))*(x2256)*(x2265)))+(((IkReal(-1.00000000000000))*(px)*(x2240)))+(((IkReal(-1.00000000000000))*(x2263)*(x2265)))+(((IkReal(-1.00000000000000))*(py)*(x2249)))+(((IkReal(0.0100000000000000))*(x2243)*(x2256)))+(((x2246)*(x2258)))+(((IkReal(-1.00000000000000))*(cj0)*(x2255)*(x2260)))+(((x2257)*(x2258)))+(((IkReal(-1.00000000000000))*(sj0)*(x2255)*(x2261)))+(((IkReal(0.0100000000000000))*(x2243)*(x2263)))+(((r12)*(sj0)*(x2246))));
06989 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
06990 {
06991 {
06992 IkReal j3array[1], cj3array[1], sj3array[1];
06993 bool j3valid[1]={false};
06994 _nj3 = 1;
06995 IkReal x2267=((sj0)*(sj5));
06996 IkReal x2268=((r00)*(sj6));
06997 IkReal x2269=((IkReal(1.00000000000000))*(cj5));
06998 IkReal x2270=((cj6)*(r11));
06999 IkReal x2271=((cj6)*(r01));
07000 IkReal x2272=((r10)*(sj6));
07001 IkReal x2273=((cj0)*(sj5));
07002 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2269)))+(((x2267)*(x2268)))+(((x2267)*(x2271)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2272)*(x2273)))+(((IkReal(-1.00000000000000))*(x2270)*(x2273))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x2271)*(x2273)))+(((x2267)*(x2270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2269)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2269)))+(((x2268)*(x2273)))+(((x2267)*(x2272))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2269)))+(((x2267)*(x2268)))+(((x2267)*(x2271)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2272)*(x2273)))+(((IkReal(-1.00000000000000))*(x2270)*(x2273)))))+IKsqr(((((x2271)*(x2273)))+(((x2267)*(x2270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2269)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2269)))+(((x2268)*(x2273)))+(((x2267)*(x2272)))))-1) <= IKFAST_SINCOS_THRESH )
07003     continue;
07004 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2269)))+(((x2267)*(x2268)))+(((x2267)*(x2271)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2272)*(x2273)))+(((IkReal(-1.00000000000000))*(x2270)*(x2273)))), ((((x2271)*(x2273)))+(((x2267)*(x2270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2269)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2269)))+(((x2268)*(x2273)))+(((x2267)*(x2272)))));
07005 sj3array[0]=IKsin(j3array[0]);
07006 cj3array[0]=IKcos(j3array[0]);
07007 if( j3array[0] > IKPI )
07008 {
07009     j3array[0]-=IK2PI;
07010 }
07011 else if( j3array[0] < -IKPI )
07012 {    j3array[0]+=IK2PI;
07013 }
07014 j3valid[0] = true;
07015 for(int ij3 = 0; ij3 < 1; ++ij3)
07016 {
07017 if( !j3valid[ij3] )
07018 {
07019     continue;
07020 }
07021 _ij3[0] = ij3; _ij3[1] = -1;
07022 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07023 {
07024 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07025 {
07026     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07027 }
07028 }
07029 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07030 {
07031 IkReal evalcond[4];
07032 IkReal x2274=IKcos(j3);
07033 IkReal x2275=IKsin(j3);
07034 IkReal x2276=((sj0)*(sj5));
07035 IkReal x2277=((r00)*(sj6));
07036 IkReal x2278=((cj6)*(sj0));
07037 IkReal x2279=((IkReal(1.00000000000000))*(cj4));
07038 IkReal x2280=((r00)*(sj4));
07039 IkReal x2281=((cj0)*(cj5));
07040 IkReal x2282=((cj5)*(sj0));
07041 IkReal x2283=((cj6)*(r11));
07042 IkReal x2284=((r10)*(sj6));
07043 IkReal x2285=((cj0)*(sj5));
07044 IkReal x2286=((r10)*(sj4));
07045 IkReal x2287=((cj4)*(cj5)*(r01));
07046 IkReal x2288=((IkReal(1.00000000000000))*(cj0)*(cj6));
07047 IkReal x2289=((cj0)*(sj4)*(sj6));
07048 IkReal x2290=((sj0)*(sj4)*(sj6));
07049 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x2282)))+(((cj6)*(r01)*(x2276)))+(((IkReal(-1.00000000000000))*(x2283)*(x2285)))+(((IkReal(-1.00000000000000))*(x2275)))+(((r12)*(x2281)))+(((x2276)*(x2277)))+(((IkReal(-1.00000000000000))*(x2284)*(x2285))));
07050 evalcond[1]=((((IkReal(-1.00000000000000))*(x2277)*(x2285)))+(((IkReal(-1.00000000000000))*(x2276)*(x2283)))+(((r12)*(x2282)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x2285)))+(x2274)+(((r02)*(x2281)))+(((IkReal(-1.00000000000000))*(x2276)*(x2284))));
07051 evalcond[2]=((((cj4)*(x2277)*(x2282)))+(((x2278)*(x2280)))+(((cj4)*(r02)*(x2276)))+(((IkReal(-1.00000000000000))*(x2279)*(x2281)*(x2284)))+(((r11)*(x2289)))+(((IkReal(-1.00000000000000))*(x2286)*(x2288)))+(x2274)+(((IkReal(-1.00000000000000))*(r01)*(x2290)))+(((IkReal(-1.00000000000000))*(x2279)*(x2281)*(x2283)))+(((IkReal(-1.00000000000000))*(r12)*(x2279)*(x2285)))+(((x2278)*(x2287))));
07052 evalcond[3]=((((r01)*(x2289)))+(((r11)*(x2290)))+(((IkReal(-1.00000000000000))*(x2279)*(x2282)*(x2284)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x2279)*(x2281)))+(((IkReal(-1.00000000000000))*(r02)*(x2279)*(x2285)))+(((IkReal(-1.00000000000000))*(x2280)*(x2288)))+(((IkReal(-1.00000000000000))*(x2278)*(x2286)))+(x2275)+(((IkReal(-1.00000000000000))*(r12)*(x2276)*(x2279)))+(((IkReal(-1.00000000000000))*(x2277)*(x2279)*(x2281)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2278)*(x2279))));
07053 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07054 {
07055 continue;
07056 }
07057 }
07058 
07059 {
07060 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
07061 vinfos[0].jointtype = 1;
07062 vinfos[0].foffset = j0;
07063 vinfos[0].indices[0] = _ij0[0];
07064 vinfos[0].indices[1] = _ij0[1];
07065 vinfos[0].maxsolutions = _nj0;
07066 vinfos[1].jointtype = 1;
07067 vinfos[1].foffset = j1;
07068 vinfos[1].indices[0] = _ij1[0];
07069 vinfos[1].indices[1] = _ij1[1];
07070 vinfos[1].maxsolutions = _nj1;
07071 vinfos[2].jointtype = 1;
07072 vinfos[2].foffset = j2;
07073 vinfos[2].indices[0] = _ij2[0];
07074 vinfos[2].indices[1] = _ij2[1];
07075 vinfos[2].maxsolutions = _nj2;
07076 vinfos[3].jointtype = 1;
07077 vinfos[3].foffset = j3;
07078 vinfos[3].indices[0] = _ij3[0];
07079 vinfos[3].indices[1] = _ij3[1];
07080 vinfos[3].maxsolutions = _nj3;
07081 vinfos[4].jointtype = 1;
07082 vinfos[4].foffset = j4;
07083 vinfos[4].indices[0] = _ij4[0];
07084 vinfos[4].indices[1] = _ij4[1];
07085 vinfos[4].maxsolutions = _nj4;
07086 vinfos[5].jointtype = 1;
07087 vinfos[5].foffset = j5;
07088 vinfos[5].indices[0] = _ij5[0];
07089 vinfos[5].indices[1] = _ij5[1];
07090 vinfos[5].maxsolutions = _nj5;
07091 vinfos[6].jointtype = 1;
07092 vinfos[6].foffset = j6;
07093 vinfos[6].indices[0] = _ij6[0];
07094 vinfos[6].indices[1] = _ij6[1];
07095 vinfos[6].maxsolutions = _nj6;
07096 std::vector<int> vfree(0);
07097 solutions.AddSolution(vinfos,vfree);
07098 }
07099 }
07100 }
07101 
07102 } else
07103 {
07104 IkReal x2291=((IkReal(1.00000000000000))*(cj0));
07105 IkReal x2292=((cj4)*(sj6));
07106 IkReal x2293=((sj0)*(sj4));
07107 IkReal x2294=((cj5)*(sj6));
07108 IkReal x2295=((sj4)*(sj5));
07109 IkReal x2296=((r12)*(sj5));
07110 IkReal x2297=((IkReal(0.374290000000000))*(cj5));
07111 IkReal x2298=((r02)*(sj0));
07112 IkReal x2299=((r20)*(sj4));
07113 IkReal x2300=((IkReal(1.00000000000000))*(sj0));
07114 IkReal x2301=((IkReal(1.00000000000000))*(cj5));
07115 IkReal x2302=((cj0)*(r10));
07116 IkReal x2303=((cj4)*(cj6));
07117 IkReal x2304=((r00)*(sj0));
07118 IkReal x2305=((cj6)*(r21));
07119 IkReal x2306=((IkReal(0.374290000000000))*(sj5));
07120 IkReal x2307=((cj0)*(r00));
07121 IkReal x2308=((IkReal(0.0100000000000000))*(sj5));
07122 IkReal x2309=((cj0)*(r02));
07123 IkReal x2310=((cj5)*(sj4));
07124 IkReal x2311=((cj6)*(r01));
07125 IkReal x2312=((cj6)*(r11));
07126 IkReal x2313=((r01)*(sj0));
07127 IkReal x2314=((r10)*(sj0));
07128 IkReal x2315=((IkReal(0.0100000000000000))*(cj5)*(cj6));
07129 IkReal x2316=((sj6)*(x2306));
07130 IkReal x2317=((cj0)*(cj6)*(x2306));
07131 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
07132 evalcond[1]=((((sj5)*(x2305)))+(((r20)*(sj5)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(x2301))));
07133 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x2295)))+(((x2294)*(x2299)))+(((r21)*(x2292)))+(((x2305)*(x2310)))+(((IkReal(-1.00000000000000))*(r20)*(x2303))));
07134 evalcond[3]=((((x2305)*(x2306)))+(((IkReal(-1.00000000000000))*(r22)*(x2308)))+(((IkReal(-1.00000000000000))*(r22)*(x2297)))+(((r20)*(x2316)))+(((IkReal(-0.0100000000000000))*(cj5)*(x2305)))+(((IkReal(-0.0100000000000000))*(r20)*(x2294)))+(pz));
07135 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x2292)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x2299)))+(((cj5)*(r21)*(x2303))));
07136 evalcond[5]=((((r02)*(sj5)*(x2293)))+(((x2302)*(x2303)))+(((r00)*(x2293)*(x2294)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x2291)*(x2294)))+(((IkReal(-1.00000000000000))*(r00)*(x2300)*(x2303)))+(((IkReal(-1.00000000000000))*(r12)*(x2291)*(x2295)))+(((IkReal(-1.00000000000000))*(x2291)*(x2310)*(x2312)))+(((cj5)*(x2293)*(x2311)))+(((IkReal(-1.00000000000000))*(r11)*(x2291)*(x2292)))+(((x2292)*(x2313))));
07137 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x2291)*(x2295)))+(((IkReal(-1.00000000000000))*(r11)*(x2292)*(x2300)))+(((IkReal(-1.00000000000000))*(x2291)*(x2310)*(x2311)))+(((x2303)*(x2314)))+(((IkReal(-1.00000000000000))*(x2293)*(x2296)))+(((IkReal(-1.00000000000000))*(x2293)*(x2301)*(x2312)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x2291)*(x2294)))+(((IkReal(-1.00000000000000))*(r10)*(x2293)*(x2294)))+(((x2303)*(x2307)))+(((IkReal(-1.00000000000000))*(r01)*(x2291)*(x2292))));
07138 evalcond[7]=((IkReal(-0.0690000000000000))+(((x2304)*(x2316)))+(((IkReal(-1.00000000000000))*(x2302)*(x2316)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x2311)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2312)))+(((IkReal(0.0100000000000000))*(cj0)*(x2296)))+(((sj0)*(x2306)*(x2311)))+(((cj0)*(r12)*(x2297)))+(((IkReal(-1.00000000000000))*(cj0)*(x2306)*(x2312)))+(((IkReal(0.0100000000000000))*(x2294)*(x2302)))+(((IkReal(-0.0100000000000000))*(x2294)*(x2304)))+(((IkReal(-1.00000000000000))*(py)*(x2291)))+(((IkReal(-1.00000000000000))*(x2298)*(x2308)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x2297)*(x2298))));
07139 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(x2294)*(x2314)))+(((IkReal(-1.00000000000000))*(x2314)*(x2316)))+(((IkReal(0.0100000000000000))*(sj0)*(x2296)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x2312)))+(((r12)*(sj0)*(x2297)))+(((IkReal(-1.00000000000000))*(cj0)*(x2306)*(x2311)))+(((IkReal(-1.00000000000000))*(px)*(x2291)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x2311)))+(((IkReal(-1.00000000000000))*(x2307)*(x2316)))+(((IkReal(-1.00000000000000))*(py)*(x2300)))+(((x2297)*(x2309)))+(((IkReal(-1.00000000000000))*(sj0)*(x2306)*(x2312)))+(((x2308)*(x2309)))+(((IkReal(0.0100000000000000))*(x2294)*(x2307))));
07140 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
07141 {
07142 {
07143 IkReal j3array[1], cj3array[1], sj3array[1];
07144 bool j3valid[1]={false};
07145 _nj3 = 1;
07146 IkReal x2318=((IkReal(1.00000000000000))*(cj5));
07147 IkReal x2319=((r10)*(sj5)*(sj6));
07148 IkReal x2320=((cj6)*(sj0)*(sj5));
07149 IkReal x2321=((r00)*(sj5)*(sj6));
07150 IkReal x2322=((cj0)*(cj6)*(sj5));
07151 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2318)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x2319)))+(((IkReal(-1.00000000000000))*(r01)*(x2320)))+(((IkReal(-1.00000000000000))*(sj0)*(x2321)))+(((r11)*(x2322))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2318)))+(((cj0)*(x2321)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2318)))+(((sj0)*(x2319)))+(((r11)*(x2320)))+(((r01)*(x2322))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2318)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x2319)))+(((IkReal(-1.00000000000000))*(r01)*(x2320)))+(((IkReal(-1.00000000000000))*(sj0)*(x2321)))+(((r11)*(x2322)))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2318)))+(((cj0)*(x2321)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2318)))+(((sj0)*(x2319)))+(((r11)*(x2320)))+(((r01)*(x2322)))))-1) <= IKFAST_SINCOS_THRESH )
07152     continue;
07153 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2318)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x2319)))+(((IkReal(-1.00000000000000))*(r01)*(x2320)))+(((IkReal(-1.00000000000000))*(sj0)*(x2321)))+(((r11)*(x2322)))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2318)))+(((cj0)*(x2321)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2318)))+(((sj0)*(x2319)))+(((r11)*(x2320)))+(((r01)*(x2322)))));
07154 sj3array[0]=IKsin(j3array[0]);
07155 cj3array[0]=IKcos(j3array[0]);
07156 if( j3array[0] > IKPI )
07157 {
07158     j3array[0]-=IK2PI;
07159 }
07160 else if( j3array[0] < -IKPI )
07161 {    j3array[0]+=IK2PI;
07162 }
07163 j3valid[0] = true;
07164 for(int ij3 = 0; ij3 < 1; ++ij3)
07165 {
07166 if( !j3valid[ij3] )
07167 {
07168     continue;
07169 }
07170 _ij3[0] = ij3; _ij3[1] = -1;
07171 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07172 {
07173 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07174 {
07175     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07176 }
07177 }
07178 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07179 {
07180 IkReal evalcond[4];
07181 IkReal x2323=IKcos(j3);
07182 IkReal x2324=IKsin(j3);
07183 IkReal x2325=((sj0)*(sj5));
07184 IkReal x2326=((r00)*(sj6));
07185 IkReal x2327=((IkReal(1.00000000000000))*(cj4));
07186 IkReal x2328=((cj6)*(sj0));
07187 IkReal x2329=((r00)*(sj4));
07188 IkReal x2330=((cj0)*(cj5));
07189 IkReal x2331=((cj6)*(r01));
07190 IkReal x2332=((cj5)*(sj0));
07191 IkReal x2333=((cj0)*(sj5));
07192 IkReal x2334=((cj6)*(r11));
07193 IkReal x2335=((r10)*(sj6));
07194 IkReal x2336=((r10)*(sj4));
07195 IkReal x2337=((cj0)*(sj4)*(sj6));
07196 IkReal x2338=((sj0)*(sj4)*(sj6));
07197 IkReal x2339=((IkReal(1.00000000000000))*(cj0)*(cj6));
07198 evalcond[0]=((((r12)*(x2330)))+(x2324)+(((IkReal(-1.00000000000000))*(r02)*(x2332)))+(((IkReal(-1.00000000000000))*(x2333)*(x2334)))+(((x2325)*(x2326)))+(((x2325)*(x2331)))+(((IkReal(-1.00000000000000))*(x2333)*(x2335))));
07199 evalcond[1]=((x2323)+(((IkReal(-1.00000000000000))*(x2325)*(x2335)))+(((IkReal(-1.00000000000000))*(x2331)*(x2333)))+(((IkReal(-1.00000000000000))*(x2325)*(x2334)))+(((r02)*(x2330)))+(((r12)*(x2332)))+(((IkReal(-1.00000000000000))*(x2326)*(x2333))));
07200 evalcond[2]=((((IkReal(-1.00000000000000))*(x2336)*(x2339)))+(((IkReal(-1.00000000000000))*(r12)*(x2327)*(x2333)))+(((x2328)*(x2329)))+(((IkReal(-1.00000000000000))*(x2327)*(x2330)*(x2334)))+(((IkReal(-1.00000000000000))*(x2323)))+(((IkReal(-1.00000000000000))*(r01)*(x2338)))+(((IkReal(-1.00000000000000))*(x2327)*(x2330)*(x2335)))+(((cj4)*(x2326)*(x2332)))+(((r11)*(x2337)))+(((cj4)*(cj5)*(r01)*(x2328)))+(((cj4)*(r02)*(x2325))));
07201 evalcond[3]=((x2324)+(((IkReal(-1.00000000000000))*(r02)*(x2327)*(x2333)))+(((IkReal(-1.00000000000000))*(x2326)*(x2327)*(x2330)))+(((IkReal(-1.00000000000000))*(x2327)*(x2330)*(x2331)))+(((IkReal(-1.00000000000000))*(x2329)*(x2339)))+(((IkReal(-1.00000000000000))*(x2328)*(x2336)))+(((IkReal(-1.00000000000000))*(x2327)*(x2332)*(x2335)))+(((IkReal(-1.00000000000000))*(r12)*(x2325)*(x2327)))+(((r11)*(x2338)))+(((r01)*(x2337)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2327)*(x2328))));
07202 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07203 {
07204 continue;
07205 }
07206 }
07207 
07208 {
07209 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
07210 vinfos[0].jointtype = 1;
07211 vinfos[0].foffset = j0;
07212 vinfos[0].indices[0] = _ij0[0];
07213 vinfos[0].indices[1] = _ij0[1];
07214 vinfos[0].maxsolutions = _nj0;
07215 vinfos[1].jointtype = 1;
07216 vinfos[1].foffset = j1;
07217 vinfos[1].indices[0] = _ij1[0];
07218 vinfos[1].indices[1] = _ij1[1];
07219 vinfos[1].maxsolutions = _nj1;
07220 vinfos[2].jointtype = 1;
07221 vinfos[2].foffset = j2;
07222 vinfos[2].indices[0] = _ij2[0];
07223 vinfos[2].indices[1] = _ij2[1];
07224 vinfos[2].maxsolutions = _nj2;
07225 vinfos[3].jointtype = 1;
07226 vinfos[3].foffset = j3;
07227 vinfos[3].indices[0] = _ij3[0];
07228 vinfos[3].indices[1] = _ij3[1];
07229 vinfos[3].maxsolutions = _nj3;
07230 vinfos[4].jointtype = 1;
07231 vinfos[4].foffset = j4;
07232 vinfos[4].indices[0] = _ij4[0];
07233 vinfos[4].indices[1] = _ij4[1];
07234 vinfos[4].maxsolutions = _nj4;
07235 vinfos[5].jointtype = 1;
07236 vinfos[5].foffset = j5;
07237 vinfos[5].indices[0] = _ij5[0];
07238 vinfos[5].indices[1] = _ij5[1];
07239 vinfos[5].maxsolutions = _nj5;
07240 vinfos[6].jointtype = 1;
07241 vinfos[6].foffset = j6;
07242 vinfos[6].indices[0] = _ij6[0];
07243 vinfos[6].indices[1] = _ij6[1];
07244 vinfos[6].maxsolutions = _nj6;
07245 std::vector<int> vfree(0);
07246 solutions.AddSolution(vinfos,vfree);
07247 }
07248 }
07249 }
07250 
07251 } else
07252 {
07253 if( 1 )
07254 {
07255 continue;
07256 
07257 } else
07258 {
07259 }
07260 }
07261 }
07262 }
07263 }
07264 }
07265 
07266 } else
07267 {
07268 {
07269 IkReal j3array[1], cj3array[1], sj3array[1];
07270 bool j3valid[1]={false};
07271 _nj3 = 1;
07272 IkReal x2340=((sj0)*(sj5));
07273 IkReal x2341=((r00)*(sj6));
07274 IkReal x2342=((IkReal(1.00000000000000))*(cj5));
07275 IkReal x2343=((cj6)*(r11));
07276 IkReal x2344=((cj6)*(r01));
07277 IkReal x2345=((cj0)*(sj5));
07278 IkReal x2346=((r10)*(sj6));
07279 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x2340)*(x2341)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2342)))+(((IkReal(-1.00000000000000))*(x2343)*(x2345)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2345)*(x2346)))+(((x2340)*(x2344))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2342)))+(((x2341)*(x2345)))+(((x2340)*(x2343)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2342)))+(((x2340)*(x2346)))+(((x2344)*(x2345))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x2340)*(x2341)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2342)))+(((IkReal(-1.00000000000000))*(x2343)*(x2345)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2345)*(x2346)))+(((x2340)*(x2344)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2342)))+(((x2341)*(x2345)))+(((x2340)*(x2343)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2342)))+(((x2340)*(x2346)))+(((x2344)*(x2345)))))-1) <= IKFAST_SINCOS_THRESH )
07280     continue;
07281 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x2340)*(x2341)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2342)))+(((IkReal(-1.00000000000000))*(x2343)*(x2345)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x2345)*(x2346)))+(((x2340)*(x2344)))))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2342)))+(((x2341)*(x2345)))+(((x2340)*(x2343)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2342)))+(((x2340)*(x2346)))+(((x2344)*(x2345)))));
07282 sj3array[0]=IKsin(j3array[0]);
07283 cj3array[0]=IKcos(j3array[0]);
07284 if( j3array[0] > IKPI )
07285 {
07286     j3array[0]-=IK2PI;
07287 }
07288 else if( j3array[0] < -IKPI )
07289 {    j3array[0]+=IK2PI;
07290 }
07291 j3valid[0] = true;
07292 for(int ij3 = 0; ij3 < 1; ++ij3)
07293 {
07294 if( !j3valid[ij3] )
07295 {
07296     continue;
07297 }
07298 _ij3[0] = ij3; _ij3[1] = -1;
07299 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07300 {
07301 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07302 {
07303     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07304 }
07305 }
07306 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07307 {
07308 IkReal evalcond[6];
07309 IkReal x2347=IKsin(j3);
07310 IkReal x2348=IKcos(j3);
07311 IkReal x2349=((sj0)*(sj5));
07312 IkReal x2350=((r00)*(sj6));
07313 IkReal x2351=((IkReal(1.00000000000000))*(cj4));
07314 IkReal x2352=((cj6)*(r01));
07315 IkReal x2353=((cj0)*(cj5));
07316 IkReal x2354=((cj5)*(sj0));
07317 IkReal x2355=((cj6)*(r11));
07318 IkReal x2356=((cj6)*(sj4));
07319 IkReal x2357=((cj0)*(sj5));
07320 IkReal x2358=((cj4)*(cj5));
07321 IkReal x2359=((cj6)*(r21));
07322 IkReal x2360=((r20)*(sj6));
07323 IkReal x2361=((r10)*(sj6));
07324 IkReal x2362=((IkReal(1.00000000000000))*(cj0));
07325 IkReal x2363=((cj0)*(sj4)*(sj6));
07326 IkReal x2364=((sj0)*(sj4)*(sj6));
07327 evalcond[0]=((((cj2)*(x2347)))+(((sj5)*(x2360)))+(((sj5)*(x2359)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
07328 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x2348)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x2356)))+(((cj4)*(r22)*(sj5)))+(((x2358)*(x2359)))+(((x2358)*(x2360))));
07329 evalcond[2]=((((IkReal(-1.00000000000000))*(x2357)*(x2361)))+(((IkReal(-1.00000000000000))*(sj2)*(x2347)))+(((IkReal(-1.00000000000000))*(x2355)*(x2357)))+(((r12)*(x2353)))+(((x2349)*(x2350)))+(((IkReal(-1.00000000000000))*(r02)*(x2354)))+(((x2349)*(x2352))));
07330 evalcond[3]=((((r02)*(x2353)))+(((IkReal(-1.00000000000000))*(x2349)*(x2361)))+(((IkReal(-1.00000000000000))*(x2350)*(x2357)))+(x2348)+(((r12)*(x2354)))+(((IkReal(-1.00000000000000))*(x2349)*(x2355)))+(((IkReal(-1.00000000000000))*(x2352)*(x2357))));
07331 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x2351)*(x2357)))+(((cj4)*(x2350)*(x2354)))+(((IkReal(-1.00000000000000))*(x2351)*(x2353)*(x2361)))+(((r00)*(sj0)*(x2356)))+(((IkReal(-1.00000000000000))*(r10)*(x2356)*(x2362)))+(((cj4)*(x2352)*(x2354)))+(((IkReal(-1.00000000000000))*(x2351)*(x2353)*(x2355)))+(((r11)*(x2363)))+(((cj4)*(r02)*(x2349)))+(((sj2)*(x2348)))+(((IkReal(-1.00000000000000))*(r01)*(x2364))));
07332 evalcond[5]=((((IkReal(-1.00000000000000))*(x2351)*(x2354)*(x2355)))+(((IkReal(-1.00000000000000))*(x2351)*(x2354)*(x2361)))+(((r11)*(x2364)))+(((IkReal(-1.00000000000000))*(r12)*(x2349)*(x2351)))+(x2347)+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2356)))+(((IkReal(-1.00000000000000))*(x2351)*(x2352)*(x2353)))+(((IkReal(-1.00000000000000))*(r02)*(x2351)*(x2357)))+(((IkReal(-1.00000000000000))*(r00)*(x2356)*(x2362)))+(((r01)*(x2363)))+(((IkReal(-1.00000000000000))*(x2350)*(x2351)*(x2353))));
07333 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
07334 {
07335 continue;
07336 }
07337 }
07338 
07339 {
07340 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
07341 vinfos[0].jointtype = 1;
07342 vinfos[0].foffset = j0;
07343 vinfos[0].indices[0] = _ij0[0];
07344 vinfos[0].indices[1] = _ij0[1];
07345 vinfos[0].maxsolutions = _nj0;
07346 vinfos[1].jointtype = 1;
07347 vinfos[1].foffset = j1;
07348 vinfos[1].indices[0] = _ij1[0];
07349 vinfos[1].indices[1] = _ij1[1];
07350 vinfos[1].maxsolutions = _nj1;
07351 vinfos[2].jointtype = 1;
07352 vinfos[2].foffset = j2;
07353 vinfos[2].indices[0] = _ij2[0];
07354 vinfos[2].indices[1] = _ij2[1];
07355 vinfos[2].maxsolutions = _nj2;
07356 vinfos[3].jointtype = 1;
07357 vinfos[3].foffset = j3;
07358 vinfos[3].indices[0] = _ij3[0];
07359 vinfos[3].indices[1] = _ij3[1];
07360 vinfos[3].maxsolutions = _nj3;
07361 vinfos[4].jointtype = 1;
07362 vinfos[4].foffset = j4;
07363 vinfos[4].indices[0] = _ij4[0];
07364 vinfos[4].indices[1] = _ij4[1];
07365 vinfos[4].maxsolutions = _nj4;
07366 vinfos[5].jointtype = 1;
07367 vinfos[5].foffset = j5;
07368 vinfos[5].indices[0] = _ij5[0];
07369 vinfos[5].indices[1] = _ij5[1];
07370 vinfos[5].maxsolutions = _nj5;
07371 vinfos[6].jointtype = 1;
07372 vinfos[6].foffset = j6;
07373 vinfos[6].indices[0] = _ij6[0];
07374 vinfos[6].indices[1] = _ij6[1];
07375 vinfos[6].maxsolutions = _nj6;
07376 std::vector<int> vfree(0);
07377 solutions.AddSolution(vinfos,vfree);
07378 }
07379 }
07380 }
07381 
07382 }
07383 
07384 }
07385 
07386 } else
07387 {
07388 {
07389 IkReal j3array[1], cj3array[1], sj3array[1];
07390 bool j3valid[1]={false};
07391 _nj3 = 1;
07392 IkReal x2365=((cj6)*(sj5));
07393 IkReal x2366=((IkReal(1.00000000000000))*(cj5));
07394 IkReal x2367=((sj5)*(sj6));
07395 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2365)))+(((IkReal(-1.00000000000000))*(r20)*(x2367)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(r01)*(x2365)))+(((r10)*(sj0)*(x2367)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2366)))+(((r11)*(sj0)*(x2365)))+(((cj0)*(r00)*(x2367)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2366))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2365)))+(((IkReal(-1.00000000000000))*(r20)*(x2367)))+(((cj5)*(r22)))))))+IKsqr(((((cj0)*(r01)*(x2365)))+(((r10)*(sj0)*(x2367)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2366)))+(((r11)*(sj0)*(x2365)))+(((cj0)*(r00)*(x2367)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2366)))))-1) <= IKFAST_SINCOS_THRESH )
07396     continue;
07397 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x2365)))+(((IkReal(-1.00000000000000))*(r20)*(x2367)))+(((cj5)*(r22)))))), ((((cj0)*(r01)*(x2365)))+(((r10)*(sj0)*(x2367)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2366)))+(((r11)*(sj0)*(x2365)))+(((cj0)*(r00)*(x2367)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2366)))));
07398 sj3array[0]=IKsin(j3array[0]);
07399 cj3array[0]=IKcos(j3array[0]);
07400 if( j3array[0] > IKPI )
07401 {
07402     j3array[0]-=IK2PI;
07403 }
07404 else if( j3array[0] < -IKPI )
07405 {    j3array[0]+=IK2PI;
07406 }
07407 j3valid[0] = true;
07408 for(int ij3 = 0; ij3 < 1; ++ij3)
07409 {
07410 if( !j3valid[ij3] )
07411 {
07412     continue;
07413 }
07414 _ij3[0] = ij3; _ij3[1] = -1;
07415 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07416 {
07417 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07418 {
07419     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07420 }
07421 }
07422 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07423 {
07424 IkReal evalcond[6];
07425 IkReal x2368=IKsin(j3);
07426 IkReal x2369=IKcos(j3);
07427 IkReal x2370=((sj0)*(sj5));
07428 IkReal x2371=((r00)*(sj6));
07429 IkReal x2372=((IkReal(1.00000000000000))*(cj4));
07430 IkReal x2373=((cj6)*(r01));
07431 IkReal x2374=((cj0)*(cj5));
07432 IkReal x2375=((cj5)*(sj0));
07433 IkReal x2376=((cj6)*(r11));
07434 IkReal x2377=((cj6)*(sj4));
07435 IkReal x2378=((cj0)*(sj5));
07436 IkReal x2379=((cj4)*(cj5));
07437 IkReal x2380=((cj6)*(r21));
07438 IkReal x2381=((r20)*(sj6));
07439 IkReal x2382=((r10)*(sj6));
07440 IkReal x2383=((IkReal(1.00000000000000))*(cj0));
07441 IkReal x2384=((cj0)*(sj4)*(sj6));
07442 IkReal x2385=((sj0)*(sj4)*(sj6));
07443 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x2380)))+(((sj5)*(x2381)))+(((cj2)*(x2368))));
07444 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj2)*(x2369)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x2377)))+(((x2379)*(x2381)))+(((x2379)*(x2380))));
07445 evalcond[2]=((((IkReal(-1.00000000000000))*(x2376)*(x2378)))+(((r12)*(x2374)))+(((x2370)*(x2373)))+(((IkReal(-1.00000000000000))*(x2378)*(x2382)))+(((IkReal(-1.00000000000000))*(r02)*(x2375)))+(((x2370)*(x2371)))+(((IkReal(-1.00000000000000))*(sj2)*(x2368))));
07446 evalcond[3]=((x2369)+(((IkReal(-1.00000000000000))*(x2370)*(x2382)))+(((r02)*(x2374)))+(((IkReal(-1.00000000000000))*(x2371)*(x2378)))+(((IkReal(-1.00000000000000))*(x2370)*(x2376)))+(((r12)*(x2375)))+(((IkReal(-1.00000000000000))*(x2373)*(x2378))));
07447 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x2372)*(x2378)))+(((IkReal(-1.00000000000000))*(x2372)*(x2374)*(x2376)))+(((r11)*(x2384)))+(((cj4)*(x2373)*(x2375)))+(((cj4)*(r02)*(x2370)))+(((sj2)*(x2369)))+(((IkReal(-1.00000000000000))*(r01)*(x2385)))+(((r00)*(sj0)*(x2377)))+(((IkReal(-1.00000000000000))*(r10)*(x2377)*(x2383)))+(((IkReal(-1.00000000000000))*(x2372)*(x2374)*(x2382)))+(((cj4)*(x2371)*(x2375))));
07448 evalcond[5]=((((IkReal(-1.00000000000000))*(x2372)*(x2373)*(x2374)))+(x2368)+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2377)))+(((IkReal(-1.00000000000000))*(x2372)*(x2375)*(x2382)))+(((IkReal(-1.00000000000000))*(r00)*(x2377)*(x2383)))+(((r01)*(x2384)))+(((IkReal(-1.00000000000000))*(x2371)*(x2372)*(x2374)))+(((IkReal(-1.00000000000000))*(x2372)*(x2375)*(x2376)))+(((IkReal(-1.00000000000000))*(r12)*(x2370)*(x2372)))+(((IkReal(-1.00000000000000))*(r02)*(x2372)*(x2378)))+(((r11)*(x2385))));
07449 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
07450 {
07451 continue;
07452 }
07453 }
07454 
07455 {
07456 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
07457 vinfos[0].jointtype = 1;
07458 vinfos[0].foffset = j0;
07459 vinfos[0].indices[0] = _ij0[0];
07460 vinfos[0].indices[1] = _ij0[1];
07461 vinfos[0].maxsolutions = _nj0;
07462 vinfos[1].jointtype = 1;
07463 vinfos[1].foffset = j1;
07464 vinfos[1].indices[0] = _ij1[0];
07465 vinfos[1].indices[1] = _ij1[1];
07466 vinfos[1].maxsolutions = _nj1;
07467 vinfos[2].jointtype = 1;
07468 vinfos[2].foffset = j2;
07469 vinfos[2].indices[0] = _ij2[0];
07470 vinfos[2].indices[1] = _ij2[1];
07471 vinfos[2].maxsolutions = _nj2;
07472 vinfos[3].jointtype = 1;
07473 vinfos[3].foffset = j3;
07474 vinfos[3].indices[0] = _ij3[0];
07475 vinfos[3].indices[1] = _ij3[1];
07476 vinfos[3].maxsolutions = _nj3;
07477 vinfos[4].jointtype = 1;
07478 vinfos[4].foffset = j4;
07479 vinfos[4].indices[0] = _ij4[0];
07480 vinfos[4].indices[1] = _ij4[1];
07481 vinfos[4].maxsolutions = _nj4;
07482 vinfos[5].jointtype = 1;
07483 vinfos[5].foffset = j5;
07484 vinfos[5].indices[0] = _ij5[0];
07485 vinfos[5].indices[1] = _ij5[1];
07486 vinfos[5].maxsolutions = _nj5;
07487 vinfos[6].jointtype = 1;
07488 vinfos[6].foffset = j6;
07489 vinfos[6].indices[0] = _ij6[0];
07490 vinfos[6].indices[1] = _ij6[1];
07491 vinfos[6].maxsolutions = _nj6;
07492 std::vector<int> vfree(0);
07493 solutions.AddSolution(vinfos,vfree);
07494 }
07495 }
07496 }
07497 
07498 }
07499 
07500 }
07501 
07502 } else
07503 {
07504 {
07505 IkReal j3array[1], cj3array[1], sj3array[1];
07506 bool j3valid[1]={false};
07507 _nj3 = 1;
07508 IkReal x2386=((IkReal(1.00000000000000))*(r21));
07509 IkReal x2387=((cj4)*(cj5));
07510 IkReal x2388=((r20)*(sj6));
07511 if( IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(sj5)*(x2388)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2386)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x2387)))+(((x2387)*(x2388)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2386))))))) < IKFAST_ATAN2_MAGTHRESH )
07512     continue;
07513 j3array[0]=IKatan2(((gconst56)*(((((IkReal(-1.00000000000000))*(sj5)*(x2388)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x2386)))+(((cj5)*(r22)))))), ((gconst56)*(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x2387)))+(((x2387)*(x2388)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x2386)))))));
07514 sj3array[0]=IKsin(j3array[0]);
07515 cj3array[0]=IKcos(j3array[0]);
07516 if( j3array[0] > IKPI )
07517 {
07518     j3array[0]-=IK2PI;
07519 }
07520 else if( j3array[0] < -IKPI )
07521 {    j3array[0]+=IK2PI;
07522 }
07523 j3valid[0] = true;
07524 for(int ij3 = 0; ij3 < 1; ++ij3)
07525 {
07526 if( !j3valid[ij3] )
07527 {
07528     continue;
07529 }
07530 _ij3[0] = ij3; _ij3[1] = -1;
07531 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07532 {
07533 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07534 {
07535     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07536 }
07537 }
07538 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07539 {
07540 IkReal evalcond[6];
07541 IkReal x2389=IKsin(j3);
07542 IkReal x2390=IKcos(j3);
07543 IkReal x2391=((sj0)*(sj5));
07544 IkReal x2392=((r00)*(sj6));
07545 IkReal x2393=((IkReal(1.00000000000000))*(cj4));
07546 IkReal x2394=((cj6)*(r01));
07547 IkReal x2395=((cj0)*(cj5));
07548 IkReal x2396=((cj5)*(sj0));
07549 IkReal x2397=((cj6)*(r11));
07550 IkReal x2398=((cj6)*(sj4));
07551 IkReal x2399=((cj0)*(sj5));
07552 IkReal x2400=((cj4)*(cj5));
07553 IkReal x2401=((cj6)*(r21));
07554 IkReal x2402=((r20)*(sj6));
07555 IkReal x2403=((r10)*(sj6));
07556 IkReal x2404=((IkReal(1.00000000000000))*(cj0));
07557 IkReal x2405=((cj0)*(sj4)*(sj6));
07558 IkReal x2406=((sj0)*(sj4)*(sj6));
07559 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x2389)))+(((sj5)*(x2401)))+(((sj5)*(x2402))));
07560 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x2398)))+(((x2400)*(x2402)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x2390)))+(((x2400)*(x2401))));
07561 evalcond[2]=((((x2391)*(x2392)))+(((IkReal(-1.00000000000000))*(r02)*(x2396)))+(((IkReal(-1.00000000000000))*(x2399)*(x2403)))+(((IkReal(-1.00000000000000))*(sj2)*(x2389)))+(((IkReal(-1.00000000000000))*(x2397)*(x2399)))+(((r12)*(x2395)))+(((x2391)*(x2394))));
07562 evalcond[3]=((((IkReal(-1.00000000000000))*(x2391)*(x2403)))+(((r12)*(x2396)))+(((r02)*(x2395)))+(((IkReal(-1.00000000000000))*(x2392)*(x2399)))+(x2390)+(((IkReal(-1.00000000000000))*(x2394)*(x2399)))+(((IkReal(-1.00000000000000))*(x2391)*(x2397))));
07563 evalcond[4]=((((cj4)*(r02)*(x2391)))+(((sj2)*(x2390)))+(((cj4)*(x2392)*(x2396)))+(((IkReal(-1.00000000000000))*(r01)*(x2406)))+(((cj4)*(x2394)*(x2396)))+(((IkReal(-1.00000000000000))*(x2393)*(x2395)*(x2397)))+(((r11)*(x2405)))+(((IkReal(-1.00000000000000))*(r10)*(x2398)*(x2404)))+(((IkReal(-1.00000000000000))*(x2393)*(x2395)*(x2403)))+(((IkReal(-1.00000000000000))*(r12)*(x2393)*(x2399)))+(((r00)*(sj0)*(x2398))));
07564 evalcond[5]=((x2389)+(((IkReal(-1.00000000000000))*(r00)*(x2398)*(x2404)))+(((r01)*(x2405)))+(((IkReal(-1.00000000000000))*(x2393)*(x2394)*(x2395)))+(((IkReal(-1.00000000000000))*(r12)*(x2391)*(x2393)))+(((IkReal(-1.00000000000000))*(x2393)*(x2396)*(x2397)))+(((IkReal(-1.00000000000000))*(x2393)*(x2396)*(x2403)))+(((r11)*(x2406)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2398)))+(((IkReal(-1.00000000000000))*(x2392)*(x2393)*(x2395)))+(((IkReal(-1.00000000000000))*(r02)*(x2393)*(x2399))));
07565 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
07566 {
07567 continue;
07568 }
07569 }
07570 
07571 {
07572 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
07573 vinfos[0].jointtype = 1;
07574 vinfos[0].foffset = j0;
07575 vinfos[0].indices[0] = _ij0[0];
07576 vinfos[0].indices[1] = _ij0[1];
07577 vinfos[0].maxsolutions = _nj0;
07578 vinfos[1].jointtype = 1;
07579 vinfos[1].foffset = j1;
07580 vinfos[1].indices[0] = _ij1[0];
07581 vinfos[1].indices[1] = _ij1[1];
07582 vinfos[1].maxsolutions = _nj1;
07583 vinfos[2].jointtype = 1;
07584 vinfos[2].foffset = j2;
07585 vinfos[2].indices[0] = _ij2[0];
07586 vinfos[2].indices[1] = _ij2[1];
07587 vinfos[2].maxsolutions = _nj2;
07588 vinfos[3].jointtype = 1;
07589 vinfos[3].foffset = j3;
07590 vinfos[3].indices[0] = _ij3[0];
07591 vinfos[3].indices[1] = _ij3[1];
07592 vinfos[3].maxsolutions = _nj3;
07593 vinfos[4].jointtype = 1;
07594 vinfos[4].foffset = j4;
07595 vinfos[4].indices[0] = _ij4[0];
07596 vinfos[4].indices[1] = _ij4[1];
07597 vinfos[4].maxsolutions = _nj4;
07598 vinfos[5].jointtype = 1;
07599 vinfos[5].foffset = j5;
07600 vinfos[5].indices[0] = _ij5[0];
07601 vinfos[5].indices[1] = _ij5[1];
07602 vinfos[5].maxsolutions = _nj5;
07603 vinfos[6].jointtype = 1;
07604 vinfos[6].foffset = j6;
07605 vinfos[6].indices[0] = _ij6[0];
07606 vinfos[6].indices[1] = _ij6[1];
07607 vinfos[6].maxsolutions = _nj6;
07608 std::vector<int> vfree(0);
07609 solutions.AddSolution(vinfos,vfree);
07610 }
07611 }
07612 }
07613 
07614 }
07615 
07616 }
07617 }
07618 }
07619 
07620 }
07621 
07622 }
07623 }
07624 }
07625 
07626 } else
07627 {
07628 IkReal x2407=((r20)*(sj6));
07629 IkReal x2408=((IkReal(0.0100000000000000))*(cj5));
07630 IkReal x2409=((IkReal(0.374290000000000))*(sj5));
07631 IkReal x2410=((cj6)*(r21));
07632 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
07633 evalcond[1]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(x2408)*(x2410)))+(((IkReal(-1.00000000000000))*(x2407)*(x2408)))+(((x2407)*(x2409)))+(((IkReal(-0.0100000000000000))*(r22)*(sj5)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x2409)*(x2410))));
07634 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  )
07635 {
07636 {
07637 IkReal j2array[1], cj2array[1], sj2array[1];
07638 bool j2valid[1]={false};
07639 _nj2 = 1;
07640 IkReal x2411=((IkReal(0.144927536231884))*(cj0));
07641 IkReal x2412=((r02)*(sj5));
07642 IkReal x2413=((IkReal(14.4927536231884))*(cj0));
07643 IkReal x2414=((cj5)*(cj6));
07644 IkReal x2415=((cj5)*(sj6));
07645 IkReal x2416=((IkReal(5.42449275362319))*(sj0));
07646 IkReal x2417=((cj5)*(r12));
07647 IkReal x2418=((IkReal(14.4927536231884))*(sj0));
07648 IkReal x2419=((IkReal(0.144927536231884))*(sj0));
07649 IkReal x2420=((sj5)*(sj6));
07650 IkReal x2421=((IkReal(5.42449275362319))*(cj0));
07651 IkReal x2422=((r12)*(sj5));
07652 IkReal x2423=((cj5)*(r02));
07653 IkReal x2424=((cj6)*(r11)*(sj5));
07654 IkReal x2425=((IkReal(5.42449275362319))*(cj6)*(r01)*(sj5));
07655 if( IKabs(((((r10)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(px)*(x2418)))+(((IkReal(-1.00000000000000))*(x2411)*(x2422)))+(((r01)*(x2414)*(x2419)))+(((py)*(x2413)))+(((x2421)*(x2424)))+(((x2412)*(x2419)))+(((IkReal(-1.00000000000000))*(r11)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2416)))+(((IkReal(-1.00000000000000))*(r10)*(x2411)*(x2415)))+(((r00)*(x2415)*(x2419)))+(((IkReal(-1.00000000000000))*(x2417)*(x2421)))+(((x2416)*(x2423))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(1.00000000000000))+(((x2411)*(x2412)))+(((IkReal(-1.00000000000000))*(px)*(x2413)))+(((r00)*(x2411)*(x2415)))+(((r11)*(x2414)*(x2419)))+(((r10)*(x2415)*(x2419)))+(((x2421)*(x2423)))+(((x2416)*(x2417)))+(((r01)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(x2416)*(x2424)))+(((x2419)*(x2422)))+(((IkReal(-1.00000000000000))*(r10)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(py)*(x2418))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r10)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(px)*(x2418)))+(((IkReal(-1.00000000000000))*(x2411)*(x2422)))+(((r01)*(x2414)*(x2419)))+(((py)*(x2413)))+(((x2421)*(x2424)))+(((x2412)*(x2419)))+(((IkReal(-1.00000000000000))*(r11)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2416)))+(((IkReal(-1.00000000000000))*(r10)*(x2411)*(x2415)))+(((r00)*(x2415)*(x2419)))+(((IkReal(-1.00000000000000))*(x2417)*(x2421)))+(((x2416)*(x2423)))))+IKsqr(((IkReal(1.00000000000000))+(((x2411)*(x2412)))+(((IkReal(-1.00000000000000))*(px)*(x2413)))+(((r00)*(x2411)*(x2415)))+(((r11)*(x2414)*(x2419)))+(((r10)*(x2415)*(x2419)))+(((x2421)*(x2423)))+(((x2416)*(x2417)))+(((r01)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(x2416)*(x2424)))+(((x2419)*(x2422)))+(((IkReal(-1.00000000000000))*(r10)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(py)*(x2418)))))-1) <= IKFAST_SINCOS_THRESH )
07656     continue;
07657 j2array[0]=IKatan2(((((r10)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(px)*(x2418)))+(((IkReal(-1.00000000000000))*(x2411)*(x2422)))+(((r01)*(x2414)*(x2419)))+(((py)*(x2413)))+(((x2421)*(x2424)))+(((x2412)*(x2419)))+(((IkReal(-1.00000000000000))*(r11)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2416)))+(((IkReal(-1.00000000000000))*(r10)*(x2411)*(x2415)))+(((r00)*(x2415)*(x2419)))+(((IkReal(-1.00000000000000))*(x2417)*(x2421)))+(((x2416)*(x2423)))), ((IkReal(1.00000000000000))+(((x2411)*(x2412)))+(((IkReal(-1.00000000000000))*(px)*(x2413)))+(((r00)*(x2411)*(x2415)))+(((r11)*(x2414)*(x2419)))+(((r10)*(x2415)*(x2419)))+(((x2421)*(x2423)))+(((x2416)*(x2417)))+(((r01)*(x2411)*(x2414)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(sj5)*(x2421)))+(((IkReal(-1.00000000000000))*(r00)*(x2420)*(x2421)))+(((IkReal(-1.00000000000000))*(x2416)*(x2424)))+(((x2419)*(x2422)))+(((IkReal(-1.00000000000000))*(r10)*(x2416)*(x2420)))+(((IkReal(-1.00000000000000))*(py)*(x2418)))));
07658 sj2array[0]=IKsin(j2array[0]);
07659 cj2array[0]=IKcos(j2array[0]);
07660 if( j2array[0] > IKPI )
07661 {
07662     j2array[0]-=IK2PI;
07663 }
07664 else if( j2array[0] < -IKPI )
07665 {    j2array[0]+=IK2PI;
07666 }
07667 j2valid[0] = true;
07668 for(int ij2 = 0; ij2 < 1; ++ij2)
07669 {
07670 if( !j2valid[ij2] )
07671 {
07672     continue;
07673 }
07674 _ij2[0] = ij2; _ij2[1] = -1;
07675 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
07676 {
07677 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
07678 {
07679     j2valid[iij2]=false; _ij2[1] = iij2; break; 
07680 }
07681 }
07682 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
07683 {
07684 IkReal evalcond[2];
07685 IkReal x2426=((IkReal(0.374290000000000))*(sj0));
07686 IkReal x2427=((cj5)*(r02));
07687 IkReal x2428=((IkReal(0.0100000000000000))*(cj0));
07688 IkReal x2429=((cj5)*(cj6));
07689 IkReal x2430=((r02)*(sj5));
07690 IkReal x2431=((cj5)*(sj6));
07691 IkReal x2432=((IkReal(1.00000000000000))*(py));
07692 IkReal x2433=((cj6)*(sj5));
07693 IkReal x2434=((IkReal(0.0100000000000000))*(sj0));
07694 IkReal x2435=((sj5)*(sj6));
07695 IkReal x2436=((cj5)*(r12));
07696 IkReal x2437=((IkReal(0.374290000000000))*(cj0));
07697 IkReal x2438=((r12)*(sj5));
07698 IkReal x2439=((x2433)*(x2437));
07699 IkReal x2440=((x2435)*(x2437));
07700 evalcond[0]=((((x2428)*(x2438)))+(((IkReal(-1.00000000000000))*(r10)*(x2440)))+(((IkReal(-1.00000000000000))*(r00)*(x2431)*(x2434)))+(((IkReal(-1.00000000000000))*(r11)*(x2439)))+(((IkReal(-1.00000000000000))*(r01)*(x2429)*(x2434)))+(((r01)*(x2426)*(x2433)))+(((IkReal(-1.00000000000000))*(x2426)*(x2427)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((r10)*(x2428)*(x2431)))+(((r00)*(x2426)*(x2435)))+(((px)*(sj0)))+(((r11)*(x2428)*(x2429)))+(((IkReal(-1.00000000000000))*(cj0)*(x2432)))+(((IkReal(-1.00000000000000))*(x2430)*(x2434)))+(((x2436)*(x2437))));
07701 evalcond[1]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x2434)*(x2438)))+(((IkReal(-0.0690000000000000))*(IKcos(j2))))+(((r00)*(x2428)*(x2431)))+(((x2426)*(x2436)))+(((r10)*(x2431)*(x2434)))+(((x2427)*(x2437)))+(((IkReal(-1.00000000000000))*(r00)*(x2440)))+(((IkReal(-1.00000000000000))*(r01)*(x2439)))+(((IkReal(-1.00000000000000))*(r10)*(x2426)*(x2435)))+(((r11)*(x2429)*(x2434)))+(((x2428)*(x2430)))+(((r01)*(x2428)*(x2429)))+(((IkReal(-1.00000000000000))*(r11)*(x2426)*(x2433)))+(((IkReal(-1.00000000000000))*(sj0)*(x2432))));
07702 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
07703 {
07704 continue;
07705 }
07706 }
07707 
07708 {
07709 IkReal dummyeval[1];
07710 IkReal gconst65;
07711 IkReal x2441=(cj6)*(cj6);
07712 IkReal x2442=(sj6)*(sj6);
07713 IkReal x2443=((IkReal(1.00000000000000))*(r21));
07714 IkReal x2444=((cj6)*(r20));
07715 IkReal x2445=((r22)*(sj5));
07716 IkReal x2446=((r01)*(sj0));
07717 IkReal x2447=((r00)*(sj0));
07718 IkReal x2448=((cj0)*(r10));
07719 IkReal x2449=((r02)*(sj0)*(sj5));
07720 IkReal x2450=((cj5)*(x2441));
07721 IkReal x2451=((cj0)*(r12)*(sj5));
07722 IkReal x2452=((IkReal(1.00000000000000))*(cj0)*(r11));
07723 IkReal x2453=((cj5)*(x2442));
07724 IkReal x2454=((r20)*(x2453));
07725 gconst65=IKsign(((((IkReal(-1.00000000000000))*(cj6)*(x2445)*(x2447)))+(((sj6)*(x2445)*(x2446)))+(((r21)*(x2448)*(x2450)))+(((IkReal(-1.00000000000000))*(x2443)*(x2447)*(x2453)))+(((x2446)*(x2454)))+(((IkReal(-1.00000000000000))*(x2443)*(x2447)*(x2450)))+(((r21)*(x2448)*(x2453)))+(((IkReal(-1.00000000000000))*(x2444)*(x2451)))+(((IkReal(-1.00000000000000))*(sj6)*(x2445)*(x2452)))+(((r20)*(x2446)*(x2450)))+(((IkReal(-1.00000000000000))*(x2452)*(x2454)))+(((IkReal(-1.00000000000000))*(r20)*(x2450)*(x2452)))+(((x2444)*(x2449)))+(((IkReal(-1.00000000000000))*(sj6)*(x2443)*(x2449)))+(((r21)*(sj6)*(x2451)))+(((cj6)*(x2445)*(x2448)))));
07726 IkReal x2455=(cj6)*(cj6);
07727 IkReal x2456=(sj6)*(sj6);
07728 IkReal x2457=((IkReal(1.00000000000000))*(r21));
07729 IkReal x2458=((cj6)*(r20));
07730 IkReal x2459=((r22)*(sj5));
07731 IkReal x2460=((r01)*(sj0));
07732 IkReal x2461=((r00)*(sj0));
07733 IkReal x2462=((cj0)*(r10));
07734 IkReal x2463=((r02)*(sj0)*(sj5));
07735 IkReal x2464=((cj5)*(x2455));
07736 IkReal x2465=((cj0)*(r12)*(sj5));
07737 IkReal x2466=((IkReal(1.00000000000000))*(cj0)*(r11));
07738 IkReal x2467=((cj5)*(x2456));
07739 IkReal x2468=((r20)*(x2467));
07740 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2458)*(x2465)))+(((r21)*(sj6)*(x2465)))+(((IkReal(-1.00000000000000))*(x2457)*(x2461)*(x2467)))+(((x2458)*(x2463)))+(((IkReal(-1.00000000000000))*(sj6)*(x2459)*(x2466)))+(((IkReal(-1.00000000000000))*(x2466)*(x2468)))+(((cj6)*(x2459)*(x2462)))+(((IkReal(-1.00000000000000))*(x2457)*(x2461)*(x2464)))+(((r20)*(x2460)*(x2464)))+(((r21)*(x2462)*(x2467)))+(((sj6)*(x2459)*(x2460)))+(((IkReal(-1.00000000000000))*(cj6)*(x2459)*(x2461)))+(((IkReal(-1.00000000000000))*(r20)*(x2464)*(x2466)))+(((IkReal(-1.00000000000000))*(sj6)*(x2457)*(x2463)))+(((r21)*(x2462)*(x2464)))+(((x2460)*(x2468))));
07741 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07742 {
07743 {
07744 IkReal dummyeval[1];
07745 IkReal gconst66;
07746 IkReal x2469=(sj6)*(sj6);
07747 IkReal x2470=(cj6)*(cj6);
07748 IkReal x2471=((r10)*(sj0));
07749 IkReal x2472=((r22)*(sj5));
07750 IkReal x2473=((cj0)*(cj5));
07751 IkReal x2474=((IkReal(1.00000000000000))*(r20));
07752 IkReal x2475=((cj0)*(sj6));
07753 IkReal x2476=((r21)*(sj5));
07754 IkReal x2477=((sj0)*(sj6));
07755 IkReal x2478=((cj6)*(sj5));
07756 IkReal x2479=((r21)*(x2470));
07757 IkReal x2480=((cj5)*(r11)*(sj0));
07758 IkReal x2481=((r21)*(x2469));
07759 gconst66=IKsign(((((r12)*(x2476)*(x2477)))+(((IkReal(-1.00000000000000))*(x2470)*(x2474)*(x2480)))+(((IkReal(-1.00000000000000))*(r01)*(x2469)*(x2473)*(x2474)))+(((IkReal(-1.00000000000000))*(r01)*(x2472)*(x2475)))+(((r00)*(x2473)*(x2481)))+(((cj5)*(x2471)*(x2481)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2474)*(x2478)))+(((r02)*(x2475)*(x2476)))+(((IkReal(-1.00000000000000))*(x2469)*(x2474)*(x2480)))+(((cj5)*(x2471)*(x2479)))+(((r00)*(x2473)*(x2479)))+(((IkReal(-1.00000000000000))*(r11)*(x2472)*(x2477)))+(((cj0)*(cj6)*(r00)*(x2472)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2474)*(x2478)))+(((IkReal(-1.00000000000000))*(r01)*(x2470)*(x2473)*(x2474)))+(((cj6)*(x2471)*(x2472)))));
07760 IkReal x2482=(sj6)*(sj6);
07761 IkReal x2483=(cj6)*(cj6);
07762 IkReal x2484=((r10)*(sj0));
07763 IkReal x2485=((r22)*(sj5));
07764 IkReal x2486=((cj0)*(cj5));
07765 IkReal x2487=((IkReal(1.00000000000000))*(r20));
07766 IkReal x2488=((cj0)*(sj6));
07767 IkReal x2489=((r21)*(sj5));
07768 IkReal x2490=((sj0)*(sj6));
07769 IkReal x2491=((cj6)*(sj5));
07770 IkReal x2492=((r21)*(x2483));
07771 IkReal x2493=((cj5)*(r11)*(sj0));
07772 IkReal x2494=((r21)*(x2482));
07773 dummyeval[0]=((((cj6)*(x2484)*(x2485)))+(((r02)*(x2488)*(x2489)))+(((r00)*(x2486)*(x2494)))+(((cj5)*(x2484)*(x2494)))+(((IkReal(-1.00000000000000))*(r01)*(x2483)*(x2486)*(x2487)))+(((IkReal(-1.00000000000000))*(x2482)*(x2487)*(x2493)))+(((IkReal(-1.00000000000000))*(x2483)*(x2487)*(x2493)))+(((IkReal(-1.00000000000000))*(r01)*(x2485)*(x2488)))+(((IkReal(-1.00000000000000))*(r01)*(x2482)*(x2486)*(x2487)))+(((cj5)*(x2484)*(x2492)))+(((IkReal(-1.00000000000000))*(r11)*(x2485)*(x2490)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2487)*(x2491)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2487)*(x2491)))+(((cj0)*(cj6)*(r00)*(x2485)))+(((r00)*(x2486)*(x2492)))+(((r12)*(x2489)*(x2490))));
07774 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07775 {
07776 {
07777 IkReal dummyeval[1];
07778 dummyeval[0]=cj2;
07779 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07780 {
07781 {
07782 IkReal evalcond[5];
07783 IkReal x2495=((cj0)*(r11));
07784 IkReal x2496=((r01)*(sj0));
07785 IkReal x2497=((cj0)*(r01));
07786 IkReal x2498=((IkReal(0.374290000000000))*(sj0));
07787 IkReal x2499=((cj5)*(r02));
07788 IkReal x2500=((IkReal(0.374290000000000))*(cj0));
07789 IkReal x2501=((r11)*(sj0));
07790 IkReal x2502=((IkReal(0.0100000000000000))*(cj0));
07791 IkReal x2503=((r02)*(sj5));
07792 IkReal x2504=((cj5)*(sj6));
07793 IkReal x2505=((IkReal(1.00000000000000))*(sj0));
07794 IkReal x2506=((cj5)*(r12));
07795 IkReal x2507=((IkReal(0.0100000000000000))*(sj5));
07796 IkReal x2508=((sj5)*(sj6));
07797 IkReal x2509=((IkReal(1.00000000000000))*(cj0));
07798 IkReal x2510=((IkReal(0.0100000000000000))*(sj0));
07799 IkReal x2511=((IkReal(0.374290000000000))*(cj6)*(sj5));
07800 IkReal x2512=((IkReal(0.0100000000000000))*(cj5)*(cj6));
07801 IkReal x2513=((r10)*(x2508));
07802 IkReal x2514=((IkReal(1.00000000000000))*(cj6)*(sj5));
07803 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
07804 evalcond[1]=((IkReal(0.364420000000000))+(((IkReal(0.374290000000000))*(r20)*(x2508)))+(((IkReal(-0.0100000000000000))*(r20)*(x2504)))+(((IkReal(-1.00000000000000))*(r21)*(x2512)))+(((r21)*(x2511)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x2507)))+(pz));
07805 evalcond[2]=((((sj0)*(x2506)))+(((IkReal(-1.00000000000000))*(x2501)*(x2514)))+(((IkReal(-1.00000000000000))*(r00)*(x2508)*(x2509)))+(((IkReal(-1.00000000000000))*(x2505)*(x2513)))+(((cj0)*(x2499)))+(((IkReal(-1.00000000000000))*(x2497)*(x2514))));
07806 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x2500)*(x2513)))+(((r10)*(x2502)*(x2504)))+(((IkReal(-1.00000000000000))*(x2495)*(x2511)))+(((IkReal(-1.00000000000000))*(py)*(x2509)))+(((x2500)*(x2506)))+(((IkReal(-1.00000000000000))*(x2498)*(x2499)))+(((x2495)*(x2512)))+(((IkReal(-1.00000000000000))*(r00)*(x2504)*(x2510)))+(((x2496)*(x2511)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x2503)*(x2510)))+(((r12)*(sj5)*(x2502)))+(((r00)*(x2498)*(x2508)))+(((IkReal(-1.00000000000000))*(x2496)*(x2512))));
07807 evalcond[4]=((IkReal(0.0690000000000000))+(((r00)*(x2502)*(x2504)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(sj5)*(x2498)))+(((x2498)*(x2506)))+(((x2502)*(x2503)))+(((IkReal(-1.00000000000000))*(r00)*(x2500)*(x2508)))+(((r12)*(sj0)*(x2507)))+(((IkReal(-1.00000000000000))*(px)*(x2509)))+(((IkReal(-1.00000000000000))*(x2497)*(x2511)))+(((x2501)*(x2512)))+(((x2499)*(x2500)))+(((x2497)*(x2512)))+(((IkReal(-1.00000000000000))*(py)*(x2505)))+(((r10)*(x2504)*(x2510)))+(((IkReal(-1.00000000000000))*(x2498)*(x2513))));
07808 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
07809 {
07810 {
07811 IkReal j3array[1], cj3array[1], sj3array[1];
07812 bool j3valid[1]={false};
07813 _nj3 = 1;
07814 IkReal x2515=((sj5)*(sj6));
07815 IkReal x2516=((cj6)*(sj5));
07816 IkReal x2517=((IkReal(1.00000000000000))*(cj0));
07817 IkReal x2518=((IkReal(1.00000000000000))*(cj5));
07818 if( IKabs(((((IkReal(-1.00000000000000))*(r11)*(x2516)*(x2517)))+(((r00)*(sj0)*(x2515)))+(((IkReal(-1.00000000000000))*(r10)*(x2515)*(x2517)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2518)))+(((cj0)*(cj5)*(r12)))+(((r01)*(sj0)*(x2516))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r20)*(x2515)))+(((r21)*(x2516)))+(((IkReal(-1.00000000000000))*(r22)*(x2518))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r11)*(x2516)*(x2517)))+(((r00)*(sj0)*(x2515)))+(((IkReal(-1.00000000000000))*(r10)*(x2515)*(x2517)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2518)))+(((cj0)*(cj5)*(r12)))+(((r01)*(sj0)*(x2516)))))+IKsqr(((((r20)*(x2515)))+(((r21)*(x2516)))+(((IkReal(-1.00000000000000))*(r22)*(x2518)))))-1) <= IKFAST_SINCOS_THRESH )
07819     continue;
07820 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r11)*(x2516)*(x2517)))+(((r00)*(sj0)*(x2515)))+(((IkReal(-1.00000000000000))*(r10)*(x2515)*(x2517)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2518)))+(((cj0)*(cj5)*(r12)))+(((r01)*(sj0)*(x2516)))), ((((r20)*(x2515)))+(((r21)*(x2516)))+(((IkReal(-1.00000000000000))*(r22)*(x2518)))));
07821 sj3array[0]=IKsin(j3array[0]);
07822 cj3array[0]=IKcos(j3array[0]);
07823 if( j3array[0] > IKPI )
07824 {
07825     j3array[0]-=IK2PI;
07826 }
07827 else if( j3array[0] < -IKPI )
07828 {    j3array[0]+=IK2PI;
07829 }
07830 j3valid[0] = true;
07831 for(int ij3 = 0; ij3 < 1; ++ij3)
07832 {
07833 if( !j3valid[ij3] )
07834 {
07835     continue;
07836 }
07837 _ij3[0] = ij3; _ij3[1] = -1;
07838 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
07839 {
07840 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
07841 {
07842     j3valid[iij3]=false; _ij3[1] = iij3; break; 
07843 }
07844 }
07845 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
07846 {
07847 IkReal evalcond[2];
07848 IkReal x2519=((sj5)*(sj6));
07849 IkReal x2520=((cj6)*(sj5));
07850 IkReal x2521=((IkReal(1.00000000000000))*(cj0));
07851 IkReal x2522=((IkReal(1.00000000000000))*(cj5));
07852 evalcond[0]=((((r21)*(x2520)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((r20)*(x2519)))+(((IkReal(-1.00000000000000))*(r22)*(x2522))));
07853 evalcond[1]=((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2522)))+(((IkReal(-1.00000000000000))*(r11)*(x2520)*(x2521)))+(((r01)*(sj0)*(x2520)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x2519)*(x2521)))+(((r00)*(sj0)*(x2519)))+(((IkReal(-1.00000000000000))*(IKsin(j3)))));
07854 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
07855 {
07856 continue;
07857 }
07858 }
07859 
07860 {
07861 IkReal dummyeval[1];
07862 IkReal gconst71;
07863 IkReal x2523=(r21)*(r21);
07864 IkReal x2524=(cj5)*(cj5);
07865 IkReal x2525=(sj6)*(sj6);
07866 IkReal x2526=(cj6)*(cj6);
07867 IkReal x2527=(r20)*(r20);
07868 IkReal x2528=((cj6)*(r21));
07869 IkReal x2529=((IkReal(2.00000000000000))*(r20)*(sj6));
07870 IkReal x2530=((cj5)*(r22)*(sj5));
07871 IkReal x2531=((IkReal(1.00000000000000))*(x2525));
07872 IkReal x2532=((IkReal(1.00000000000000))*(x2526));
07873 gconst71=IKsign(((((IkReal(-1.00000000000000))*(x2523)*(x2531)))+(((IkReal(-2.00000000000000))*(x2528)*(x2530)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x2523)*(x2524)*(x2532)))+(((IkReal(-1.00000000000000))*(x2527)*(x2532)))+(((IkReal(-1.00000000000000))*(x2524)*(x2527)*(x2531)))+(((x2528)*(x2529)))+(((IkReal(-1.00000000000000))*(x2524)*(x2528)*(x2529)))+(((IkReal(-1.00000000000000))*(x2529)*(x2530)))));
07874 IkReal x2533=(r21)*(r21);
07875 IkReal x2534=(cj5)*(cj5);
07876 IkReal x2535=(sj6)*(sj6);
07877 IkReal x2536=(cj6)*(cj6);
07878 IkReal x2537=(r20)*(r20);
07879 IkReal x2538=((cj6)*(r21));
07880 IkReal x2539=((IkReal(2.00000000000000))*(r20)*(sj6));
07881 IkReal x2540=((cj5)*(r22)*(sj5));
07882 IkReal x2541=((IkReal(1.00000000000000))*(x2535));
07883 IkReal x2542=((IkReal(1.00000000000000))*(x2536));
07884 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2533)*(x2534)*(x2542)))+(((IkReal(-2.00000000000000))*(x2538)*(x2540)))+(((IkReal(-1.00000000000000))*(x2533)*(x2541)))+(((IkReal(-1.00000000000000))*(x2534)*(x2537)*(x2541)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x2534)*(x2538)*(x2539)))+(((x2538)*(x2539)))+(((IkReal(-1.00000000000000))*(x2537)*(x2542)))+(((IkReal(-1.00000000000000))*(x2539)*(x2540))));
07885 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07886 {
07887 {
07888 IkReal dummyeval[1];
07889 IkReal gconst72;
07890 IkReal x2543=(sj6)*(sj6);
07891 IkReal x2544=(cj5)*(cj5);
07892 IkReal x2545=(cj6)*(cj6);
07893 IkReal x2546=(sj5)*(sj5);
07894 IkReal x2547=((r01)*(sj0));
07895 IkReal x2548=((cj0)*(sj6));
07896 IkReal x2549=((cj6)*(r21));
07897 IkReal x2550=((r22)*(sj0));
07898 IkReal x2551=((cj5)*(sj5));
07899 IkReal x2552=((r00)*(sj6));
07900 IkReal x2553=((IkReal(1.00000000000000))*(cj0));
07901 IkReal x2554=((cj6)*(r22));
07902 IkReal x2555=((r02)*(sj0));
07903 IkReal x2556=((r20)*(sj6));
07904 IkReal x2557=((IkReal(1.00000000000000))*(cj6));
07905 IkReal x2558=((r00)*(sj0));
07906 IkReal x2559=((r21)*(x2544));
07907 IkReal x2560=((IkReal(1.00000000000000))*(x2551));
07908 IkReal x2561=((r21)*(x2543));
07909 IkReal x2562=((cj6)*(r11)*(r20));
07910 IkReal x2563=((r20)*(x2545));
07911 IkReal x2564=((r20)*(x2543)*(x2544));
07912 gconst72=IKsign(((((IkReal(-1.00000000000000))*(r11)*(x2551)*(x2553)*(x2554)))+(((x2558)*(x2563)))+(((x2558)*(x2564)))+(((cj6)*(x2544)*(x2547)*(x2556)))+(((IkReal(-1.00000000000000))*(x2547)*(x2556)*(x2557)))+(((x2547)*(x2561)))+(((x2550)*(x2551)*(x2552)))+(((r10)*(x2548)*(x2549)))+(((IkReal(-1.00000000000000))*(r11)*(r20)*(x2544)*(x2548)*(x2557)))+(((r02)*(x2546)*(x2550)))+(((IkReal(-1.00000000000000))*(r12)*(x2549)*(x2551)*(x2553)))+(((IkReal(-1.00000000000000))*(r11)*(x2545)*(x2553)*(x2559)))+(((IkReal(-1.00000000000000))*(r12)*(r20)*(x2548)*(x2560)))+(((x2549)*(x2551)*(x2555)))+(((x2547)*(x2551)*(x2554)))+(((IkReal(-1.00000000000000))*(r12)*(r22)*(x2546)*(x2553)))+(((x2548)*(x2562)))+(((sj0)*(x2544)*(x2549)*(x2552)))+(((IkReal(-1.00000000000000))*(r10)*(x2544)*(x2548)*(x2549)))+(((IkReal(-1.00000000000000))*(r10)*(x2553)*(x2563)))+(((IkReal(-1.00000000000000))*(r10)*(x2553)*(x2564)))+(((IkReal(-1.00000000000000))*(r10)*(r22)*(x2548)*(x2560)))+(((x2545)*(x2547)*(x2559)))+(((IkReal(-1.00000000000000))*(sj0)*(x2549)*(x2552)))+(((x2551)*(x2555)*(x2556)))+(((IkReal(-1.00000000000000))*(r11)*(x2553)*(x2561)))));
07913 IkReal x2565=(sj6)*(sj6);
07914 IkReal x2566=(cj5)*(cj5);
07915 IkReal x2567=(cj6)*(cj6);
07916 IkReal x2568=(sj5)*(sj5);
07917 IkReal x2569=((r01)*(sj0));
07918 IkReal x2570=((cj0)*(sj6));
07919 IkReal x2571=((cj6)*(r21));
07920 IkReal x2572=((r22)*(sj0));
07921 IkReal x2573=((cj5)*(sj5));
07922 IkReal x2574=((r00)*(sj6));
07923 IkReal x2575=((IkReal(1.00000000000000))*(cj0));
07924 IkReal x2576=((cj6)*(r22));
07925 IkReal x2577=((r02)*(sj0));
07926 IkReal x2578=((r20)*(sj6));
07927 IkReal x2579=((IkReal(1.00000000000000))*(cj6));
07928 IkReal x2580=((r00)*(sj0));
07929 IkReal x2581=((r21)*(x2566));
07930 IkReal x2582=((IkReal(1.00000000000000))*(x2573));
07931 IkReal x2583=((r21)*(x2565));
07932 IkReal x2584=((cj6)*(r11)*(r20));
07933 IkReal x2585=((r20)*(x2567));
07934 IkReal x2586=((r20)*(x2565)*(x2566));
07935 dummyeval[0]=((((IkReal(-1.00000000000000))*(r11)*(x2567)*(x2575)*(x2581)))+(((x2580)*(x2585)))+(((cj6)*(x2566)*(x2569)*(x2578)))+(((IkReal(-1.00000000000000))*(sj0)*(x2571)*(x2574)))+(((x2569)*(x2583)))+(((IkReal(-1.00000000000000))*(r12)*(x2571)*(x2573)*(x2575)))+(((IkReal(-1.00000000000000))*(r12)*(r20)*(x2570)*(x2582)))+(((IkReal(-1.00000000000000))*(r11)*(r20)*(x2566)*(x2570)*(x2579)))+(((IkReal(-1.00000000000000))*(r10)*(x2575)*(x2585)))+(((x2570)*(x2584)))+(((x2580)*(x2586)))+(((x2567)*(x2569)*(x2581)))+(((IkReal(-1.00000000000000))*(x2569)*(x2578)*(x2579)))+(((x2571)*(x2573)*(x2577)))+(((x2572)*(x2573)*(x2574)))+(((sj0)*(x2566)*(x2571)*(x2574)))+(((IkReal(-1.00000000000000))*(r12)*(r22)*(x2568)*(x2575)))+(((IkReal(-1.00000000000000))*(r10)*(r22)*(x2570)*(x2582)))+(((IkReal(-1.00000000000000))*(r10)*(x2566)*(x2570)*(x2571)))+(((r02)*(x2568)*(x2572)))+(((IkReal(-1.00000000000000))*(r11)*(x2573)*(x2575)*(x2576)))+(((x2569)*(x2573)*(x2576)))+(((x2573)*(x2577)*(x2578)))+(((IkReal(-1.00000000000000))*(r11)*(x2575)*(x2583)))+(((IkReal(-1.00000000000000))*(r10)*(x2575)*(x2586)))+(((r10)*(x2570)*(x2571))));
07936 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07937 {
07938 continue;
07939 
07940 } else
07941 {
07942 {
07943 IkReal j4array[1], cj4array[1], sj4array[1];
07944 bool j4valid[1]={false};
07945 _nj4 = 1;
07946 IkReal x2587=((IkReal(1.00000000000000))*(cj3));
07947 IkReal x2588=((cj5)*(x2587));
07948 if( IKabs(((gconst72)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2587)))+(((cj3)*(r21)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst72)*(((((IkReal(-1.00000000000000))*(cj6)*(r21)*(x2588)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x2588)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2587))))))) < IKFAST_ATAN2_MAGTHRESH )
07949     continue;
07950 j4array[0]=IKatan2(((gconst72)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2587)))+(((cj3)*(r21)*(sj6)))))), ((gconst72)*(((((IkReal(-1.00000000000000))*(cj6)*(r21)*(x2588)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x2588)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2587)))))));
07951 sj4array[0]=IKsin(j4array[0]);
07952 cj4array[0]=IKcos(j4array[0]);
07953 if( j4array[0] > IKPI )
07954 {
07955     j4array[0]-=IK2PI;
07956 }
07957 else if( j4array[0] < -IKPI )
07958 {    j4array[0]+=IK2PI;
07959 }
07960 j4valid[0] = true;
07961 for(int ij4 = 0; ij4 < 1; ++ij4)
07962 {
07963 if( !j4valid[ij4] )
07964 {
07965     continue;
07966 }
07967 _ij4[0] = ij4; _ij4[1] = -1;
07968 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
07969 {
07970 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
07971 {
07972     j4valid[iij4]=false; _ij4[1] = iij4; break; 
07973 }
07974 }
07975 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
07976 {
07977 IkReal evalcond[6];
07978 IkReal x2589=IKsin(j4);
07979 IkReal x2590=IKcos(j4);
07980 IkReal x2591=((r22)*(sj5));
07981 IkReal x2592=((IkReal(1.00000000000000))*(cj6));
07982 IkReal x2593=((IkReal(1.00000000000000))*(cj0));
07983 IkReal x2594=((cj5)*(r11));
07984 IkReal x2595=((cj5)*(cj6));
07985 IkReal x2596=((r11)*(sj6));
07986 IkReal x2597=((IkReal(1.00000000000000))*(sj6));
07987 IkReal x2598=((cj6)*(r00));
07988 IkReal x2599=((r12)*(sj5));
07989 IkReal x2600=((r02)*(sj5));
07990 IkReal x2601=((cj6)*(r10));
07991 IkReal x2602=((cj5)*(sj6));
07992 IkReal x2603=((cj5)*(r01));
07993 IkReal x2604=((sj0)*(x2589));
07994 IkReal x2605=((r00)*(x2602));
07995 IkReal x2606=((cj0)*(x2589));
07996 IkReal x2607=((sj0)*(x2590));
07997 IkReal x2608=((r20)*(x2590));
07998 IkReal x2609=((cj0)*(x2590));
07999 IkReal x2610=((r21)*(x2589));
08000 IkReal x2611=((r21)*(x2590));
08001 IkReal x2612=((r20)*(x2589));
08002 IkReal x2613=((x2590)*(x2599));
08003 IkReal x2614=((r01)*(sj6)*(x2590));
08004 IkReal x2615=((cj5)*(r10)*(x2597));
08005 evalcond[0]=((((sj6)*(x2611)))+(((IkReal(-1.00000000000000))*(x2592)*(x2608)))+(((x2602)*(x2612)))+(((x2595)*(x2610)))+(((x2589)*(x2591))));
08006 evalcond[1]=((((x2602)*(x2608)))+(((x2590)*(x2591)))+(((IkReal(-1.00000000000000))*(x2597)*(x2610)))+(((cj6)*(x2612)))+(((IkReal(-1.00000000000000))*(sj3)))+(((x2595)*(x2611))));
08007 evalcond[2]=((((IkReal(-1.00000000000000))*(x2589)*(x2593)*(x2599)))+(((IkReal(-1.00000000000000))*(r10)*(x2589)*(x2593)*(x2602)))+(((x2600)*(x2604)))+(((x2604)*(x2605)))+(((IkReal(-1.00000000000000))*(r00)*(x2592)*(x2607)))+(((r01)*(x2595)*(x2604)))+(((IkReal(-1.00000000000000))*(x2592)*(x2594)*(x2606)))+(((IkReal(-1.00000000000000))*(x2590)*(x2593)*(x2596)))+(((x2601)*(x2609)))+(((r01)*(sj6)*(x2607))));
08008 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x2592)*(x2606)))+(((IkReal(-1.00000000000000))*(x2593)*(x2613)))+(((IkReal(-1.00000000000000))*(r10)*(x2590)*(x2593)*(x2602)))+(((IkReal(-1.00000000000000))*(x2592)*(x2594)*(x2609)))+(cj3)+(((x2600)*(x2607)))+(((x2598)*(x2604)))+(((IkReal(-1.00000000000000))*(r01)*(x2597)*(x2604)))+(((r01)*(x2595)*(x2607)))+(((x2605)*(x2607)))+(((x2596)*(x2606))));
08009 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2604)*(x2615)))+(((IkReal(-1.00000000000000))*(x2589)*(x2593)*(x2600)))+(((IkReal(-1.00000000000000))*(x2589)*(x2593)*(x2605)))+(((IkReal(-1.00000000000000))*(x2592)*(x2594)*(x2604)))+(((IkReal(-1.00000000000000))*(x2592)*(x2603)*(x2606)))+(((IkReal(-1.00000000000000))*(x2599)*(x2604)))+(((x2601)*(x2607)))+(((IkReal(-1.00000000000000))*(x2596)*(x2607)))+(((x2598)*(x2609)))+(((IkReal(-1.00000000000000))*(x2593)*(x2614))));
08010 evalcond[5]=((((IkReal(-1.00000000000000))*(x2607)*(x2615)))+(((r01)*(sj6)*(x2606)))+(((IkReal(-1.00000000000000))*(r00)*(x2592)*(x2606)))+(((IkReal(-1.00000000000000))*(x2592)*(x2603)*(x2609)))+(((IkReal(-1.00000000000000))*(x2590)*(x2593)*(x2600)))+(((IkReal(-1.00000000000000))*(x2599)*(x2607)))+(((IkReal(-1.00000000000000))*(x2590)*(x2593)*(x2605)))+(((IkReal(-1.00000000000000))*(x2592)*(x2594)*(x2607)))+(((x2596)*(x2604)))+(((IkReal(-1.00000000000000))*(r10)*(x2592)*(x2604))));
08011 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08012 {
08013 continue;
08014 }
08015 }
08016 
08017 {
08018 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08019 vinfos[0].jointtype = 1;
08020 vinfos[0].foffset = j0;
08021 vinfos[0].indices[0] = _ij0[0];
08022 vinfos[0].indices[1] = _ij0[1];
08023 vinfos[0].maxsolutions = _nj0;
08024 vinfos[1].jointtype = 1;
08025 vinfos[1].foffset = j1;
08026 vinfos[1].indices[0] = _ij1[0];
08027 vinfos[1].indices[1] = _ij1[1];
08028 vinfos[1].maxsolutions = _nj1;
08029 vinfos[2].jointtype = 1;
08030 vinfos[2].foffset = j2;
08031 vinfos[2].indices[0] = _ij2[0];
08032 vinfos[2].indices[1] = _ij2[1];
08033 vinfos[2].maxsolutions = _nj2;
08034 vinfos[3].jointtype = 1;
08035 vinfos[3].foffset = j3;
08036 vinfos[3].indices[0] = _ij3[0];
08037 vinfos[3].indices[1] = _ij3[1];
08038 vinfos[3].maxsolutions = _nj3;
08039 vinfos[4].jointtype = 1;
08040 vinfos[4].foffset = j4;
08041 vinfos[4].indices[0] = _ij4[0];
08042 vinfos[4].indices[1] = _ij4[1];
08043 vinfos[4].maxsolutions = _nj4;
08044 vinfos[5].jointtype = 1;
08045 vinfos[5].foffset = j5;
08046 vinfos[5].indices[0] = _ij5[0];
08047 vinfos[5].indices[1] = _ij5[1];
08048 vinfos[5].maxsolutions = _nj5;
08049 vinfos[6].jointtype = 1;
08050 vinfos[6].foffset = j6;
08051 vinfos[6].indices[0] = _ij6[0];
08052 vinfos[6].indices[1] = _ij6[1];
08053 vinfos[6].maxsolutions = _nj6;
08054 std::vector<int> vfree(0);
08055 solutions.AddSolution(vinfos,vfree);
08056 }
08057 }
08058 }
08059 
08060 }
08061 
08062 }
08063 
08064 } else
08065 {
08066 {
08067 IkReal j4array[1], cj4array[1], sj4array[1];
08068 bool j4valid[1]={false};
08069 _nj4 = 1;
08070 IkReal x2616=((r21)*(sj3));
08071 IkReal x2617=((IkReal(1.00000000000000))*(r20)*(sj3));
08072 if( IKabs(((gconst71)*(((((IkReal(-1.00000000000000))*(cj6)*(x2617)))+(((sj6)*(x2616))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst71)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2617)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2616)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
08073     continue;
08074 j4array[0]=IKatan2(((gconst71)*(((((IkReal(-1.00000000000000))*(cj6)*(x2617)))+(((sj6)*(x2616)))))), ((gconst71)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2617)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2616)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
08075 sj4array[0]=IKsin(j4array[0]);
08076 cj4array[0]=IKcos(j4array[0]);
08077 if( j4array[0] > IKPI )
08078 {
08079     j4array[0]-=IK2PI;
08080 }
08081 else if( j4array[0] < -IKPI )
08082 {    j4array[0]+=IK2PI;
08083 }
08084 j4valid[0] = true;
08085 for(int ij4 = 0; ij4 < 1; ++ij4)
08086 {
08087 if( !j4valid[ij4] )
08088 {
08089     continue;
08090 }
08091 _ij4[0] = ij4; _ij4[1] = -1;
08092 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
08093 {
08094 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
08095 {
08096     j4valid[iij4]=false; _ij4[1] = iij4; break; 
08097 }
08098 }
08099 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
08100 {
08101 IkReal evalcond[6];
08102 IkReal x2618=IKsin(j4);
08103 IkReal x2619=IKcos(j4);
08104 IkReal x2620=((r22)*(sj5));
08105 IkReal x2621=((IkReal(1.00000000000000))*(cj6));
08106 IkReal x2622=((IkReal(1.00000000000000))*(cj0));
08107 IkReal x2623=((cj5)*(r11));
08108 IkReal x2624=((cj5)*(cj6));
08109 IkReal x2625=((r11)*(sj6));
08110 IkReal x2626=((IkReal(1.00000000000000))*(sj6));
08111 IkReal x2627=((cj6)*(r00));
08112 IkReal x2628=((r12)*(sj5));
08113 IkReal x2629=((r02)*(sj5));
08114 IkReal x2630=((cj6)*(r10));
08115 IkReal x2631=((cj5)*(sj6));
08116 IkReal x2632=((cj5)*(r01));
08117 IkReal x2633=((sj0)*(x2618));
08118 IkReal x2634=((r00)*(x2631));
08119 IkReal x2635=((cj0)*(x2618));
08120 IkReal x2636=((sj0)*(x2619));
08121 IkReal x2637=((r20)*(x2619));
08122 IkReal x2638=((cj0)*(x2619));
08123 IkReal x2639=((r21)*(x2618));
08124 IkReal x2640=((r21)*(x2619));
08125 IkReal x2641=((r20)*(x2618));
08126 IkReal x2642=((x2619)*(x2628));
08127 IkReal x2643=((r01)*(sj6)*(x2619));
08128 IkReal x2644=((cj5)*(r10)*(x2626));
08129 evalcond[0]=((((sj6)*(x2640)))+(((IkReal(-1.00000000000000))*(x2621)*(x2637)))+(((x2631)*(x2641)))+(((x2618)*(x2620)))+(((x2624)*(x2639))));
08130 evalcond[1]=((((x2624)*(x2640)))+(((IkReal(-1.00000000000000))*(x2626)*(x2639)))+(((x2619)*(x2620)))+(((x2631)*(x2637)))+(((cj6)*(x2641)))+(((IkReal(-1.00000000000000))*(sj3))));
08131 evalcond[2]=((((IkReal(-1.00000000000000))*(x2618)*(x2622)*(x2628)))+(((IkReal(-1.00000000000000))*(x2621)*(x2623)*(x2635)))+(((IkReal(-1.00000000000000))*(r00)*(x2621)*(x2636)))+(((r01)*(sj6)*(x2636)))+(((x2633)*(x2634)))+(((x2630)*(x2638)))+(((IkReal(-1.00000000000000))*(x2619)*(x2622)*(x2625)))+(((r01)*(x2624)*(x2633)))+(((x2629)*(x2633)))+(((IkReal(-1.00000000000000))*(r10)*(x2618)*(x2622)*(x2631))));
08132 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x2621)*(x2635)))+(((IkReal(-1.00000000000000))*(r01)*(x2626)*(x2633)))+(((r01)*(x2624)*(x2636)))+(((x2629)*(x2636)))+(((IkReal(-1.00000000000000))*(x2622)*(x2642)))+(((x2634)*(x2636)))+(cj3)+(((x2627)*(x2633)))+(((x2625)*(x2635)))+(((IkReal(-1.00000000000000))*(x2621)*(x2623)*(x2638)))+(((IkReal(-1.00000000000000))*(r10)*(x2619)*(x2622)*(x2631))));
08133 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2618)*(x2622)*(x2629)))+(((x2630)*(x2636)))+(((IkReal(-1.00000000000000))*(x2628)*(x2633)))+(((IkReal(-1.00000000000000))*(x2621)*(x2623)*(x2633)))+(((IkReal(-1.00000000000000))*(x2625)*(x2636)))+(((x2627)*(x2638)))+(((IkReal(-1.00000000000000))*(x2633)*(x2644)))+(((IkReal(-1.00000000000000))*(x2621)*(x2632)*(x2635)))+(((IkReal(-1.00000000000000))*(x2622)*(x2643)))+(((IkReal(-1.00000000000000))*(x2618)*(x2622)*(x2634))));
08134 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x2621)*(x2635)))+(((x2625)*(x2633)))+(((IkReal(-1.00000000000000))*(r10)*(x2621)*(x2633)))+(((IkReal(-1.00000000000000))*(x2621)*(x2632)*(x2638)))+(((IkReal(-1.00000000000000))*(x2636)*(x2644)))+(((IkReal(-1.00000000000000))*(x2619)*(x2622)*(x2629)))+(((IkReal(-1.00000000000000))*(x2619)*(x2622)*(x2634)))+(((IkReal(-1.00000000000000))*(x2621)*(x2623)*(x2636)))+(((r01)*(sj6)*(x2635)))+(((IkReal(-1.00000000000000))*(x2628)*(x2636))));
08135 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08136 {
08137 continue;
08138 }
08139 }
08140 
08141 {
08142 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08143 vinfos[0].jointtype = 1;
08144 vinfos[0].foffset = j0;
08145 vinfos[0].indices[0] = _ij0[0];
08146 vinfos[0].indices[1] = _ij0[1];
08147 vinfos[0].maxsolutions = _nj0;
08148 vinfos[1].jointtype = 1;
08149 vinfos[1].foffset = j1;
08150 vinfos[1].indices[0] = _ij1[0];
08151 vinfos[1].indices[1] = _ij1[1];
08152 vinfos[1].maxsolutions = _nj1;
08153 vinfos[2].jointtype = 1;
08154 vinfos[2].foffset = j2;
08155 vinfos[2].indices[0] = _ij2[0];
08156 vinfos[2].indices[1] = _ij2[1];
08157 vinfos[2].maxsolutions = _nj2;
08158 vinfos[3].jointtype = 1;
08159 vinfos[3].foffset = j3;
08160 vinfos[3].indices[0] = _ij3[0];
08161 vinfos[3].indices[1] = _ij3[1];
08162 vinfos[3].maxsolutions = _nj3;
08163 vinfos[4].jointtype = 1;
08164 vinfos[4].foffset = j4;
08165 vinfos[4].indices[0] = _ij4[0];
08166 vinfos[4].indices[1] = _ij4[1];
08167 vinfos[4].maxsolutions = _nj4;
08168 vinfos[5].jointtype = 1;
08169 vinfos[5].foffset = j5;
08170 vinfos[5].indices[0] = _ij5[0];
08171 vinfos[5].indices[1] = _ij5[1];
08172 vinfos[5].maxsolutions = _nj5;
08173 vinfos[6].jointtype = 1;
08174 vinfos[6].foffset = j6;
08175 vinfos[6].indices[0] = _ij6[0];
08176 vinfos[6].indices[1] = _ij6[1];
08177 vinfos[6].maxsolutions = _nj6;
08178 std::vector<int> vfree(0);
08179 solutions.AddSolution(vinfos,vfree);
08180 }
08181 }
08182 }
08183 
08184 }
08185 
08186 }
08187 }
08188 }
08189 
08190 } else
08191 {
08192 IkReal x2645=((cj0)*(r11));
08193 IkReal x2646=((r01)*(sj0));
08194 IkReal x2647=((cj0)*(r01));
08195 IkReal x2648=((IkReal(0.374290000000000))*(sj0));
08196 IkReal x2649=((cj5)*(r02));
08197 IkReal x2650=((IkReal(0.374290000000000))*(cj0));
08198 IkReal x2651=((r11)*(sj0));
08199 IkReal x2652=((IkReal(0.0100000000000000))*(cj0));
08200 IkReal x2653=((r02)*(sj5));
08201 IkReal x2654=((cj5)*(sj6));
08202 IkReal x2655=((IkReal(1.00000000000000))*(sj0));
08203 IkReal x2656=((cj5)*(r12));
08204 IkReal x2657=((IkReal(0.0100000000000000))*(sj5));
08205 IkReal x2658=((sj5)*(sj6));
08206 IkReal x2659=((IkReal(1.00000000000000))*(cj0));
08207 IkReal x2660=((IkReal(0.0100000000000000))*(sj0));
08208 IkReal x2661=((IkReal(0.374290000000000))*(cj6)*(sj5));
08209 IkReal x2662=((IkReal(0.0100000000000000))*(cj5)*(cj6));
08210 IkReal x2663=((r10)*(x2658));
08211 IkReal x2664=((IkReal(1.00000000000000))*(cj6)*(sj5));
08212 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
08213 evalcond[1]=((IkReal(0.364420000000000))+(((IkReal(-0.0100000000000000))*(r20)*(x2654)))+(((IkReal(-1.00000000000000))*(r21)*(x2662)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(0.374290000000000))*(r20)*(x2658)))+(((IkReal(-1.00000000000000))*(r22)*(x2657)))+(pz)+(((r21)*(x2661))));
08214 evalcond[2]=((((IkReal(-1.00000000000000))*(x2651)*(x2664)))+(((IkReal(-1.00000000000000))*(r00)*(x2658)*(x2659)))+(((IkReal(-1.00000000000000))*(x2647)*(x2664)))+(((sj0)*(x2656)))+(((cj0)*(x2649)))+(((IkReal(-1.00000000000000))*(x2655)*(x2663))));
08215 evalcond[3]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x2648)*(x2649)))+(((r10)*(x2652)*(x2654)))+(((IkReal(-1.00000000000000))*(x2650)*(x2663)))+(((x2645)*(x2662)))+(((IkReal(-1.00000000000000))*(x2646)*(x2662)))+(((IkReal(-1.00000000000000))*(x2645)*(x2661)))+(((IkReal(-1.00000000000000))*(r00)*(x2654)*(x2660)))+(((IkReal(-1.00000000000000))*(py)*(x2659)))+(((r12)*(sj5)*(x2652)))+(((x2650)*(x2656)))+(((r00)*(x2648)*(x2658)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x2653)*(x2660)))+(((x2646)*(x2661))));
08216 evalcond[4]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x2648)*(x2663)))+(((x2648)*(x2656)))+(((x2651)*(x2662)))+(((x2652)*(x2653)))+(((IkReal(-1.00000000000000))*(px)*(x2659)))+(((x2649)*(x2650)))+(((r10)*(x2654)*(x2660)))+(((r12)*(sj0)*(x2657)))+(((x2647)*(x2662)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(sj5)*(x2648)))+(((r00)*(x2652)*(x2654)))+(((IkReal(-1.00000000000000))*(r00)*(x2650)*(x2658)))+(((IkReal(-1.00000000000000))*(x2647)*(x2661)))+(((IkReal(-1.00000000000000))*(py)*(x2655))));
08217 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
08218 {
08219 {
08220 IkReal j3array[1], cj3array[1], sj3array[1];
08221 bool j3valid[1]={false};
08222 _nj3 = 1;
08223 IkReal x2665=((sj5)*(sj6));
08224 IkReal x2666=((IkReal(1.00000000000000))*(cj5));
08225 IkReal x2667=((IkReal(1.00000000000000))*(sj0));
08226 IkReal x2668=((cj6)*(sj5));
08227 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2666)))+(((cj0)*(r11)*(x2668)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x2667)*(x2668)))+(((cj0)*(r10)*(x2665)))+(((IkReal(-1.00000000000000))*(r00)*(x2665)*(x2667))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r20)*(x2665)))+(((IkReal(-1.00000000000000))*(r22)*(x2666)))+(((r21)*(x2668))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2666)))+(((cj0)*(r11)*(x2668)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x2667)*(x2668)))+(((cj0)*(r10)*(x2665)))+(((IkReal(-1.00000000000000))*(r00)*(x2665)*(x2667)))))+IKsqr(((((r20)*(x2665)))+(((IkReal(-1.00000000000000))*(r22)*(x2666)))+(((r21)*(x2668)))))-1) <= IKFAST_SINCOS_THRESH )
08228     continue;
08229 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x2666)))+(((cj0)*(r11)*(x2668)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x2667)*(x2668)))+(((cj0)*(r10)*(x2665)))+(((IkReal(-1.00000000000000))*(r00)*(x2665)*(x2667)))), ((((r20)*(x2665)))+(((IkReal(-1.00000000000000))*(r22)*(x2666)))+(((r21)*(x2668)))));
08230 sj3array[0]=IKsin(j3array[0]);
08231 cj3array[0]=IKcos(j3array[0]);
08232 if( j3array[0] > IKPI )
08233 {
08234     j3array[0]-=IK2PI;
08235 }
08236 else if( j3array[0] < -IKPI )
08237 {    j3array[0]+=IK2PI;
08238 }
08239 j3valid[0] = true;
08240 for(int ij3 = 0; ij3 < 1; ++ij3)
08241 {
08242 if( !j3valid[ij3] )
08243 {
08244     continue;
08245 }
08246 _ij3[0] = ij3; _ij3[1] = -1;
08247 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
08248 {
08249 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
08250 {
08251     j3valid[iij3]=false; _ij3[1] = iij3; break; 
08252 }
08253 }
08254 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
08255 {
08256 IkReal evalcond[2];
08257 IkReal x2669=((sj5)*(sj6));
08258 IkReal x2670=((cj6)*(sj5));
08259 IkReal x2671=((IkReal(1.00000000000000))*(cj0));
08260 IkReal x2672=((IkReal(1.00000000000000))*(cj5));
08261 evalcond[0]=((((IkReal(-1.00000000000000))*(IKcos(j3))))+(((r21)*(x2670)))+(((IkReal(-1.00000000000000))*(r22)*(x2672)))+(((r20)*(x2669))));
08262 evalcond[1]=((((r00)*(sj0)*(x2669)))+(((IkReal(-1.00000000000000))*(r10)*(x2669)*(x2671)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x2672)))+(((r01)*(sj0)*(x2670)))+(((IkReal(-1.00000000000000))*(r11)*(x2670)*(x2671)))+(IKsin(j3)));
08263 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
08264 {
08265 continue;
08266 }
08267 }
08268 
08269 {
08270 IkReal dummyeval[1];
08271 IkReal gconst75;
08272 IkReal x2673=(r21)*(r21);
08273 IkReal x2674=(cj5)*(cj5);
08274 IkReal x2675=(sj6)*(sj6);
08275 IkReal x2676=(cj6)*(cj6);
08276 IkReal x2677=(r20)*(r20);
08277 IkReal x2678=((cj6)*(r21));
08278 IkReal x2679=((IkReal(2.00000000000000))*(r20)*(sj6));
08279 IkReal x2680=((cj5)*(r22)*(sj5));
08280 IkReal x2681=((IkReal(1.00000000000000))*(x2675));
08281 IkReal x2682=((IkReal(1.00000000000000))*(x2676));
08282 gconst75=IKsign(((((x2678)*(x2679)))+(((IkReal(-1.00000000000000))*(x2674)*(x2677)*(x2681)))+(((IkReal(-1.00000000000000))*(x2673)*(x2681)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x2679)*(x2680)))+(((IkReal(-2.00000000000000))*(x2678)*(x2680)))+(((IkReal(-1.00000000000000))*(x2674)*(x2678)*(x2679)))+(((IkReal(-1.00000000000000))*(x2677)*(x2682)))+(((IkReal(-1.00000000000000))*(x2673)*(x2674)*(x2682)))));
08283 IkReal x2683=(r21)*(r21);
08284 IkReal x2684=(cj5)*(cj5);
08285 IkReal x2685=(sj6)*(sj6);
08286 IkReal x2686=(cj6)*(cj6);
08287 IkReal x2687=(r20)*(r20);
08288 IkReal x2688=((cj6)*(r21));
08289 IkReal x2689=((IkReal(2.00000000000000))*(r20)*(sj6));
08290 IkReal x2690=((cj5)*(r22)*(sj5));
08291 IkReal x2691=((IkReal(1.00000000000000))*(x2685));
08292 IkReal x2692=((IkReal(1.00000000000000))*(x2686));
08293 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2689)*(x2690)))+(((IkReal(-1.00000000000000))*(x2683)*(x2691)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((x2688)*(x2689)))+(((IkReal(-1.00000000000000))*(x2683)*(x2684)*(x2692)))+(((IkReal(-2.00000000000000))*(x2688)*(x2690)))+(((IkReal(-1.00000000000000))*(x2684)*(x2687)*(x2691)))+(((IkReal(-1.00000000000000))*(x2684)*(x2688)*(x2689)))+(((IkReal(-1.00000000000000))*(x2687)*(x2692))));
08294 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08295 {
08296 {
08297 IkReal dummyeval[1];
08298 IkReal gconst76;
08299 IkReal x2693=(cj6)*(cj6);
08300 IkReal x2694=(cj5)*(cj5);
08301 IkReal x2695=(sj6)*(sj6);
08302 IkReal x2696=(sj5)*(sj5);
08303 IkReal x2697=((cj0)*(r12));
08304 IkReal x2698=((cj6)*(sj6));
08305 IkReal x2699=((cj0)*(r21));
08306 IkReal x2700=((cj0)*(r11));
08307 IkReal x2701=((IkReal(1.00000000000000))*(r20));
08308 IkReal x2702=((r01)*(sj0));
08309 IkReal x2703=((r00)*(sj0));
08310 IkReal x2704=((IkReal(1.00000000000000))*(r22));
08311 IkReal x2705=((cj0)*(r10));
08312 IkReal x2706=((r02)*(sj0));
08313 IkReal x2707=((r22)*(x2696));
08314 IkReal x2708=((IkReal(1.00000000000000))*(r21)*(sj0));
08315 IkReal x2709=((cj5)*(cj6)*(sj5));
08316 IkReal x2710=((cj5)*(sj5)*(sj6));
08317 IkReal x2711=((cj0)*(r20)*(x2694));
08318 IkReal x2712=((x2693)*(x2694));
08319 gconst76=IKsign(((((IkReal(-1.00000000000000))*(r10)*(x2698)*(x2699)))+(((x2697)*(x2707)))+(((r21)*(x2698)*(x2703)))+(((IkReal(-1.00000000000000))*(x2698)*(x2700)*(x2701)))+(((r20)*(x2694)*(x2698)*(x2700)))+(((r20)*(x2694)*(x2695)*(x2705)))+(((IkReal(-1.00000000000000))*(x2696)*(x2704)*(x2706)))+(((IkReal(-1.00000000000000))*(x2701)*(x2706)*(x2710)))+(((r20)*(x2693)*(x2705)))+(((IkReal(-1.00000000000000))*(r21)*(x2706)*(x2709)))+(((IkReal(-1.00000000000000))*(x2693)*(x2701)*(x2703)))+(((r22)*(x2705)*(x2710)))+(((IkReal(-1.00000000000000))*(x2694)*(x2698)*(x2701)*(x2702)))+(((r21)*(x2697)*(x2709)))+(((IkReal(-1.00000000000000))*(x2703)*(x2704)*(x2710)))+(((IkReal(-1.00000000000000))*(x2694)*(x2695)*(x2701)*(x2703)))+(((IkReal(-1.00000000000000))*(x2702)*(x2704)*(x2709)))+(((r20)*(x2698)*(x2702)))+(((r10)*(x2694)*(x2698)*(x2699)))+(((r11)*(x2695)*(x2699)))+(((IkReal(-1.00000000000000))*(r21)*(x2702)*(x2712)))+(((IkReal(-1.00000000000000))*(r21)*(x2694)*(x2698)*(x2703)))+(((r20)*(x2697)*(x2710)))+(((r22)*(x2700)*(x2709)))+(((IkReal(-1.00000000000000))*(r21)*(x2695)*(x2702)))+(((r11)*(x2699)*(x2712)))));
08320 IkReal x2713=(cj6)*(cj6);
08321 IkReal x2714=(cj5)*(cj5);
08322 IkReal x2715=(sj6)*(sj6);
08323 IkReal x2716=(sj5)*(sj5);
08324 IkReal x2717=((cj0)*(r12));
08325 IkReal x2718=((cj6)*(sj6));
08326 IkReal x2719=((cj0)*(r21));
08327 IkReal x2720=((cj0)*(r11));
08328 IkReal x2721=((IkReal(1.00000000000000))*(r20));
08329 IkReal x2722=((r01)*(sj0));
08330 IkReal x2723=((r00)*(sj0));
08331 IkReal x2724=((IkReal(1.00000000000000))*(r22));
08332 IkReal x2725=((cj0)*(r10));
08333 IkReal x2726=((r02)*(sj0));
08334 IkReal x2727=((r22)*(x2716));
08335 IkReal x2728=((IkReal(1.00000000000000))*(r21)*(sj0));
08336 IkReal x2729=((cj5)*(cj6)*(sj5));
08337 IkReal x2730=((cj5)*(sj5)*(sj6));
08338 IkReal x2731=((cj0)*(r20)*(x2714));
08339 IkReal x2732=((x2713)*(x2714));
08340 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2714)*(x2715)*(x2721)*(x2723)))+(((r22)*(x2725)*(x2730)))+(((IkReal(-1.00000000000000))*(x2714)*(x2718)*(x2721)*(x2722)))+(((IkReal(-1.00000000000000))*(r21)*(x2715)*(x2722)))+(((r11)*(x2715)*(x2719)))+(((x2717)*(x2727)))+(((IkReal(-1.00000000000000))*(x2723)*(x2724)*(x2730)))+(((IkReal(-1.00000000000000))*(x2722)*(x2724)*(x2729)))+(((r21)*(x2717)*(x2729)))+(((IkReal(-1.00000000000000))*(r10)*(x2718)*(x2719)))+(((r11)*(x2719)*(x2732)))+(((r21)*(x2718)*(x2723)))+(((IkReal(-1.00000000000000))*(x2713)*(x2721)*(x2723)))+(((IkReal(-1.00000000000000))*(x2716)*(x2724)*(x2726)))+(((r20)*(x2714)*(x2715)*(x2725)))+(((r10)*(x2714)*(x2718)*(x2719)))+(((r20)*(x2713)*(x2725)))+(((IkReal(-1.00000000000000))*(x2718)*(x2720)*(x2721)))+(((r20)*(x2718)*(x2722)))+(((IkReal(-1.00000000000000))*(r21)*(x2714)*(x2718)*(x2723)))+(((IkReal(-1.00000000000000))*(r21)*(x2726)*(x2729)))+(((IkReal(-1.00000000000000))*(x2721)*(x2726)*(x2730)))+(((r20)*(x2714)*(x2718)*(x2720)))+(((r20)*(x2717)*(x2730)))+(((r22)*(x2720)*(x2729)))+(((IkReal(-1.00000000000000))*(r21)*(x2722)*(x2732))));
08341 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08342 {
08343 continue;
08344 
08345 } else
08346 {
08347 {
08348 IkReal j4array[1], cj4array[1], sj4array[1];
08349 bool j4valid[1]={false};
08350 _nj4 = 1;
08351 IkReal x2733=((IkReal(1.00000000000000))*(cj3));
08352 IkReal x2734=((cj5)*(x2733));
08353 if( IKabs(((gconst76)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2733)))+(((cj3)*(r21)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst76)*(((((IkReal(-1.00000000000000))*(r20)*(sj6)*(x2734)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2733)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x2734))))))) < IKFAST_ATAN2_MAGTHRESH )
08354     continue;
08355 j4array[0]=IKatan2(((gconst76)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2733)))+(((cj3)*(r21)*(sj6)))))), ((gconst76)*(((((IkReal(-1.00000000000000))*(r20)*(sj6)*(x2734)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2733)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x2734)))))));
08356 sj4array[0]=IKsin(j4array[0]);
08357 cj4array[0]=IKcos(j4array[0]);
08358 if( j4array[0] > IKPI )
08359 {
08360     j4array[0]-=IK2PI;
08361 }
08362 else if( j4array[0] < -IKPI )
08363 {    j4array[0]+=IK2PI;
08364 }
08365 j4valid[0] = true;
08366 for(int ij4 = 0; ij4 < 1; ++ij4)
08367 {
08368 if( !j4valid[ij4] )
08369 {
08370     continue;
08371 }
08372 _ij4[0] = ij4; _ij4[1] = -1;
08373 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
08374 {
08375 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
08376 {
08377     j4valid[iij4]=false; _ij4[1] = iij4; break; 
08378 }
08379 }
08380 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
08381 {
08382 IkReal evalcond[6];
08383 IkReal x2735=IKsin(j4);
08384 IkReal x2736=IKcos(j4);
08385 IkReal x2737=((r22)*(sj5));
08386 IkReal x2738=((IkReal(1.00000000000000))*(cj6));
08387 IkReal x2739=((IkReal(1.00000000000000))*(cj0));
08388 IkReal x2740=((cj5)*(r11));
08389 IkReal x2741=((cj5)*(cj6));
08390 IkReal x2742=((r11)*(sj6));
08391 IkReal x2743=((IkReal(1.00000000000000))*(sj6));
08392 IkReal x2744=((cj6)*(r00));
08393 IkReal x2745=((r12)*(sj5));
08394 IkReal x2746=((r02)*(sj5));
08395 IkReal x2747=((cj6)*(r10));
08396 IkReal x2748=((cj5)*(sj6));
08397 IkReal x2749=((cj5)*(r01));
08398 IkReal x2750=((sj0)*(x2735));
08399 IkReal x2751=((r00)*(x2748));
08400 IkReal x2752=((cj0)*(x2735));
08401 IkReal x2753=((sj0)*(x2736));
08402 IkReal x2754=((r20)*(x2736));
08403 IkReal x2755=((cj0)*(x2736));
08404 IkReal x2756=((r21)*(x2735));
08405 IkReal x2757=((r21)*(x2736));
08406 IkReal x2758=((r20)*(x2735));
08407 IkReal x2759=((x2736)*(x2745));
08408 IkReal x2760=((r01)*(sj6)*(x2736));
08409 IkReal x2761=((cj5)*(r10)*(x2743));
08410 evalcond[0]=((((x2748)*(x2758)))+(((x2735)*(x2737)))+(((x2741)*(x2756)))+(((IkReal(-1.00000000000000))*(x2738)*(x2754)))+(((sj6)*(x2757))));
08411 evalcond[1]=((((x2736)*(x2737)))+(((x2741)*(x2757)))+(((x2748)*(x2754)))+(((cj6)*(x2758)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x2743)*(x2756))));
08412 evalcond[2]=((((IkReal(-1.00000000000000))*(x2736)*(x2739)*(x2742)))+(((IkReal(-1.00000000000000))*(r00)*(x2738)*(x2753)))+(((x2750)*(x2751)))+(((r01)*(x2741)*(x2750)))+(((IkReal(-1.00000000000000))*(r10)*(x2735)*(x2739)*(x2748)))+(((IkReal(-1.00000000000000))*(x2738)*(x2740)*(x2752)))+(((x2746)*(x2750)))+(((x2747)*(x2755)))+(((IkReal(-1.00000000000000))*(x2735)*(x2739)*(x2745)))+(((r01)*(sj6)*(x2753))));
08413 evalcond[3]=((((x2751)*(x2753)))+(((IkReal(-1.00000000000000))*(x2738)*(x2740)*(x2755)))+(((IkReal(-1.00000000000000))*(x2739)*(x2759)))+(((IkReal(-1.00000000000000))*(r10)*(x2738)*(x2752)))+(((IkReal(-1.00000000000000))*(r10)*(x2736)*(x2739)*(x2748)))+(((x2744)*(x2750)))+(((x2746)*(x2753)))+(((r01)*(x2741)*(x2753)))+(((x2742)*(x2752)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(r01)*(x2743)*(x2750))));
08414 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2739)*(x2760)))+(((IkReal(-1.00000000000000))*(x2745)*(x2750)))+(((IkReal(-1.00000000000000))*(x2735)*(x2739)*(x2746)))+(((IkReal(-1.00000000000000))*(x2742)*(x2753)))+(((IkReal(-1.00000000000000))*(x2735)*(x2739)*(x2751)))+(((IkReal(-1.00000000000000))*(x2738)*(x2740)*(x2750)))+(((IkReal(-1.00000000000000))*(x2750)*(x2761)))+(((IkReal(-1.00000000000000))*(x2738)*(x2749)*(x2752)))+(((x2744)*(x2755)))+(((x2747)*(x2753))));
08415 evalcond[5]=((((IkReal(-1.00000000000000))*(x2736)*(x2739)*(x2751)))+(((r01)*(sj6)*(x2752)))+(((IkReal(-1.00000000000000))*(x2738)*(x2740)*(x2753)))+(((x2742)*(x2750)))+(((IkReal(-1.00000000000000))*(x2745)*(x2753)))+(((IkReal(-1.00000000000000))*(x2738)*(x2749)*(x2755)))+(((IkReal(-1.00000000000000))*(x2736)*(x2739)*(x2746)))+(((IkReal(-1.00000000000000))*(x2753)*(x2761)))+(((IkReal(-1.00000000000000))*(r00)*(x2738)*(x2752)))+(((IkReal(-1.00000000000000))*(r10)*(x2738)*(x2750))));
08416 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08417 {
08418 continue;
08419 }
08420 }
08421 
08422 {
08423 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08424 vinfos[0].jointtype = 1;
08425 vinfos[0].foffset = j0;
08426 vinfos[0].indices[0] = _ij0[0];
08427 vinfos[0].indices[1] = _ij0[1];
08428 vinfos[0].maxsolutions = _nj0;
08429 vinfos[1].jointtype = 1;
08430 vinfos[1].foffset = j1;
08431 vinfos[1].indices[0] = _ij1[0];
08432 vinfos[1].indices[1] = _ij1[1];
08433 vinfos[1].maxsolutions = _nj1;
08434 vinfos[2].jointtype = 1;
08435 vinfos[2].foffset = j2;
08436 vinfos[2].indices[0] = _ij2[0];
08437 vinfos[2].indices[1] = _ij2[1];
08438 vinfos[2].maxsolutions = _nj2;
08439 vinfos[3].jointtype = 1;
08440 vinfos[3].foffset = j3;
08441 vinfos[3].indices[0] = _ij3[0];
08442 vinfos[3].indices[1] = _ij3[1];
08443 vinfos[3].maxsolutions = _nj3;
08444 vinfos[4].jointtype = 1;
08445 vinfos[4].foffset = j4;
08446 vinfos[4].indices[0] = _ij4[0];
08447 vinfos[4].indices[1] = _ij4[1];
08448 vinfos[4].maxsolutions = _nj4;
08449 vinfos[5].jointtype = 1;
08450 vinfos[5].foffset = j5;
08451 vinfos[5].indices[0] = _ij5[0];
08452 vinfos[5].indices[1] = _ij5[1];
08453 vinfos[5].maxsolutions = _nj5;
08454 vinfos[6].jointtype = 1;
08455 vinfos[6].foffset = j6;
08456 vinfos[6].indices[0] = _ij6[0];
08457 vinfos[6].indices[1] = _ij6[1];
08458 vinfos[6].maxsolutions = _nj6;
08459 std::vector<int> vfree(0);
08460 solutions.AddSolution(vinfos,vfree);
08461 }
08462 }
08463 }
08464 
08465 }
08466 
08467 }
08468 
08469 } else
08470 {
08471 {
08472 IkReal j4array[1], cj4array[1], sj4array[1];
08473 bool j4valid[1]={false};
08474 _nj4 = 1;
08475 IkReal x2762=((r21)*(sj3));
08476 IkReal x2763=((IkReal(1.00000000000000))*(r20)*(sj3));
08477 if( IKabs(((gconst75)*(((((IkReal(-1.00000000000000))*(cj6)*(x2763)))+(((sj6)*(x2762))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst75)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2762)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2763)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
08478     continue;
08479 j4array[0]=IKatan2(((gconst75)*(((((IkReal(-1.00000000000000))*(cj6)*(x2763)))+(((sj6)*(x2762)))))), ((gconst75)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2762)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2763)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
08480 sj4array[0]=IKsin(j4array[0]);
08481 cj4array[0]=IKcos(j4array[0]);
08482 if( j4array[0] > IKPI )
08483 {
08484     j4array[0]-=IK2PI;
08485 }
08486 else if( j4array[0] < -IKPI )
08487 {    j4array[0]+=IK2PI;
08488 }
08489 j4valid[0] = true;
08490 for(int ij4 = 0; ij4 < 1; ++ij4)
08491 {
08492 if( !j4valid[ij4] )
08493 {
08494     continue;
08495 }
08496 _ij4[0] = ij4; _ij4[1] = -1;
08497 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
08498 {
08499 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
08500 {
08501     j4valid[iij4]=false; _ij4[1] = iij4; break; 
08502 }
08503 }
08504 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
08505 {
08506 IkReal evalcond[6];
08507 IkReal x2764=IKsin(j4);
08508 IkReal x2765=IKcos(j4);
08509 IkReal x2766=((r22)*(sj5));
08510 IkReal x2767=((IkReal(1.00000000000000))*(cj6));
08511 IkReal x2768=((IkReal(1.00000000000000))*(cj0));
08512 IkReal x2769=((cj5)*(r11));
08513 IkReal x2770=((cj5)*(cj6));
08514 IkReal x2771=((r11)*(sj6));
08515 IkReal x2772=((IkReal(1.00000000000000))*(sj6));
08516 IkReal x2773=((cj6)*(r00));
08517 IkReal x2774=((r12)*(sj5));
08518 IkReal x2775=((r02)*(sj5));
08519 IkReal x2776=((cj6)*(r10));
08520 IkReal x2777=((cj5)*(sj6));
08521 IkReal x2778=((cj5)*(r01));
08522 IkReal x2779=((sj0)*(x2764));
08523 IkReal x2780=((r00)*(x2777));
08524 IkReal x2781=((cj0)*(x2764));
08525 IkReal x2782=((sj0)*(x2765));
08526 IkReal x2783=((r20)*(x2765));
08527 IkReal x2784=((cj0)*(x2765));
08528 IkReal x2785=((r21)*(x2764));
08529 IkReal x2786=((r21)*(x2765));
08530 IkReal x2787=((r20)*(x2764));
08531 IkReal x2788=((x2765)*(x2774));
08532 IkReal x2789=((r01)*(sj6)*(x2765));
08533 IkReal x2790=((cj5)*(r10)*(x2772));
08534 evalcond[0]=((((sj6)*(x2786)))+(((x2777)*(x2787)))+(((IkReal(-1.00000000000000))*(x2767)*(x2783)))+(((x2764)*(x2766)))+(((x2770)*(x2785))));
08535 evalcond[1]=((((x2770)*(x2786)))+(((x2765)*(x2766)))+(((x2777)*(x2783)))+(((IkReal(-1.00000000000000))*(sj3)))+(((cj6)*(x2787)))+(((IkReal(-1.00000000000000))*(x2772)*(x2785))));
08536 evalcond[2]=((((IkReal(-1.00000000000000))*(x2767)*(x2769)*(x2781)))+(((IkReal(-1.00000000000000))*(x2764)*(x2768)*(x2774)))+(((r01)*(sj6)*(x2782)))+(((IkReal(-1.00000000000000))*(x2765)*(x2768)*(x2771)))+(((IkReal(-1.00000000000000))*(r10)*(x2764)*(x2768)*(x2777)))+(((x2779)*(x2780)))+(((x2775)*(x2779)))+(((r01)*(x2770)*(x2779)))+(((x2776)*(x2784)))+(((IkReal(-1.00000000000000))*(r00)*(x2767)*(x2782))));
08537 evalcond[3]=((((r01)*(x2770)*(x2782)))+(((x2773)*(x2779)))+(((IkReal(-1.00000000000000))*(x2767)*(x2769)*(x2784)))+(((IkReal(-1.00000000000000))*(r10)*(x2767)*(x2781)))+(((IkReal(-1.00000000000000))*(r10)*(x2765)*(x2768)*(x2777)))+(((x2780)*(x2782)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x2775)*(x2782)))+(((IkReal(-1.00000000000000))*(r01)*(x2772)*(x2779)))+(((x2771)*(x2781)))+(((IkReal(-1.00000000000000))*(x2768)*(x2788))));
08538 evalcond[4]=((IkReal(-1.00000000000000))+(((x2776)*(x2782)))+(((IkReal(-1.00000000000000))*(x2764)*(x2768)*(x2775)))+(((IkReal(-1.00000000000000))*(x2774)*(x2779)))+(((IkReal(-1.00000000000000))*(x2764)*(x2768)*(x2780)))+(((IkReal(-1.00000000000000))*(x2767)*(x2778)*(x2781)))+(((x2773)*(x2784)))+(((IkReal(-1.00000000000000))*(x2771)*(x2782)))+(((IkReal(-1.00000000000000))*(x2768)*(x2789)))+(((IkReal(-1.00000000000000))*(x2779)*(x2790)))+(((IkReal(-1.00000000000000))*(x2767)*(x2769)*(x2779))));
08539 evalcond[5]=((((IkReal(-1.00000000000000))*(x2767)*(x2778)*(x2784)))+(((r01)*(sj6)*(x2781)))+(((IkReal(-1.00000000000000))*(r10)*(x2767)*(x2779)))+(((IkReal(-1.00000000000000))*(x2765)*(x2768)*(x2780)))+(((IkReal(-1.00000000000000))*(x2767)*(x2769)*(x2782)))+(((IkReal(-1.00000000000000))*(x2774)*(x2782)))+(((x2771)*(x2779)))+(((IkReal(-1.00000000000000))*(x2782)*(x2790)))+(((IkReal(-1.00000000000000))*(r00)*(x2767)*(x2781)))+(((IkReal(-1.00000000000000))*(x2765)*(x2768)*(x2775))));
08540 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08541 {
08542 continue;
08543 }
08544 }
08545 
08546 {
08547 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08548 vinfos[0].jointtype = 1;
08549 vinfos[0].foffset = j0;
08550 vinfos[0].indices[0] = _ij0[0];
08551 vinfos[0].indices[1] = _ij0[1];
08552 vinfos[0].maxsolutions = _nj0;
08553 vinfos[1].jointtype = 1;
08554 vinfos[1].foffset = j1;
08555 vinfos[1].indices[0] = _ij1[0];
08556 vinfos[1].indices[1] = _ij1[1];
08557 vinfos[1].maxsolutions = _nj1;
08558 vinfos[2].jointtype = 1;
08559 vinfos[2].foffset = j2;
08560 vinfos[2].indices[0] = _ij2[0];
08561 vinfos[2].indices[1] = _ij2[1];
08562 vinfos[2].maxsolutions = _nj2;
08563 vinfos[3].jointtype = 1;
08564 vinfos[3].foffset = j3;
08565 vinfos[3].indices[0] = _ij3[0];
08566 vinfos[3].indices[1] = _ij3[1];
08567 vinfos[3].maxsolutions = _nj3;
08568 vinfos[4].jointtype = 1;
08569 vinfos[4].foffset = j4;
08570 vinfos[4].indices[0] = _ij4[0];
08571 vinfos[4].indices[1] = _ij4[1];
08572 vinfos[4].maxsolutions = _nj4;
08573 vinfos[5].jointtype = 1;
08574 vinfos[5].foffset = j5;
08575 vinfos[5].indices[0] = _ij5[0];
08576 vinfos[5].indices[1] = _ij5[1];
08577 vinfos[5].maxsolutions = _nj5;
08578 vinfos[6].jointtype = 1;
08579 vinfos[6].foffset = j6;
08580 vinfos[6].indices[0] = _ij6[0];
08581 vinfos[6].indices[1] = _ij6[1];
08582 vinfos[6].maxsolutions = _nj6;
08583 std::vector<int> vfree(0);
08584 solutions.AddSolution(vinfos,vfree);
08585 }
08586 }
08587 }
08588 
08589 }
08590 
08591 }
08592 }
08593 }
08594 
08595 } else
08596 {
08597 if( 1 )
08598 {
08599 continue;
08600 
08601 } else
08602 {
08603 }
08604 }
08605 }
08606 }
08607 
08608 } else
08609 {
08610 {
08611 IkReal j3array[1], cj3array[1], sj3array[1];
08612 bool j3valid[1]={false};
08613 _nj3 = 1;
08614 IkReal x2791=((sj5)*(sj6));
08615 IkReal x2792=((IkReal(1.00000000000000))*(cj5));
08616 IkReal x2793=((cj6)*(sj5));
08617 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj0)*(r00)*(x2791)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2792)))+(((r11)*(sj0)*(x2793)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2792)))+(((r10)*(sj0)*(x2791)))+(((cj0)*(r01)*(x2793))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r22)*(x2792)))+(((r21)*(x2793)))+(((r20)*(x2791))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj0)*(r00)*(x2791)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2792)))+(((r11)*(sj0)*(x2793)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2792)))+(((r10)*(sj0)*(x2791)))+(((cj0)*(r01)*(x2793)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r22)*(x2792)))+(((r21)*(x2793)))+(((r20)*(x2791)))))-1) <= IKFAST_SINCOS_THRESH )
08618     continue;
08619 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj0)*(r00)*(x2791)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x2792)))+(((r11)*(sj0)*(x2793)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x2792)))+(((r10)*(sj0)*(x2791)))+(((cj0)*(r01)*(x2793)))))), ((((IkReal(-1.00000000000000))*(r22)*(x2792)))+(((r21)*(x2793)))+(((r20)*(x2791)))));
08620 sj3array[0]=IKsin(j3array[0]);
08621 cj3array[0]=IKcos(j3array[0]);
08622 if( j3array[0] > IKPI )
08623 {
08624     j3array[0]-=IK2PI;
08625 }
08626 else if( j3array[0] < -IKPI )
08627 {    j3array[0]+=IK2PI;
08628 }
08629 j3valid[0] = true;
08630 for(int ij3 = 0; ij3 < 1; ++ij3)
08631 {
08632 if( !j3valid[ij3] )
08633 {
08634     continue;
08635 }
08636 _ij3[0] = ij3; _ij3[1] = -1;
08637 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
08638 {
08639 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
08640 {
08641     j3valid[iij3]=false; _ij3[1] = iij3; break; 
08642 }
08643 }
08644 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
08645 {
08646 IkReal evalcond[3];
08647 IkReal x2794=IKsin(j3);
08648 IkReal x2795=((sj5)*(sj6));
08649 IkReal x2796=((cj0)*(cj5));
08650 IkReal x2797=((IkReal(1.00000000000000))*(cj0));
08651 IkReal x2798=((IkReal(1.00000000000000))*(sj0));
08652 IkReal x2799=((cj6)*(r01)*(sj5));
08653 IkReal x2800=((cj6)*(r11)*(sj5));
08654 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((r20)*(x2795)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
08655 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(x2795)*(x2797)))+(((sj0)*(x2799)))+(((r12)*(x2796)))+(((IkReal(-1.00000000000000))*(x2797)*(x2800)))+(((r00)*(sj0)*(x2795)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x2798)))+(((IkReal(-1.00000000000000))*(sj2)*(x2794))));
08656 evalcond[2]=((((cj2)*(x2794)))+(((IkReal(-1.00000000000000))*(x2797)*(x2799)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x2795)*(x2797)))+(((IkReal(-1.00000000000000))*(x2798)*(x2800)))+(((IkReal(-1.00000000000000))*(r10)*(x2795)*(x2798)))+(((r02)*(x2796))));
08657 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
08658 {
08659 continue;
08660 }
08661 }
08662 
08663 {
08664 IkReal dummyeval[1];
08665 IkReal gconst67;
08666 IkReal x2801=(r21)*(r21);
08667 IkReal x2802=(cj5)*(cj5);
08668 IkReal x2803=(sj6)*(sj6);
08669 IkReal x2804=(cj6)*(cj6);
08670 IkReal x2805=(r20)*(r20);
08671 IkReal x2806=((cj6)*(r21));
08672 IkReal x2807=((IkReal(2.00000000000000))*(r20)*(sj6));
08673 IkReal x2808=((cj5)*(r22)*(sj5));
08674 IkReal x2809=((IkReal(1.00000000000000))*(x2803));
08675 IkReal x2810=((IkReal(1.00000000000000))*(x2804));
08676 gconst67=IKsign(((((IkReal(-1.00000000000000))*(x2807)*(x2808)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x2802)*(x2805)*(x2809)))+(((IkReal(-1.00000000000000))*(x2805)*(x2810)))+(((IkReal(-1.00000000000000))*(x2801)*(x2809)))+(((IkReal(-1.00000000000000))*(x2802)*(x2806)*(x2807)))+(((x2806)*(x2807)))+(((IkReal(-2.00000000000000))*(x2806)*(x2808)))+(((IkReal(-1.00000000000000))*(x2801)*(x2802)*(x2810)))));
08677 IkReal x2811=(r21)*(r21);
08678 IkReal x2812=(cj5)*(cj5);
08679 IkReal x2813=(sj6)*(sj6);
08680 IkReal x2814=(cj6)*(cj6);
08681 IkReal x2815=(r20)*(r20);
08682 IkReal x2816=((cj6)*(r21));
08683 IkReal x2817=((IkReal(2.00000000000000))*(r20)*(sj6));
08684 IkReal x2818=((cj5)*(r22)*(sj5));
08685 IkReal x2819=((IkReal(1.00000000000000))*(x2813));
08686 IkReal x2820=((IkReal(1.00000000000000))*(x2814));
08687 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2817)*(x2818)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x2811)*(x2819)))+(((IkReal(-1.00000000000000))*(x2815)*(x2820)))+(((IkReal(-1.00000000000000))*(x2812)*(x2816)*(x2817)))+(((IkReal(-1.00000000000000))*(x2812)*(x2815)*(x2819)))+(((x2816)*(x2817)))+(((IkReal(-1.00000000000000))*(x2811)*(x2812)*(x2820)))+(((IkReal(-2.00000000000000))*(x2816)*(x2818))));
08688 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08689 {
08690 {
08691 IkReal dummyeval[1];
08692 IkReal gconst68;
08693 IkReal x2821=(cj6)*(cj6);
08694 IkReal x2822=(sj6)*(sj6);
08695 IkReal x2823=((IkReal(1.00000000000000))*(r21));
08696 IkReal x2824=((cj6)*(r20));
08697 IkReal x2825=((r22)*(sj5));
08698 IkReal x2826=((r01)*(sj0));
08699 IkReal x2827=((r00)*(sj0));
08700 IkReal x2828=((cj0)*(r10));
08701 IkReal x2829=((r02)*(sj0)*(sj5));
08702 IkReal x2830=((cj5)*(x2821));
08703 IkReal x2831=((cj0)*(r12)*(sj5));
08704 IkReal x2832=((IkReal(1.00000000000000))*(cj0)*(r11));
08705 IkReal x2833=((cj5)*(x2822));
08706 IkReal x2834=((r20)*(x2833));
08707 gconst68=IKsign(((((cj6)*(x2825)*(x2828)))+(((IkReal(-1.00000000000000))*(x2823)*(x2827)*(x2833)))+(((IkReal(-1.00000000000000))*(sj6)*(x2823)*(x2829)))+(((IkReal(-1.00000000000000))*(sj6)*(x2825)*(x2832)))+(((IkReal(-1.00000000000000))*(x2832)*(x2834)))+(((IkReal(-1.00000000000000))*(cj6)*(x2825)*(x2827)))+(((x2826)*(x2834)))+(((r20)*(x2826)*(x2830)))+(((IkReal(-1.00000000000000))*(x2824)*(x2831)))+(((x2824)*(x2829)))+(((r21)*(x2828)*(x2833)))+(((IkReal(-1.00000000000000))*(x2823)*(x2827)*(x2830)))+(((sj6)*(x2825)*(x2826)))+(((r21)*(sj6)*(x2831)))+(((r21)*(x2828)*(x2830)))+(((IkReal(-1.00000000000000))*(r20)*(x2830)*(x2832)))));
08708 IkReal x2835=(cj6)*(cj6);
08709 IkReal x2836=(sj6)*(sj6);
08710 IkReal x2837=((IkReal(1.00000000000000))*(r21));
08711 IkReal x2838=((cj6)*(r20));
08712 IkReal x2839=((r22)*(sj5));
08713 IkReal x2840=((r01)*(sj0));
08714 IkReal x2841=((r00)*(sj0));
08715 IkReal x2842=((cj0)*(r10));
08716 IkReal x2843=((r02)*(sj0)*(sj5));
08717 IkReal x2844=((cj5)*(x2835));
08718 IkReal x2845=((cj0)*(r12)*(sj5));
08719 IkReal x2846=((IkReal(1.00000000000000))*(cj0)*(r11));
08720 IkReal x2847=((cj5)*(x2836));
08721 IkReal x2848=((r20)*(x2847));
08722 dummyeval[0]=((((x2838)*(x2843)))+(((IkReal(-1.00000000000000))*(sj6)*(x2839)*(x2846)))+(((r21)*(x2842)*(x2847)))+(((cj6)*(x2839)*(x2842)))+(((IkReal(-1.00000000000000))*(cj6)*(x2839)*(x2841)))+(((r21)*(x2842)*(x2844)))+(((IkReal(-1.00000000000000))*(x2837)*(x2841)*(x2844)))+(((r20)*(x2840)*(x2844)))+(((sj6)*(x2839)*(x2840)))+(((x2840)*(x2848)))+(((IkReal(-1.00000000000000))*(x2838)*(x2845)))+(((IkReal(-1.00000000000000))*(sj6)*(x2837)*(x2843)))+(((r21)*(sj6)*(x2845)))+(((IkReal(-1.00000000000000))*(x2846)*(x2848)))+(((IkReal(-1.00000000000000))*(r20)*(x2844)*(x2846)))+(((IkReal(-1.00000000000000))*(x2837)*(x2841)*(x2847))));
08723 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08724 {
08725 continue;
08726 
08727 } else
08728 {
08729 {
08730 IkReal j4array[1], cj4array[1], sj4array[1];
08731 bool j4valid[1]={false};
08732 _nj4 = 1;
08733 IkReal x2849=((cj2)*(sj6));
08734 IkReal x2850=((IkReal(1.00000000000000))*(r20));
08735 IkReal x2851=((cj2)*(cj6));
08736 if( IKabs(((gconst68)*(((((r21)*(x2849)))+(((IkReal(-1.00000000000000))*(x2850)*(x2851))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst68)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2851)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(x2849)*(x2850))))))) < IKFAST_ATAN2_MAGTHRESH )
08737     continue;
08738 j4array[0]=IKatan2(((gconst68)*(((((r21)*(x2849)))+(((IkReal(-1.00000000000000))*(x2850)*(x2851)))))), ((gconst68)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2851)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(x2849)*(x2850)))))));
08739 sj4array[0]=IKsin(j4array[0]);
08740 cj4array[0]=IKcos(j4array[0]);
08741 if( j4array[0] > IKPI )
08742 {
08743     j4array[0]-=IK2PI;
08744 }
08745 else if( j4array[0] < -IKPI )
08746 {    j4array[0]+=IK2PI;
08747 }
08748 j4valid[0] = true;
08749 for(int ij4 = 0; ij4 < 1; ++ij4)
08750 {
08751 if( !j4valid[ij4] )
08752 {
08753     continue;
08754 }
08755 _ij4[0] = ij4; _ij4[1] = -1;
08756 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
08757 {
08758 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
08759 {
08760     j4valid[iij4]=false; _ij4[1] = iij4; break; 
08761 }
08762 }
08763 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
08764 {
08765 IkReal evalcond[6];
08766 IkReal x2852=IKsin(j4);
08767 IkReal x2853=IKcos(j4);
08768 IkReal x2854=((r00)*(sj6));
08769 IkReal x2855=((IkReal(1.00000000000000))*(r12));
08770 IkReal x2856=((IkReal(1.00000000000000))*(cj6));
08771 IkReal x2857=((cj6)*(r01));
08772 IkReal x2858=((r11)*(sj6));
08773 IkReal x2859=((r01)*(sj6));
08774 IkReal x2860=((IkReal(1.00000000000000))*(cj5));
08775 IkReal x2861=((r10)*(sj6));
08776 IkReal x2862=((cj5)*(r11));
08777 IkReal x2863=((cj6)*(r00));
08778 IkReal x2864=((r21)*(sj6));
08779 IkReal x2865=((r02)*(sj5));
08780 IkReal x2866=((cj6)*(r10));
08781 IkReal x2867=((cj5)*(sj6));
08782 IkReal x2868=((cj5)*(r01));
08783 IkReal x2869=((sj5)*(x2852));
08784 IkReal x2870=((cj0)*(x2853));
08785 IkReal x2871=((cj0)*(x2852));
08786 IkReal x2872=((sj0)*(x2853));
08787 IkReal x2873=((sj0)*(x2852));
08788 IkReal x2874=((r20)*(x2853));
08789 IkReal x2875=((cj5)*(cj6)*(r21));
08790 IkReal x2876=((r20)*(x2852));
08791 IkReal x2877=((cj5)*(x2873));
08792 evalcond[0]=((((r22)*(x2869)))+(((x2852)*(x2875)))+(((IkReal(-1.00000000000000))*(x2856)*(x2874)))+(((x2853)*(x2864)))+(((x2867)*(x2876))));
08793 evalcond[1]=((((cj6)*(x2876)))+(((IkReal(-1.00000000000000))*(x2852)*(x2864)))+(((x2867)*(x2874)))+(((IkReal(-1.00000000000000))*(sj3)))+(((r22)*(sj5)*(x2853)))+(((x2853)*(x2875))));
08794 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x2856)*(x2872)))+(((IkReal(-1.00000000000000))*(cj0)*(x2855)*(x2869)))+(((IkReal(-1.00000000000000))*(x2858)*(x2870)))+(((x2857)*(x2877)))+(((x2865)*(x2873)))+(((IkReal(-1.00000000000000))*(x2856)*(x2862)*(x2871)))+(cj2)+(((x2859)*(x2872)))+(((x2854)*(x2877)))+(((IkReal(-1.00000000000000))*(x2860)*(x2861)*(x2871)))+(((x2866)*(x2870))));
08795 evalcond[3]=((((x2865)*(x2872)))+(((x2858)*(x2871)))+(((IkReal(-1.00000000000000))*(x2856)*(x2862)*(x2870)))+(((cj5)*(x2857)*(x2872)))+(((x2863)*(x2873)))+(((IkReal(-1.00000000000000))*(x2859)*(x2873)))+(((cj3)*(sj2)))+(((cj5)*(x2854)*(x2872)))+(((IkReal(-1.00000000000000))*(r10)*(x2856)*(x2871)))+(((IkReal(-1.00000000000000))*(sj5)*(x2855)*(x2870)))+(((IkReal(-1.00000000000000))*(x2860)*(x2861)*(x2870))));
08796 evalcond[4]=((((x2866)*(x2872)))+(((IkReal(-1.00000000000000))*(x2856)*(x2868)*(x2871)))+(sj2)+(((IkReal(-1.00000000000000))*(x2859)*(x2870)))+(((IkReal(-1.00000000000000))*(x2860)*(x2861)*(x2873)))+(((IkReal(-1.00000000000000))*(x2854)*(x2860)*(x2871)))+(((IkReal(-1.00000000000000))*(x2856)*(x2862)*(x2873)))+(((IkReal(-1.00000000000000))*(x2858)*(x2872)))+(((x2863)*(x2870)))+(((IkReal(-1.00000000000000))*(sj0)*(x2855)*(x2869)))+(((IkReal(-1.00000000000000))*(x2865)*(x2871))));
08797 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x2856)*(x2873)))+(((IkReal(-1.00000000000000))*(r00)*(x2856)*(x2871)))+(((IkReal(-1.00000000000000))*(x2860)*(x2861)*(x2872)))+(((IkReal(-1.00000000000000))*(sj5)*(x2855)*(x2872)))+(((IkReal(-1.00000000000000))*(x2856)*(x2868)*(x2870)))+(((x2859)*(x2871)))+(((IkReal(-1.00000000000000))*(x2865)*(x2870)))+(((x2858)*(x2873)))+(((IkReal(-1.00000000000000))*(x2854)*(x2860)*(x2870)))+(((IkReal(-1.00000000000000))*(x2856)*(x2862)*(x2872)))+(((IkReal(-1.00000000000000))*(cj2)*(cj3))));
08798 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08799 {
08800 continue;
08801 }
08802 }
08803 
08804 {
08805 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08806 vinfos[0].jointtype = 1;
08807 vinfos[0].foffset = j0;
08808 vinfos[0].indices[0] = _ij0[0];
08809 vinfos[0].indices[1] = _ij0[1];
08810 vinfos[0].maxsolutions = _nj0;
08811 vinfos[1].jointtype = 1;
08812 vinfos[1].foffset = j1;
08813 vinfos[1].indices[0] = _ij1[0];
08814 vinfos[1].indices[1] = _ij1[1];
08815 vinfos[1].maxsolutions = _nj1;
08816 vinfos[2].jointtype = 1;
08817 vinfos[2].foffset = j2;
08818 vinfos[2].indices[0] = _ij2[0];
08819 vinfos[2].indices[1] = _ij2[1];
08820 vinfos[2].maxsolutions = _nj2;
08821 vinfos[3].jointtype = 1;
08822 vinfos[3].foffset = j3;
08823 vinfos[3].indices[0] = _ij3[0];
08824 vinfos[3].indices[1] = _ij3[1];
08825 vinfos[3].maxsolutions = _nj3;
08826 vinfos[4].jointtype = 1;
08827 vinfos[4].foffset = j4;
08828 vinfos[4].indices[0] = _ij4[0];
08829 vinfos[4].indices[1] = _ij4[1];
08830 vinfos[4].maxsolutions = _nj4;
08831 vinfos[5].jointtype = 1;
08832 vinfos[5].foffset = j5;
08833 vinfos[5].indices[0] = _ij5[0];
08834 vinfos[5].indices[1] = _ij5[1];
08835 vinfos[5].maxsolutions = _nj5;
08836 vinfos[6].jointtype = 1;
08837 vinfos[6].foffset = j6;
08838 vinfos[6].indices[0] = _ij6[0];
08839 vinfos[6].indices[1] = _ij6[1];
08840 vinfos[6].maxsolutions = _nj6;
08841 std::vector<int> vfree(0);
08842 solutions.AddSolution(vinfos,vfree);
08843 }
08844 }
08845 }
08846 
08847 }
08848 
08849 }
08850 
08851 } else
08852 {
08853 {
08854 IkReal j4array[1], cj4array[1], sj4array[1];
08855 bool j4valid[1]={false};
08856 _nj4 = 1;
08857 IkReal x2878=((r21)*(sj3));
08858 IkReal x2879=((IkReal(1.00000000000000))*(r20)*(sj3));
08859 if( IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(cj6)*(x2879)))+(((sj6)*(x2878))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2878)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2879)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
08860     continue;
08861 j4array[0]=IKatan2(((gconst67)*(((((IkReal(-1.00000000000000))*(cj6)*(x2879)))+(((sj6)*(x2878)))))), ((gconst67)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x2878)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x2879)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
08862 sj4array[0]=IKsin(j4array[0]);
08863 cj4array[0]=IKcos(j4array[0]);
08864 if( j4array[0] > IKPI )
08865 {
08866     j4array[0]-=IK2PI;
08867 }
08868 else if( j4array[0] < -IKPI )
08869 {    j4array[0]+=IK2PI;
08870 }
08871 j4valid[0] = true;
08872 for(int ij4 = 0; ij4 < 1; ++ij4)
08873 {
08874 if( !j4valid[ij4] )
08875 {
08876     continue;
08877 }
08878 _ij4[0] = ij4; _ij4[1] = -1;
08879 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
08880 {
08881 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
08882 {
08883     j4valid[iij4]=false; _ij4[1] = iij4; break; 
08884 }
08885 }
08886 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
08887 {
08888 IkReal evalcond[6];
08889 IkReal x2880=IKsin(j4);
08890 IkReal x2881=IKcos(j4);
08891 IkReal x2882=((r00)*(sj6));
08892 IkReal x2883=((IkReal(1.00000000000000))*(r12));
08893 IkReal x2884=((IkReal(1.00000000000000))*(cj6));
08894 IkReal x2885=((cj6)*(r01));
08895 IkReal x2886=((r11)*(sj6));
08896 IkReal x2887=((r01)*(sj6));
08897 IkReal x2888=((IkReal(1.00000000000000))*(cj5));
08898 IkReal x2889=((r10)*(sj6));
08899 IkReal x2890=((cj5)*(r11));
08900 IkReal x2891=((cj6)*(r00));
08901 IkReal x2892=((r21)*(sj6));
08902 IkReal x2893=((r02)*(sj5));
08903 IkReal x2894=((cj6)*(r10));
08904 IkReal x2895=((cj5)*(sj6));
08905 IkReal x2896=((cj5)*(r01));
08906 IkReal x2897=((sj5)*(x2880));
08907 IkReal x2898=((cj0)*(x2881));
08908 IkReal x2899=((cj0)*(x2880));
08909 IkReal x2900=((sj0)*(x2881));
08910 IkReal x2901=((sj0)*(x2880));
08911 IkReal x2902=((r20)*(x2881));
08912 IkReal x2903=((cj5)*(cj6)*(r21));
08913 IkReal x2904=((r20)*(x2880));
08914 IkReal x2905=((cj5)*(x2901));
08915 evalcond[0]=((((IkReal(-1.00000000000000))*(x2884)*(x2902)))+(((r22)*(x2897)))+(((x2895)*(x2904)))+(((x2880)*(x2903)))+(((x2881)*(x2892))));
08916 evalcond[1]=((((x2881)*(x2903)))+(((x2895)*(x2902)))+(((cj6)*(x2904)))+(((r22)*(sj5)*(x2881)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x2880)*(x2892))));
08917 evalcond[2]=((((IkReal(-1.00000000000000))*(x2886)*(x2898)))+(((IkReal(-1.00000000000000))*(r00)*(x2884)*(x2900)))+(((x2894)*(x2898)))+(((x2885)*(x2905)))+(((IkReal(-1.00000000000000))*(x2888)*(x2889)*(x2899)))+(((IkReal(-1.00000000000000))*(x2884)*(x2890)*(x2899)))+(((x2893)*(x2901)))+(cj2)+(((IkReal(-1.00000000000000))*(cj0)*(x2883)*(x2897)))+(((x2882)*(x2905)))+(((x2887)*(x2900))));
08918 evalcond[3]=((((x2893)*(x2900)))+(((cj5)*(x2885)*(x2900)))+(((IkReal(-1.00000000000000))*(x2888)*(x2889)*(x2898)))+(((cj5)*(x2882)*(x2900)))+(((IkReal(-1.00000000000000))*(x2887)*(x2901)))+(((IkReal(-1.00000000000000))*(sj5)*(x2883)*(x2898)))+(((IkReal(-1.00000000000000))*(x2884)*(x2890)*(x2898)))+(((x2886)*(x2899)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(r10)*(x2884)*(x2899)))+(((x2891)*(x2901))));
08919 evalcond[4]=((((IkReal(-1.00000000000000))*(x2886)*(x2900)))+(((IkReal(-1.00000000000000))*(sj0)*(x2883)*(x2897)))+(((IkReal(-1.00000000000000))*(x2882)*(x2888)*(x2899)))+(sj2)+(((IkReal(-1.00000000000000))*(x2888)*(x2889)*(x2901)))+(((IkReal(-1.00000000000000))*(x2893)*(x2899)))+(((IkReal(-1.00000000000000))*(x2887)*(x2898)))+(((IkReal(-1.00000000000000))*(x2884)*(x2896)*(x2899)))+(((x2891)*(x2898)))+(((x2894)*(x2900)))+(((IkReal(-1.00000000000000))*(x2884)*(x2890)*(x2901))));
08920 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x2884)*(x2901)))+(((IkReal(-1.00000000000000))*(sj5)*(x2883)*(x2900)))+(((IkReal(-1.00000000000000))*(x2884)*(x2890)*(x2900)))+(((IkReal(-1.00000000000000))*(x2888)*(x2889)*(x2900)))+(((IkReal(-1.00000000000000))*(x2884)*(x2896)*(x2898)))+(((IkReal(-1.00000000000000))*(r00)*(x2884)*(x2899)))+(((x2887)*(x2899)))+(((IkReal(-1.00000000000000))*(x2882)*(x2888)*(x2898)))+(((x2886)*(x2901)))+(((IkReal(-1.00000000000000))*(x2893)*(x2898)))+(((IkReal(-1.00000000000000))*(cj2)*(cj3))));
08921 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
08922 {
08923 continue;
08924 }
08925 }
08926 
08927 {
08928 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
08929 vinfos[0].jointtype = 1;
08930 vinfos[0].foffset = j0;
08931 vinfos[0].indices[0] = _ij0[0];
08932 vinfos[0].indices[1] = _ij0[1];
08933 vinfos[0].maxsolutions = _nj0;
08934 vinfos[1].jointtype = 1;
08935 vinfos[1].foffset = j1;
08936 vinfos[1].indices[0] = _ij1[0];
08937 vinfos[1].indices[1] = _ij1[1];
08938 vinfos[1].maxsolutions = _nj1;
08939 vinfos[2].jointtype = 1;
08940 vinfos[2].foffset = j2;
08941 vinfos[2].indices[0] = _ij2[0];
08942 vinfos[2].indices[1] = _ij2[1];
08943 vinfos[2].maxsolutions = _nj2;
08944 vinfos[3].jointtype = 1;
08945 vinfos[3].foffset = j3;
08946 vinfos[3].indices[0] = _ij3[0];
08947 vinfos[3].indices[1] = _ij3[1];
08948 vinfos[3].maxsolutions = _nj3;
08949 vinfos[4].jointtype = 1;
08950 vinfos[4].foffset = j4;
08951 vinfos[4].indices[0] = _ij4[0];
08952 vinfos[4].indices[1] = _ij4[1];
08953 vinfos[4].maxsolutions = _nj4;
08954 vinfos[5].jointtype = 1;
08955 vinfos[5].foffset = j5;
08956 vinfos[5].indices[0] = _ij5[0];
08957 vinfos[5].indices[1] = _ij5[1];
08958 vinfos[5].maxsolutions = _nj5;
08959 vinfos[6].jointtype = 1;
08960 vinfos[6].foffset = j6;
08961 vinfos[6].indices[0] = _ij6[0];
08962 vinfos[6].indices[1] = _ij6[1];
08963 vinfos[6].maxsolutions = _nj6;
08964 std::vector<int> vfree(0);
08965 solutions.AddSolution(vinfos,vfree);
08966 }
08967 }
08968 }
08969 
08970 }
08971 
08972 }
08973 }
08974 }
08975 
08976 }
08977 
08978 }
08979 
08980 } else
08981 {
08982 {
08983 IkReal j4array[1], cj4array[1], sj4array[1];
08984 bool j4valid[1]={false};
08985 _nj4 = 1;
08986 IkReal x2906=((IkReal(1.00000000000000))*(sj2));
08987 if( IKabs(((gconst66)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2906)))+(((r21)*(sj2)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst66)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2906)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(r21)*(x2906)))+(((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj6)*(x2906))))))) < IKFAST_ATAN2_MAGTHRESH )
08988     continue;
08989 j4array[0]=IKatan2(((gconst66)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x2906)))+(((r21)*(sj2)*(sj6)))))), ((gconst66)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x2906)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(r21)*(x2906)))+(((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj6)*(x2906)))))));
08990 sj4array[0]=IKsin(j4array[0]);
08991 cj4array[0]=IKcos(j4array[0]);
08992 if( j4array[0] > IKPI )
08993 {
08994     j4array[0]-=IK2PI;
08995 }
08996 else if( j4array[0] < -IKPI )
08997 {    j4array[0]+=IK2PI;
08998 }
08999 j4valid[0] = true;
09000 for(int ij4 = 0; ij4 < 1; ++ij4)
09001 {
09002 if( !j4valid[ij4] )
09003 {
09004     continue;
09005 }
09006 _ij4[0] = ij4; _ij4[1] = -1;
09007 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
09008 {
09009 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
09010 {
09011     j4valid[iij4]=false; _ij4[1] = iij4; break; 
09012 }
09013 }
09014 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
09015 {
09016 IkReal evalcond[3];
09017 IkReal x2907=IKsin(j4);
09018 IkReal x2908=IKcos(j4);
09019 IkReal x2909=((r00)*(sj6));
09020 IkReal x2910=((cj6)*(r01));
09021 IkReal x2911=((IkReal(1.00000000000000))*(cj0));
09022 IkReal x2912=((IkReal(1.00000000000000))*(sj0));
09023 IkReal x2913=((r10)*(sj6));
09024 IkReal x2914=((sj5)*(x2907));
09025 IkReal x2915=((IkReal(1.00000000000000))*(cj6)*(r11));
09026 IkReal x2916=((cj5)*(x2907));
09027 IkReal x2917=((cj6)*(x2908));
09028 IkReal x2918=((sj0)*(x2916));
09029 IkReal x2919=((r01)*(sj6)*(x2908));
09030 IkReal x2920=((r11)*(sj6)*(x2908));
09031 evalcond[0]=((((cj6)*(r21)*(x2916)))+(((IkReal(-1.00000000000000))*(r20)*(x2917)))+(((r22)*(x2914)))+(((r21)*(sj6)*(x2908)))+(((r20)*(sj6)*(x2916))));
09032 evalcond[1]=((((IkReal(-1.00000000000000))*(x2911)*(x2913)*(x2916)))+(((IkReal(-1.00000000000000))*(x2911)*(x2920)))+(((cj0)*(r10)*(x2917)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2911)*(x2916)))+(((IkReal(-1.00000000000000))*(r00)*(x2912)*(x2917)))+(((x2910)*(x2918)))+(cj2)+(((IkReal(-1.00000000000000))*(r12)*(x2911)*(x2914)))+(((r02)*(sj0)*(x2914)))+(((sj0)*(x2919)))+(((x2909)*(x2918))));
09033 evalcond[2]=((((IkReal(-1.00000000000000))*(x2909)*(x2911)*(x2916)))+(((IkReal(-1.00000000000000))*(x2912)*(x2920)))+(((cj0)*(r00)*(x2917)))+(sj2)+(((IkReal(-1.00000000000000))*(x2910)*(x2911)*(x2916)))+(((IkReal(-1.00000000000000))*(r02)*(x2911)*(x2914)))+(((IkReal(-1.00000000000000))*(x2912)*(x2913)*(x2916)))+(((IkReal(-1.00000000000000))*(x2911)*(x2919)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2912)*(x2916)))+(((IkReal(-1.00000000000000))*(r12)*(x2912)*(x2914)))+(((r10)*(sj0)*(x2917))));
09034 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
09035 {
09036 continue;
09037 }
09038 }
09039 
09040 {
09041 IkReal j3array[1], cj3array[1], sj3array[1];
09042 bool j3valid[1]={false};
09043 _nj3 = 1;
09044 IkReal x2921=((r20)*(sj6));
09045 IkReal x2922=((cj4)*(cj5));
09046 IkReal x2923=((cj6)*(r21));
09047 if( IKabs(((((x2922)*(x2923)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2921)*(x2922))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x2923)))+(((sj5)*(x2921)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x2922)*(x2923)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2921)*(x2922)))))+IKsqr(((((sj5)*(x2923)))+(((sj5)*(x2921)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
09048     continue;
09049 j3array[0]=IKatan2(((((x2922)*(x2923)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2921)*(x2922)))), ((((sj5)*(x2923)))+(((sj5)*(x2921)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))));
09050 sj3array[0]=IKsin(j3array[0]);
09051 cj3array[0]=IKcos(j3array[0]);
09052 if( j3array[0] > IKPI )
09053 {
09054     j3array[0]-=IK2PI;
09055 }
09056 else if( j3array[0] < -IKPI )
09057 {    j3array[0]+=IK2PI;
09058 }
09059 j3valid[0] = true;
09060 for(int ij3 = 0; ij3 < 1; ++ij3)
09061 {
09062 if( !j3valid[ij3] )
09063 {
09064     continue;
09065 }
09066 _ij3[0] = ij3; _ij3[1] = -1;
09067 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
09068 {
09069 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
09070 {
09071     j3valid[iij3]=false; _ij3[1] = iij3; break; 
09072 }
09073 }
09074 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
09075 {
09076 IkReal evalcond[6];
09077 IkReal x2924=IKsin(j3);
09078 IkReal x2925=IKcos(j3);
09079 IkReal x2926=((sj0)*(sj5));
09080 IkReal x2927=((r00)*(sj6));
09081 IkReal x2928=((cj6)*(r01));
09082 IkReal x2929=((cj4)*(cj5));
09083 IkReal x2930=((IkReal(1.00000000000000))*(cj0));
09084 IkReal x2931=((cj5)*(r12));
09085 IkReal x2932=((IkReal(1.00000000000000))*(sj0));
09086 IkReal x2933=((cj6)*(r11));
09087 IkReal x2934=((cj6)*(sj4));
09088 IkReal x2935=((cj5)*(r02));
09089 IkReal x2936=((cj6)*(r21));
09090 IkReal x2937=((r20)*(sj6));
09091 IkReal x2938=((r10)*(sj6));
09092 IkReal x2939=((sj4)*(sj6));
09093 IkReal x2940=((cj4)*(r02));
09094 IkReal x2941=((IkReal(1.00000000000000))*(cj4)*(r12));
09095 IkReal x2942=((cj0)*(x2939));
09096 IkReal x2943=((IkReal(1.00000000000000))*(x2924));
09097 IkReal x2944=((IkReal(1.00000000000000))*(x2925));
09098 evalcond[0]=((((sj5)*(x2937)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x2944)))+(((sj5)*(x2936))));
09099 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x2939)))+(((x2929)*(x2936)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x2943)))+(((r20)*(x2934)))+(((x2929)*(x2937))));
09100 evalcond[2]=((((x2926)*(x2927)))+(((cj0)*(x2931)))+(((IkReal(-1.00000000000000))*(sj5)*(x2930)*(x2938)))+(((IkReal(-1.00000000000000))*(x2932)*(x2935)))+(((IkReal(-1.00000000000000))*(sj5)*(x2930)*(x2933)))+(((x2926)*(x2928)))+(((IkReal(-1.00000000000000))*(sj2)*(x2943))));
09101 evalcond[3]=((((IkReal(-1.00000000000000))*(x2926)*(x2938)))+(((cj2)*(x2924)))+(((IkReal(-1.00000000000000))*(sj5)*(x2928)*(x2930)))+(((IkReal(-1.00000000000000))*(x2926)*(x2933)))+(((cj0)*(x2935)))+(((sj0)*(x2931)))+(((IkReal(-1.00000000000000))*(sj5)*(x2927)*(x2930))));
09102 evalcond[4]=((((x2926)*(x2940)))+(((IkReal(-1.00000000000000))*(r01)*(x2932)*(x2939)))+(((r11)*(x2942)))+(((sj0)*(x2928)*(x2929)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x2930)))+(((r00)*(sj0)*(x2934)))+(((sj0)*(x2927)*(x2929)))+(((IkReal(-1.00000000000000))*(x2929)*(x2930)*(x2933)))+(((IkReal(-1.00000000000000))*(r10)*(x2930)*(x2934)))+(((IkReal(-1.00000000000000))*(x2929)*(x2930)*(x2938)))+(((sj2)*(x2925))));
09103 evalcond[5]=((((r11)*(sj0)*(x2939)))+(((IkReal(-1.00000000000000))*(x2927)*(x2929)*(x2930)))+(((r01)*(x2942)))+(((IkReal(-1.00000000000000))*(r10)*(x2932)*(x2934)))+(((IkReal(-1.00000000000000))*(x2926)*(x2941)))+(((IkReal(-1.00000000000000))*(r00)*(x2930)*(x2934)))+(((IkReal(-1.00000000000000))*(sj5)*(x2930)*(x2940)))+(((IkReal(-1.00000000000000))*(x2929)*(x2932)*(x2933)))+(((IkReal(-1.00000000000000))*(x2928)*(x2929)*(x2930)))+(((IkReal(-1.00000000000000))*(cj2)*(x2944)))+(((IkReal(-1.00000000000000))*(x2929)*(x2932)*(x2938))));
09104 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
09105 {
09106 continue;
09107 }
09108 }
09109 
09110 {
09111 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
09112 vinfos[0].jointtype = 1;
09113 vinfos[0].foffset = j0;
09114 vinfos[0].indices[0] = _ij0[0];
09115 vinfos[0].indices[1] = _ij0[1];
09116 vinfos[0].maxsolutions = _nj0;
09117 vinfos[1].jointtype = 1;
09118 vinfos[1].foffset = j1;
09119 vinfos[1].indices[0] = _ij1[0];
09120 vinfos[1].indices[1] = _ij1[1];
09121 vinfos[1].maxsolutions = _nj1;
09122 vinfos[2].jointtype = 1;
09123 vinfos[2].foffset = j2;
09124 vinfos[2].indices[0] = _ij2[0];
09125 vinfos[2].indices[1] = _ij2[1];
09126 vinfos[2].maxsolutions = _nj2;
09127 vinfos[3].jointtype = 1;
09128 vinfos[3].foffset = j3;
09129 vinfos[3].indices[0] = _ij3[0];
09130 vinfos[3].indices[1] = _ij3[1];
09131 vinfos[3].maxsolutions = _nj3;
09132 vinfos[4].jointtype = 1;
09133 vinfos[4].foffset = j4;
09134 vinfos[4].indices[0] = _ij4[0];
09135 vinfos[4].indices[1] = _ij4[1];
09136 vinfos[4].maxsolutions = _nj4;
09137 vinfos[5].jointtype = 1;
09138 vinfos[5].foffset = j5;
09139 vinfos[5].indices[0] = _ij5[0];
09140 vinfos[5].indices[1] = _ij5[1];
09141 vinfos[5].maxsolutions = _nj5;
09142 vinfos[6].jointtype = 1;
09143 vinfos[6].foffset = j6;
09144 vinfos[6].indices[0] = _ij6[0];
09145 vinfos[6].indices[1] = _ij6[1];
09146 vinfos[6].maxsolutions = _nj6;
09147 std::vector<int> vfree(0);
09148 solutions.AddSolution(vinfos,vfree);
09149 }
09150 }
09151 }
09152 }
09153 }
09154 
09155 }
09156 
09157 }
09158 
09159 } else
09160 {
09161 {
09162 IkReal j4array[1], cj4array[1], sj4array[1];
09163 bool j4valid[1]={false};
09164 _nj4 = 1;
09165 IkReal x2945=((cj2)*(sj6));
09166 IkReal x2946=((IkReal(1.00000000000000))*(r20));
09167 IkReal x2947=((cj2)*(cj6));
09168 if( IKabs(((gconst65)*(((((IkReal(-1.00000000000000))*(x2946)*(x2947)))+(((r21)*(x2945))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst65)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2947)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(x2945)*(x2946))))))) < IKFAST_ATAN2_MAGTHRESH )
09169     continue;
09170 j4array[0]=IKatan2(((gconst65)*(((((IkReal(-1.00000000000000))*(x2946)*(x2947)))+(((r21)*(x2945)))))), ((gconst65)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x2947)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(x2945)*(x2946)))))));
09171 sj4array[0]=IKsin(j4array[0]);
09172 cj4array[0]=IKcos(j4array[0]);
09173 if( j4array[0] > IKPI )
09174 {
09175     j4array[0]-=IK2PI;
09176 }
09177 else if( j4array[0] < -IKPI )
09178 {    j4array[0]+=IK2PI;
09179 }
09180 j4valid[0] = true;
09181 for(int ij4 = 0; ij4 < 1; ++ij4)
09182 {
09183 if( !j4valid[ij4] )
09184 {
09185     continue;
09186 }
09187 _ij4[0] = ij4; _ij4[1] = -1;
09188 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
09189 {
09190 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
09191 {
09192     j4valid[iij4]=false; _ij4[1] = iij4; break; 
09193 }
09194 }
09195 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
09196 {
09197 IkReal evalcond[3];
09198 IkReal x2948=IKsin(j4);
09199 IkReal x2949=IKcos(j4);
09200 IkReal x2950=((r00)*(sj6));
09201 IkReal x2951=((cj6)*(r01));
09202 IkReal x2952=((IkReal(1.00000000000000))*(cj0));
09203 IkReal x2953=((IkReal(1.00000000000000))*(sj0));
09204 IkReal x2954=((r10)*(sj6));
09205 IkReal x2955=((sj5)*(x2948));
09206 IkReal x2956=((IkReal(1.00000000000000))*(cj6)*(r11));
09207 IkReal x2957=((cj5)*(x2948));
09208 IkReal x2958=((cj6)*(x2949));
09209 IkReal x2959=((sj0)*(x2957));
09210 IkReal x2960=((r01)*(sj6)*(x2949));
09211 IkReal x2961=((r11)*(sj6)*(x2949));
09212 evalcond[0]=((((r20)*(sj6)*(x2957)))+(((cj6)*(r21)*(x2957)))+(((r22)*(x2955)))+(((IkReal(-1.00000000000000))*(r20)*(x2958)))+(((r21)*(sj6)*(x2949))));
09213 evalcond[1]=((((IkReal(-1.00000000000000))*(x2952)*(x2954)*(x2957)))+(((IkReal(-1.00000000000000))*(r12)*(x2952)*(x2955)))+(((IkReal(-1.00000000000000))*(r00)*(x2953)*(x2958)))+(((x2950)*(x2959)))+(((x2951)*(x2959)))+(cj2)+(((sj0)*(x2960)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2952)*(x2957)))+(((IkReal(-1.00000000000000))*(x2952)*(x2961)))+(((cj0)*(r10)*(x2958)))+(((r02)*(sj0)*(x2955))));
09214 evalcond[2]=((sj2)+(((IkReal(-1.00000000000000))*(x2950)*(x2952)*(x2957)))+(((IkReal(-1.00000000000000))*(x2951)*(x2952)*(x2957)))+(((cj0)*(r00)*(x2958)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x2953)*(x2957)))+(((IkReal(-1.00000000000000))*(r12)*(x2953)*(x2955)))+(((IkReal(-1.00000000000000))*(x2953)*(x2961)))+(((r10)*(sj0)*(x2958)))+(((IkReal(-1.00000000000000))*(x2952)*(x2960)))+(((IkReal(-1.00000000000000))*(x2953)*(x2954)*(x2957)))+(((IkReal(-1.00000000000000))*(r02)*(x2952)*(x2955))));
09215 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
09216 {
09217 continue;
09218 }
09219 }
09220 
09221 {
09222 IkReal j3array[1], cj3array[1], sj3array[1];
09223 bool j3valid[1]={false};
09224 _nj3 = 1;
09225 IkReal x2962=((r20)*(sj6));
09226 IkReal x2963=((cj4)*(cj5));
09227 IkReal x2964=((cj6)*(r21));
09228 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x2962)*(x2963)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2963)*(x2964))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x2962)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x2964))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x2962)*(x2963)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2963)*(x2964)))))+IKsqr(((((sj5)*(x2962)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x2964)))))-1) <= IKFAST_SINCOS_THRESH )
09229     continue;
09230 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x2962)*(x2963)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x2963)*(x2964)))), ((((sj5)*(x2962)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x2964)))));
09231 sj3array[0]=IKsin(j3array[0]);
09232 cj3array[0]=IKcos(j3array[0]);
09233 if( j3array[0] > IKPI )
09234 {
09235     j3array[0]-=IK2PI;
09236 }
09237 else if( j3array[0] < -IKPI )
09238 {    j3array[0]+=IK2PI;
09239 }
09240 j3valid[0] = true;
09241 for(int ij3 = 0; ij3 < 1; ++ij3)
09242 {
09243 if( !j3valid[ij3] )
09244 {
09245     continue;
09246 }
09247 _ij3[0] = ij3; _ij3[1] = -1;
09248 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
09249 {
09250 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
09251 {
09252     j3valid[iij3]=false; _ij3[1] = iij3; break; 
09253 }
09254 }
09255 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
09256 {
09257 IkReal evalcond[6];
09258 IkReal x2965=IKsin(j3);
09259 IkReal x2966=IKcos(j3);
09260 IkReal x2967=((sj0)*(sj5));
09261 IkReal x2968=((r00)*(sj6));
09262 IkReal x2969=((cj6)*(r01));
09263 IkReal x2970=((cj4)*(cj5));
09264 IkReal x2971=((IkReal(1.00000000000000))*(cj0));
09265 IkReal x2972=((cj5)*(r12));
09266 IkReal x2973=((IkReal(1.00000000000000))*(sj0));
09267 IkReal x2974=((cj6)*(r11));
09268 IkReal x2975=((cj6)*(sj4));
09269 IkReal x2976=((cj5)*(r02));
09270 IkReal x2977=((cj6)*(r21));
09271 IkReal x2978=((r20)*(sj6));
09272 IkReal x2979=((r10)*(sj6));
09273 IkReal x2980=((sj4)*(sj6));
09274 IkReal x2981=((cj4)*(r02));
09275 IkReal x2982=((IkReal(1.00000000000000))*(cj4)*(r12));
09276 IkReal x2983=((cj0)*(x2980));
09277 IkReal x2984=((IkReal(1.00000000000000))*(x2965));
09278 IkReal x2985=((IkReal(1.00000000000000))*(x2966));
09279 evalcond[0]=((((sj5)*(x2978)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x2985)))+(((sj5)*(x2977))));
09280 evalcond[1]=((((IkReal(-1.00000000000000))*(x2984)))+(((cj4)*(r22)*(sj5)))+(((x2970)*(x2977)))+(((IkReal(-1.00000000000000))*(r21)*(x2980)))+(((r20)*(x2975)))+(((x2970)*(x2978))));
09281 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x2984)))+(((IkReal(-1.00000000000000))*(x2973)*(x2976)))+(((IkReal(-1.00000000000000))*(sj5)*(x2971)*(x2979)))+(((cj0)*(x2972)))+(((x2967)*(x2968)))+(((x2967)*(x2969)))+(((IkReal(-1.00000000000000))*(sj5)*(x2971)*(x2974))));
09282 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x2968)*(x2971)))+(((IkReal(-1.00000000000000))*(x2967)*(x2974)))+(((IkReal(-1.00000000000000))*(sj5)*(x2969)*(x2971)))+(((sj0)*(x2972)))+(((cj0)*(x2976)))+(((IkReal(-1.00000000000000))*(x2967)*(x2979)))+(((cj2)*(x2965))));
09283 evalcond[4]=((((sj0)*(x2969)*(x2970)))+(((IkReal(-1.00000000000000))*(r01)*(x2973)*(x2980)))+(((r11)*(x2983)))+(((IkReal(-1.00000000000000))*(r10)*(x2971)*(x2975)))+(((IkReal(-1.00000000000000))*(x2970)*(x2971)*(x2979)))+(((x2967)*(x2981)))+(((sj0)*(x2968)*(x2970)))+(((IkReal(-1.00000000000000))*(x2970)*(x2971)*(x2974)))+(((r00)*(sj0)*(x2975)))+(((sj2)*(x2966)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x2971))));
09284 evalcond[5]=((((r01)*(x2983)))+(((IkReal(-1.00000000000000))*(sj5)*(x2971)*(x2981)))+(((IkReal(-1.00000000000000))*(r10)*(x2973)*(x2975)))+(((IkReal(-1.00000000000000))*(r00)*(x2971)*(x2975)))+(((IkReal(-1.00000000000000))*(x2967)*(x2982)))+(((IkReal(-1.00000000000000))*(x2970)*(x2973)*(x2979)))+(((IkReal(-1.00000000000000))*(x2969)*(x2970)*(x2971)))+(((r11)*(sj0)*(x2980)))+(((IkReal(-1.00000000000000))*(x2968)*(x2970)*(x2971)))+(((IkReal(-1.00000000000000))*(cj2)*(x2985)))+(((IkReal(-1.00000000000000))*(x2970)*(x2973)*(x2974))));
09285 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
09286 {
09287 continue;
09288 }
09289 }
09290 
09291 {
09292 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
09293 vinfos[0].jointtype = 1;
09294 vinfos[0].foffset = j0;
09295 vinfos[0].indices[0] = _ij0[0];
09296 vinfos[0].indices[1] = _ij0[1];
09297 vinfos[0].maxsolutions = _nj0;
09298 vinfos[1].jointtype = 1;
09299 vinfos[1].foffset = j1;
09300 vinfos[1].indices[0] = _ij1[0];
09301 vinfos[1].indices[1] = _ij1[1];
09302 vinfos[1].maxsolutions = _nj1;
09303 vinfos[2].jointtype = 1;
09304 vinfos[2].foffset = j2;
09305 vinfos[2].indices[0] = _ij2[0];
09306 vinfos[2].indices[1] = _ij2[1];
09307 vinfos[2].maxsolutions = _nj2;
09308 vinfos[3].jointtype = 1;
09309 vinfos[3].foffset = j3;
09310 vinfos[3].indices[0] = _ij3[0];
09311 vinfos[3].indices[1] = _ij3[1];
09312 vinfos[3].maxsolutions = _nj3;
09313 vinfos[4].jointtype = 1;
09314 vinfos[4].foffset = j4;
09315 vinfos[4].indices[0] = _ij4[0];
09316 vinfos[4].indices[1] = _ij4[1];
09317 vinfos[4].maxsolutions = _nj4;
09318 vinfos[5].jointtype = 1;
09319 vinfos[5].foffset = j5;
09320 vinfos[5].indices[0] = _ij5[0];
09321 vinfos[5].indices[1] = _ij5[1];
09322 vinfos[5].maxsolutions = _nj5;
09323 vinfos[6].jointtype = 1;
09324 vinfos[6].foffset = j6;
09325 vinfos[6].indices[0] = _ij6[0];
09326 vinfos[6].indices[1] = _ij6[1];
09327 vinfos[6].maxsolutions = _nj6;
09328 std::vector<int> vfree(0);
09329 solutions.AddSolution(vinfos,vfree);
09330 }
09331 }
09332 }
09333 }
09334 }
09335 
09336 }
09337 
09338 }
09339 }
09340 }
09341 
09342 } else
09343 {
09344 IkReal x2986=((r20)*(sj6));
09345 IkReal x2987=((IkReal(0.0100000000000000))*(cj5));
09346 IkReal x2988=((IkReal(0.374290000000000))*(sj5));
09347 IkReal x2989=((cj6)*(r21));
09348 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
09349 evalcond[1]=((IkReal(-0.364420000000000))+(((x2988)*(x2989)))+(((IkReal(-1.00000000000000))*(x2986)*(x2987)))+(((IkReal(-0.0100000000000000))*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x2987)*(x2989)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x2986)*(x2988))));
09350 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  )
09351 {
09352 {
09353 IkReal j2array[1], cj2array[1], sj2array[1];
09354 bool j2valid[1]={false};
09355 _nj2 = 1;
09356 IkReal x2990=((r00)*(sj6));
09357 IkReal x2991=((IkReal(14.4927536231884))*(cj0));
09358 IkReal x2992=((cj6)*(r11));
09359 IkReal x2993=((cj0)*(sj5));
09360 IkReal x2994=((IkReal(0.144927536231884))*(r02));
09361 IkReal x2995=((r10)*(sj6));
09362 IkReal x2996=((cj5)*(sj0));
09363 IkReal x2997=((IkReal(5.42449275362319))*(r12));
09364 IkReal x2998=((IkReal(14.4927536231884))*(sj0));
09365 IkReal x2999=((cj6)*(r01));
09366 IkReal x3000=((sj0)*(sj5));
09367 IkReal x3001=((IkReal(0.144927536231884))*(r12));
09368 IkReal x3002=((IkReal(5.42449275362319))*(r02));
09369 IkReal x3003=((cj0)*(cj5));
09370 IkReal x3004=((IkReal(0.144927536231884))*(x3003));
09371 IkReal x3005=((IkReal(5.42449275362319))*(sj5)*(x2999));
09372 if( IKabs(((((IkReal(0.144927536231884))*(x2990)*(x2996)))+(((IkReal(5.42449275362319))*(x2993)*(x2995)))+(((IkReal(-1.00000000000000))*(px)*(x2998)))+(((IkReal(-1.00000000000000))*(x2997)*(x3003)))+(((x2996)*(x3002)))+(((IkReal(-5.42449275362319))*(x2999)*(x3000)))+(((py)*(x2991)))+(((IkReal(0.144927536231884))*(x2996)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x2993)))+(((IkReal(-1.00000000000000))*(x2993)*(x3001)))+(((IkReal(-1.00000000000000))*(x2995)*(x3004)))+(((x2994)*(x3000)))+(((IkReal(-1.00000000000000))*(x2992)*(x3004)))+(((IkReal(-5.42449275362319))*(x2990)*(x3000))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2990)*(x3004)))+(((IkReal(5.42449275362319))*(x2993)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x3000)))+(((IkReal(-1.00000000000000))*(x3000)*(x3001)))+(((IkReal(5.42449275362319))*(x2990)*(x2993)))+(((IkReal(5.42449275362319))*(x2995)*(x3000)))+(((IkReal(-1.00000000000000))*(x2999)*(x3004)))+(((px)*(x2991)))+(((IkReal(-1.00000000000000))*(x3002)*(x3003)))+(((IkReal(-1.00000000000000))*(x2993)*(x2994)))+(((py)*(x2998)))+(((IkReal(-0.144927536231884))*(x2992)*(x2996)))+(((IkReal(-0.144927536231884))*(x2995)*(x2996)))+(((IkReal(-1.00000000000000))*(x2996)*(x2997))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(0.144927536231884))*(x2990)*(x2996)))+(((IkReal(5.42449275362319))*(x2993)*(x2995)))+(((IkReal(-1.00000000000000))*(px)*(x2998)))+(((IkReal(-1.00000000000000))*(x2997)*(x3003)))+(((x2996)*(x3002)))+(((IkReal(-5.42449275362319))*(x2999)*(x3000)))+(((py)*(x2991)))+(((IkReal(0.144927536231884))*(x2996)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x2993)))+(((IkReal(-1.00000000000000))*(x2993)*(x3001)))+(((IkReal(-1.00000000000000))*(x2995)*(x3004)))+(((x2994)*(x3000)))+(((IkReal(-1.00000000000000))*(x2992)*(x3004)))+(((IkReal(-5.42449275362319))*(x2990)*(x3000)))))+IKsqr(((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2990)*(x3004)))+(((IkReal(5.42449275362319))*(x2993)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x3000)))+(((IkReal(-1.00000000000000))*(x3000)*(x3001)))+(((IkReal(5.42449275362319))*(x2990)*(x2993)))+(((IkReal(5.42449275362319))*(x2995)*(x3000)))+(((IkReal(-1.00000000000000))*(x2999)*(x3004)))+(((px)*(x2991)))+(((IkReal(-1.00000000000000))*(x3002)*(x3003)))+(((IkReal(-1.00000000000000))*(x2993)*(x2994)))+(((py)*(x2998)))+(((IkReal(-0.144927536231884))*(x2992)*(x2996)))+(((IkReal(-0.144927536231884))*(x2995)*(x2996)))+(((IkReal(-1.00000000000000))*(x2996)*(x2997)))))-1) <= IKFAST_SINCOS_THRESH )
09373     continue;
09374 j2array[0]=IKatan2(((((IkReal(0.144927536231884))*(x2990)*(x2996)))+(((IkReal(5.42449275362319))*(x2993)*(x2995)))+(((IkReal(-1.00000000000000))*(px)*(x2998)))+(((IkReal(-1.00000000000000))*(x2997)*(x3003)))+(((x2996)*(x3002)))+(((IkReal(-5.42449275362319))*(x2999)*(x3000)))+(((py)*(x2991)))+(((IkReal(0.144927536231884))*(x2996)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x2993)))+(((IkReal(-1.00000000000000))*(x2993)*(x3001)))+(((IkReal(-1.00000000000000))*(x2995)*(x3004)))+(((x2994)*(x3000)))+(((IkReal(-1.00000000000000))*(x2992)*(x3004)))+(((IkReal(-5.42449275362319))*(x2990)*(x3000)))), ((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2990)*(x3004)))+(((IkReal(5.42449275362319))*(x2993)*(x2999)))+(((IkReal(5.42449275362319))*(x2992)*(x3000)))+(((IkReal(-1.00000000000000))*(x3000)*(x3001)))+(((IkReal(5.42449275362319))*(x2990)*(x2993)))+(((IkReal(5.42449275362319))*(x2995)*(x3000)))+(((IkReal(-1.00000000000000))*(x2999)*(x3004)))+(((px)*(x2991)))+(((IkReal(-1.00000000000000))*(x3002)*(x3003)))+(((IkReal(-1.00000000000000))*(x2993)*(x2994)))+(((py)*(x2998)))+(((IkReal(-0.144927536231884))*(x2992)*(x2996)))+(((IkReal(-0.144927536231884))*(x2995)*(x2996)))+(((IkReal(-1.00000000000000))*(x2996)*(x2997)))));
09375 sj2array[0]=IKsin(j2array[0]);
09376 cj2array[0]=IKcos(j2array[0]);
09377 if( j2array[0] > IKPI )
09378 {
09379     j2array[0]-=IK2PI;
09380 }
09381 else if( j2array[0] < -IKPI )
09382 {    j2array[0]+=IK2PI;
09383 }
09384 j2valid[0] = true;
09385 for(int ij2 = 0; ij2 < 1; ++ij2)
09386 {
09387 if( !j2valid[ij2] )
09388 {
09389     continue;
09390 }
09391 _ij2[0] = ij2; _ij2[1] = -1;
09392 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
09393 {
09394 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
09395 {
09396     j2valid[iij2]=false; _ij2[1] = iij2; break; 
09397 }
09398 }
09399 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
09400 {
09401 IkReal evalcond[2];
09402 IkReal x3006=((IkReal(0.374290000000000))*(sj0));
09403 IkReal x3007=((cj5)*(r02));
09404 IkReal x3008=((IkReal(0.0100000000000000))*(cj0));
09405 IkReal x3009=((cj5)*(cj6));
09406 IkReal x3010=((r02)*(sj5));
09407 IkReal x3011=((cj5)*(sj6));
09408 IkReal x3012=((IkReal(1.00000000000000))*(py));
09409 IkReal x3013=((cj6)*(sj5));
09410 IkReal x3014=((IkReal(0.0100000000000000))*(sj0));
09411 IkReal x3015=((sj5)*(sj6));
09412 IkReal x3016=((cj5)*(r12));
09413 IkReal x3017=((IkReal(0.374290000000000))*(cj0));
09414 IkReal x3018=((r12)*(sj5));
09415 IkReal x3019=((x3013)*(x3017));
09416 IkReal x3020=((x3015)*(x3017));
09417 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(x3012)))+(((IkReal(-1.00000000000000))*(r10)*(x3020)))+(((IkReal(-1.00000000000000))*(x3006)*(x3007)))+(((r10)*(x3008)*(x3011)))+(((r00)*(x3006)*(x3015)))+(((IkReal(-1.00000000000000))*(r01)*(x3009)*(x3014)))+(((IkReal(-1.00000000000000))*(r11)*(x3019)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(r00)*(x3011)*(x3014)))+(((x3016)*(x3017)))+(((x3008)*(x3018)))+(((r01)*(x3006)*(x3013)))+(((px)*(sj0)))+(((r11)*(x3008)*(x3009)))+(((IkReal(-1.00000000000000))*(x3010)*(x3014))));
09418 evalcond[1]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3006)*(x3015)))+(((r01)*(x3008)*(x3009)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(sj0)*(x3012)))+(((x3007)*(x3017)))+(((x3008)*(x3010)))+(((IkReal(-1.00000000000000))*(r00)*(x3020)))+(((IkReal(0.0690000000000000))*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(r11)*(x3006)*(x3013)))+(((r00)*(x3008)*(x3011)))+(((x3006)*(x3016)))+(((IkReal(-1.00000000000000))*(r01)*(x3019)))+(((r10)*(x3011)*(x3014)))+(((r11)*(x3009)*(x3014)))+(((x3014)*(x3018))));
09419 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09420 {
09421 continue;
09422 }
09423 }
09424 
09425 {
09426 IkReal dummyeval[1];
09427 IkReal gconst77;
09428 IkReal x3021=(cj6)*(cj6);
09429 IkReal x3022=(sj6)*(sj6);
09430 IkReal x3023=((IkReal(1.00000000000000))*(r21));
09431 IkReal x3024=((cj6)*(r20));
09432 IkReal x3025=((r22)*(sj5));
09433 IkReal x3026=((r01)*(sj0));
09434 IkReal x3027=((r00)*(sj0));
09435 IkReal x3028=((cj0)*(r10));
09436 IkReal x3029=((r02)*(sj0)*(sj5));
09437 IkReal x3030=((cj5)*(x3021));
09438 IkReal x3031=((cj0)*(r12)*(sj5));
09439 IkReal x3032=((IkReal(1.00000000000000))*(cj0)*(r11));
09440 IkReal x3033=((cj5)*(x3022));
09441 IkReal x3034=((r20)*(x3033));
09442 gconst77=IKsign(((((IkReal(-1.00000000000000))*(sj6)*(x3023)*(x3029)))+(((sj6)*(x3025)*(x3026)))+(((x3026)*(x3034)))+(((r20)*(x3026)*(x3030)))+(((r21)*(sj6)*(x3031)))+(((IkReal(-1.00000000000000))*(sj6)*(x3025)*(x3032)))+(((IkReal(-1.00000000000000))*(x3024)*(x3031)))+(((IkReal(-1.00000000000000))*(x3023)*(x3027)*(x3030)))+(((IkReal(-1.00000000000000))*(cj6)*(x3025)*(x3027)))+(((IkReal(-1.00000000000000))*(x3032)*(x3034)))+(((x3024)*(x3029)))+(((IkReal(-1.00000000000000))*(r20)*(x3030)*(x3032)))+(((r21)*(x3028)*(x3030)))+(((IkReal(-1.00000000000000))*(x3023)*(x3027)*(x3033)))+(((cj6)*(x3025)*(x3028)))+(((r21)*(x3028)*(x3033)))));
09443 IkReal x3035=(cj6)*(cj6);
09444 IkReal x3036=(sj6)*(sj6);
09445 IkReal x3037=((IkReal(1.00000000000000))*(r21));
09446 IkReal x3038=((cj6)*(r20));
09447 IkReal x3039=((r22)*(sj5));
09448 IkReal x3040=((r01)*(sj0));
09449 IkReal x3041=((r00)*(sj0));
09450 IkReal x3042=((cj0)*(r10));
09451 IkReal x3043=((r02)*(sj0)*(sj5));
09452 IkReal x3044=((cj5)*(x3035));
09453 IkReal x3045=((cj0)*(r12)*(sj5));
09454 IkReal x3046=((IkReal(1.00000000000000))*(cj0)*(r11));
09455 IkReal x3047=((cj5)*(x3036));
09456 IkReal x3048=((r20)*(x3047));
09457 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3046)*(x3048)))+(((IkReal(-1.00000000000000))*(x3037)*(x3041)*(x3047)))+(((r20)*(x3040)*(x3044)))+(((r21)*(x3042)*(x3044)))+(((x3040)*(x3048)))+(((cj6)*(x3039)*(x3042)))+(((IkReal(-1.00000000000000))*(sj6)*(x3039)*(x3046)))+(((r21)*(sj6)*(x3045)))+(((IkReal(-1.00000000000000))*(cj6)*(x3039)*(x3041)))+(((IkReal(-1.00000000000000))*(r20)*(x3044)*(x3046)))+(((r21)*(x3042)*(x3047)))+(((IkReal(-1.00000000000000))*(x3038)*(x3045)))+(((x3038)*(x3043)))+(((sj6)*(x3039)*(x3040)))+(((IkReal(-1.00000000000000))*(x3037)*(x3041)*(x3044)))+(((IkReal(-1.00000000000000))*(sj6)*(x3037)*(x3043))));
09458 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09459 {
09460 {
09461 IkReal dummyeval[1];
09462 IkReal gconst78;
09463 IkReal x3049=(cj6)*(cj6);
09464 IkReal x3050=(sj6)*(sj6);
09465 IkReal x3051=((sj5)*(sj6));
09466 IkReal x3052=((IkReal(1.00000000000000))*(cj0));
09467 IkReal x3053=((cj6)*(sj5));
09468 IkReal x3054=((r20)*(sj0));
09469 IkReal x3055=((cj0)*(r20));
09470 IkReal x3056=((r00)*(r21));
09471 IkReal x3057=((r22)*(sj0));
09472 IkReal x3058=((IkReal(1.00000000000000))*(r21)*(sj0));
09473 IkReal x3059=((cj5)*(x3050));
09474 IkReal x3060=((cj5)*(x3049));
09475 gconst78=IKsign(((((r12)*(x3053)*(x3054)))+(((r01)*(x3055)*(x3060)))+(((IkReal(-1.00000000000000))*(x3052)*(x3056)*(x3060)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3052)*(x3053)))+(((IkReal(-1.00000000000000))*(x3052)*(x3056)*(x3059)))+(((IkReal(-1.00000000000000))*(r12)*(x3051)*(x3058)))+(((IkReal(-1.00000000000000))*(r10)*(x3058)*(x3060)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3051)*(x3052)))+(((IkReal(-1.00000000000000))*(r10)*(x3053)*(x3057)))+(((r02)*(x3053)*(x3055)))+(((cj0)*(r01)*(r22)*(x3051)))+(((r11)*(x3054)*(x3059)))+(((IkReal(-1.00000000000000))*(r10)*(x3058)*(x3059)))+(((r11)*(x3051)*(x3057)))+(((r11)*(x3054)*(x3060)))+(((r01)*(x3055)*(x3059)))));
09476 IkReal x3061=(cj6)*(cj6);
09477 IkReal x3062=(sj6)*(sj6);
09478 IkReal x3063=((sj5)*(sj6));
09479 IkReal x3064=((IkReal(1.00000000000000))*(cj0));
09480 IkReal x3065=((cj6)*(sj5));
09481 IkReal x3066=((r20)*(sj0));
09482 IkReal x3067=((cj0)*(r20));
09483 IkReal x3068=((r00)*(r21));
09484 IkReal x3069=((r22)*(sj0));
09485 IkReal x3070=((IkReal(1.00000000000000))*(r21)*(sj0));
09486 IkReal x3071=((cj5)*(x3062));
09487 IkReal x3072=((cj5)*(x3061));
09488 dummyeval[0]=((((r12)*(x3065)*(x3066)))+(((IkReal(-1.00000000000000))*(r10)*(x3070)*(x3071)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3064)*(x3065)))+(((r01)*(x3067)*(x3072)))+(((IkReal(-1.00000000000000))*(r12)*(x3063)*(x3070)))+(((cj0)*(r01)*(r22)*(x3063)))+(((r11)*(x3063)*(x3069)))+(((IkReal(-1.00000000000000))*(r10)*(x3070)*(x3072)))+(((r02)*(x3065)*(x3067)))+(((r01)*(x3067)*(x3071)))+(((r11)*(x3066)*(x3072)))+(((r11)*(x3066)*(x3071)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3063)*(x3064)))+(((IkReal(-1.00000000000000))*(x3064)*(x3068)*(x3071)))+(((IkReal(-1.00000000000000))*(x3064)*(x3068)*(x3072)))+(((IkReal(-1.00000000000000))*(r10)*(x3065)*(x3069))));
09489 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09490 {
09491 {
09492 IkReal dummyeval[1];
09493 dummyeval[0]=sj2;
09494 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09495 {
09496 {
09497 IkReal evalcond[5];
09498 IkReal x3073=((sj0)*(sj5));
09499 IkReal x3074=((r00)*(sj6));
09500 IkReal x3075=((cj6)*(r01));
09501 IkReal x3076=((cj0)*(cj5));
09502 IkReal x3077=((cj0)*(sj5));
09503 IkReal x3078=((r10)*(sj6));
09504 IkReal x3079=((cj6)*(r11));
09505 IkReal x3080=((IkReal(0.374290000000000))*(sj5));
09506 IkReal x3081=((IkReal(0.0100000000000000))*(r02));
09507 IkReal x3082=((IkReal(1.00000000000000))*(py));
09508 IkReal x3083=((cj5)*(sj0));
09509 IkReal x3084=((IkReal(0.374290000000000))*(r12));
09510 IkReal x3085=((r20)*(sj6));
09511 IkReal x3086=((IkReal(0.0100000000000000))*(r12));
09512 IkReal x3087=((IkReal(0.0100000000000000))*(cj5)*(cj6));
09513 IkReal x3088=((r02)*(x3083));
09514 IkReal x3089=((IkReal(0.374290000000000))*(cj6)*(x3077));
09515 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
09516 evalcond[1]=((IkReal(-0.364420000000000))+(((IkReal(-0.0100000000000000))*(cj5)*(x3085)))+(((cj6)*(r21)*(x3080)))+(((IkReal(-0.0100000000000000))*(r22)*(sj5)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x3080)*(x3085)))+(pz)+(((IkReal(-1.00000000000000))*(r21)*(x3087))));
09517 evalcond[2]=((((IkReal(-1.00000000000000))*(x3077)*(x3078)))+(((IkReal(-1.00000000000000))*(x3077)*(x3079)))+(((x3073)*(x3075)))+(((x3073)*(x3074)))+(((r12)*(x3076)))+(((IkReal(-1.00000000000000))*(x3088))));
09518 evalcond[3]=((((x3076)*(x3084)))+(((IkReal(-1.00000000000000))*(cj0)*(x3082)))+(((IkReal(-0.374290000000000))*(x3077)*(x3078)))+(((IkReal(0.0100000000000000))*(x3076)*(x3079)))+(((IkReal(0.374290000000000))*(x3073)*(x3075)))+(((IkReal(-1.00000000000000))*(x3073)*(x3081)))+(((IkReal(-0.0100000000000000))*(x3075)*(x3083)))+(((IkReal(-0.0100000000000000))*(x3074)*(x3083)))+(((IkReal(-0.374290000000000))*(x3077)*(x3079)))+(((x3077)*(x3086)))+(((px)*(sj0)))+(((IkReal(-0.374290000000000))*(x3088)))+(((IkReal(0.0100000000000000))*(x3076)*(x3078)))+(((IkReal(0.374290000000000))*(x3073)*(x3074))));
09519 evalcond[4]=((IkReal(0.138000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x3073)*(x3086)))+(((IkReal(0.0100000000000000))*(x3075)*(x3076)))+(((x3083)*(x3084)))+(((IkReal(-0.374290000000000))*(x3074)*(x3077)))+(((IkReal(-1.00000000000000))*(sj0)*(x3082)))+(((IkReal(0.0100000000000000))*(x3079)*(x3083)))+(((IkReal(0.374290000000000))*(r02)*(x3076)))+(((x3077)*(x3081)))+(((IkReal(-0.374290000000000))*(x3073)*(x3078)))+(((IkReal(0.0100000000000000))*(x3074)*(x3076)))+(((IkReal(0.0100000000000000))*(x3078)*(x3083)))+(((IkReal(-0.374290000000000))*(x3073)*(x3079)))+(((IkReal(-0.374290000000000))*(x3075)*(x3077))));
09520 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
09521 {
09522 {
09523 IkReal j3array[1], cj3array[1], sj3array[1];
09524 bool j3valid[1]={false};
09525 _nj3 = 1;
09526 IkReal x3090=((IkReal(1.00000000000000))*(cj6)*(sj5));
09527 IkReal x3091=((IkReal(1.00000000000000))*(sj5)*(sj6));
09528 if( IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x3090)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3091)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3091)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x3090))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r20)*(x3091)))+(((IkReal(-1.00000000000000))*(r21)*(x3090)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x3090)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3091)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3091)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x3090)))))+IKsqr(((((IkReal(-1.00000000000000))*(r20)*(x3091)))+(((IkReal(-1.00000000000000))*(r21)*(x3090)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
09529     continue;
09530 j3array[0]=IKatan2(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x3090)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3091)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3091)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x3090)))), ((((IkReal(-1.00000000000000))*(r20)*(x3091)))+(((IkReal(-1.00000000000000))*(r21)*(x3090)))+(((cj5)*(r22)))));
09531 sj3array[0]=IKsin(j3array[0]);
09532 cj3array[0]=IKcos(j3array[0]);
09533 if( j3array[0] > IKPI )
09534 {
09535     j3array[0]-=IK2PI;
09536 }
09537 else if( j3array[0] < -IKPI )
09538 {    j3array[0]+=IK2PI;
09539 }
09540 j3valid[0] = true;
09541 for(int ij3 = 0; ij3 < 1; ++ij3)
09542 {
09543 if( !j3valid[ij3] )
09544 {
09545     continue;
09546 }
09547 _ij3[0] = ij3; _ij3[1] = -1;
09548 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
09549 {
09550 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
09551 {
09552     j3valid[iij3]=false; _ij3[1] = iij3; break; 
09553 }
09554 }
09555 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
09556 {
09557 IkReal evalcond[2];
09558 IkReal x3092=((sj5)*(sj6));
09559 IkReal x3093=((IkReal(1.00000000000000))*(cj6)*(sj5));
09560 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(IKcos(j3))+(((r20)*(x3092))));
09561 evalcond[1]=((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x3093)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3092)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3092)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x3093)))+(((IkReal(-1.00000000000000))*(IKsin(j3)))));
09562 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09563 {
09564 continue;
09565 }
09566 }
09567 
09568 {
09569 IkReal dummyeval[1];
09570 IkReal gconst83;
09571 IkReal x3094=(cj5)*(cj5);
09572 IkReal x3095=(r20)*(r20);
09573 IkReal x3096=(sj6)*(sj6);
09574 IkReal x3097=(cj6)*(cj6);
09575 IkReal x3098=(r21)*(r21);
09576 IkReal x3099=((cj6)*(r21));
09577 IkReal x3100=((IkReal(2.00000000000000))*(r20)*(sj6));
09578 IkReal x3101=((cj5)*(r22)*(sj5));
09579 gconst83=IKsign(((((x3100)*(x3101)))+(((x3094)*(x3095)*(x3096)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3096)*(x3098)))+(((x3094)*(x3097)*(x3098)))+(((x3095)*(x3097)))+(((IkReal(2.00000000000000))*(x3099)*(x3101)))+(((x3094)*(x3099)*(x3100)))+(((IkReal(-1.00000000000000))*(x3099)*(x3100)))));
09580 IkReal x3102=(cj5)*(cj5);
09581 IkReal x3103=(r20)*(r20);
09582 IkReal x3104=(sj6)*(sj6);
09583 IkReal x3105=(cj6)*(cj6);
09584 IkReal x3106=(r21)*(r21);
09585 IkReal x3107=((cj6)*(r21));
09586 IkReal x3108=((IkReal(2.00000000000000))*(r20)*(sj6));
09587 IkReal x3109=((cj5)*(r22)*(sj5));
09588 dummyeval[0]=((((x3104)*(x3106)))+(((x3103)*(x3105)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3102)*(x3105)*(x3106)))+(((x3102)*(x3103)*(x3104)))+(((x3102)*(x3107)*(x3108)))+(((IkReal(2.00000000000000))*(x3107)*(x3109)))+(((x3108)*(x3109)))+(((IkReal(-1.00000000000000))*(x3107)*(x3108))));
09589 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09590 {
09591 {
09592 IkReal dummyeval[1];
09593 IkReal gconst84;
09594 IkReal x3110=(cj6)*(cj6);
09595 IkReal x3111=(sj6)*(sj6);
09596 IkReal x3112=((IkReal(1.00000000000000))*(r21));
09597 IkReal x3113=((cj6)*(r20));
09598 IkReal x3114=((r22)*(sj5));
09599 IkReal x3115=((r01)*(sj0));
09600 IkReal x3116=((r00)*(sj0));
09601 IkReal x3117=((cj0)*(r10));
09602 IkReal x3118=((r02)*(sj0)*(sj5));
09603 IkReal x3119=((cj5)*(x3110));
09604 IkReal x3120=((cj0)*(r12)*(sj5));
09605 IkReal x3121=((IkReal(1.00000000000000))*(cj0)*(r11));
09606 IkReal x3122=((cj5)*(x3111));
09607 IkReal x3123=((r20)*(x3122));
09608 gconst84=IKsign(((((IkReal(-1.00000000000000))*(x3112)*(x3116)*(x3122)))+(((IkReal(-1.00000000000000))*(x3112)*(x3116)*(x3119)))+(((IkReal(-1.00000000000000))*(x3113)*(x3120)))+(((r21)*(sj6)*(x3120)))+(((r20)*(x3115)*(x3119)))+(((IkReal(-1.00000000000000))*(x3121)*(x3123)))+(((IkReal(-1.00000000000000))*(cj6)*(x3114)*(x3116)))+(((IkReal(-1.00000000000000))*(sj6)*(x3114)*(x3121)))+(((x3115)*(x3123)))+(((IkReal(-1.00000000000000))*(sj6)*(x3112)*(x3118)))+(((x3113)*(x3118)))+(((sj6)*(x3114)*(x3115)))+(((IkReal(-1.00000000000000))*(r20)*(x3119)*(x3121)))+(((r21)*(x3117)*(x3119)))+(((cj6)*(x3114)*(x3117)))+(((r21)*(x3117)*(x3122)))));
09609 IkReal x3124=(cj6)*(cj6);
09610 IkReal x3125=(sj6)*(sj6);
09611 IkReal x3126=((IkReal(1.00000000000000))*(r21));
09612 IkReal x3127=((cj6)*(r20));
09613 IkReal x3128=((r22)*(sj5));
09614 IkReal x3129=((r01)*(sj0));
09615 IkReal x3130=((r00)*(sj0));
09616 IkReal x3131=((cj0)*(r10));
09617 IkReal x3132=((r02)*(sj0)*(sj5));
09618 IkReal x3133=((cj5)*(x3124));
09619 IkReal x3134=((cj0)*(r12)*(sj5));
09620 IkReal x3135=((IkReal(1.00000000000000))*(cj0)*(r11));
09621 IkReal x3136=((cj5)*(x3125));
09622 IkReal x3137=((r20)*(x3136));
09623 dummyeval[0]=((((cj6)*(x3128)*(x3131)))+(((sj6)*(x3128)*(x3129)))+(((IkReal(-1.00000000000000))*(x3135)*(x3137)))+(((r21)*(x3131)*(x3136)))+(((IkReal(-1.00000000000000))*(x3127)*(x3134)))+(((r21)*(sj6)*(x3134)))+(((r21)*(x3131)*(x3133)))+(((r20)*(x3129)*(x3133)))+(((IkReal(-1.00000000000000))*(r20)*(x3133)*(x3135)))+(((IkReal(-1.00000000000000))*(cj6)*(x3128)*(x3130)))+(((IkReal(-1.00000000000000))*(x3126)*(x3130)*(x3133)))+(((IkReal(-1.00000000000000))*(sj6)*(x3128)*(x3135)))+(((x3129)*(x3137)))+(((IkReal(-1.00000000000000))*(sj6)*(x3126)*(x3132)))+(((IkReal(-1.00000000000000))*(x3126)*(x3130)*(x3136)))+(((x3127)*(x3132))));
09624 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09625 {
09626 continue;
09627 
09628 } else
09629 {
09630 {
09631 IkReal j4array[1], cj4array[1], sj4array[1];
09632 bool j4valid[1]={false};
09633 _nj4 = 1;
09634 IkReal x3138=((IkReal(1.00000000000000))*(cj5));
09635 if( IKabs(((gconst84)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst84)*(((((IkReal(-1.00000000000000))*(cj6)*(r21)*(x3138)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x3138)))+(((IkReal(-1.00000000000000))*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
09636     continue;
09637 j4array[0]=IKatan2(((gconst84)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))), ((gconst84)*(((((IkReal(-1.00000000000000))*(cj6)*(r21)*(x3138)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x3138)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)))))));
09638 sj4array[0]=IKsin(j4array[0]);
09639 cj4array[0]=IKcos(j4array[0]);
09640 if( j4array[0] > IKPI )
09641 {
09642     j4array[0]-=IK2PI;
09643 }
09644 else if( j4array[0] < -IKPI )
09645 {    j4array[0]+=IK2PI;
09646 }
09647 j4valid[0] = true;
09648 for(int ij4 = 0; ij4 < 1; ++ij4)
09649 {
09650 if( !j4valid[ij4] )
09651 {
09652     continue;
09653 }
09654 _ij4[0] = ij4; _ij4[1] = -1;
09655 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
09656 {
09657 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
09658 {
09659     j4valid[iij4]=false; _ij4[1] = iij4; break; 
09660 }
09661 }
09662 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
09663 {
09664 IkReal evalcond[6];
09665 IkReal x3139=IKsin(j4);
09666 IkReal x3140=IKcos(j4);
09667 IkReal x3141=((r22)*(sj5));
09668 IkReal x3142=((IkReal(1.00000000000000))*(cj6));
09669 IkReal x3143=((IkReal(1.00000000000000))*(cj0));
09670 IkReal x3144=((cj5)*(r11));
09671 IkReal x3145=((cj5)*(cj6));
09672 IkReal x3146=((r11)*(sj6));
09673 IkReal x3147=((IkReal(1.00000000000000))*(sj6));
09674 IkReal x3148=((cj6)*(r00));
09675 IkReal x3149=((r12)*(sj5));
09676 IkReal x3150=((r02)*(sj5));
09677 IkReal x3151=((cj6)*(r10));
09678 IkReal x3152=((cj5)*(sj6));
09679 IkReal x3153=((cj5)*(r01));
09680 IkReal x3154=((sj0)*(x3139));
09681 IkReal x3155=((r00)*(x3152));
09682 IkReal x3156=((cj0)*(x3139));
09683 IkReal x3157=((sj0)*(x3140));
09684 IkReal x3158=((r20)*(x3140));
09685 IkReal x3159=((cj0)*(x3140));
09686 IkReal x3160=((r21)*(x3139));
09687 IkReal x3161=((r21)*(x3140));
09688 IkReal x3162=((r20)*(x3139));
09689 IkReal x3163=((x3140)*(x3149));
09690 IkReal x3164=((r01)*(sj6)*(x3140));
09691 IkReal x3165=((cj5)*(r10)*(x3147));
09692 evalcond[0]=((((x3139)*(x3141)))+(((IkReal(-1.00000000000000))*(x3142)*(x3158)))+(((sj6)*(x3161)))+(((x3152)*(x3162)))+(((x3145)*(x3160))));
09693 evalcond[1]=((((x3152)*(x3158)))+(sj3)+(((cj6)*(x3162)))+(((IkReal(-1.00000000000000))*(x3147)*(x3160)))+(((x3145)*(x3161)))+(((x3140)*(x3141))));
09694 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x3139)*(x3143)*(x3149)))+(((IkReal(-1.00000000000000))*(r00)*(x3142)*(x3157)))+(((r01)*(sj6)*(x3157)))+(((x3150)*(x3154)))+(((IkReal(-1.00000000000000))*(r10)*(x3139)*(x3143)*(x3152)))+(((IkReal(-1.00000000000000))*(x3140)*(x3143)*(x3146)))+(((IkReal(-1.00000000000000))*(x3142)*(x3144)*(x3156)))+(((r01)*(x3145)*(x3154)))+(((x3151)*(x3159)))+(((x3154)*(x3155))));
09695 evalcond[3]=((((r01)*(x3145)*(x3157)))+(((x3155)*(x3157)))+(((x3146)*(x3156)))+(((IkReal(-1.00000000000000))*(x3142)*(x3144)*(x3159)))+(((IkReal(-1.00000000000000))*(x3143)*(x3163)))+(((IkReal(-1.00000000000000))*(r10)*(x3142)*(x3156)))+(((IkReal(-1.00000000000000))*(r01)*(x3147)*(x3154)))+(((x3148)*(x3154)))+(((IkReal(-1.00000000000000))*(r10)*(x3140)*(x3143)*(x3152)))+(((x3150)*(x3157))));
09696 evalcond[4]=((((IkReal(-1.00000000000000))*(x3154)*(x3165)))+(((IkReal(-1.00000000000000))*(x3142)*(x3153)*(x3156)))+(((IkReal(-1.00000000000000))*(x3146)*(x3157)))+(((IkReal(-1.00000000000000))*(x3143)*(x3164)))+(((IkReal(-1.00000000000000))*(x3142)*(x3144)*(x3154)))+(((IkReal(-1.00000000000000))*(x3149)*(x3154)))+(((x3151)*(x3157)))+(((IkReal(-1.00000000000000))*(x3139)*(x3143)*(x3155)))+(((IkReal(-1.00000000000000))*(x3139)*(x3143)*(x3150)))+(((x3148)*(x3159))));
09697 evalcond[5]=((((IkReal(-1.00000000000000))*(x3142)*(x3153)*(x3159)))+(((IkReal(-1.00000000000000))*(r00)*(x3142)*(x3156)))+(((x3146)*(x3154)))+(((IkReal(-1.00000000000000))*(x3140)*(x3143)*(x3150)))+(cj3)+(((IkReal(-1.00000000000000))*(x3149)*(x3157)))+(((IkReal(-1.00000000000000))*(r10)*(x3142)*(x3154)))+(((IkReal(-1.00000000000000))*(x3157)*(x3165)))+(((IkReal(-1.00000000000000))*(x3142)*(x3144)*(x3157)))+(((r01)*(sj6)*(x3156)))+(((IkReal(-1.00000000000000))*(x3140)*(x3143)*(x3155))));
09698 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
09699 {
09700 continue;
09701 }
09702 }
09703 
09704 {
09705 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
09706 vinfos[0].jointtype = 1;
09707 vinfos[0].foffset = j0;
09708 vinfos[0].indices[0] = _ij0[0];
09709 vinfos[0].indices[1] = _ij0[1];
09710 vinfos[0].maxsolutions = _nj0;
09711 vinfos[1].jointtype = 1;
09712 vinfos[1].foffset = j1;
09713 vinfos[1].indices[0] = _ij1[0];
09714 vinfos[1].indices[1] = _ij1[1];
09715 vinfos[1].maxsolutions = _nj1;
09716 vinfos[2].jointtype = 1;
09717 vinfos[2].foffset = j2;
09718 vinfos[2].indices[0] = _ij2[0];
09719 vinfos[2].indices[1] = _ij2[1];
09720 vinfos[2].maxsolutions = _nj2;
09721 vinfos[3].jointtype = 1;
09722 vinfos[3].foffset = j3;
09723 vinfos[3].indices[0] = _ij3[0];
09724 vinfos[3].indices[1] = _ij3[1];
09725 vinfos[3].maxsolutions = _nj3;
09726 vinfos[4].jointtype = 1;
09727 vinfos[4].foffset = j4;
09728 vinfos[4].indices[0] = _ij4[0];
09729 vinfos[4].indices[1] = _ij4[1];
09730 vinfos[4].maxsolutions = _nj4;
09731 vinfos[5].jointtype = 1;
09732 vinfos[5].foffset = j5;
09733 vinfos[5].indices[0] = _ij5[0];
09734 vinfos[5].indices[1] = _ij5[1];
09735 vinfos[5].maxsolutions = _nj5;
09736 vinfos[6].jointtype = 1;
09737 vinfos[6].foffset = j6;
09738 vinfos[6].indices[0] = _ij6[0];
09739 vinfos[6].indices[1] = _ij6[1];
09740 vinfos[6].maxsolutions = _nj6;
09741 std::vector<int> vfree(0);
09742 solutions.AddSolution(vinfos,vfree);
09743 }
09744 }
09745 }
09746 
09747 }
09748 
09749 }
09750 
09751 } else
09752 {
09753 {
09754 IkReal j4array[1], cj4array[1], sj4array[1];
09755 bool j4valid[1]={false};
09756 _nj4 = 1;
09757 IkReal x3166=((r21)*(sj3));
09758 IkReal x3167=((IkReal(1.00000000000000))*(r20)*(sj3));
09759 if( IKabs(((gconst83)*(((((IkReal(-1.00000000000000))*(cj6)*(x3167)))+(((sj6)*(x3166))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst83)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3166)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3167)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
09760     continue;
09761 j4array[0]=IKatan2(((gconst83)*(((((IkReal(-1.00000000000000))*(cj6)*(x3167)))+(((sj6)*(x3166)))))), ((gconst83)*(((((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3166)))+(((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3167)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
09762 sj4array[0]=IKsin(j4array[0]);
09763 cj4array[0]=IKcos(j4array[0]);
09764 if( j4array[0] > IKPI )
09765 {
09766     j4array[0]-=IK2PI;
09767 }
09768 else if( j4array[0] < -IKPI )
09769 {    j4array[0]+=IK2PI;
09770 }
09771 j4valid[0] = true;
09772 for(int ij4 = 0; ij4 < 1; ++ij4)
09773 {
09774 if( !j4valid[ij4] )
09775 {
09776     continue;
09777 }
09778 _ij4[0] = ij4; _ij4[1] = -1;
09779 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
09780 {
09781 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
09782 {
09783     j4valid[iij4]=false; _ij4[1] = iij4; break; 
09784 }
09785 }
09786 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
09787 {
09788 IkReal evalcond[6];
09789 IkReal x3168=IKsin(j4);
09790 IkReal x3169=IKcos(j4);
09791 IkReal x3170=((r22)*(sj5));
09792 IkReal x3171=((IkReal(1.00000000000000))*(cj6));
09793 IkReal x3172=((IkReal(1.00000000000000))*(cj0));
09794 IkReal x3173=((cj5)*(r11));
09795 IkReal x3174=((cj5)*(cj6));
09796 IkReal x3175=((r11)*(sj6));
09797 IkReal x3176=((IkReal(1.00000000000000))*(sj6));
09798 IkReal x3177=((cj6)*(r00));
09799 IkReal x3178=((r12)*(sj5));
09800 IkReal x3179=((r02)*(sj5));
09801 IkReal x3180=((cj6)*(r10));
09802 IkReal x3181=((cj5)*(sj6));
09803 IkReal x3182=((cj5)*(r01));
09804 IkReal x3183=((sj0)*(x3168));
09805 IkReal x3184=((r00)*(x3181));
09806 IkReal x3185=((cj0)*(x3168));
09807 IkReal x3186=((sj0)*(x3169));
09808 IkReal x3187=((r20)*(x3169));
09809 IkReal x3188=((cj0)*(x3169));
09810 IkReal x3189=((r21)*(x3168));
09811 IkReal x3190=((r21)*(x3169));
09812 IkReal x3191=((r20)*(x3168));
09813 IkReal x3192=((x3169)*(x3178));
09814 IkReal x3193=((r01)*(sj6)*(x3169));
09815 IkReal x3194=((cj5)*(r10)*(x3176));
09816 evalcond[0]=((((sj6)*(x3190)))+(((x3181)*(x3191)))+(((x3168)*(x3170)))+(((IkReal(-1.00000000000000))*(x3171)*(x3187)))+(((x3174)*(x3189))));
09817 evalcond[1]=((((x3169)*(x3170)))+(sj3)+(((cj6)*(x3191)))+(((x3174)*(x3190)))+(((x3181)*(x3187)))+(((IkReal(-1.00000000000000))*(x3176)*(x3189))));
09818 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3168)*(x3172)*(x3181)))+(((x3180)*(x3188)))+(((IkReal(-1.00000000000000))*(r00)*(x3171)*(x3186)))+(((x3183)*(x3184)))+(((r01)*(x3174)*(x3183)))+(((r01)*(sj6)*(x3186)))+(((IkReal(-1.00000000000000))*(x3168)*(x3172)*(x3178)))+(((IkReal(-1.00000000000000))*(x3169)*(x3172)*(x3175)))+(((x3179)*(x3183)))+(((IkReal(-1.00000000000000))*(x3171)*(x3173)*(x3185))));
09819 evalcond[3]=((((IkReal(-1.00000000000000))*(x3171)*(x3173)*(x3188)))+(((x3175)*(x3185)))+(((IkReal(-1.00000000000000))*(r10)*(x3169)*(x3172)*(x3181)))+(((x3184)*(x3186)))+(((x3179)*(x3186)))+(((IkReal(-1.00000000000000))*(x3172)*(x3192)))+(((IkReal(-1.00000000000000))*(r01)*(x3176)*(x3183)))+(((IkReal(-1.00000000000000))*(r10)*(x3171)*(x3185)))+(((x3177)*(x3183)))+(((r01)*(x3174)*(x3186))));
09820 evalcond[4]=((((IkReal(-1.00000000000000))*(x3171)*(x3173)*(x3183)))+(((x3180)*(x3186)))+(((x3177)*(x3188)))+(((IkReal(-1.00000000000000))*(x3168)*(x3172)*(x3184)))+(((IkReal(-1.00000000000000))*(x3172)*(x3193)))+(((IkReal(-1.00000000000000))*(x3168)*(x3172)*(x3179)))+(((IkReal(-1.00000000000000))*(x3183)*(x3194)))+(((IkReal(-1.00000000000000))*(x3175)*(x3186)))+(((IkReal(-1.00000000000000))*(x3178)*(x3183)))+(((IkReal(-1.00000000000000))*(x3171)*(x3182)*(x3185))));
09821 evalcond[5]=((((r01)*(sj6)*(x3185)))+(((IkReal(-1.00000000000000))*(x3178)*(x3186)))+(((IkReal(-1.00000000000000))*(x3169)*(x3172)*(x3184)))+(((IkReal(-1.00000000000000))*(x3186)*(x3194)))+(((IkReal(-1.00000000000000))*(x3171)*(x3173)*(x3186)))+(cj3)+(((IkReal(-1.00000000000000))*(x3171)*(x3182)*(x3188)))+(((x3175)*(x3183)))+(((IkReal(-1.00000000000000))*(x3169)*(x3172)*(x3179)))+(((IkReal(-1.00000000000000))*(r00)*(x3171)*(x3185)))+(((IkReal(-1.00000000000000))*(r10)*(x3171)*(x3183))));
09822 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
09823 {
09824 continue;
09825 }
09826 }
09827 
09828 {
09829 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
09830 vinfos[0].jointtype = 1;
09831 vinfos[0].foffset = j0;
09832 vinfos[0].indices[0] = _ij0[0];
09833 vinfos[0].indices[1] = _ij0[1];
09834 vinfos[0].maxsolutions = _nj0;
09835 vinfos[1].jointtype = 1;
09836 vinfos[1].foffset = j1;
09837 vinfos[1].indices[0] = _ij1[0];
09838 vinfos[1].indices[1] = _ij1[1];
09839 vinfos[1].maxsolutions = _nj1;
09840 vinfos[2].jointtype = 1;
09841 vinfos[2].foffset = j2;
09842 vinfos[2].indices[0] = _ij2[0];
09843 vinfos[2].indices[1] = _ij2[1];
09844 vinfos[2].maxsolutions = _nj2;
09845 vinfos[3].jointtype = 1;
09846 vinfos[3].foffset = j3;
09847 vinfos[3].indices[0] = _ij3[0];
09848 vinfos[3].indices[1] = _ij3[1];
09849 vinfos[3].maxsolutions = _nj3;
09850 vinfos[4].jointtype = 1;
09851 vinfos[4].foffset = j4;
09852 vinfos[4].indices[0] = _ij4[0];
09853 vinfos[4].indices[1] = _ij4[1];
09854 vinfos[4].maxsolutions = _nj4;
09855 vinfos[5].jointtype = 1;
09856 vinfos[5].foffset = j5;
09857 vinfos[5].indices[0] = _ij5[0];
09858 vinfos[5].indices[1] = _ij5[1];
09859 vinfos[5].maxsolutions = _nj5;
09860 vinfos[6].jointtype = 1;
09861 vinfos[6].foffset = j6;
09862 vinfos[6].indices[0] = _ij6[0];
09863 vinfos[6].indices[1] = _ij6[1];
09864 vinfos[6].maxsolutions = _nj6;
09865 std::vector<int> vfree(0);
09866 solutions.AddSolution(vinfos,vfree);
09867 }
09868 }
09869 }
09870 
09871 }
09872 
09873 }
09874 }
09875 }
09876 
09877 } else
09878 {
09879 IkReal x3195=((sj0)*(sj5));
09880 IkReal x3196=((r00)*(sj6));
09881 IkReal x3197=((cj6)*(r01));
09882 IkReal x3198=((cj0)*(cj5));
09883 IkReal x3199=((cj0)*(sj5));
09884 IkReal x3200=((r10)*(sj6));
09885 IkReal x3201=((cj6)*(r11));
09886 IkReal x3202=((IkReal(0.374290000000000))*(sj5));
09887 IkReal x3203=((IkReal(0.0100000000000000))*(r02));
09888 IkReal x3204=((IkReal(1.00000000000000))*(py));
09889 IkReal x3205=((cj5)*(sj0));
09890 IkReal x3206=((IkReal(0.374290000000000))*(r12));
09891 IkReal x3207=((r20)*(sj6));
09892 IkReal x3208=((IkReal(0.0100000000000000))*(r12));
09893 IkReal x3209=((IkReal(0.0100000000000000))*(cj5)*(cj6));
09894 IkReal x3210=((r02)*(x3205));
09895 IkReal x3211=((IkReal(0.374290000000000))*(cj6)*(x3199));
09896 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
09897 evalcond[1]=((IkReal(-0.364420000000000))+(((IkReal(-0.0100000000000000))*(cj5)*(x3207)))+(((IkReal(-0.0100000000000000))*(r22)*(sj5)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r21)*(x3209)))+(pz)+(((x3202)*(x3207)))+(((cj6)*(r21)*(x3202))));
09898 evalcond[2]=((((r12)*(x3198)))+(((IkReal(-1.00000000000000))*(x3210)))+(((IkReal(-1.00000000000000))*(x3199)*(x3201)))+(((IkReal(-1.00000000000000))*(x3199)*(x3200)))+(((x3195)*(x3197)))+(((x3195)*(x3196))));
09899 evalcond[3]=((((IkReal(0.374290000000000))*(x3195)*(x3196)))+(((IkReal(-0.374290000000000))*(x3199)*(x3200)))+(((IkReal(0.374290000000000))*(x3195)*(x3197)))+(((IkReal(0.0100000000000000))*(x3198)*(x3200)))+(((IkReal(-1.00000000000000))*(cj0)*(x3204)))+(((IkReal(-1.00000000000000))*(x3195)*(x3203)))+(((x3198)*(x3206)))+(((x3199)*(x3208)))+(((IkReal(0.0100000000000000))*(x3198)*(x3201)))+(((IkReal(-0.374290000000000))*(x3199)*(x3201)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(x3197)*(x3205)))+(((IkReal(-0.374290000000000))*(x3210)))+(((IkReal(-0.0100000000000000))*(x3196)*(x3205))));
09900 evalcond[4]=((((IkReal(0.0100000000000000))*(x3197)*(x3198)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-0.374290000000000))*(x3196)*(x3199)))+(((x3195)*(x3208)))+(((IkReal(0.374290000000000))*(r02)*(x3198)))+(((IkReal(-0.374290000000000))*(x3197)*(x3199)))+(((IkReal(-0.374290000000000))*(x3195)*(x3200)))+(((x3199)*(x3203)))+(((IkReal(-1.00000000000000))*(sj0)*(x3204)))+(((x3205)*(x3206)))+(((IkReal(0.0100000000000000))*(x3200)*(x3205)))+(((IkReal(-0.374290000000000))*(x3195)*(x3201)))+(((IkReal(0.0100000000000000))*(x3201)*(x3205)))+(((IkReal(0.0100000000000000))*(x3196)*(x3198))));
09901 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
09902 {
09903 {
09904 IkReal j3array[1], cj3array[1], sj3array[1];
09905 bool j3valid[1]={false};
09906 _nj3 = 1;
09907 IkReal x3212=((IkReal(1.00000000000000))*(cj5));
09908 IkReal x3213=((cj6)*(sj5));
09909 IkReal x3214=((sj5)*(sj6));
09910 if( IKabs(((((r10)*(sj0)*(x3214)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3212)))+(((r11)*(sj0)*(x3213)))+(((cj0)*(r00)*(x3214)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3212)))+(((cj0)*(r01)*(x3213))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r21)*(x3213)))+(((IkReal(-1.00000000000000))*(r20)*(x3214)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r10)*(sj0)*(x3214)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3212)))+(((r11)*(sj0)*(x3213)))+(((cj0)*(r00)*(x3214)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3212)))+(((cj0)*(r01)*(x3213)))))+IKsqr(((((IkReal(-1.00000000000000))*(r21)*(x3213)))+(((IkReal(-1.00000000000000))*(r20)*(x3214)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
09911     continue;
09912 j3array[0]=IKatan2(((((r10)*(sj0)*(x3214)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3212)))+(((r11)*(sj0)*(x3213)))+(((cj0)*(r00)*(x3214)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3212)))+(((cj0)*(r01)*(x3213)))), ((((IkReal(-1.00000000000000))*(r21)*(x3213)))+(((IkReal(-1.00000000000000))*(r20)*(x3214)))+(((cj5)*(r22)))));
09913 sj3array[0]=IKsin(j3array[0]);
09914 cj3array[0]=IKcos(j3array[0]);
09915 if( j3array[0] > IKPI )
09916 {
09917     j3array[0]-=IK2PI;
09918 }
09919 else if( j3array[0] < -IKPI )
09920 {    j3array[0]+=IK2PI;
09921 }
09922 j3valid[0] = true;
09923 for(int ij3 = 0; ij3 < 1; ++ij3)
09924 {
09925 if( !j3valid[ij3] )
09926 {
09927     continue;
09928 }
09929 _ij3[0] = ij3; _ij3[1] = -1;
09930 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
09931 {
09932 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
09933 {
09934     j3valid[iij3]=false; _ij3[1] = iij3; break; 
09935 }
09936 }
09937 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
09938 {
09939 IkReal evalcond[2];
09940 IkReal x3215=((sj5)*(sj6));
09941 IkReal x3216=((IkReal(1.00000000000000))*(cj6)*(sj5));
09942 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((r20)*(x3215)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(IKcos(j3)));
09943 evalcond[1]=((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3215)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x3216)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3215)))+(IKsin(j3))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x3216))));
09944 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09945 {
09946 continue;
09947 }
09948 }
09949 
09950 {
09951 IkReal dummyeval[1];
09952 IkReal gconst87;
09953 IkReal x3217=(cj5)*(cj5);
09954 IkReal x3218=(r20)*(r20);
09955 IkReal x3219=(sj6)*(sj6);
09956 IkReal x3220=(cj6)*(cj6);
09957 IkReal x3221=(r21)*(r21);
09958 IkReal x3222=((cj6)*(r21));
09959 IkReal x3223=((IkReal(2.00000000000000))*(r20)*(sj6));
09960 IkReal x3224=((cj5)*(r22)*(sj5));
09961 gconst87=IKsign(((((IkReal(-1.00000000000000))*(x3222)*(x3223)))+(((x3217)*(x3218)*(x3219)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3219)*(x3221)))+(((x3218)*(x3220)))+(((x3217)*(x3222)*(x3223)))+(((x3223)*(x3224)))+(((x3217)*(x3220)*(x3221)))+(((IkReal(2.00000000000000))*(x3222)*(x3224)))));
09962 IkReal x3225=(cj5)*(cj5);
09963 IkReal x3226=(r20)*(r20);
09964 IkReal x3227=(sj6)*(sj6);
09965 IkReal x3228=(cj6)*(cj6);
09966 IkReal x3229=(r21)*(r21);
09967 IkReal x3230=((cj6)*(r21));
09968 IkReal x3231=((IkReal(2.00000000000000))*(r20)*(sj6));
09969 IkReal x3232=((cj5)*(r22)*(sj5));
09970 dummyeval[0]=((((x3227)*(x3229)))+(((x3231)*(x3232)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3225)*(x3228)*(x3229)))+(((IkReal(-1.00000000000000))*(x3230)*(x3231)))+(((x3226)*(x3228)))+(((x3225)*(x3230)*(x3231)))+(((x3225)*(x3226)*(x3227)))+(((IkReal(2.00000000000000))*(x3230)*(x3232))));
09971 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09972 {
09973 {
09974 IkReal dummyeval[1];
09975 IkReal gconst88;
09976 IkReal x3233=(cj6)*(cj6);
09977 IkReal x3234=(sj6)*(sj6);
09978 IkReal x3235=((IkReal(1.00000000000000))*(r01));
09979 IkReal x3236=((sj0)*(sj5));
09980 IkReal x3237=((cj6)*(r22));
09981 IkReal x3238=((r21)*(sj6));
09982 IkReal x3239=((r00)*(r21));
09983 IkReal x3240=((cj0)*(sj5));
09984 IkReal x3241=((cj6)*(r20));
09985 IkReal x3242=((r22)*(sj6));
09986 IkReal x3243=((cj0)*(cj5));
09987 IkReal x3244=((IkReal(1.00000000000000))*(r10));
09988 IkReal x3245=((cj5)*(sj0));
09989 IkReal x3246=((r20)*(x3234));
09990 IkReal x3247=((x3233)*(x3245));
09991 gconst88=IKsign(((((IkReal(-1.00000000000000))*(r21)*(x3234)*(x3243)*(x3244)))+(((r11)*(x3240)*(x3242)))+(((x3234)*(x3239)*(x3245)))+(((r12)*(x3240)*(x3241)))+(((IkReal(-1.00000000000000))*(r21)*(x3233)*(x3243)*(x3244)))+(((r00)*(x3236)*(x3237)))+(((IkReal(-1.00000000000000))*(x3237)*(x3240)*(x3244)))+(((r11)*(r20)*(x3233)*(x3243)))+(((r02)*(x3236)*(x3238)))+(((IkReal(-1.00000000000000))*(x3235)*(x3245)*(x3246)))+(((IkReal(-1.00000000000000))*(x3235)*(x3236)*(x3242)))+(((IkReal(-1.00000000000000))*(r20)*(x3235)*(x3247)))+(((IkReal(-1.00000000000000))*(r02)*(x3236)*(x3241)))+(((IkReal(-1.00000000000000))*(r12)*(x3238)*(x3240)))+(((x3239)*(x3247)))+(((r11)*(x3243)*(x3246)))));
09992 IkReal x3248=(cj6)*(cj6);
09993 IkReal x3249=(sj6)*(sj6);
09994 IkReal x3250=((IkReal(1.00000000000000))*(r01));
09995 IkReal x3251=((sj0)*(sj5));
09996 IkReal x3252=((cj6)*(r22));
09997 IkReal x3253=((r21)*(sj6));
09998 IkReal x3254=((r00)*(r21));
09999 IkReal x3255=((cj0)*(sj5));
10000 IkReal x3256=((cj6)*(r20));
10001 IkReal x3257=((r22)*(sj6));
10002 IkReal x3258=((cj0)*(cj5));
10003 IkReal x3259=((IkReal(1.00000000000000))*(r10));
10004 IkReal x3260=((cj5)*(sj0));
10005 IkReal x3261=((r20)*(x3249));
10006 IkReal x3262=((x3248)*(x3260));
10007 dummyeval[0]=((((r11)*(x3258)*(x3261)))+(((IkReal(-1.00000000000000))*(x3252)*(x3255)*(x3259)))+(((IkReal(-1.00000000000000))*(x3250)*(x3251)*(x3257)))+(((IkReal(-1.00000000000000))*(r12)*(x3253)*(x3255)))+(((IkReal(-1.00000000000000))*(r02)*(x3251)*(x3256)))+(((r02)*(x3251)*(x3253)))+(((r11)*(r20)*(x3248)*(x3258)))+(((IkReal(-1.00000000000000))*(r21)*(x3248)*(x3258)*(x3259)))+(((r00)*(x3251)*(x3252)))+(((x3249)*(x3254)*(x3260)))+(((r11)*(x3255)*(x3257)))+(((IkReal(-1.00000000000000))*(r21)*(x3249)*(x3258)*(x3259)))+(((IkReal(-1.00000000000000))*(r20)*(x3250)*(x3262)))+(((IkReal(-1.00000000000000))*(x3250)*(x3260)*(x3261)))+(((r12)*(x3255)*(x3256)))+(((x3254)*(x3262))));
10008 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10009 {
10010 continue;
10011 
10012 } else
10013 {
10014 {
10015 IkReal j4array[1], cj4array[1], sj4array[1];
10016 bool j4valid[1]={false};
10017 _nj4 = 1;
10018 IkReal x3263=((IkReal(1.00000000000000))*(cj5));
10019 if( IKabs(((gconst88)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst88)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x3263)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x3263))))))) < IKFAST_ATAN2_MAGTHRESH )
10020     continue;
10021 j4array[0]=IKatan2(((gconst88)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))), ((gconst88)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x3263)))+(((IkReal(-1.00000000000000))*(cj6)*(r21)*(x3263)))))));
10022 sj4array[0]=IKsin(j4array[0]);
10023 cj4array[0]=IKcos(j4array[0]);
10024 if( j4array[0] > IKPI )
10025 {
10026     j4array[0]-=IK2PI;
10027 }
10028 else if( j4array[0] < -IKPI )
10029 {    j4array[0]+=IK2PI;
10030 }
10031 j4valid[0] = true;
10032 for(int ij4 = 0; ij4 < 1; ++ij4)
10033 {
10034 if( !j4valid[ij4] )
10035 {
10036     continue;
10037 }
10038 _ij4[0] = ij4; _ij4[1] = -1;
10039 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10040 {
10041 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10042 {
10043     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10044 }
10045 }
10046 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10047 {
10048 IkReal evalcond[6];
10049 IkReal x3264=IKsin(j4);
10050 IkReal x3265=IKcos(j4);
10051 IkReal x3266=((r22)*(sj5));
10052 IkReal x3267=((IkReal(1.00000000000000))*(cj6));
10053 IkReal x3268=((IkReal(1.00000000000000))*(cj0));
10054 IkReal x3269=((cj5)*(r11));
10055 IkReal x3270=((cj5)*(cj6));
10056 IkReal x3271=((r11)*(sj6));
10057 IkReal x3272=((IkReal(1.00000000000000))*(sj6));
10058 IkReal x3273=((cj6)*(r00));
10059 IkReal x3274=((r12)*(sj5));
10060 IkReal x3275=((r02)*(sj5));
10061 IkReal x3276=((cj6)*(r10));
10062 IkReal x3277=((cj5)*(sj6));
10063 IkReal x3278=((cj5)*(r01));
10064 IkReal x3279=((sj0)*(x3264));
10065 IkReal x3280=((r00)*(x3277));
10066 IkReal x3281=((cj0)*(x3264));
10067 IkReal x3282=((sj0)*(x3265));
10068 IkReal x3283=((r20)*(x3265));
10069 IkReal x3284=((cj0)*(x3265));
10070 IkReal x3285=((r21)*(x3264));
10071 IkReal x3286=((r21)*(x3265));
10072 IkReal x3287=((r20)*(x3264));
10073 IkReal x3288=((x3265)*(x3274));
10074 IkReal x3289=((r01)*(sj6)*(x3265));
10075 IkReal x3290=((cj5)*(r10)*(x3272));
10076 evalcond[0]=((((x3277)*(x3287)))+(((x3264)*(x3266)))+(((IkReal(-1.00000000000000))*(x3267)*(x3283)))+(((x3270)*(x3285)))+(((sj6)*(x3286))));
10077 evalcond[1]=((sj3)+(((cj6)*(x3287)))+(((IkReal(-1.00000000000000))*(x3272)*(x3285)))+(((x3277)*(x3283)))+(((x3270)*(x3286)))+(((x3265)*(x3266))));
10078 evalcond[2]=((IkReal(-1.00000000000000))+(((r01)*(sj6)*(x3282)))+(((r01)*(x3270)*(x3279)))+(((x3275)*(x3279)))+(((IkReal(-1.00000000000000))*(x3264)*(x3268)*(x3274)))+(((IkReal(-1.00000000000000))*(x3267)*(x3269)*(x3281)))+(((IkReal(-1.00000000000000))*(r10)*(x3264)*(x3268)*(x3277)))+(((x3276)*(x3284)))+(((IkReal(-1.00000000000000))*(r00)*(x3267)*(x3282)))+(((x3279)*(x3280)))+(((IkReal(-1.00000000000000))*(x3265)*(x3268)*(x3271))));
10079 evalcond[3]=((((x3273)*(x3279)))+(((x3275)*(x3282)))+(((IkReal(-1.00000000000000))*(r10)*(x3265)*(x3268)*(x3277)))+(((r01)*(x3270)*(x3282)))+(((x3280)*(x3282)))+(((IkReal(-1.00000000000000))*(r10)*(x3267)*(x3281)))+(((IkReal(-1.00000000000000))*(x3267)*(x3269)*(x3284)))+(((IkReal(-1.00000000000000))*(x3268)*(x3288)))+(((x3271)*(x3281)))+(((IkReal(-1.00000000000000))*(r01)*(x3272)*(x3279))));
10080 evalcond[4]=((((IkReal(-1.00000000000000))*(x3274)*(x3279)))+(((x3273)*(x3284)))+(((IkReal(-1.00000000000000))*(x3279)*(x3290)))+(((IkReal(-1.00000000000000))*(x3267)*(x3278)*(x3281)))+(((IkReal(-1.00000000000000))*(x3267)*(x3269)*(x3279)))+(((IkReal(-1.00000000000000))*(x3264)*(x3268)*(x3280)))+(((x3276)*(x3282)))+(((IkReal(-1.00000000000000))*(x3264)*(x3268)*(x3275)))+(((IkReal(-1.00000000000000))*(x3271)*(x3282)))+(((IkReal(-1.00000000000000))*(x3268)*(x3289))));
10081 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3267)*(x3279)))+(((IkReal(-1.00000000000000))*(r00)*(x3267)*(x3281)))+(((IkReal(-1.00000000000000))*(x3274)*(x3282)))+(((x3271)*(x3279)))+(((IkReal(-1.00000000000000))*(x3267)*(x3278)*(x3284)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x3265)*(x3268)*(x3280)))+(((IkReal(-1.00000000000000))*(x3265)*(x3268)*(x3275)))+(((IkReal(-1.00000000000000))*(x3267)*(x3269)*(x3282)))+(((r01)*(sj6)*(x3281)))+(((IkReal(-1.00000000000000))*(x3282)*(x3290))));
10082 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10083 {
10084 continue;
10085 }
10086 }
10087 
10088 {
10089 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10090 vinfos[0].jointtype = 1;
10091 vinfos[0].foffset = j0;
10092 vinfos[0].indices[0] = _ij0[0];
10093 vinfos[0].indices[1] = _ij0[1];
10094 vinfos[0].maxsolutions = _nj0;
10095 vinfos[1].jointtype = 1;
10096 vinfos[1].foffset = j1;
10097 vinfos[1].indices[0] = _ij1[0];
10098 vinfos[1].indices[1] = _ij1[1];
10099 vinfos[1].maxsolutions = _nj1;
10100 vinfos[2].jointtype = 1;
10101 vinfos[2].foffset = j2;
10102 vinfos[2].indices[0] = _ij2[0];
10103 vinfos[2].indices[1] = _ij2[1];
10104 vinfos[2].maxsolutions = _nj2;
10105 vinfos[3].jointtype = 1;
10106 vinfos[3].foffset = j3;
10107 vinfos[3].indices[0] = _ij3[0];
10108 vinfos[3].indices[1] = _ij3[1];
10109 vinfos[3].maxsolutions = _nj3;
10110 vinfos[4].jointtype = 1;
10111 vinfos[4].foffset = j4;
10112 vinfos[4].indices[0] = _ij4[0];
10113 vinfos[4].indices[1] = _ij4[1];
10114 vinfos[4].maxsolutions = _nj4;
10115 vinfos[5].jointtype = 1;
10116 vinfos[5].foffset = j5;
10117 vinfos[5].indices[0] = _ij5[0];
10118 vinfos[5].indices[1] = _ij5[1];
10119 vinfos[5].maxsolutions = _nj5;
10120 vinfos[6].jointtype = 1;
10121 vinfos[6].foffset = j6;
10122 vinfos[6].indices[0] = _ij6[0];
10123 vinfos[6].indices[1] = _ij6[1];
10124 vinfos[6].maxsolutions = _nj6;
10125 std::vector<int> vfree(0);
10126 solutions.AddSolution(vinfos,vfree);
10127 }
10128 }
10129 }
10130 
10131 }
10132 
10133 }
10134 
10135 } else
10136 {
10137 {
10138 IkReal j4array[1], cj4array[1], sj4array[1];
10139 bool j4valid[1]={false};
10140 _nj4 = 1;
10141 IkReal x3291=((r21)*(sj3));
10142 IkReal x3292=((IkReal(1.00000000000000))*(r20)*(sj3));
10143 if( IKabs(((gconst87)*(((((sj6)*(x3291)))+(((IkReal(-1.00000000000000))*(cj6)*(x3292))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst87)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3292)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3291)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
10144     continue;
10145 j4array[0]=IKatan2(((gconst87)*(((((sj6)*(x3291)))+(((IkReal(-1.00000000000000))*(cj6)*(x3292)))))), ((gconst87)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3292)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3291)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
10146 sj4array[0]=IKsin(j4array[0]);
10147 cj4array[0]=IKcos(j4array[0]);
10148 if( j4array[0] > IKPI )
10149 {
10150     j4array[0]-=IK2PI;
10151 }
10152 else if( j4array[0] < -IKPI )
10153 {    j4array[0]+=IK2PI;
10154 }
10155 j4valid[0] = true;
10156 for(int ij4 = 0; ij4 < 1; ++ij4)
10157 {
10158 if( !j4valid[ij4] )
10159 {
10160     continue;
10161 }
10162 _ij4[0] = ij4; _ij4[1] = -1;
10163 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10164 {
10165 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10166 {
10167     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10168 }
10169 }
10170 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10171 {
10172 IkReal evalcond[6];
10173 IkReal x3293=IKsin(j4);
10174 IkReal x3294=IKcos(j4);
10175 IkReal x3295=((r22)*(sj5));
10176 IkReal x3296=((IkReal(1.00000000000000))*(cj6));
10177 IkReal x3297=((IkReal(1.00000000000000))*(cj0));
10178 IkReal x3298=((cj5)*(r11));
10179 IkReal x3299=((cj5)*(cj6));
10180 IkReal x3300=((r11)*(sj6));
10181 IkReal x3301=((IkReal(1.00000000000000))*(sj6));
10182 IkReal x3302=((cj6)*(r00));
10183 IkReal x3303=((r12)*(sj5));
10184 IkReal x3304=((r02)*(sj5));
10185 IkReal x3305=((cj6)*(r10));
10186 IkReal x3306=((cj5)*(sj6));
10187 IkReal x3307=((cj5)*(r01));
10188 IkReal x3308=((sj0)*(x3293));
10189 IkReal x3309=((r00)*(x3306));
10190 IkReal x3310=((cj0)*(x3293));
10191 IkReal x3311=((sj0)*(x3294));
10192 IkReal x3312=((r20)*(x3294));
10193 IkReal x3313=((cj0)*(x3294));
10194 IkReal x3314=((r21)*(x3293));
10195 IkReal x3315=((r21)*(x3294));
10196 IkReal x3316=((r20)*(x3293));
10197 IkReal x3317=((x3294)*(x3303));
10198 IkReal x3318=((r01)*(sj6)*(x3294));
10199 IkReal x3319=((cj5)*(r10)*(x3301));
10200 evalcond[0]=((((IkReal(-1.00000000000000))*(x3296)*(x3312)))+(((x3299)*(x3314)))+(((x3293)*(x3295)))+(((x3306)*(x3316)))+(((sj6)*(x3315))));
10201 evalcond[1]=((((cj6)*(x3316)))+(sj3)+(((x3306)*(x3312)))+(((IkReal(-1.00000000000000))*(x3301)*(x3314)))+(((x3294)*(x3295)))+(((x3299)*(x3315))));
10202 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x3294)*(x3297)*(x3300)))+(((r01)*(x3299)*(x3308)))+(((IkReal(-1.00000000000000))*(x3296)*(x3298)*(x3310)))+(((x3305)*(x3313)))+(((IkReal(-1.00000000000000))*(r00)*(x3296)*(x3311)))+(((x3308)*(x3309)))+(((IkReal(-1.00000000000000))*(r10)*(x3293)*(x3297)*(x3306)))+(((x3304)*(x3308)))+(((r01)*(sj6)*(x3311)))+(((IkReal(-1.00000000000000))*(x3293)*(x3297)*(x3303))));
10203 evalcond[3]=((((x3300)*(x3310)))+(((IkReal(-1.00000000000000))*(x3296)*(x3298)*(x3313)))+(((IkReal(-1.00000000000000))*(x3297)*(x3317)))+(((IkReal(-1.00000000000000))*(r10)*(x3294)*(x3297)*(x3306)))+(((x3304)*(x3311)))+(((x3309)*(x3311)))+(((IkReal(-1.00000000000000))*(r01)*(x3301)*(x3308)))+(((IkReal(-1.00000000000000))*(r10)*(x3296)*(x3310)))+(((r01)*(x3299)*(x3311)))+(((x3302)*(x3308))));
10204 evalcond[4]=((((IkReal(-1.00000000000000))*(x3300)*(x3311)))+(((x3305)*(x3311)))+(((x3302)*(x3313)))+(((IkReal(-1.00000000000000))*(x3308)*(x3319)))+(((IkReal(-1.00000000000000))*(x3296)*(x3298)*(x3308)))+(((IkReal(-1.00000000000000))*(x3293)*(x3297)*(x3304)))+(((IkReal(-1.00000000000000))*(x3296)*(x3307)*(x3310)))+(((IkReal(-1.00000000000000))*(x3293)*(x3297)*(x3309)))+(((IkReal(-1.00000000000000))*(x3303)*(x3308)))+(((IkReal(-1.00000000000000))*(x3297)*(x3318))));
10205 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3296)*(x3308)))+(((r01)*(sj6)*(x3310)))+(((IkReal(-1.00000000000000))*(r00)*(x3296)*(x3310)))+(((IkReal(-1.00000000000000))*(x3296)*(x3307)*(x3313)))+(((IkReal(-1.00000000000000))*(x3311)*(x3319)))+(((x3300)*(x3308)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x3294)*(x3297)*(x3304)))+(((IkReal(-1.00000000000000))*(x3303)*(x3311)))+(((IkReal(-1.00000000000000))*(x3296)*(x3298)*(x3311)))+(((IkReal(-1.00000000000000))*(x3294)*(x3297)*(x3309))));
10206 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10207 {
10208 continue;
10209 }
10210 }
10211 
10212 {
10213 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10214 vinfos[0].jointtype = 1;
10215 vinfos[0].foffset = j0;
10216 vinfos[0].indices[0] = _ij0[0];
10217 vinfos[0].indices[1] = _ij0[1];
10218 vinfos[0].maxsolutions = _nj0;
10219 vinfos[1].jointtype = 1;
10220 vinfos[1].foffset = j1;
10221 vinfos[1].indices[0] = _ij1[0];
10222 vinfos[1].indices[1] = _ij1[1];
10223 vinfos[1].maxsolutions = _nj1;
10224 vinfos[2].jointtype = 1;
10225 vinfos[2].foffset = j2;
10226 vinfos[2].indices[0] = _ij2[0];
10227 vinfos[2].indices[1] = _ij2[1];
10228 vinfos[2].maxsolutions = _nj2;
10229 vinfos[3].jointtype = 1;
10230 vinfos[3].foffset = j3;
10231 vinfos[3].indices[0] = _ij3[0];
10232 vinfos[3].indices[1] = _ij3[1];
10233 vinfos[3].maxsolutions = _nj3;
10234 vinfos[4].jointtype = 1;
10235 vinfos[4].foffset = j4;
10236 vinfos[4].indices[0] = _ij4[0];
10237 vinfos[4].indices[1] = _ij4[1];
10238 vinfos[4].maxsolutions = _nj4;
10239 vinfos[5].jointtype = 1;
10240 vinfos[5].foffset = j5;
10241 vinfos[5].indices[0] = _ij5[0];
10242 vinfos[5].indices[1] = _ij5[1];
10243 vinfos[5].maxsolutions = _nj5;
10244 vinfos[6].jointtype = 1;
10245 vinfos[6].foffset = j6;
10246 vinfos[6].indices[0] = _ij6[0];
10247 vinfos[6].indices[1] = _ij6[1];
10248 vinfos[6].maxsolutions = _nj6;
10249 std::vector<int> vfree(0);
10250 solutions.AddSolution(vinfos,vfree);
10251 }
10252 }
10253 }
10254 
10255 }
10256 
10257 }
10258 }
10259 }
10260 
10261 } else
10262 {
10263 if( 1 )
10264 {
10265 continue;
10266 
10267 } else
10268 {
10269 }
10270 }
10271 }
10272 }
10273 
10274 } else
10275 {
10276 {
10277 IkReal j3array[1], cj3array[1], sj3array[1];
10278 bool j3valid[1]={false};
10279 _nj3 = 1;
10280 IkReal x3320=((sj0)*(sj5));
10281 IkReal x3321=((IkReal(1.00000000000000))*(cj6)*(sj5));
10282 IkReal x3322=((IkReal(1.00000000000000))*(sj5)*(sj6));
10283 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((cj6)*(r01)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3321)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj6)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x3322)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(sj0))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r20)*(x3322)))+(((IkReal(-1.00000000000000))*(r21)*(x3321)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((cj6)*(r01)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3321)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj6)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x3322)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(sj0)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r20)*(x3322)))+(((IkReal(-1.00000000000000))*(r21)*(x3321)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
10284     continue;
10285 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((cj6)*(r01)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3321)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj6)*(x3320)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x3322)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(sj0)))))), ((((IkReal(-1.00000000000000))*(r20)*(x3322)))+(((IkReal(-1.00000000000000))*(r21)*(x3321)))+(((cj5)*(r22)))));
10286 sj3array[0]=IKsin(j3array[0]);
10287 cj3array[0]=IKcos(j3array[0]);
10288 if( j3array[0] > IKPI )
10289 {
10290     j3array[0]-=IK2PI;
10291 }
10292 else if( j3array[0] < -IKPI )
10293 {    j3array[0]+=IK2PI;
10294 }
10295 j3valid[0] = true;
10296 for(int ij3 = 0; ij3 < 1; ++ij3)
10297 {
10298 if( !j3valid[ij3] )
10299 {
10300     continue;
10301 }
10302 _ij3[0] = ij3; _ij3[1] = -1;
10303 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10304 {
10305 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10306 {
10307     j3valid[iij3]=false; _ij3[1] = iij3; break; 
10308 }
10309 }
10310 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10311 {
10312 IkReal evalcond[3];
10313 IkReal x3323=IKsin(j3);
10314 IkReal x3324=((sj5)*(sj6));
10315 IkReal x3325=((cj0)*(cj5));
10316 IkReal x3326=((IkReal(1.00000000000000))*(cj0));
10317 IkReal x3327=((IkReal(1.00000000000000))*(sj0));
10318 IkReal x3328=((IkReal(1.00000000000000))*(x3323));
10319 IkReal x3329=((cj6)*(r01)*(sj5));
10320 IkReal x3330=((cj6)*(r11)*(sj5));
10321 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x3324)))+(IKcos(j3)));
10322 evalcond[1]=((((IkReal(-1.00000000000000))*(x3326)*(x3330)))+(((r12)*(x3325)))+(((r00)*(sj0)*(x3324)))+(((IkReal(-1.00000000000000))*(sj2)*(x3328)))+(((IkReal(-1.00000000000000))*(r10)*(x3324)*(x3326)))+(((sj0)*(x3329)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x3327))));
10323 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x3324)*(x3326)))+(((r02)*(x3325)))+(((IkReal(-1.00000000000000))*(x3327)*(x3330)))+(((IkReal(-1.00000000000000))*(r10)*(x3324)*(x3327)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj2)*(x3328)))+(((IkReal(-1.00000000000000))*(x3326)*(x3329))));
10324 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
10325 {
10326 continue;
10327 }
10328 }
10329 
10330 {
10331 IkReal dummyeval[1];
10332 IkReal gconst79;
10333 IkReal x3331=(cj5)*(cj5);
10334 IkReal x3332=(r20)*(r20);
10335 IkReal x3333=(sj6)*(sj6);
10336 IkReal x3334=(cj6)*(cj6);
10337 IkReal x3335=(r21)*(r21);
10338 IkReal x3336=((cj6)*(r21));
10339 IkReal x3337=((IkReal(2.00000000000000))*(r20)*(sj6));
10340 IkReal x3338=((cj5)*(r22)*(sj5));
10341 gconst79=IKsign(((((x3337)*(x3338)))+(((IkReal(-1.00000000000000))*(x3336)*(x3337)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3331)*(x3334)*(x3335)))+(((x3331)*(x3336)*(x3337)))+(((x3331)*(x3332)*(x3333)))+(((x3333)*(x3335)))+(((IkReal(2.00000000000000))*(x3336)*(x3338)))+(((x3332)*(x3334)))));
10342 IkReal x3339=(cj5)*(cj5);
10343 IkReal x3340=(r20)*(r20);
10344 IkReal x3341=(sj6)*(sj6);
10345 IkReal x3342=(cj6)*(cj6);
10346 IkReal x3343=(r21)*(r21);
10347 IkReal x3344=((cj6)*(r21));
10348 IkReal x3345=((IkReal(2.00000000000000))*(r20)*(sj6));
10349 IkReal x3346=((cj5)*(r22)*(sj5));
10350 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3344)*(x3345)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3340)*(x3342)))+(((x3341)*(x3343)))+(((x3339)*(x3340)*(x3341)))+(((x3339)*(x3342)*(x3343)))+(((x3345)*(x3346)))+(((IkReal(2.00000000000000))*(x3344)*(x3346)))+(((x3339)*(x3344)*(x3345))));
10351 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10352 {
10353 {
10354 IkReal dummyeval[1];
10355 IkReal gconst80;
10356 IkReal x3347=(cj6)*(cj6);
10357 IkReal x3348=(sj6)*(sj6);
10358 IkReal x3349=((IkReal(1.00000000000000))*(r21));
10359 IkReal x3350=((cj6)*(r20));
10360 IkReal x3351=((r22)*(sj5));
10361 IkReal x3352=((r01)*(sj0));
10362 IkReal x3353=((r00)*(sj0));
10363 IkReal x3354=((cj0)*(r10));
10364 IkReal x3355=((r02)*(sj0)*(sj5));
10365 IkReal x3356=((cj5)*(x3347));
10366 IkReal x3357=((cj0)*(r12)*(sj5));
10367 IkReal x3358=((IkReal(1.00000000000000))*(cj0)*(r11));
10368 IkReal x3359=((cj5)*(x3348));
10369 IkReal x3360=((r20)*(x3359));
10370 gconst80=IKsign(((((x3352)*(x3360)))+(((IkReal(-1.00000000000000))*(x3349)*(x3353)*(x3359)))+(((r20)*(x3352)*(x3356)))+(((IkReal(-1.00000000000000))*(x3358)*(x3360)))+(((x3350)*(x3355)))+(((cj6)*(x3351)*(x3354)))+(((IkReal(-1.00000000000000))*(sj6)*(x3351)*(x3358)))+(((IkReal(-1.00000000000000))*(cj6)*(x3351)*(x3353)))+(((r21)*(sj6)*(x3357)))+(((r21)*(x3354)*(x3356)))+(((sj6)*(x3351)*(x3352)))+(((r21)*(x3354)*(x3359)))+(((IkReal(-1.00000000000000))*(r20)*(x3356)*(x3358)))+(((IkReal(-1.00000000000000))*(x3349)*(x3353)*(x3356)))+(((IkReal(-1.00000000000000))*(x3350)*(x3357)))+(((IkReal(-1.00000000000000))*(sj6)*(x3349)*(x3355)))));
10371 IkReal x3361=(cj6)*(cj6);
10372 IkReal x3362=(sj6)*(sj6);
10373 IkReal x3363=((IkReal(1.00000000000000))*(r21));
10374 IkReal x3364=((cj6)*(r20));
10375 IkReal x3365=((r22)*(sj5));
10376 IkReal x3366=((r01)*(sj0));
10377 IkReal x3367=((r00)*(sj0));
10378 IkReal x3368=((cj0)*(r10));
10379 IkReal x3369=((r02)*(sj0)*(sj5));
10380 IkReal x3370=((cj5)*(x3361));
10381 IkReal x3371=((cj0)*(r12)*(sj5));
10382 IkReal x3372=((IkReal(1.00000000000000))*(cj0)*(r11));
10383 IkReal x3373=((cj5)*(x3362));
10384 IkReal x3374=((r20)*(x3373));
10385 dummyeval[0]=((((IkReal(-1.00000000000000))*(r20)*(x3370)*(x3372)))+(((x3366)*(x3374)))+(((x3364)*(x3369)))+(((r21)*(x3368)*(x3370)))+(((IkReal(-1.00000000000000))*(x3363)*(x3367)*(x3370)))+(((r21)*(sj6)*(x3371)))+(((r21)*(x3368)*(x3373)))+(((IkReal(-1.00000000000000))*(x3364)*(x3371)))+(((IkReal(-1.00000000000000))*(sj6)*(x3363)*(x3369)))+(((IkReal(-1.00000000000000))*(x3372)*(x3374)))+(((cj6)*(x3365)*(x3368)))+(((r20)*(x3366)*(x3370)))+(((sj6)*(x3365)*(x3366)))+(((IkReal(-1.00000000000000))*(x3363)*(x3367)*(x3373)))+(((IkReal(-1.00000000000000))*(sj6)*(x3365)*(x3372)))+(((IkReal(-1.00000000000000))*(cj6)*(x3365)*(x3367))));
10386 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10387 {
10388 continue;
10389 
10390 } else
10391 {
10392 {
10393 IkReal j4array[1], cj4array[1], sj4array[1];
10394 bool j4valid[1]={false};
10395 _nj4 = 1;
10396 IkReal x3375=((cj2)*(sj6));
10397 IkReal x3376=((IkReal(1.00000000000000))*(r20));
10398 IkReal x3377=((cj2)*(cj6));
10399 if( IKabs(((gconst80)*(((((r21)*(x3375)))+(((IkReal(-1.00000000000000))*(x3376)*(x3377))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst80)*(((((IkReal(-1.00000000000000))*(cj5)*(x3375)*(x3376)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3377))))))) < IKFAST_ATAN2_MAGTHRESH )
10400     continue;
10401 j4array[0]=IKatan2(((gconst80)*(((((r21)*(x3375)))+(((IkReal(-1.00000000000000))*(x3376)*(x3377)))))), ((gconst80)*(((((IkReal(-1.00000000000000))*(cj5)*(x3375)*(x3376)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3377)))))));
10402 sj4array[0]=IKsin(j4array[0]);
10403 cj4array[0]=IKcos(j4array[0]);
10404 if( j4array[0] > IKPI )
10405 {
10406     j4array[0]-=IK2PI;
10407 }
10408 else if( j4array[0] < -IKPI )
10409 {    j4array[0]+=IK2PI;
10410 }
10411 j4valid[0] = true;
10412 for(int ij4 = 0; ij4 < 1; ++ij4)
10413 {
10414 if( !j4valid[ij4] )
10415 {
10416     continue;
10417 }
10418 _ij4[0] = ij4; _ij4[1] = -1;
10419 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10420 {
10421 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10422 {
10423     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10424 }
10425 }
10426 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10427 {
10428 IkReal evalcond[6];
10429 IkReal x3378=IKsin(j4);
10430 IkReal x3379=IKcos(j4);
10431 IkReal x3380=((r00)*(sj6));
10432 IkReal x3381=((IkReal(1.00000000000000))*(r12));
10433 IkReal x3382=((IkReal(1.00000000000000))*(cj6));
10434 IkReal x3383=((cj6)*(r01));
10435 IkReal x3384=((r11)*(sj6));
10436 IkReal x3385=((r01)*(sj6));
10437 IkReal x3386=((IkReal(1.00000000000000))*(cj5));
10438 IkReal x3387=((IkReal(1.00000000000000))*(sj6));
10439 IkReal x3388=((cj5)*(r11));
10440 IkReal x3389=((cj6)*(r00));
10441 IkReal x3390=((cj5)*(cj6));
10442 IkReal x3391=((r02)*(sj5));
10443 IkReal x3392=((cj6)*(r10));
10444 IkReal x3393=((cj5)*(sj6));
10445 IkReal x3394=((r10)*(sj6));
10446 IkReal x3395=((cj5)*(r01));
10447 IkReal x3396=((sj5)*(x3378));
10448 IkReal x3397=((cj0)*(x3379));
10449 IkReal x3398=((cj0)*(x3378));
10450 IkReal x3399=((sj0)*(x3379));
10451 IkReal x3400=((sj0)*(x3378));
10452 IkReal x3401=((r20)*(x3379));
10453 IkReal x3402=((r21)*(x3378));
10454 IkReal x3403=((r21)*(x3379));
10455 IkReal x3404=((r20)*(x3378));
10456 IkReal x3405=((cj5)*(x3400));
10457 evalcond[0]=((((r22)*(x3396)))+(((IkReal(-1.00000000000000))*(x3382)*(x3401)))+(((x3393)*(x3404)))+(((x3390)*(x3402)))+(((sj6)*(x3403))));
10458 evalcond[1]=((((cj6)*(x3404)))+(sj3)+(((IkReal(-1.00000000000000))*(x3387)*(x3402)))+(((r22)*(sj5)*(x3379)))+(((x3393)*(x3401)))+(((x3390)*(x3403))));
10459 evalcond[2]=((((IkReal(-1.00000000000000))*(x3384)*(x3397)))+(((x3385)*(x3399)))+(((x3391)*(x3400)))+(((IkReal(-1.00000000000000))*(x3386)*(x3394)*(x3398)))+(((x3392)*(x3397)))+(((x3380)*(x3405)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x3382)*(x3399)))+(((IkReal(-1.00000000000000))*(x3382)*(x3388)*(x3398)))+(((IkReal(-1.00000000000000))*(cj0)*(x3381)*(x3396)))+(((x3383)*(x3405))));
10460 evalcond[3]=((((IkReal(-1.00000000000000))*(x3382)*(x3388)*(x3397)))+(((IkReal(-1.00000000000000))*(x3386)*(x3394)*(x3397)))+(((x3389)*(x3400)))+(((IkReal(-1.00000000000000))*(sj5)*(x3381)*(x3397)))+(((cj5)*(x3380)*(x3399)))+(((IkReal(-1.00000000000000))*(r10)*(x3382)*(x3398)))+(((IkReal(-1.00000000000000))*(x3385)*(x3400)))+(((cj5)*(x3383)*(x3399)))+(((cj3)*(sj2)))+(((x3391)*(x3399)))+(((x3384)*(x3398))));
10461 evalcond[4]=((((IkReal(-1.00000000000000))*(sj0)*(x3381)*(x3396)))+(((IkReal(-1.00000000000000))*(sj2)))+(((x3389)*(x3397)))+(((IkReal(-1.00000000000000))*(x3385)*(x3397)))+(((x3392)*(x3399)))+(((IkReal(-1.00000000000000))*(x3391)*(x3398)))+(((IkReal(-1.00000000000000))*(x3380)*(x3386)*(x3398)))+(((IkReal(-1.00000000000000))*(x3386)*(x3394)*(x3400)))+(((IkReal(-1.00000000000000))*(x3382)*(x3395)*(x3398)))+(((IkReal(-1.00000000000000))*(x3384)*(x3399)))+(((IkReal(-1.00000000000000))*(x3382)*(x3388)*(x3400))));
10462 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3382)*(x3400)))+(((IkReal(-1.00000000000000))*(x3380)*(x3386)*(x3397)))+(((IkReal(-1.00000000000000))*(x3391)*(x3397)))+(((IkReal(-1.00000000000000))*(x3386)*(x3394)*(x3399)))+(((IkReal(-1.00000000000000))*(r00)*(x3382)*(x3398)))+(((x3384)*(x3400)))+(((cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(x3382)*(x3395)*(x3397)))+(((IkReal(-1.00000000000000))*(sj5)*(x3381)*(x3399)))+(((x3385)*(x3398)))+(((IkReal(-1.00000000000000))*(x3382)*(x3388)*(x3399))));
10463 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10464 {
10465 continue;
10466 }
10467 }
10468 
10469 {
10470 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10471 vinfos[0].jointtype = 1;
10472 vinfos[0].foffset = j0;
10473 vinfos[0].indices[0] = _ij0[0];
10474 vinfos[0].indices[1] = _ij0[1];
10475 vinfos[0].maxsolutions = _nj0;
10476 vinfos[1].jointtype = 1;
10477 vinfos[1].foffset = j1;
10478 vinfos[1].indices[0] = _ij1[0];
10479 vinfos[1].indices[1] = _ij1[1];
10480 vinfos[1].maxsolutions = _nj1;
10481 vinfos[2].jointtype = 1;
10482 vinfos[2].foffset = j2;
10483 vinfos[2].indices[0] = _ij2[0];
10484 vinfos[2].indices[1] = _ij2[1];
10485 vinfos[2].maxsolutions = _nj2;
10486 vinfos[3].jointtype = 1;
10487 vinfos[3].foffset = j3;
10488 vinfos[3].indices[0] = _ij3[0];
10489 vinfos[3].indices[1] = _ij3[1];
10490 vinfos[3].maxsolutions = _nj3;
10491 vinfos[4].jointtype = 1;
10492 vinfos[4].foffset = j4;
10493 vinfos[4].indices[0] = _ij4[0];
10494 vinfos[4].indices[1] = _ij4[1];
10495 vinfos[4].maxsolutions = _nj4;
10496 vinfos[5].jointtype = 1;
10497 vinfos[5].foffset = j5;
10498 vinfos[5].indices[0] = _ij5[0];
10499 vinfos[5].indices[1] = _ij5[1];
10500 vinfos[5].maxsolutions = _nj5;
10501 vinfos[6].jointtype = 1;
10502 vinfos[6].foffset = j6;
10503 vinfos[6].indices[0] = _ij6[0];
10504 vinfos[6].indices[1] = _ij6[1];
10505 vinfos[6].maxsolutions = _nj6;
10506 std::vector<int> vfree(0);
10507 solutions.AddSolution(vinfos,vfree);
10508 }
10509 }
10510 }
10511 
10512 }
10513 
10514 }
10515 
10516 } else
10517 {
10518 {
10519 IkReal j4array[1], cj4array[1], sj4array[1];
10520 bool j4valid[1]={false};
10521 _nj4 = 1;
10522 IkReal x3406=((r21)*(sj3));
10523 IkReal x3407=((IkReal(1.00000000000000))*(r20)*(sj3));
10524 if( IKabs(((gconst79)*(((((sj6)*(x3406)))+(((IkReal(-1.00000000000000))*(cj6)*(x3407))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3407)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3406)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
10525     continue;
10526 j4array[0]=IKatan2(((gconst79)*(((((sj6)*(x3406)))+(((IkReal(-1.00000000000000))*(cj6)*(x3407)))))), ((gconst79)*(((((IkReal(-1.00000000000000))*(cj5)*(sj6)*(x3407)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(x3406)))+(((IkReal(-1.00000000000000))*(r22)*(sj3)*(sj5)))))));
10527 sj4array[0]=IKsin(j4array[0]);
10528 cj4array[0]=IKcos(j4array[0]);
10529 if( j4array[0] > IKPI )
10530 {
10531     j4array[0]-=IK2PI;
10532 }
10533 else if( j4array[0] < -IKPI )
10534 {    j4array[0]+=IK2PI;
10535 }
10536 j4valid[0] = true;
10537 for(int ij4 = 0; ij4 < 1; ++ij4)
10538 {
10539 if( !j4valid[ij4] )
10540 {
10541     continue;
10542 }
10543 _ij4[0] = ij4; _ij4[1] = -1;
10544 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10545 {
10546 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10547 {
10548     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10549 }
10550 }
10551 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10552 {
10553 IkReal evalcond[6];
10554 IkReal x3408=IKsin(j4);
10555 IkReal x3409=IKcos(j4);
10556 IkReal x3410=((r00)*(sj6));
10557 IkReal x3411=((IkReal(1.00000000000000))*(r12));
10558 IkReal x3412=((IkReal(1.00000000000000))*(cj6));
10559 IkReal x3413=((cj6)*(r01));
10560 IkReal x3414=((r11)*(sj6));
10561 IkReal x3415=((r01)*(sj6));
10562 IkReal x3416=((IkReal(1.00000000000000))*(cj5));
10563 IkReal x3417=((IkReal(1.00000000000000))*(sj6));
10564 IkReal x3418=((cj5)*(r11));
10565 IkReal x3419=((cj6)*(r00));
10566 IkReal x3420=((cj5)*(cj6));
10567 IkReal x3421=((r02)*(sj5));
10568 IkReal x3422=((cj6)*(r10));
10569 IkReal x3423=((cj5)*(sj6));
10570 IkReal x3424=((r10)*(sj6));
10571 IkReal x3425=((cj5)*(r01));
10572 IkReal x3426=((sj5)*(x3408));
10573 IkReal x3427=((cj0)*(x3409));
10574 IkReal x3428=((cj0)*(x3408));
10575 IkReal x3429=((sj0)*(x3409));
10576 IkReal x3430=((sj0)*(x3408));
10577 IkReal x3431=((r20)*(x3409));
10578 IkReal x3432=((r21)*(x3408));
10579 IkReal x3433=((r21)*(x3409));
10580 IkReal x3434=((r20)*(x3408));
10581 IkReal x3435=((cj5)*(x3430));
10582 evalcond[0]=((((r22)*(x3426)))+(((sj6)*(x3433)))+(((x3420)*(x3432)))+(((IkReal(-1.00000000000000))*(x3412)*(x3431)))+(((x3423)*(x3434))));
10583 evalcond[1]=((((r22)*(sj5)*(x3409)))+(sj3)+(((cj6)*(x3434)))+(((x3423)*(x3431)))+(((x3420)*(x3433)))+(((IkReal(-1.00000000000000))*(x3417)*(x3432))));
10584 evalcond[2]=((((IkReal(-1.00000000000000))*(x3414)*(x3427)))+(((IkReal(-1.00000000000000))*(r00)*(x3412)*(x3429)))+(((IkReal(-1.00000000000000))*(x3416)*(x3424)*(x3428)))+(((x3422)*(x3427)))+(((x3415)*(x3429)))+(((x3413)*(x3435)))+(cj2)+(((IkReal(-1.00000000000000))*(cj0)*(x3411)*(x3426)))+(((x3410)*(x3435)))+(((IkReal(-1.00000000000000))*(x3412)*(x3418)*(x3428)))+(((x3421)*(x3430))));
10585 evalcond[3]=((((IkReal(-1.00000000000000))*(x3415)*(x3430)))+(((IkReal(-1.00000000000000))*(x3412)*(x3418)*(x3427)))+(((x3419)*(x3430)))+(((IkReal(-1.00000000000000))*(sj5)*(x3411)*(x3427)))+(((cj5)*(x3410)*(x3429)))+(((IkReal(-1.00000000000000))*(r10)*(x3412)*(x3428)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(x3416)*(x3424)*(x3427)))+(((x3421)*(x3429)))+(((x3414)*(x3428)))+(((cj5)*(x3413)*(x3429))));
10586 evalcond[4]=((((x3419)*(x3427)))+(((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x3421)*(x3428)))+(((IkReal(-1.00000000000000))*(x3412)*(x3425)*(x3428)))+(((IkReal(-1.00000000000000))*(x3412)*(x3418)*(x3430)))+(((x3422)*(x3429)))+(((IkReal(-1.00000000000000))*(x3410)*(x3416)*(x3428)))+(((IkReal(-1.00000000000000))*(x3414)*(x3429)))+(((IkReal(-1.00000000000000))*(sj0)*(x3411)*(x3426)))+(((IkReal(-1.00000000000000))*(x3415)*(x3427)))+(((IkReal(-1.00000000000000))*(x3416)*(x3424)*(x3430))));
10587 evalcond[5]=((((IkReal(-1.00000000000000))*(x3412)*(x3418)*(x3429)))+(((IkReal(-1.00000000000000))*(x3410)*(x3416)*(x3427)))+(((x3415)*(x3428)))+(((x3414)*(x3430)))+(((IkReal(-1.00000000000000))*(r00)*(x3412)*(x3428)))+(((IkReal(-1.00000000000000))*(x3416)*(x3424)*(x3429)))+(((cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(x3412)*(x3425)*(x3427)))+(((IkReal(-1.00000000000000))*(r10)*(x3412)*(x3430)))+(((IkReal(-1.00000000000000))*(sj5)*(x3411)*(x3429)))+(((IkReal(-1.00000000000000))*(x3421)*(x3427))));
10588 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10589 {
10590 continue;
10591 }
10592 }
10593 
10594 {
10595 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10596 vinfos[0].jointtype = 1;
10597 vinfos[0].foffset = j0;
10598 vinfos[0].indices[0] = _ij0[0];
10599 vinfos[0].indices[1] = _ij0[1];
10600 vinfos[0].maxsolutions = _nj0;
10601 vinfos[1].jointtype = 1;
10602 vinfos[1].foffset = j1;
10603 vinfos[1].indices[0] = _ij1[0];
10604 vinfos[1].indices[1] = _ij1[1];
10605 vinfos[1].maxsolutions = _nj1;
10606 vinfos[2].jointtype = 1;
10607 vinfos[2].foffset = j2;
10608 vinfos[2].indices[0] = _ij2[0];
10609 vinfos[2].indices[1] = _ij2[1];
10610 vinfos[2].maxsolutions = _nj2;
10611 vinfos[3].jointtype = 1;
10612 vinfos[3].foffset = j3;
10613 vinfos[3].indices[0] = _ij3[0];
10614 vinfos[3].indices[1] = _ij3[1];
10615 vinfos[3].maxsolutions = _nj3;
10616 vinfos[4].jointtype = 1;
10617 vinfos[4].foffset = j4;
10618 vinfos[4].indices[0] = _ij4[0];
10619 vinfos[4].indices[1] = _ij4[1];
10620 vinfos[4].maxsolutions = _nj4;
10621 vinfos[5].jointtype = 1;
10622 vinfos[5].foffset = j5;
10623 vinfos[5].indices[0] = _ij5[0];
10624 vinfos[5].indices[1] = _ij5[1];
10625 vinfos[5].maxsolutions = _nj5;
10626 vinfos[6].jointtype = 1;
10627 vinfos[6].foffset = j6;
10628 vinfos[6].indices[0] = _ij6[0];
10629 vinfos[6].indices[1] = _ij6[1];
10630 vinfos[6].maxsolutions = _nj6;
10631 std::vector<int> vfree(0);
10632 solutions.AddSolution(vinfos,vfree);
10633 }
10634 }
10635 }
10636 
10637 }
10638 
10639 }
10640 }
10641 }
10642 
10643 }
10644 
10645 }
10646 
10647 } else
10648 {
10649 {
10650 IkReal j4array[1], cj4array[1], sj4array[1];
10651 bool j4valid[1]={false};
10652 _nj4 = 1;
10653 IkReal x3436=((IkReal(1.00000000000000))*(sj2));
10654 if( IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x3436)))+(((r21)*(sj2)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x3436)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(r21)*(x3436)))+(((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj6)*(x3436))))))) < IKFAST_ATAN2_MAGTHRESH )
10655     continue;
10656 j4array[0]=IKatan2(((gconst78)*(((((IkReal(-1.00000000000000))*(cj6)*(r20)*(x3436)))+(((r21)*(sj2)*(sj6)))))), ((gconst78)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x3436)))+(((IkReal(-1.00000000000000))*(cj5)*(cj6)*(r21)*(x3436)))+(((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj6)*(x3436)))))));
10657 sj4array[0]=IKsin(j4array[0]);
10658 cj4array[0]=IKcos(j4array[0]);
10659 if( j4array[0] > IKPI )
10660 {
10661     j4array[0]-=IK2PI;
10662 }
10663 else if( j4array[0] < -IKPI )
10664 {    j4array[0]+=IK2PI;
10665 }
10666 j4valid[0] = true;
10667 for(int ij4 = 0; ij4 < 1; ++ij4)
10668 {
10669 if( !j4valid[ij4] )
10670 {
10671     continue;
10672 }
10673 _ij4[0] = ij4; _ij4[1] = -1;
10674 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10675 {
10676 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10677 {
10678     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10679 }
10680 }
10681 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10682 {
10683 IkReal evalcond[3];
10684 IkReal x3437=IKsin(j4);
10685 IkReal x3438=IKcos(j4);
10686 IkReal x3439=((r00)*(sj6));
10687 IkReal x3440=((cj6)*(r01));
10688 IkReal x3441=((IkReal(1.00000000000000))*(cj0));
10689 IkReal x3442=((IkReal(1.00000000000000))*(sj0));
10690 IkReal x3443=((r10)*(sj6));
10691 IkReal x3444=((sj5)*(x3437));
10692 IkReal x3445=((IkReal(1.00000000000000))*(cj6)*(r11));
10693 IkReal x3446=((cj5)*(x3437));
10694 IkReal x3447=((cj6)*(x3438));
10695 IkReal x3448=((sj0)*(x3446));
10696 IkReal x3449=((r01)*(sj6)*(x3438));
10697 IkReal x3450=((r11)*(sj6)*(x3438));
10698 evalcond[0]=((((r22)*(x3444)))+(((r21)*(sj6)*(x3438)))+(((r20)*(sj6)*(x3446)))+(((cj6)*(r21)*(x3446)))+(((IkReal(-1.00000000000000))*(r20)*(x3447))));
10699 evalcond[1]=((((IkReal(-1.00000000000000))*(r12)*(x3441)*(x3444)))+(((r02)*(sj0)*(x3444)))+(((sj0)*(x3449)))+(((x3440)*(x3448)))+(((IkReal(-1.00000000000000))*(x3441)*(x3450)))+(cj2)+(((cj0)*(r10)*(x3447)))+(((x3439)*(x3448)))+(((IkReal(-1.00000000000000))*(r00)*(x3442)*(x3447)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x3441)*(x3446)))+(((IkReal(-1.00000000000000))*(x3441)*(x3443)*(x3446))));
10700 evalcond[2]=((((IkReal(-1.00000000000000))*(x3440)*(x3441)*(x3446)))+(((IkReal(-1.00000000000000))*(x3442)*(x3443)*(x3446)))+(((IkReal(-1.00000000000000))*(x3439)*(x3441)*(x3446)))+(((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(r02)*(x3441)*(x3444)))+(((r10)*(sj0)*(x3447)))+(((cj0)*(r00)*(x3447)))+(((IkReal(-1.00000000000000))*(x3442)*(x3450)))+(((IkReal(-1.00000000000000))*(r12)*(x3442)*(x3444)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x3442)*(x3446)))+(((IkReal(-1.00000000000000))*(x3441)*(x3449))));
10701 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
10702 {
10703 continue;
10704 }
10705 }
10706 
10707 {
10708 IkReal j3array[1], cj3array[1], sj3array[1];
10709 bool j3valid[1]={false};
10710 _nj3 = 1;
10711 IkReal x3451=((IkReal(1.00000000000000))*(sj5));
10712 IkReal x3452=((cj6)*(r21));
10713 IkReal x3453=((r20)*(sj6));
10714 IkReal x3454=((IkReal(1.00000000000000))*(cj4)*(cj5));
10715 if( IKabs(((((IkReal(-1.00000000000000))*(x3452)*(x3454)))+(((IkReal(-1.00000000000000))*(x3453)*(x3454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3451)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x3451)*(x3452)))+(((IkReal(-1.00000000000000))*(x3451)*(x3453)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x3452)*(x3454)))+(((IkReal(-1.00000000000000))*(x3453)*(x3454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3451)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x3451)*(x3452)))+(((IkReal(-1.00000000000000))*(x3451)*(x3453)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
10716     continue;
10717 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x3452)*(x3454)))+(((IkReal(-1.00000000000000))*(x3453)*(x3454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3451)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x3451)*(x3452)))+(((IkReal(-1.00000000000000))*(x3451)*(x3453)))+(((cj5)*(r22)))));
10718 sj3array[0]=IKsin(j3array[0]);
10719 cj3array[0]=IKcos(j3array[0]);
10720 if( j3array[0] > IKPI )
10721 {
10722     j3array[0]-=IK2PI;
10723 }
10724 else if( j3array[0] < -IKPI )
10725 {    j3array[0]+=IK2PI;
10726 }
10727 j3valid[0] = true;
10728 for(int ij3 = 0; ij3 < 1; ++ij3)
10729 {
10730 if( !j3valid[ij3] )
10731 {
10732     continue;
10733 }
10734 _ij3[0] = ij3; _ij3[1] = -1;
10735 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10736 {
10737 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10738 {
10739     j3valid[iij3]=false; _ij3[1] = iij3; break; 
10740 }
10741 }
10742 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10743 {
10744 IkReal evalcond[6];
10745 IkReal x3455=IKsin(j3);
10746 IkReal x3456=IKcos(j3);
10747 IkReal x3457=((sj0)*(sj5));
10748 IkReal x3458=((r00)*(sj6));
10749 IkReal x3459=((IkReal(1.00000000000000))*(cj4));
10750 IkReal x3460=((cj6)*(r01));
10751 IkReal x3461=((cj0)*(cj5));
10752 IkReal x3462=((cj5)*(sj0));
10753 IkReal x3463=((cj6)*(r11));
10754 IkReal x3464=((cj0)*(sj5));
10755 IkReal x3465=((cj6)*(sj4));
10756 IkReal x3466=((cj4)*(cj5));
10757 IkReal x3467=((cj6)*(r21));
10758 IkReal x3468=((r20)*(sj6));
10759 IkReal x3469=((r10)*(sj6));
10760 IkReal x3470=((IkReal(1.00000000000000))*(cj0));
10761 IkReal x3471=((IkReal(1.00000000000000))*(x3455));
10762 IkReal x3472=((cj0)*(sj4)*(sj6));
10763 IkReal x3473=((sj0)*(sj4)*(sj6));
10764 evalcond[0]=((x3456)+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x3468)))+(((sj5)*(x3467))));
10765 evalcond[1]=((((r20)*(x3465)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(x3455)+(((cj4)*(r22)*(sj5)))+(((x3466)*(x3468)))+(((x3466)*(x3467))));
10766 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x3471)))+(((IkReal(-1.00000000000000))*(r02)*(x3462)))+(((x3457)*(x3460)))+(((IkReal(-1.00000000000000))*(x3464)*(x3469)))+(((x3457)*(x3458)))+(((IkReal(-1.00000000000000))*(x3463)*(x3464)))+(((r12)*(x3461))));
10767 evalcond[3]=((((IkReal(-1.00000000000000))*(x3457)*(x3463)))+(((IkReal(-1.00000000000000))*(cj2)*(x3471)))+(((r02)*(x3461)))+(((IkReal(-1.00000000000000))*(x3460)*(x3464)))+(((r12)*(x3462)))+(((IkReal(-1.00000000000000))*(x3457)*(x3469)))+(((IkReal(-1.00000000000000))*(x3458)*(x3464))));
10768 evalcond[4]=((((r00)*(sj0)*(x3465)))+(((cj4)*(x3458)*(x3462)))+(((IkReal(-1.00000000000000))*(r12)*(x3459)*(x3464)))+(((cj4)*(r02)*(x3457)))+(((IkReal(-1.00000000000000))*(r01)*(x3473)))+(((IkReal(-1.00000000000000))*(x3459)*(x3461)*(x3469)))+(((sj2)*(x3456)))+(((cj4)*(x3460)*(x3462)))+(((IkReal(-1.00000000000000))*(r10)*(x3465)*(x3470)))+(((IkReal(-1.00000000000000))*(x3459)*(x3461)*(x3463)))+(((r11)*(x3472))));
10769 evalcond[5]=((((IkReal(-1.00000000000000))*(x3458)*(x3459)*(x3461)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3465)))+(((IkReal(-1.00000000000000))*(x3459)*(x3460)*(x3461)))+(((r01)*(x3472)))+(((cj2)*(x3456)))+(((IkReal(-1.00000000000000))*(r00)*(x3465)*(x3470)))+(((IkReal(-1.00000000000000))*(r02)*(x3459)*(x3464)))+(((r11)*(x3473)))+(((IkReal(-1.00000000000000))*(r12)*(x3457)*(x3459)))+(((IkReal(-1.00000000000000))*(x3459)*(x3462)*(x3469)))+(((IkReal(-1.00000000000000))*(x3459)*(x3462)*(x3463))));
10770 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10771 {
10772 continue;
10773 }
10774 }
10775 
10776 {
10777 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10778 vinfos[0].jointtype = 1;
10779 vinfos[0].foffset = j0;
10780 vinfos[0].indices[0] = _ij0[0];
10781 vinfos[0].indices[1] = _ij0[1];
10782 vinfos[0].maxsolutions = _nj0;
10783 vinfos[1].jointtype = 1;
10784 vinfos[1].foffset = j1;
10785 vinfos[1].indices[0] = _ij1[0];
10786 vinfos[1].indices[1] = _ij1[1];
10787 vinfos[1].maxsolutions = _nj1;
10788 vinfos[2].jointtype = 1;
10789 vinfos[2].foffset = j2;
10790 vinfos[2].indices[0] = _ij2[0];
10791 vinfos[2].indices[1] = _ij2[1];
10792 vinfos[2].maxsolutions = _nj2;
10793 vinfos[3].jointtype = 1;
10794 vinfos[3].foffset = j3;
10795 vinfos[3].indices[0] = _ij3[0];
10796 vinfos[3].indices[1] = _ij3[1];
10797 vinfos[3].maxsolutions = _nj3;
10798 vinfos[4].jointtype = 1;
10799 vinfos[4].foffset = j4;
10800 vinfos[4].indices[0] = _ij4[0];
10801 vinfos[4].indices[1] = _ij4[1];
10802 vinfos[4].maxsolutions = _nj4;
10803 vinfos[5].jointtype = 1;
10804 vinfos[5].foffset = j5;
10805 vinfos[5].indices[0] = _ij5[0];
10806 vinfos[5].indices[1] = _ij5[1];
10807 vinfos[5].maxsolutions = _nj5;
10808 vinfos[6].jointtype = 1;
10809 vinfos[6].foffset = j6;
10810 vinfos[6].indices[0] = _ij6[0];
10811 vinfos[6].indices[1] = _ij6[1];
10812 vinfos[6].maxsolutions = _nj6;
10813 std::vector<int> vfree(0);
10814 solutions.AddSolution(vinfos,vfree);
10815 }
10816 }
10817 }
10818 }
10819 }
10820 
10821 }
10822 
10823 }
10824 
10825 } else
10826 {
10827 {
10828 IkReal j4array[1], cj4array[1], sj4array[1];
10829 bool j4valid[1]={false};
10830 _nj4 = 1;
10831 IkReal x3474=((cj2)*(sj6));
10832 IkReal x3475=((IkReal(1.00000000000000))*(r20));
10833 IkReal x3476=((cj2)*(cj6));
10834 if( IKabs(((gconst77)*(((((r21)*(x3474)))+(((IkReal(-1.00000000000000))*(x3475)*(x3476))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst77)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3476)))+(((IkReal(-1.00000000000000))*(cj5)*(x3474)*(x3475)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
10835     continue;
10836 j4array[0]=IKatan2(((gconst77)*(((((r21)*(x3474)))+(((IkReal(-1.00000000000000))*(x3475)*(x3476)))))), ((gconst77)*(((((IkReal(-1.00000000000000))*(cj5)*(r21)*(x3476)))+(((IkReal(-1.00000000000000))*(cj5)*(x3474)*(x3475)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))))));
10837 sj4array[0]=IKsin(j4array[0]);
10838 cj4array[0]=IKcos(j4array[0]);
10839 if( j4array[0] > IKPI )
10840 {
10841     j4array[0]-=IK2PI;
10842 }
10843 else if( j4array[0] < -IKPI )
10844 {    j4array[0]+=IK2PI;
10845 }
10846 j4valid[0] = true;
10847 for(int ij4 = 0; ij4 < 1; ++ij4)
10848 {
10849 if( !j4valid[ij4] )
10850 {
10851     continue;
10852 }
10853 _ij4[0] = ij4; _ij4[1] = -1;
10854 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
10855 {
10856 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
10857 {
10858     j4valid[iij4]=false; _ij4[1] = iij4; break; 
10859 }
10860 }
10861 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
10862 {
10863 IkReal evalcond[3];
10864 IkReal x3477=IKsin(j4);
10865 IkReal x3478=IKcos(j4);
10866 IkReal x3479=((r00)*(sj6));
10867 IkReal x3480=((cj6)*(r01));
10868 IkReal x3481=((IkReal(1.00000000000000))*(cj0));
10869 IkReal x3482=((IkReal(1.00000000000000))*(sj0));
10870 IkReal x3483=((r10)*(sj6));
10871 IkReal x3484=((sj5)*(x3477));
10872 IkReal x3485=((IkReal(1.00000000000000))*(cj6)*(r11));
10873 IkReal x3486=((cj5)*(x3477));
10874 IkReal x3487=((cj6)*(x3478));
10875 IkReal x3488=((sj0)*(x3486));
10876 IkReal x3489=((r01)*(sj6)*(x3478));
10877 IkReal x3490=((r11)*(sj6)*(x3478));
10878 evalcond[0]=((((r20)*(sj6)*(x3486)))+(((cj6)*(r21)*(x3486)))+(((r21)*(sj6)*(x3478)))+(((IkReal(-1.00000000000000))*(r20)*(x3487)))+(((r22)*(x3484))));
10879 evalcond[1]=((((sj0)*(x3489)))+(((IkReal(-1.00000000000000))*(r12)*(x3481)*(x3484)))+(((IkReal(-1.00000000000000))*(x3481)*(x3483)*(x3486)))+(((r02)*(sj0)*(x3484)))+(((cj0)*(r10)*(x3487)))+(((IkReal(-1.00000000000000))*(r00)*(x3482)*(x3487)))+(cj2)+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x3481)*(x3486)))+(((x3479)*(x3488)))+(((x3480)*(x3488)))+(((IkReal(-1.00000000000000))*(x3481)*(x3490))));
10880 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x3481)*(x3484)))+(((IkReal(-1.00000000000000))*(x3482)*(x3483)*(x3486)))+(((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x3479)*(x3481)*(x3486)))+(((IkReal(-1.00000000000000))*(x3482)*(x3490)))+(((cj0)*(r00)*(x3487)))+(((IkReal(-1.00000000000000))*(r12)*(x3482)*(x3484)))+(((r10)*(sj0)*(x3487)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x3482)*(x3486)))+(((IkReal(-1.00000000000000))*(x3480)*(x3481)*(x3486)))+(((IkReal(-1.00000000000000))*(x3481)*(x3489))));
10881 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
10882 {
10883 continue;
10884 }
10885 }
10886 
10887 {
10888 IkReal j3array[1], cj3array[1], sj3array[1];
10889 bool j3valid[1]={false};
10890 _nj3 = 1;
10891 IkReal x3491=((IkReal(1.00000000000000))*(sj5));
10892 IkReal x3492=((cj6)*(r21));
10893 IkReal x3493=((r20)*(sj6));
10894 IkReal x3494=((IkReal(1.00000000000000))*(cj4)*(cj5));
10895 if( IKabs(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3491)))+(((IkReal(-1.00000000000000))*(x3493)*(x3494)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x3492)*(x3494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x3491)*(x3492)))+(((IkReal(-1.00000000000000))*(x3491)*(x3493)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3491)))+(((IkReal(-1.00000000000000))*(x3493)*(x3494)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x3492)*(x3494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x3491)*(x3492)))+(((IkReal(-1.00000000000000))*(x3491)*(x3493)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
10896     continue;
10897 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x3491)))+(((IkReal(-1.00000000000000))*(x3493)*(x3494)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x3492)*(x3494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x3491)*(x3492)))+(((IkReal(-1.00000000000000))*(x3491)*(x3493)))+(((cj5)*(r22)))));
10898 sj3array[0]=IKsin(j3array[0]);
10899 cj3array[0]=IKcos(j3array[0]);
10900 if( j3array[0] > IKPI )
10901 {
10902     j3array[0]-=IK2PI;
10903 }
10904 else if( j3array[0] < -IKPI )
10905 {    j3array[0]+=IK2PI;
10906 }
10907 j3valid[0] = true;
10908 for(int ij3 = 0; ij3 < 1; ++ij3)
10909 {
10910 if( !j3valid[ij3] )
10911 {
10912     continue;
10913 }
10914 _ij3[0] = ij3; _ij3[1] = -1;
10915 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
10916 {
10917 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
10918 {
10919     j3valid[iij3]=false; _ij3[1] = iij3; break; 
10920 }
10921 }
10922 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
10923 {
10924 IkReal evalcond[6];
10925 IkReal x3495=IKsin(j3);
10926 IkReal x3496=IKcos(j3);
10927 IkReal x3497=((sj0)*(sj5));
10928 IkReal x3498=((r00)*(sj6));
10929 IkReal x3499=((IkReal(1.00000000000000))*(cj4));
10930 IkReal x3500=((cj6)*(r01));
10931 IkReal x3501=((cj0)*(cj5));
10932 IkReal x3502=((cj5)*(sj0));
10933 IkReal x3503=((cj6)*(r11));
10934 IkReal x3504=((cj0)*(sj5));
10935 IkReal x3505=((cj6)*(sj4));
10936 IkReal x3506=((cj4)*(cj5));
10937 IkReal x3507=((cj6)*(r21));
10938 IkReal x3508=((r20)*(sj6));
10939 IkReal x3509=((r10)*(sj6));
10940 IkReal x3510=((IkReal(1.00000000000000))*(cj0));
10941 IkReal x3511=((IkReal(1.00000000000000))*(x3495));
10942 IkReal x3512=((cj0)*(sj4)*(sj6));
10943 IkReal x3513=((sj0)*(sj4)*(sj6));
10944 evalcond[0]=((x3496)+(((sj5)*(x3508)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x3507))));
10945 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x3506)*(x3507)))+(x3495)+(((cj4)*(r22)*(sj5)))+(((x3506)*(x3508)))+(((r20)*(x3505))));
10946 evalcond[2]=((((IkReal(-1.00000000000000))*(x3503)*(x3504)))+(((IkReal(-1.00000000000000))*(x3504)*(x3509)))+(((IkReal(-1.00000000000000))*(r02)*(x3502)))+(((r12)*(x3501)))+(((x3497)*(x3500)))+(((x3497)*(x3498)))+(((IkReal(-1.00000000000000))*(sj2)*(x3511))));
10947 evalcond[3]=((((r02)*(x3501)))+(((IkReal(-1.00000000000000))*(x3497)*(x3509)))+(((IkReal(-1.00000000000000))*(x3498)*(x3504)))+(((IkReal(-1.00000000000000))*(x3500)*(x3504)))+(((IkReal(-1.00000000000000))*(x3497)*(x3503)))+(((IkReal(-1.00000000000000))*(cj2)*(x3511)))+(((r12)*(x3502))));
10948 evalcond[4]=((((cj4)*(r02)*(x3497)))+(((IkReal(-1.00000000000000))*(r10)*(x3505)*(x3510)))+(((IkReal(-1.00000000000000))*(x3499)*(x3501)*(x3509)))+(((r00)*(sj0)*(x3505)))+(((IkReal(-1.00000000000000))*(x3499)*(x3501)*(x3503)))+(((IkReal(-1.00000000000000))*(r01)*(x3513)))+(((r11)*(x3512)))+(((cj4)*(x3500)*(x3502)))+(((sj2)*(x3496)))+(((cj4)*(x3498)*(x3502)))+(((IkReal(-1.00000000000000))*(r12)*(x3499)*(x3504))));
10949 evalcond[5]=((((IkReal(-1.00000000000000))*(x3499)*(x3502)*(x3509)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3505)))+(((IkReal(-1.00000000000000))*(x3499)*(x3502)*(x3503)))+(((IkReal(-1.00000000000000))*(r02)*(x3499)*(x3504)))+(((IkReal(-1.00000000000000))*(x3498)*(x3499)*(x3501)))+(((r01)*(x3512)))+(((cj2)*(x3496)))+(((IkReal(-1.00000000000000))*(r12)*(x3497)*(x3499)))+(((r11)*(x3513)))+(((IkReal(-1.00000000000000))*(x3499)*(x3500)*(x3501)))+(((IkReal(-1.00000000000000))*(r00)*(x3505)*(x3510))));
10950 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
10951 {
10952 continue;
10953 }
10954 }
10955 
10956 {
10957 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
10958 vinfos[0].jointtype = 1;
10959 vinfos[0].foffset = j0;
10960 vinfos[0].indices[0] = _ij0[0];
10961 vinfos[0].indices[1] = _ij0[1];
10962 vinfos[0].maxsolutions = _nj0;
10963 vinfos[1].jointtype = 1;
10964 vinfos[1].foffset = j1;
10965 vinfos[1].indices[0] = _ij1[0];
10966 vinfos[1].indices[1] = _ij1[1];
10967 vinfos[1].maxsolutions = _nj1;
10968 vinfos[2].jointtype = 1;
10969 vinfos[2].foffset = j2;
10970 vinfos[2].indices[0] = _ij2[0];
10971 vinfos[2].indices[1] = _ij2[1];
10972 vinfos[2].maxsolutions = _nj2;
10973 vinfos[3].jointtype = 1;
10974 vinfos[3].foffset = j3;
10975 vinfos[3].indices[0] = _ij3[0];
10976 vinfos[3].indices[1] = _ij3[1];
10977 vinfos[3].maxsolutions = _nj3;
10978 vinfos[4].jointtype = 1;
10979 vinfos[4].foffset = j4;
10980 vinfos[4].indices[0] = _ij4[0];
10981 vinfos[4].indices[1] = _ij4[1];
10982 vinfos[4].maxsolutions = _nj4;
10983 vinfos[5].jointtype = 1;
10984 vinfos[5].foffset = j5;
10985 vinfos[5].indices[0] = _ij5[0];
10986 vinfos[5].indices[1] = _ij5[1];
10987 vinfos[5].maxsolutions = _nj5;
10988 vinfos[6].jointtype = 1;
10989 vinfos[6].foffset = j6;
10990 vinfos[6].indices[0] = _ij6[0];
10991 vinfos[6].indices[1] = _ij6[1];
10992 vinfos[6].maxsolutions = _nj6;
10993 std::vector<int> vfree(0);
10994 solutions.AddSolution(vinfos,vfree);
10995 }
10996 }
10997 }
10998 }
10999 }
11000 
11001 }
11002 
11003 }
11004 }
11005 }
11006 
11007 } else
11008 {
11009 if( 1 )
11010 {
11011 continue;
11012 
11013 } else
11014 {
11015 }
11016 }
11017 }
11018 }
11019 }
11020 }
11021 
11022 } else
11023 {
11024 {
11025 IkReal j2array[1], cj2array[1], sj2array[1];
11026 bool j2valid[1]={false};
11027 _nj2 = 1;
11028 IkReal x3514=((cj6)*(r01));
11029 IkReal x3515=((cj0)*(cj5));
11030 IkReal x3516=((sj0)*(sj5));
11031 IkReal x3517=((cj0)*(sj5));
11032 IkReal x3518=((cj6)*(r11));
11033 IkReal x3519=((r10)*(sj6));
11034 IkReal x3520=((cj5)*(sj0));
11035 IkReal x3521=((r00)*(sj6));
11036 if( IKabs(((((IkReal(-5.42449275362319))*(x3516)*(x3521)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(5.42449275362319))*(x3517)*(x3518)))+(((IkReal(-0.144927536231884))*(x3515)*(x3519)))+(((IkReal(5.42449275362319))*(x3517)*(x3519)))+(((IkReal(-0.144927536231884))*(r12)*(x3517)))+(((IkReal(0.144927536231884))*(x3514)*(x3520)))+(((IkReal(0.144927536231884))*(x3520)*(x3521)))+(((IkReal(-5.42449275362319))*(r12)*(x3515)))+(((IkReal(-0.144927536231884))*(x3515)*(x3518)))+(((IkReal(-5.42449275362319))*(x3514)*(x3516)))+(((IkReal(5.42449275362319))*(r02)*(x3520)))+(((IkReal(0.144927536231884))*(r02)*(x3516))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(0.0144927536231884))*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((IkReal(69.0000000000000))+(((IkReal(-374.290000000000))*(x3514)*(x3517)))+(((IkReal(10.0000000000000))*(x3515)*(x3521)))+(((IkReal(10.0000000000000))*(r02)*(x3517)))+(((IkReal(10.0000000000000))*(x3519)*(x3520)))+(((IkReal(-374.290000000000))*(x3517)*(x3521)))+(((IkReal(-1000.00000000000))*(cj0)*(px)))+(((IkReal(10.0000000000000))*(x3518)*(x3520)))+(((IkReal(364.420000000000))*(cj1)))+(((IkReal(10.0000000000000))*(x3514)*(x3515)))+(((IkReal(-374.290000000000))*(x3516)*(x3519)))+(((IkReal(-374.290000000000))*(x3516)*(x3518)))+(((IkReal(374.290000000000))*(r12)*(x3520)))+(((IkReal(374.290000000000))*(r02)*(x3515)))+(((IkReal(-1000.00000000000))*(py)*(sj0)))+(((IkReal(10.0000000000000))*(r12)*(x3516))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-5.42449275362319))*(x3516)*(x3521)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(5.42449275362319))*(x3517)*(x3518)))+(((IkReal(-0.144927536231884))*(x3515)*(x3519)))+(((IkReal(5.42449275362319))*(x3517)*(x3519)))+(((IkReal(-0.144927536231884))*(r12)*(x3517)))+(((IkReal(0.144927536231884))*(x3514)*(x3520)))+(((IkReal(0.144927536231884))*(x3520)*(x3521)))+(((IkReal(-5.42449275362319))*(r12)*(x3515)))+(((IkReal(-0.144927536231884))*(x3515)*(x3518)))+(((IkReal(-5.42449275362319))*(x3514)*(x3516)))+(((IkReal(5.42449275362319))*(r02)*(x3520)))+(((IkReal(0.144927536231884))*(r02)*(x3516)))))+IKsqr(((IkReal(0.0144927536231884))*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((IkReal(69.0000000000000))+(((IkReal(-374.290000000000))*(x3514)*(x3517)))+(((IkReal(10.0000000000000))*(x3515)*(x3521)))+(((IkReal(10.0000000000000))*(r02)*(x3517)))+(((IkReal(10.0000000000000))*(x3519)*(x3520)))+(((IkReal(-374.290000000000))*(x3517)*(x3521)))+(((IkReal(-1000.00000000000))*(cj0)*(px)))+(((IkReal(10.0000000000000))*(x3518)*(x3520)))+(((IkReal(364.420000000000))*(cj1)))+(((IkReal(10.0000000000000))*(x3514)*(x3515)))+(((IkReal(-374.290000000000))*(x3516)*(x3519)))+(((IkReal(-374.290000000000))*(x3516)*(x3518)))+(((IkReal(374.290000000000))*(r12)*(x3520)))+(((IkReal(374.290000000000))*(r02)*(x3515)))+(((IkReal(-1000.00000000000))*(py)*(sj0)))+(((IkReal(10.0000000000000))*(r12)*(x3516)))))))-1) <= IKFAST_SINCOS_THRESH )
11037     continue;
11038 j2array[0]=IKatan2(((((IkReal(-5.42449275362319))*(x3516)*(x3521)))+(((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(5.42449275362319))*(x3517)*(x3518)))+(((IkReal(-0.144927536231884))*(x3515)*(x3519)))+(((IkReal(5.42449275362319))*(x3517)*(x3519)))+(((IkReal(-0.144927536231884))*(r12)*(x3517)))+(((IkReal(0.144927536231884))*(x3514)*(x3520)))+(((IkReal(0.144927536231884))*(x3520)*(x3521)))+(((IkReal(-5.42449275362319))*(r12)*(x3515)))+(((IkReal(-0.144927536231884))*(x3515)*(x3518)))+(((IkReal(-5.42449275362319))*(x3514)*(x3516)))+(((IkReal(5.42449275362319))*(r02)*(x3520)))+(((IkReal(0.144927536231884))*(r02)*(x3516)))), ((IkReal(0.0144927536231884))*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((IkReal(69.0000000000000))+(((IkReal(-374.290000000000))*(x3514)*(x3517)))+(((IkReal(10.0000000000000))*(x3515)*(x3521)))+(((IkReal(10.0000000000000))*(r02)*(x3517)))+(((IkReal(10.0000000000000))*(x3519)*(x3520)))+(((IkReal(-374.290000000000))*(x3517)*(x3521)))+(((IkReal(-1000.00000000000))*(cj0)*(px)))+(((IkReal(10.0000000000000))*(x3518)*(x3520)))+(((IkReal(364.420000000000))*(cj1)))+(((IkReal(10.0000000000000))*(x3514)*(x3515)))+(((IkReal(-374.290000000000))*(x3516)*(x3519)))+(((IkReal(-374.290000000000))*(x3516)*(x3518)))+(((IkReal(374.290000000000))*(r12)*(x3520)))+(((IkReal(374.290000000000))*(r02)*(x3515)))+(((IkReal(-1000.00000000000))*(py)*(sj0)))+(((IkReal(10.0000000000000))*(r12)*(x3516)))))));
11039 sj2array[0]=IKsin(j2array[0]);
11040 cj2array[0]=IKcos(j2array[0]);
11041 if( j2array[0] > IKPI )
11042 {
11043     j2array[0]-=IK2PI;
11044 }
11045 else if( j2array[0] < -IKPI )
11046 {    j2array[0]+=IK2PI;
11047 }
11048 j2valid[0] = true;
11049 for(int ij2 = 0; ij2 < 1; ++ij2)
11050 {
11051 if( !j2valid[ij2] )
11052 {
11053     continue;
11054 }
11055 _ij2[0] = ij2; _ij2[1] = -1;
11056 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
11057 {
11058 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
11059 {
11060     j2valid[iij2]=false; _ij2[1] = iij2; break; 
11061 }
11062 }
11063 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
11064 {
11065 IkReal evalcond[3];
11066 IkReal x3522=IKcos(j2);
11067 IkReal x3523=((IkReal(0.374290000000000))*(sj5));
11068 IkReal x3524=((cj0)*(sj6));
11069 IkReal x3525=((IkReal(0.0100000000000000))*(sj5));
11070 IkReal x3526=((cj0)*(r02));
11071 IkReal x3527=((IkReal(0.0100000000000000))*(cj5));
11072 IkReal x3528=((IkReal(1.00000000000000))*(py));
11073 IkReal x3529=((r01)*(sj0));
11074 IkReal x3530=((r20)*(sj6));
11075 IkReal x3531=((r11)*(sj0));
11076 IkReal x3532=((IkReal(0.374290000000000))*(cj5));
11077 IkReal x3533=((cj0)*(r12));
11078 IkReal x3534=((sj0)*(x3532));
11079 IkReal x3535=((cj6)*(x3527));
11080 IkReal x3536=((IkReal(0.0690000000000000))*(x3522));
11081 IkReal x3537=((r10)*(sj0)*(sj6));
11082 IkReal x3538=((r00)*(sj0)*(sj6));
11083 IkReal x3539=((cj0)*(cj6)*(x3523));
11084 evalcond[0]=((((x3523)*(x3530)))+(((IkReal(0.364420000000000))*(sj1)))+(((cj1)*(x3536)))+(((IkReal(-1.00000000000000))*(r21)*(x3535)))+(((IkReal(-1.00000000000000))*(x3527)*(x3530)))+(((IkReal(-1.00000000000000))*(r22)*(x3532)))+(((cj6)*(r21)*(x3523)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x3525))));
11085 evalcond[1]=((((IkReal(-1.00000000000000))*(x3529)*(x3535)))+(((x3532)*(x3533)))+(((x3525)*(x3533)))+(((r10)*(x3524)*(x3527)))+(((IkReal(-1.00000000000000))*(r11)*(x3539)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3525)))+(((cj6)*(x3523)*(x3529)))+(((x3523)*(x3538)))+(((IkReal(-1.00000000000000))*(x3527)*(x3538)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(r10)*(x3523)*(x3524)))+(((IkReal(-1.00000000000000))*(r02)*(x3534)))+(((IkReal(-1.00000000000000))*(cj0)*(x3528)))+(((px)*(sj0)))+(((cj0)*(r11)*(x3535))));
11086 evalcond[2]=((IkReal(0.0690000000000000))+(((x3526)*(x3532)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(r01)*(x3539)))+(((x3527)*(x3537)))+(((r12)*(sj0)*(x3525)))+(((IkReal(-1.00000000000000))*(cj6)*(x3523)*(x3531)))+(((r00)*(x3524)*(x3527)))+(((IkReal(-1.00000000000000))*(x3523)*(x3537)))+(((IkReal(-1.00000000000000))*(sj0)*(x3528)))+(((x3525)*(x3526)))+(((cj0)*(r01)*(x3535)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(r00)*(x3523)*(x3524)))+(((r12)*(x3534)))+(((IkReal(-1.00000000000000))*(sj1)*(x3536)))+(((x3531)*(x3535))));
11087 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
11088 {
11089 continue;
11090 }
11091 }
11092 
11093 {
11094 IkReal dummyeval[1];
11095 IkReal gconst0;
11096 IkReal x3540=(cj6)*(cj6);
11097 IkReal x3541=(sj6)*(sj6);
11098 IkReal x3542=((IkReal(1.00000000000000))*(r01));
11099 IkReal x3543=((sj0)*(sj5));
11100 IkReal x3544=((cj6)*(r22));
11101 IkReal x3545=((r21)*(sj6));
11102 IkReal x3546=((r00)*(r21));
11103 IkReal x3547=((cj0)*(sj5));
11104 IkReal x3548=((cj6)*(r20));
11105 IkReal x3549=((r22)*(sj6));
11106 IkReal x3550=((cj0)*(cj5));
11107 IkReal x3551=((IkReal(1.00000000000000))*(r10));
11108 IkReal x3552=((cj5)*(sj0));
11109 IkReal x3553=((r20)*(x3541));
11110 IkReal x3554=((x3540)*(x3552));
11111 gconst0=IKsign(((((r00)*(x3543)*(x3544)))+(((x3546)*(x3554)))+(((IkReal(-1.00000000000000))*(x3544)*(x3547)*(x3551)))+(((IkReal(-1.00000000000000))*(r21)*(x3541)*(x3550)*(x3551)))+(((IkReal(-1.00000000000000))*(r12)*(x3545)*(x3547)))+(((IkReal(-1.00000000000000))*(r20)*(x3542)*(x3554)))+(((r11)*(x3547)*(x3549)))+(((r12)*(x3547)*(x3548)))+(((r11)*(x3550)*(x3553)))+(((r11)*(r20)*(x3540)*(x3550)))+(((IkReal(-1.00000000000000))*(x3542)*(x3552)*(x3553)))+(((IkReal(-1.00000000000000))*(r21)*(x3540)*(x3550)*(x3551)))+(((IkReal(-1.00000000000000))*(x3542)*(x3543)*(x3549)))+(((IkReal(-1.00000000000000))*(r02)*(x3543)*(x3548)))+(((r02)*(x3543)*(x3545)))+(((x3541)*(x3546)*(x3552)))));
11112 IkReal x3555=(cj6)*(cj6);
11113 IkReal x3556=(sj6)*(sj6);
11114 IkReal x3557=((IkReal(1.00000000000000))*(r01));
11115 IkReal x3558=((sj0)*(sj5));
11116 IkReal x3559=((cj6)*(r22));
11117 IkReal x3560=((r21)*(sj6));
11118 IkReal x3561=((r00)*(r21));
11119 IkReal x3562=((cj0)*(sj5));
11120 IkReal x3563=((cj6)*(r20));
11121 IkReal x3564=((r22)*(sj6));
11122 IkReal x3565=((cj0)*(cj5));
11123 IkReal x3566=((IkReal(1.00000000000000))*(r10));
11124 IkReal x3567=((cj5)*(sj0));
11125 IkReal x3568=((r20)*(x3556));
11126 IkReal x3569=((x3555)*(x3567));
11127 dummyeval[0]=((((r11)*(x3562)*(x3564)))+(((IkReal(-1.00000000000000))*(x3557)*(x3558)*(x3564)))+(((IkReal(-1.00000000000000))*(r02)*(x3558)*(x3563)))+(((IkReal(-1.00000000000000))*(r21)*(x3555)*(x3565)*(x3566)))+(((r11)*(r20)*(x3555)*(x3565)))+(((r00)*(x3558)*(x3559)))+(((IkReal(-1.00000000000000))*(r21)*(x3556)*(x3565)*(x3566)))+(((r11)*(x3565)*(x3568)))+(((x3561)*(x3569)))+(((IkReal(-1.00000000000000))*(x3559)*(x3562)*(x3566)))+(((r02)*(x3558)*(x3560)))+(((IkReal(-1.00000000000000))*(r12)*(x3560)*(x3562)))+(((IkReal(-1.00000000000000))*(r20)*(x3557)*(x3569)))+(((r12)*(x3562)*(x3563)))+(((x3556)*(x3561)*(x3567)))+(((IkReal(-1.00000000000000))*(x3557)*(x3567)*(x3568))));
11128 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11129 {
11130 {
11131 IkReal dummyeval[1];
11132 IkReal gconst1;
11133 IkReal x3570=(cj6)*(cj6);
11134 IkReal x3571=(sj6)*(sj6);
11135 IkReal x3572=((sj5)*(sj6));
11136 IkReal x3573=((IkReal(1.00000000000000))*(cj0));
11137 IkReal x3574=((cj6)*(sj5));
11138 IkReal x3575=((r20)*(sj0));
11139 IkReal x3576=((cj0)*(r20));
11140 IkReal x3577=((r00)*(r21));
11141 IkReal x3578=((r22)*(sj0));
11142 IkReal x3579=((IkReal(1.00000000000000))*(r21)*(sj0));
11143 IkReal x3580=((cj5)*(x3571));
11144 IkReal x3581=((cj5)*(x3570));
11145 gconst1=IKsign(((((IkReal(-1.00000000000000))*(x3573)*(x3577)*(x3580)))+(((IkReal(-1.00000000000000))*(r10)*(x3579)*(x3580)))+(((r02)*(x3574)*(x3576)))+(((r12)*(x3574)*(x3575)))+(((r11)*(x3575)*(x3580)))+(((IkReal(-1.00000000000000))*(r10)*(x3579)*(x3581)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3572)*(x3573)))+(((IkReal(-1.00000000000000))*(r10)*(x3574)*(x3578)))+(((r11)*(x3575)*(x3581)))+(((r01)*(x3576)*(x3580)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3573)*(x3574)))+(((r11)*(x3572)*(x3578)))+(((r01)*(x3576)*(x3581)))+(((cj0)*(r01)*(r22)*(x3572)))+(((IkReal(-1.00000000000000))*(r12)*(x3572)*(x3579)))+(((IkReal(-1.00000000000000))*(x3573)*(x3577)*(x3581)))));
11146 IkReal x3582=(cj6)*(cj6);
11147 IkReal x3583=(sj6)*(sj6);
11148 IkReal x3584=((sj5)*(sj6));
11149 IkReal x3585=((IkReal(1.00000000000000))*(cj0));
11150 IkReal x3586=((cj6)*(sj5));
11151 IkReal x3587=((r20)*(sj0));
11152 IkReal x3588=((cj0)*(r20));
11153 IkReal x3589=((r00)*(r21));
11154 IkReal x3590=((r22)*(sj0));
11155 IkReal x3591=((IkReal(1.00000000000000))*(r21)*(sj0));
11156 IkReal x3592=((cj5)*(x3583));
11157 IkReal x3593=((cj5)*(x3582));
11158 dummyeval[0]=((((r02)*(x3586)*(x3588)))+(((r11)*(x3584)*(x3590)))+(((r11)*(x3587)*(x3592)))+(((IkReal(-1.00000000000000))*(r10)*(x3591)*(x3593)))+(((IkReal(-1.00000000000000))*(r10)*(x3586)*(x3590)))+(((r01)*(x3588)*(x3593)))+(((IkReal(-1.00000000000000))*(r10)*(x3591)*(x3592)))+(((cj0)*(r01)*(r22)*(x3584)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3584)*(x3585)))+(((IkReal(-1.00000000000000))*(x3585)*(x3589)*(x3592)))+(((IkReal(-1.00000000000000))*(r12)*(x3584)*(x3591)))+(((r01)*(x3588)*(x3592)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3585)*(x3586)))+(((r11)*(x3587)*(x3593)))+(((r12)*(x3586)*(x3587)))+(((IkReal(-1.00000000000000))*(x3585)*(x3589)*(x3593))));
11159 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11160 {
11161 {
11162 IkReal dummyeval[2];
11163 IkReal x3594=(cj1)*(cj1);
11164 IkReal x3595=(sj1)*(sj1);
11165 dummyeval[0]=((((cj2)*(x3594)))+(((cj2)*(x3595))));
11166 dummyeval[1]=((x3595)+(x3594));
11167 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
11168 {
11169 {
11170 IkReal evalcond[4];
11171 IkReal x3596=((IkReal(0.374290000000000))*(sj5));
11172 IkReal x3597=((cj0)*(sj6));
11173 IkReal x3598=((IkReal(0.0100000000000000))*(sj5));
11174 IkReal x3599=((cj0)*(r02));
11175 IkReal x3600=((IkReal(0.0100000000000000))*(cj5));
11176 IkReal x3601=((IkReal(1.00000000000000))*(py));
11177 IkReal x3602=((r01)*(sj0));
11178 IkReal x3603=((r20)*(sj6));
11179 IkReal x3604=((r11)*(sj0));
11180 IkReal x3605=((IkReal(0.374290000000000))*(cj5));
11181 IkReal x3606=((cj0)*(r12));
11182 IkReal x3607=((sj0)*(x3605));
11183 IkReal x3608=((cj6)*(x3600));
11184 IkReal x3609=((r10)*(sj0)*(sj6));
11185 IkReal x3610=((r00)*(sj0)*(sj6));
11186 IkReal x3611=((cj0)*(cj6)*(x3596));
11187 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
11188 evalcond[1]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x3598)))+(((IkReal(-1.00000000000000))*(r21)*(x3608)))+(((cj6)*(r21)*(x3596)))+(((x3596)*(x3603)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x3605)))+(((IkReal(-1.00000000000000))*(x3600)*(x3603))));
11189 evalcond[2]=((IkReal(0.0690000000000000))+(((r10)*(x3597)*(x3600)))+(((IkReal(-1.00000000000000))*(x3600)*(x3610)))+(((IkReal(-1.00000000000000))*(cj0)*(x3601)))+(((x3596)*(x3610)))+(((cj0)*(r11)*(x3608)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3598)))+(((IkReal(-1.00000000000000))*(x3602)*(x3608)))+(((x3598)*(x3606)))+(((IkReal(-1.00000000000000))*(r11)*(x3611)))+(((x3605)*(x3606)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r02)*(x3607)))+(((cj6)*(x3596)*(x3602)))+(((IkReal(-1.00000000000000))*(r10)*(x3596)*(x3597))));
11190 evalcond[3]=((IkReal(0.0690000000000000))+(((x3599)*(x3605)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((r12)*(sj0)*(x3598)))+(((IkReal(-1.00000000000000))*(sj0)*(x3601)))+(((x3600)*(x3609)))+(((IkReal(-1.00000000000000))*(r01)*(x3611)))+(((IkReal(-1.00000000000000))*(x3596)*(x3609)))+(((x3604)*(x3608)))+(((cj0)*(r01)*(x3608)))+(((IkReal(-1.00000000000000))*(cj6)*(x3596)*(x3604)))+(((r00)*(x3597)*(x3600)))+(((IkReal(0.364420000000000))*(cj1)))+(((r12)*(x3607)))+(((IkReal(-1.00000000000000))*(r00)*(x3596)*(x3597)))+(((x3598)*(x3599))));
11191 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  )
11192 {
11193 {
11194 IkReal dummyeval[1];
11195 IkReal gconst13;
11196 IkReal x3612=(cj6)*(cj6);
11197 IkReal x3613=(sj6)*(sj6);
11198 IkReal x3614=((IkReal(1.00000000000000))*(r21));
11199 IkReal x3615=((cj6)*(r20));
11200 IkReal x3616=((r22)*(sj5));
11201 IkReal x3617=((r01)*(sj0));
11202 IkReal x3618=((r00)*(sj0));
11203 IkReal x3619=((cj0)*(r10));
11204 IkReal x3620=((r02)*(sj0)*(sj5));
11205 IkReal x3621=((cj5)*(x3612));
11206 IkReal x3622=((cj0)*(r12)*(sj5));
11207 IkReal x3623=((IkReal(1.00000000000000))*(cj0)*(r11));
11208 IkReal x3624=((cj5)*(x3613));
11209 IkReal x3625=((r20)*(x3624));
11210 gconst13=IKsign(((((r20)*(x3617)*(x3621)))+(((IkReal(-1.00000000000000))*(x3614)*(x3618)*(x3621)))+(((sj6)*(x3616)*(x3617)))+(((x3615)*(x3620)))+(((x3617)*(x3625)))+(((IkReal(-1.00000000000000))*(x3623)*(x3625)))+(((r21)*(sj6)*(x3622)))+(((r21)*(x3619)*(x3624)))+(((r21)*(x3619)*(x3621)))+(((IkReal(-1.00000000000000))*(x3614)*(x3618)*(x3624)))+(((IkReal(-1.00000000000000))*(sj6)*(x3614)*(x3620)))+(((cj6)*(x3616)*(x3619)))+(((IkReal(-1.00000000000000))*(sj6)*(x3616)*(x3623)))+(((IkReal(-1.00000000000000))*(cj6)*(x3616)*(x3618)))+(((IkReal(-1.00000000000000))*(r20)*(x3621)*(x3623)))+(((IkReal(-1.00000000000000))*(x3615)*(x3622)))));
11211 IkReal x3626=(cj6)*(cj6);
11212 IkReal x3627=(sj6)*(sj6);
11213 IkReal x3628=((IkReal(1.00000000000000))*(r21));
11214 IkReal x3629=((cj6)*(r20));
11215 IkReal x3630=((r22)*(sj5));
11216 IkReal x3631=((r01)*(sj0));
11217 IkReal x3632=((r00)*(sj0));
11218 IkReal x3633=((cj0)*(r10));
11219 IkReal x3634=((r02)*(sj0)*(sj5));
11220 IkReal x3635=((cj5)*(x3626));
11221 IkReal x3636=((cj0)*(r12)*(sj5));
11222 IkReal x3637=((IkReal(1.00000000000000))*(cj0)*(r11));
11223 IkReal x3638=((cj5)*(x3627));
11224 IkReal x3639=((r20)*(x3638));
11225 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3637)*(x3639)))+(((r21)*(sj6)*(x3636)))+(((IkReal(-1.00000000000000))*(sj6)*(x3630)*(x3637)))+(((sj6)*(x3630)*(x3631)))+(((IkReal(-1.00000000000000))*(x3628)*(x3632)*(x3635)))+(((cj6)*(x3630)*(x3633)))+(((IkReal(-1.00000000000000))*(x3629)*(x3636)))+(((IkReal(-1.00000000000000))*(sj6)*(x3628)*(x3634)))+(((x3631)*(x3639)))+(((r20)*(x3631)*(x3635)))+(((IkReal(-1.00000000000000))*(x3628)*(x3632)*(x3638)))+(((IkReal(-1.00000000000000))*(r20)*(x3635)*(x3637)))+(((r21)*(x3633)*(x3635)))+(((x3629)*(x3634)))+(((IkReal(-1.00000000000000))*(cj6)*(x3630)*(x3632)))+(((r21)*(x3633)*(x3638))));
11226 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11227 {
11228 {
11229 IkReal dummyeval[1];
11230 IkReal gconst14;
11231 IkReal x3640=(cj6)*(cj6);
11232 IkReal x3641=(sj6)*(sj6);
11233 IkReal x3642=((sj5)*(sj6));
11234 IkReal x3643=((IkReal(1.00000000000000))*(cj0));
11235 IkReal x3644=((cj6)*(sj5));
11236 IkReal x3645=((r20)*(sj0));
11237 IkReal x3646=((cj0)*(r20));
11238 IkReal x3647=((r00)*(r21));
11239 IkReal x3648=((r22)*(sj0));
11240 IkReal x3649=((IkReal(1.00000000000000))*(r21)*(sj0));
11241 IkReal x3650=((cj5)*(x3641));
11242 IkReal x3651=((cj5)*(x3640));
11243 gconst14=IKsign(((((cj0)*(r01)*(r22)*(x3642)))+(((r11)*(x3645)*(x3651)))+(((r01)*(x3646)*(x3651)))+(((IkReal(-1.00000000000000))*(x3643)*(x3647)*(x3650)))+(((r02)*(x3644)*(x3646)))+(((r12)*(x3644)*(x3645)))+(((r01)*(x3646)*(x3650)))+(((IkReal(-1.00000000000000))*(r10)*(x3649)*(x3651)))+(((r11)*(x3645)*(x3650)))+(((IkReal(-1.00000000000000))*(r12)*(x3642)*(x3649)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3643)*(x3644)))+(((IkReal(-1.00000000000000))*(r10)*(x3649)*(x3650)))+(((IkReal(-1.00000000000000))*(x3643)*(x3647)*(x3651)))+(((IkReal(-1.00000000000000))*(r10)*(x3644)*(x3648)))+(((r11)*(x3642)*(x3648)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3642)*(x3643)))));
11244 IkReal x3652=(cj6)*(cj6);
11245 IkReal x3653=(sj6)*(sj6);
11246 IkReal x3654=((sj5)*(sj6));
11247 IkReal x3655=((IkReal(1.00000000000000))*(cj0));
11248 IkReal x3656=((cj6)*(sj5));
11249 IkReal x3657=((r20)*(sj0));
11250 IkReal x3658=((cj0)*(r20));
11251 IkReal x3659=((r00)*(r21));
11252 IkReal x3660=((r22)*(sj0));
11253 IkReal x3661=((IkReal(1.00000000000000))*(r21)*(sj0));
11254 IkReal x3662=((cj5)*(x3653));
11255 IkReal x3663=((cj5)*(x3652));
11256 dummyeval[0]=((((cj0)*(r01)*(r22)*(x3654)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x3655)*(x3656)))+(((r11)*(x3657)*(x3663)))+(((r11)*(x3657)*(x3662)))+(((IkReal(-1.00000000000000))*(x3655)*(x3659)*(x3663)))+(((r12)*(x3656)*(x3657)))+(((IkReal(-1.00000000000000))*(r10)*(x3656)*(x3660)))+(((IkReal(-1.00000000000000))*(r12)*(x3654)*(x3661)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x3654)*(x3655)))+(((r01)*(x3658)*(x3662)))+(((r11)*(x3654)*(x3660)))+(((IkReal(-1.00000000000000))*(r10)*(x3661)*(x3663)))+(((r01)*(x3658)*(x3663)))+(((IkReal(-1.00000000000000))*(x3655)*(x3659)*(x3662)))+(((IkReal(-1.00000000000000))*(r10)*(x3661)*(x3662)))+(((r02)*(x3656)*(x3658))));
11257 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11258 {
11259 {
11260 IkReal dummyeval[1];
11261 dummyeval[0]=sj1;
11262 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11263 {
11264 {
11265 IkReal evalcond[5];
11266 IkReal x3664=((cj5)*(r22));
11267 IkReal x3665=((IkReal(0.374290000000000))*(sj5));
11268 IkReal x3666=((cj0)*(sj6));
11269 IkReal x3667=((cj6)*(r21));
11270 IkReal x3668=((IkReal(0.0100000000000000))*(sj5));
11271 IkReal x3669=((cj0)*(r02));
11272 IkReal x3670=((IkReal(0.0100000000000000))*(cj5));
11273 IkReal x3671=((IkReal(1.00000000000000))*(py));
11274 IkReal x3672=((r01)*(sj0));
11275 IkReal x3673=((r20)*(sj6));
11276 IkReal x3674=((r11)*(sj0));
11277 IkReal x3675=((IkReal(0.374290000000000))*(cj5));
11278 IkReal x3676=((cj0)*(r12));
11279 IkReal x3677=((sj0)*(x3675));
11280 IkReal x3678=((cj6)*(x3670));
11281 IkReal x3679=((r10)*(sj0)*(sj6));
11282 IkReal x3680=((r00)*(sj0)*(sj6));
11283 IkReal x3681=((cj0)*(cj6)*(x3665));
11284 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
11285 evalcond[1]=((((sj5)*(x3667)))+(((IkReal(-1.00000000000000))*(x3664)))+(((sj5)*(x3673))));
11286 evalcond[2]=((((IkReal(-1.00000000000000))*(x3670)*(x3673)))+(((IkReal(-1.00000000000000))*(r22)*(x3668)))+(pz)+(((x3665)*(x3673)))+(((IkReal(-0.374290000000000))*(x3664)))+(((IkReal(-1.00000000000000))*(x3667)*(x3670)))+(((x3665)*(x3667))));
11287 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x3671)))+(((x3668)*(x3676)))+(((IkReal(-1.00000000000000))*(r10)*(x3665)*(x3666)))+(((x3665)*(x3680)))+(((IkReal(-1.00000000000000))*(x3670)*(x3680)))+(((IkReal(-1.00000000000000))*(r02)*(x3677)))+(((cj0)*(r11)*(x3678)))+(((r10)*(x3666)*(x3670)))+(((x3675)*(x3676)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3668)))+(((IkReal(-1.00000000000000))*(x3672)*(x3678)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x3681)))+(((cj6)*(x3665)*(x3672))));
11288 evalcond[4]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(cj6)*(x3665)*(x3674)))+(((r12)*(x3677)))+(((x3674)*(x3678)))+(((x3668)*(x3669)))+(((IkReal(-1.00000000000000))*(sj0)*(x3671)))+(((x3670)*(x3679)))+(((IkReal(-1.00000000000000))*(r00)*(x3665)*(x3666)))+(((r00)*(x3666)*(x3670)))+(((IkReal(-1.00000000000000))*(r01)*(x3681)))+(((IkReal(-1.00000000000000))*(x3665)*(x3679)))+(((r12)*(sj0)*(x3668)))+(((x3669)*(x3675)))+(((cj0)*(r01)*(x3678))));
11289 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
11290 {
11291 {
11292 IkReal j3array[1], cj3array[1], sj3array[1];
11293 bool j3valid[1]={false};
11294 _nj3 = 1;
11295 IkReal x3682=((cj0)*(cj5));
11296 IkReal x3683=((IkReal(1.00000000000000))*(cj0));
11297 IkReal x3684=((cj6)*(r11));
11298 IkReal x3685=((r10)*(sj6));
11299 IkReal x3686=((cj5)*(sj0));
11300 IkReal x3687=((r00)*(sj5)*(sj6));
11301 IkReal x3688=((cj6)*(r01)*(sj5));
11302 IkReal x3689=((IkReal(1.00000000000000))*(sj0)*(sj5));
11303 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(x3686)))+(((sj0)*(x3687)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3684)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3685)))+(((r12)*(x3682)))+(((sj0)*(x3688))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r02)*(x3682)))+(((IkReal(-1.00000000000000))*(x3685)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3687)))+(((r12)*(x3686)))+(((IkReal(-1.00000000000000))*(x3684)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3688))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(x3686)))+(((sj0)*(x3687)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3684)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3685)))+(((r12)*(x3682)))+(((sj0)*(x3688)))))+IKsqr(((((r02)*(x3682)))+(((IkReal(-1.00000000000000))*(x3685)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3687)))+(((r12)*(x3686)))+(((IkReal(-1.00000000000000))*(x3684)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3688)))))-1) <= IKFAST_SINCOS_THRESH )
11304     continue;
11305 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(x3686)))+(((sj0)*(x3687)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3684)))+(((IkReal(-1.00000000000000))*(sj5)*(x3683)*(x3685)))+(((r12)*(x3682)))+(((sj0)*(x3688)))), ((((r02)*(x3682)))+(((IkReal(-1.00000000000000))*(x3685)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3687)))+(((r12)*(x3686)))+(((IkReal(-1.00000000000000))*(x3684)*(x3689)))+(((IkReal(-1.00000000000000))*(x3683)*(x3688)))));
11306 sj3array[0]=IKsin(j3array[0]);
11307 cj3array[0]=IKcos(j3array[0]);
11308 if( j3array[0] > IKPI )
11309 {
11310     j3array[0]-=IK2PI;
11311 }
11312 else if( j3array[0] < -IKPI )
11313 {    j3array[0]+=IK2PI;
11314 }
11315 j3valid[0] = true;
11316 for(int ij3 = 0; ij3 < 1; ++ij3)
11317 {
11318 if( !j3valid[ij3] )
11319 {
11320     continue;
11321 }
11322 _ij3[0] = ij3; _ij3[1] = -1;
11323 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11324 {
11325 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11326 {
11327     j3valid[iij3]=false; _ij3[1] = iij3; break; 
11328 }
11329 }
11330 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11331 {
11332 IkReal evalcond[2];
11333 IkReal x3690=((cj0)*(cj5));
11334 IkReal x3691=((IkReal(1.00000000000000))*(cj0));
11335 IkReal x3692=((cj6)*(r11));
11336 IkReal x3693=((r10)*(sj6));
11337 IkReal x3694=((cj5)*(sj0));
11338 IkReal x3695=((r00)*(sj5)*(sj6));
11339 IkReal x3696=((cj6)*(r01)*(sj5));
11340 IkReal x3697=((IkReal(1.00000000000000))*(sj0)*(sj5));
11341 evalcond[0]=((((IkReal(-1.00000000000000))*(sj5)*(x3691)*(x3692)))+(((sj0)*(x3696)))+(((IkReal(-1.00000000000000))*(sj5)*(x3691)*(x3693)))+(((IkReal(-1.00000000000000))*(r02)*(x3694)))+(((sj0)*(x3695)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((r12)*(x3690))));
11342 evalcond[1]=((((IkReal(-1.00000000000000))*(x3692)*(x3697)))+(((IkReal(-1.00000000000000))*(x3691)*(x3696)))+(((IkReal(-1.00000000000000))*(x3691)*(x3695)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(x3693)*(x3697)))+(((r02)*(x3690)))+(((r12)*(x3694))));
11343 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
11344 {
11345 continue;
11346 }
11347 }
11348 
11349 {
11350 IkReal dummyeval[1];
11351 IkReal gconst20;
11352 IkReal x3698=(cj5)*(cj5);
11353 IkReal x3699=(r20)*(r20);
11354 IkReal x3700=(sj6)*(sj6);
11355 IkReal x3701=(cj6)*(cj6);
11356 IkReal x3702=(r21)*(r21);
11357 IkReal x3703=((cj6)*(r21));
11358 IkReal x3704=((IkReal(2.00000000000000))*(r20)*(sj6));
11359 IkReal x3705=((cj5)*(r22)*(sj5));
11360 gconst20=IKsign(((((x3698)*(x3699)*(x3700)))+(((x3700)*(x3702)))+(((x3704)*(x3705)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3698)*(x3703)*(x3704)))+(((x3698)*(x3701)*(x3702)))+(((x3699)*(x3701)))+(((IkReal(-1.00000000000000))*(x3703)*(x3704)))+(((IkReal(2.00000000000000))*(x3703)*(x3705)))));
11361 IkReal x3706=(cj5)*(cj5);
11362 IkReal x3707=(r20)*(r20);
11363 IkReal x3708=(sj6)*(sj6);
11364 IkReal x3709=(cj6)*(cj6);
11365 IkReal x3710=(r21)*(r21);
11366 IkReal x3711=((cj6)*(r21));
11367 IkReal x3712=((IkReal(2.00000000000000))*(r20)*(sj6));
11368 IkReal x3713=((cj5)*(r22)*(sj5));
11369 dummyeval[0]=((((x3706)*(x3707)*(x3708)))+(((IkReal(2.00000000000000))*(x3711)*(x3713)))+(((x3707)*(x3709)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x3706)*(x3709)*(x3710)))+(((IkReal(-1.00000000000000))*(x3711)*(x3712)))+(((x3712)*(x3713)))+(((x3708)*(x3710)))+(((x3706)*(x3711)*(x3712))));
11370 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11371 {
11372 {
11373 IkReal dummyeval[1];
11374 IkReal gconst21;
11375 IkReal x3714=(cj6)*(cj6);
11376 IkReal x3715=(sj6)*(sj6);
11377 IkReal x3716=((IkReal(1.00000000000000))*(r21));
11378 IkReal x3717=((cj6)*(r20));
11379 IkReal x3718=((r22)*(sj5));
11380 IkReal x3719=((r01)*(sj0));
11381 IkReal x3720=((r00)*(sj0));
11382 IkReal x3721=((cj0)*(r10));
11383 IkReal x3722=((r02)*(sj0)*(sj5));
11384 IkReal x3723=((cj5)*(x3714));
11385 IkReal x3724=((cj0)*(r12)*(sj5));
11386 IkReal x3725=((IkReal(1.00000000000000))*(cj0)*(r11));
11387 IkReal x3726=((cj5)*(x3715));
11388 IkReal x3727=((r20)*(x3726));
11389 gconst21=IKsign(((((IkReal(-1.00000000000000))*(r20)*(x3723)*(x3725)))+(((cj6)*(x3718)*(x3721)))+(((IkReal(-1.00000000000000))*(x3717)*(x3724)))+(((IkReal(-1.00000000000000))*(cj6)*(x3718)*(x3720)))+(((IkReal(-1.00000000000000))*(sj6)*(x3718)*(x3725)))+(((IkReal(-1.00000000000000))*(sj6)*(x3716)*(x3722)))+(((r21)*(sj6)*(x3724)))+(((x3717)*(x3722)))+(((r20)*(x3719)*(x3723)))+(((r21)*(x3721)*(x3726)))+(((x3719)*(x3727)))+(((IkReal(-1.00000000000000))*(x3725)*(x3727)))+(((r21)*(x3721)*(x3723)))+(((IkReal(-1.00000000000000))*(x3716)*(x3720)*(x3726)))+(((IkReal(-1.00000000000000))*(x3716)*(x3720)*(x3723)))+(((sj6)*(x3718)*(x3719)))));
11390 IkReal x3728=(cj6)*(cj6);
11391 IkReal x3729=(sj6)*(sj6);
11392 IkReal x3730=((IkReal(1.00000000000000))*(r21));
11393 IkReal x3731=((cj6)*(r20));
11394 IkReal x3732=((r22)*(sj5));
11395 IkReal x3733=((r01)*(sj0));
11396 IkReal x3734=((r00)*(sj0));
11397 IkReal x3735=((cj0)*(r10));
11398 IkReal x3736=((r02)*(sj0)*(sj5));
11399 IkReal x3737=((cj5)*(x3728));
11400 IkReal x3738=((cj0)*(r12)*(sj5));
11401 IkReal x3739=((IkReal(1.00000000000000))*(cj0)*(r11));
11402 IkReal x3740=((cj5)*(x3729));
11403 IkReal x3741=((r20)*(x3740));
11404 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3730)*(x3734)*(x3737)))+(((sj6)*(x3732)*(x3733)))+(((x3731)*(x3736)))+(((r21)*(sj6)*(x3738)))+(((cj6)*(x3732)*(x3735)))+(((r21)*(x3735)*(x3740)))+(((r20)*(x3733)*(x3737)))+(((IkReal(-1.00000000000000))*(x3731)*(x3738)))+(((IkReal(-1.00000000000000))*(x3739)*(x3741)))+(((r21)*(x3735)*(x3737)))+(((x3733)*(x3741)))+(((IkReal(-1.00000000000000))*(sj6)*(x3730)*(x3736)))+(((IkReal(-1.00000000000000))*(r20)*(x3737)*(x3739)))+(((IkReal(-1.00000000000000))*(x3730)*(x3734)*(x3740)))+(((IkReal(-1.00000000000000))*(cj6)*(x3732)*(x3734)))+(((IkReal(-1.00000000000000))*(sj6)*(x3732)*(x3739))));
11405 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11406 {
11407 continue;
11408 
11409 } else
11410 {
11411 {
11412 IkReal j4array[1], cj4array[1], sj4array[1];
11413 bool j4valid[1]={false};
11414 _nj4 = 1;
11415 IkReal x3742=((sj0)*(sj6));
11416 IkReal x3743=((cj0)*(cj6));
11417 IkReal x3744=((IkReal(1.00000000000000))*(cj5));
11418 IkReal x3745=((cj6)*(sj0));
11419 IkReal x3746=((cj0)*(sj6));
11420 if( IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(r00)*(x3745)))+(((IkReal(-1.00000000000000))*(r11)*(x3746)))+(((r10)*(x3743)))+(((r01)*(x3742))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((cj5)*(r11)*(x3743)))+(((IkReal(-1.00000000000000))*(r00)*(x3742)*(x3744)))+(((IkReal(-1.00000000000000))*(r01)*(x3744)*(x3745)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(r10)*(x3746))))))) < IKFAST_ATAN2_MAGTHRESH )
11421     continue;
11422 j4array[0]=IKatan2(((gconst21)*(((((IkReal(-1.00000000000000))*(r00)*(x3745)))+(((IkReal(-1.00000000000000))*(r11)*(x3746)))+(((r10)*(x3743)))+(((r01)*(x3742)))))), ((gconst21)*(((((cj5)*(r11)*(x3743)))+(((IkReal(-1.00000000000000))*(r00)*(x3742)*(x3744)))+(((IkReal(-1.00000000000000))*(r01)*(x3744)*(x3745)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(r10)*(x3746)))))));
11423 sj4array[0]=IKsin(j4array[0]);
11424 cj4array[0]=IKcos(j4array[0]);
11425 if( j4array[0] > IKPI )
11426 {
11427     j4array[0]-=IK2PI;
11428 }
11429 else if( j4array[0] < -IKPI )
11430 {    j4array[0]+=IK2PI;
11431 }
11432 j4valid[0] = true;
11433 for(int ij4 = 0; ij4 < 1; ++ij4)
11434 {
11435 if( !j4valid[ij4] )
11436 {
11437     continue;
11438 }
11439 _ij4[0] = ij4; _ij4[1] = -1;
11440 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11441 {
11442 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11443 {
11444     j4valid[iij4]=false; _ij4[1] = iij4; break; 
11445 }
11446 }
11447 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11448 {
11449 IkReal evalcond[6];
11450 IkReal x3747=IKsin(j4);
11451 IkReal x3748=IKcos(j4);
11452 IkReal x3749=((r22)*(sj5));
11453 IkReal x3750=((IkReal(1.00000000000000))*(cj6));
11454 IkReal x3751=((IkReal(1.00000000000000))*(cj0));
11455 IkReal x3752=((cj5)*(r11));
11456 IkReal x3753=((cj5)*(cj6));
11457 IkReal x3754=((r11)*(sj6));
11458 IkReal x3755=((IkReal(1.00000000000000))*(sj6));
11459 IkReal x3756=((cj6)*(r00));
11460 IkReal x3757=((r12)*(sj5));
11461 IkReal x3758=((r02)*(sj5));
11462 IkReal x3759=((cj6)*(r10));
11463 IkReal x3760=((cj5)*(sj6));
11464 IkReal x3761=((cj5)*(r01));
11465 IkReal x3762=((sj0)*(x3747));
11466 IkReal x3763=((r00)*(x3760));
11467 IkReal x3764=((cj0)*(x3747));
11468 IkReal x3765=((sj0)*(x3748));
11469 IkReal x3766=((r20)*(x3748));
11470 IkReal x3767=((cj0)*(x3748));
11471 IkReal x3768=((r21)*(x3747));
11472 IkReal x3769=((r21)*(x3748));
11473 IkReal x3770=((r20)*(x3747));
11474 IkReal x3771=((x3748)*(x3757));
11475 IkReal x3772=((r01)*(sj6)*(x3748));
11476 IkReal x3773=((cj5)*(r10)*(x3755));
11477 evalcond[0]=((IkReal(-1.00000000000000))+(((x3753)*(x3768)))+(((x3747)*(x3749)))+(((x3760)*(x3770)))+(((sj6)*(x3769)))+(((IkReal(-1.00000000000000))*(x3750)*(x3766))));
11478 evalcond[1]=((((cj6)*(x3770)))+(((x3753)*(x3769)))+(((x3760)*(x3766)))+(((x3748)*(x3749)))+(((IkReal(-1.00000000000000))*(x3755)*(x3768))));
11479 evalcond[2]=((((x3759)*(x3767)))+(((x3762)*(x3763)))+(((r01)*(sj6)*(x3765)))+(((IkReal(-1.00000000000000))*(x3748)*(x3751)*(x3754)))+(((r01)*(x3753)*(x3762)))+(((IkReal(-1.00000000000000))*(r00)*(x3750)*(x3765)))+(((IkReal(-1.00000000000000))*(x3750)*(x3752)*(x3764)))+(((x3758)*(x3762)))+(((IkReal(-1.00000000000000))*(x3747)*(x3751)*(x3757)))+(((IkReal(-1.00000000000000))*(r10)*(x3747)*(x3751)*(x3760))));
11480 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x3750)*(x3764)))+(((IkReal(-1.00000000000000))*(x3750)*(x3752)*(x3767)))+(((IkReal(-1.00000000000000))*(r01)*(x3755)*(x3762)))+(((x3754)*(x3764)))+(((IkReal(-1.00000000000000))*(x3751)*(x3771)))+(((x3756)*(x3762)))+(cj3)+(((IkReal(-1.00000000000000))*(r10)*(x3748)*(x3751)*(x3760)))+(((r01)*(x3753)*(x3765)))+(((x3758)*(x3765)))+(((x3763)*(x3765))));
11481 evalcond[4]=((((IkReal(-1.00000000000000))*(x3750)*(x3752)*(x3762)))+(((IkReal(-1.00000000000000))*(x3747)*(x3751)*(x3758)))+(((IkReal(-1.00000000000000))*(x3762)*(x3773)))+(((IkReal(-1.00000000000000))*(x3757)*(x3762)))+(((IkReal(-1.00000000000000))*(x3754)*(x3765)))+(((IkReal(-1.00000000000000))*(x3750)*(x3761)*(x3764)))+(((IkReal(-1.00000000000000))*(x3751)*(x3772)))+(((x3759)*(x3765)))+(((IkReal(-1.00000000000000))*(x3747)*(x3751)*(x3763)))+(((x3756)*(x3767))));
11482 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3750)*(x3762)))+(((IkReal(-1.00000000000000))*(x3757)*(x3765)))+(((IkReal(-1.00000000000000))*(x3750)*(x3752)*(x3765)))+(((IkReal(-1.00000000000000))*(x3748)*(x3751)*(x3758)))+(((IkReal(-1.00000000000000))*(r00)*(x3750)*(x3764)))+(((IkReal(-1.00000000000000))*(x3750)*(x3761)*(x3767)))+(((IkReal(-1.00000000000000))*(x3765)*(x3773)))+(((x3754)*(x3762)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x3748)*(x3751)*(x3763)))+(((r01)*(sj6)*(x3764))));
11483 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
11484 {
11485 continue;
11486 }
11487 }
11488 
11489 {
11490 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
11491 vinfos[0].jointtype = 1;
11492 vinfos[0].foffset = j0;
11493 vinfos[0].indices[0] = _ij0[0];
11494 vinfos[0].indices[1] = _ij0[1];
11495 vinfos[0].maxsolutions = _nj0;
11496 vinfos[1].jointtype = 1;
11497 vinfos[1].foffset = j1;
11498 vinfos[1].indices[0] = _ij1[0];
11499 vinfos[1].indices[1] = _ij1[1];
11500 vinfos[1].maxsolutions = _nj1;
11501 vinfos[2].jointtype = 1;
11502 vinfos[2].foffset = j2;
11503 vinfos[2].indices[0] = _ij2[0];
11504 vinfos[2].indices[1] = _ij2[1];
11505 vinfos[2].maxsolutions = _nj2;
11506 vinfos[3].jointtype = 1;
11507 vinfos[3].foffset = j3;
11508 vinfos[3].indices[0] = _ij3[0];
11509 vinfos[3].indices[1] = _ij3[1];
11510 vinfos[3].maxsolutions = _nj3;
11511 vinfos[4].jointtype = 1;
11512 vinfos[4].foffset = j4;
11513 vinfos[4].indices[0] = _ij4[0];
11514 vinfos[4].indices[1] = _ij4[1];
11515 vinfos[4].maxsolutions = _nj4;
11516 vinfos[5].jointtype = 1;
11517 vinfos[5].foffset = j5;
11518 vinfos[5].indices[0] = _ij5[0];
11519 vinfos[5].indices[1] = _ij5[1];
11520 vinfos[5].maxsolutions = _nj5;
11521 vinfos[6].jointtype = 1;
11522 vinfos[6].foffset = j6;
11523 vinfos[6].indices[0] = _ij6[0];
11524 vinfos[6].indices[1] = _ij6[1];
11525 vinfos[6].maxsolutions = _nj6;
11526 std::vector<int> vfree(0);
11527 solutions.AddSolution(vinfos,vfree);
11528 }
11529 }
11530 }
11531 
11532 }
11533 
11534 }
11535 
11536 } else
11537 {
11538 {
11539 IkReal j4array[1], cj4array[1], sj4array[1];
11540 bool j4valid[1]={false};
11541 _nj4 = 1;
11542 if( IKabs(((gconst20)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst20)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
11543     continue;
11544 j4array[0]=IKatan2(((gconst20)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst20)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
11545 sj4array[0]=IKsin(j4array[0]);
11546 cj4array[0]=IKcos(j4array[0]);
11547 if( j4array[0] > IKPI )
11548 {
11549     j4array[0]-=IK2PI;
11550 }
11551 else if( j4array[0] < -IKPI )
11552 {    j4array[0]+=IK2PI;
11553 }
11554 j4valid[0] = true;
11555 for(int ij4 = 0; ij4 < 1; ++ij4)
11556 {
11557 if( !j4valid[ij4] )
11558 {
11559     continue;
11560 }
11561 _ij4[0] = ij4; _ij4[1] = -1;
11562 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11563 {
11564 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11565 {
11566     j4valid[iij4]=false; _ij4[1] = iij4; break; 
11567 }
11568 }
11569 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11570 {
11571 IkReal evalcond[6];
11572 IkReal x3774=IKsin(j4);
11573 IkReal x3775=IKcos(j4);
11574 IkReal x3776=((r22)*(sj5));
11575 IkReal x3777=((IkReal(1.00000000000000))*(cj6));
11576 IkReal x3778=((IkReal(1.00000000000000))*(cj0));
11577 IkReal x3779=((cj5)*(r11));
11578 IkReal x3780=((cj5)*(cj6));
11579 IkReal x3781=((r11)*(sj6));
11580 IkReal x3782=((IkReal(1.00000000000000))*(sj6));
11581 IkReal x3783=((cj6)*(r00));
11582 IkReal x3784=((r12)*(sj5));
11583 IkReal x3785=((r02)*(sj5));
11584 IkReal x3786=((cj6)*(r10));
11585 IkReal x3787=((cj5)*(sj6));
11586 IkReal x3788=((cj5)*(r01));
11587 IkReal x3789=((sj0)*(x3774));
11588 IkReal x3790=((r00)*(x3787));
11589 IkReal x3791=((cj0)*(x3774));
11590 IkReal x3792=((sj0)*(x3775));
11591 IkReal x3793=((r20)*(x3775));
11592 IkReal x3794=((cj0)*(x3775));
11593 IkReal x3795=((r21)*(x3774));
11594 IkReal x3796=((r21)*(x3775));
11595 IkReal x3797=((r20)*(x3774));
11596 IkReal x3798=((x3775)*(x3784));
11597 IkReal x3799=((r01)*(sj6)*(x3775));
11598 IkReal x3800=((cj5)*(r10)*(x3782));
11599 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x3777)*(x3793)))+(((x3787)*(x3797)))+(((x3780)*(x3795)))+(((x3774)*(x3776)))+(((sj6)*(x3796))));
11600 evalcond[1]=((((x3787)*(x3793)))+(((IkReal(-1.00000000000000))*(x3782)*(x3795)))+(((x3775)*(x3776)))+(((x3780)*(x3796)))+(((cj6)*(x3797))));
11601 evalcond[2]=((((x3789)*(x3790)))+(((IkReal(-1.00000000000000))*(x3775)*(x3778)*(x3781)))+(((x3785)*(x3789)))+(((IkReal(-1.00000000000000))*(x3774)*(x3778)*(x3784)))+(((r01)*(sj6)*(x3792)))+(((r01)*(x3780)*(x3789)))+(((x3786)*(x3794)))+(((IkReal(-1.00000000000000))*(r00)*(x3777)*(x3792)))+(((IkReal(-1.00000000000000))*(x3777)*(x3779)*(x3791)))+(((IkReal(-1.00000000000000))*(r10)*(x3774)*(x3778)*(x3787))));
11602 evalcond[3]=((((x3785)*(x3792)))+(((IkReal(-1.00000000000000))*(r10)*(x3775)*(x3778)*(x3787)))+(((IkReal(-1.00000000000000))*(x3778)*(x3798)))+(((x3783)*(x3789)))+(cj3)+(((IkReal(-1.00000000000000))*(x3777)*(x3779)*(x3794)))+(((IkReal(-1.00000000000000))*(r10)*(x3777)*(x3791)))+(((r01)*(x3780)*(x3792)))+(((x3781)*(x3791)))+(((x3790)*(x3792)))+(((IkReal(-1.00000000000000))*(r01)*(x3782)*(x3789))));
11603 evalcond[4]=((((IkReal(-1.00000000000000))*(x3774)*(x3778)*(x3785)))+(((x3786)*(x3792)))+(((IkReal(-1.00000000000000))*(x3784)*(x3789)))+(((IkReal(-1.00000000000000))*(x3777)*(x3788)*(x3791)))+(((IkReal(-1.00000000000000))*(x3778)*(x3799)))+(((IkReal(-1.00000000000000))*(x3774)*(x3778)*(x3790)))+(((IkReal(-1.00000000000000))*(x3789)*(x3800)))+(((IkReal(-1.00000000000000))*(x3777)*(x3779)*(x3789)))+(((IkReal(-1.00000000000000))*(x3781)*(x3792)))+(((x3783)*(x3794))));
11604 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3777)*(x3789)))+(((IkReal(-1.00000000000000))*(x3784)*(x3792)))+(((r01)*(sj6)*(x3791)))+(((IkReal(-1.00000000000000))*(x3792)*(x3800)))+(((x3781)*(x3789)))+(((IkReal(-1.00000000000000))*(x3775)*(x3778)*(x3790)))+(((IkReal(-1.00000000000000))*(x3777)*(x3779)*(x3792)))+(((IkReal(-1.00000000000000))*(x3777)*(x3788)*(x3794)))+(((IkReal(-1.00000000000000))*(x3775)*(x3778)*(x3785)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r00)*(x3777)*(x3791))));
11605 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
11606 {
11607 continue;
11608 }
11609 }
11610 
11611 {
11612 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
11613 vinfos[0].jointtype = 1;
11614 vinfos[0].foffset = j0;
11615 vinfos[0].indices[0] = _ij0[0];
11616 vinfos[0].indices[1] = _ij0[1];
11617 vinfos[0].maxsolutions = _nj0;
11618 vinfos[1].jointtype = 1;
11619 vinfos[1].foffset = j1;
11620 vinfos[1].indices[0] = _ij1[0];
11621 vinfos[1].indices[1] = _ij1[1];
11622 vinfos[1].maxsolutions = _nj1;
11623 vinfos[2].jointtype = 1;
11624 vinfos[2].foffset = j2;
11625 vinfos[2].indices[0] = _ij2[0];
11626 vinfos[2].indices[1] = _ij2[1];
11627 vinfos[2].maxsolutions = _nj2;
11628 vinfos[3].jointtype = 1;
11629 vinfos[3].foffset = j3;
11630 vinfos[3].indices[0] = _ij3[0];
11631 vinfos[3].indices[1] = _ij3[1];
11632 vinfos[3].maxsolutions = _nj3;
11633 vinfos[4].jointtype = 1;
11634 vinfos[4].foffset = j4;
11635 vinfos[4].indices[0] = _ij4[0];
11636 vinfos[4].indices[1] = _ij4[1];
11637 vinfos[4].maxsolutions = _nj4;
11638 vinfos[5].jointtype = 1;
11639 vinfos[5].foffset = j5;
11640 vinfos[5].indices[0] = _ij5[0];
11641 vinfos[5].indices[1] = _ij5[1];
11642 vinfos[5].maxsolutions = _nj5;
11643 vinfos[6].jointtype = 1;
11644 vinfos[6].foffset = j6;
11645 vinfos[6].indices[0] = _ij6[0];
11646 vinfos[6].indices[1] = _ij6[1];
11647 vinfos[6].maxsolutions = _nj6;
11648 std::vector<int> vfree(0);
11649 solutions.AddSolution(vinfos,vfree);
11650 }
11651 }
11652 }
11653 
11654 }
11655 
11656 }
11657 }
11658 }
11659 
11660 } else
11661 {
11662 IkReal x3801=((cj5)*(r22));
11663 IkReal x3802=((IkReal(0.374290000000000))*(sj5));
11664 IkReal x3803=((cj0)*(sj6));
11665 IkReal x3804=((cj6)*(r21));
11666 IkReal x3805=((IkReal(0.0100000000000000))*(sj5));
11667 IkReal x3806=((cj0)*(r02));
11668 IkReal x3807=((IkReal(0.0100000000000000))*(cj5));
11669 IkReal x3808=((IkReal(1.00000000000000))*(py));
11670 IkReal x3809=((r01)*(sj0));
11671 IkReal x3810=((r20)*(sj6));
11672 IkReal x3811=((r11)*(sj0));
11673 IkReal x3812=((IkReal(0.374290000000000))*(cj5));
11674 IkReal x3813=((cj0)*(r12));
11675 IkReal x3814=((sj0)*(x3812));
11676 IkReal x3815=((cj6)*(x3807));
11677 IkReal x3816=((r10)*(sj0)*(sj6));
11678 IkReal x3817=((r00)*(sj0)*(sj6));
11679 IkReal x3818=((cj0)*(cj6)*(x3802));
11680 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
11681 evalcond[1]=((((sj5)*(x3804)))+(((sj5)*(x3810)))+(((IkReal(-1.00000000000000))*(x3801))));
11682 evalcond[2]=((((IkReal(-1.00000000000000))*(x3807)*(x3810)))+(((IkReal(-0.374290000000000))*(x3801)))+(((x3802)*(x3810)))+(((IkReal(-1.00000000000000))*(x3804)*(x3807)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x3805)))+(((x3802)*(x3804))));
11683 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r02)*(x3814)))+(((x3805)*(x3813)))+(((IkReal(-1.00000000000000))*(r11)*(x3818)))+(((x3802)*(x3817)))+(((x3812)*(x3813)))+(((IkReal(-1.00000000000000))*(cj0)*(x3808)))+(((IkReal(-1.00000000000000))*(r10)*(x3802)*(x3803)))+(((cj0)*(r11)*(x3815)))+(((IkReal(-1.00000000000000))*(x3809)*(x3815)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3805)))+(((IkReal(-1.00000000000000))*(x3807)*(x3817)))+(((cj6)*(x3802)*(x3809)))+(((px)*(sj0)))+(((r10)*(x3803)*(x3807))));
11684 evalcond[4]=((IkReal(-0.295420000000000))+(((r12)*(x3814)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x3805)*(x3806)))+(((IkReal(-1.00000000000000))*(cj6)*(x3802)*(x3811)))+(((x3811)*(x3815)))+(((IkReal(-1.00000000000000))*(x3802)*(x3816)))+(((x3807)*(x3816)))+(((r12)*(sj0)*(x3805)))+(((r00)*(x3803)*(x3807)))+(((IkReal(-1.00000000000000))*(r00)*(x3802)*(x3803)))+(((IkReal(-1.00000000000000))*(r01)*(x3818)))+(((cj0)*(r01)*(x3815)))+(((IkReal(-1.00000000000000))*(sj0)*(x3808)))+(((x3806)*(x3812))));
11685 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
11686 {
11687 {
11688 IkReal j3array[1], cj3array[1], sj3array[1];
11689 bool j3valid[1]={false};
11690 _nj3 = 1;
11691 IkReal x3819=((sj0)*(sj5));
11692 IkReal x3820=((r00)*(sj6));
11693 IkReal x3821=((IkReal(1.00000000000000))*(cj5));
11694 IkReal x3822=((cj6)*(r11));
11695 IkReal x3823=((cj6)*(r01));
11696 IkReal x3824=((r10)*(sj6));
11697 IkReal x3825=((cj0)*(sj5));
11698 if( IKabs(((((x3819)*(x3820)))+(((IkReal(-1.00000000000000))*(x3822)*(x3825)))+(((IkReal(-1.00000000000000))*(x3824)*(x3825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3821)))+(((cj0)*(cj5)*(r12)))+(((x3819)*(x3823))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x3823)*(x3825)))+(((x3820)*(x3825)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3821)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3821)))+(((x3819)*(x3822)))+(((x3819)*(x3824))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x3819)*(x3820)))+(((IkReal(-1.00000000000000))*(x3822)*(x3825)))+(((IkReal(-1.00000000000000))*(x3824)*(x3825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3821)))+(((cj0)*(cj5)*(r12)))+(((x3819)*(x3823)))))+IKsqr(((((x3823)*(x3825)))+(((x3820)*(x3825)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3821)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3821)))+(((x3819)*(x3822)))+(((x3819)*(x3824)))))-1) <= IKFAST_SINCOS_THRESH )
11699     continue;
11700 j3array[0]=IKatan2(((((x3819)*(x3820)))+(((IkReal(-1.00000000000000))*(x3822)*(x3825)))+(((IkReal(-1.00000000000000))*(x3824)*(x3825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3821)))+(((cj0)*(cj5)*(r12)))+(((x3819)*(x3823)))), ((((x3823)*(x3825)))+(((x3820)*(x3825)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x3821)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x3821)))+(((x3819)*(x3822)))+(((x3819)*(x3824)))));
11701 sj3array[0]=IKsin(j3array[0]);
11702 cj3array[0]=IKcos(j3array[0]);
11703 if( j3array[0] > IKPI )
11704 {
11705     j3array[0]-=IK2PI;
11706 }
11707 else if( j3array[0] < -IKPI )
11708 {    j3array[0]+=IK2PI;
11709 }
11710 j3valid[0] = true;
11711 for(int ij3 = 0; ij3 < 1; ++ij3)
11712 {
11713 if( !j3valid[ij3] )
11714 {
11715     continue;
11716 }
11717 _ij3[0] = ij3; _ij3[1] = -1;
11718 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
11719 {
11720 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
11721 {
11722     j3valid[iij3]=false; _ij3[1] = iij3; break; 
11723 }
11724 }
11725 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
11726 {
11727 IkReal evalcond[2];
11728 IkReal x3826=((cj0)*(cj5));
11729 IkReal x3827=((IkReal(1.00000000000000))*(cj0));
11730 IkReal x3828=((cj6)*(r11));
11731 IkReal x3829=((r10)*(sj6));
11732 IkReal x3830=((cj5)*(sj0));
11733 IkReal x3831=((r00)*(sj5)*(sj6));
11734 IkReal x3832=((cj6)*(r01)*(sj5));
11735 IkReal x3833=((IkReal(1.00000000000000))*(sj0)*(sj5));
11736 evalcond[0]=((((IkReal(-1.00000000000000))*(sj5)*(x3827)*(x3828)))+(((IkReal(-1.00000000000000))*(r02)*(x3830)))+(((IkReal(-1.00000000000000))*(sj5)*(x3827)*(x3829)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((sj0)*(x3832)))+(((sj0)*(x3831)))+(((r12)*(x3826))));
11737 evalcond[1]=((((r12)*(x3830)))+(((IkReal(-1.00000000000000))*(x3827)*(x3831)))+(((IkReal(-1.00000000000000))*(x3828)*(x3833)))+(((r02)*(x3826)))+(((IkReal(-1.00000000000000))*(x3829)*(x3833)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x3827)*(x3832))));
11738 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
11739 {
11740 continue;
11741 }
11742 }
11743 
11744 {
11745 IkReal dummyeval[1];
11746 IkReal gconst24;
11747 IkReal x3834=(r21)*(r21);
11748 IkReal x3835=(cj5)*(cj5);
11749 IkReal x3836=(sj6)*(sj6);
11750 IkReal x3837=(cj6)*(cj6);
11751 IkReal x3838=(r20)*(r20);
11752 IkReal x3839=((cj6)*(r21));
11753 IkReal x3840=((IkReal(2.00000000000000))*(r20)*(sj6));
11754 IkReal x3841=((cj5)*(r22)*(sj5));
11755 IkReal x3842=((IkReal(1.00000000000000))*(x3836));
11756 IkReal x3843=((IkReal(1.00000000000000))*(x3837));
11757 gconst24=IKsign(((((IkReal(-1.00000000000000))*(x3834)*(x3835)*(x3843)))+(((x3839)*(x3840)))+(((IkReal(-1.00000000000000))*(x3835)*(x3839)*(x3840)))+(((IkReal(-1.00000000000000))*(x3835)*(x3838)*(x3842)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x3834)*(x3842)))+(((IkReal(-2.00000000000000))*(x3839)*(x3841)))+(((IkReal(-1.00000000000000))*(x3838)*(x3843)))+(((IkReal(-1.00000000000000))*(x3840)*(x3841)))));
11758 IkReal x3844=(r21)*(r21);
11759 IkReal x3845=(cj5)*(cj5);
11760 IkReal x3846=(sj6)*(sj6);
11761 IkReal x3847=(cj6)*(cj6);
11762 IkReal x3848=(r20)*(r20);
11763 IkReal x3849=((cj6)*(r21));
11764 IkReal x3850=((IkReal(2.00000000000000))*(r20)*(sj6));
11765 IkReal x3851=((cj5)*(r22)*(sj5));
11766 IkReal x3852=((IkReal(1.00000000000000))*(x3846));
11767 IkReal x3853=((IkReal(1.00000000000000))*(x3847));
11768 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3848)*(x3853)))+(((IkReal(-2.00000000000000))*(x3849)*(x3851)))+(((x3849)*(x3850)))+(((IkReal(-1.00000000000000))*(x3844)*(x3845)*(x3853)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x3845)*(x3848)*(x3852)))+(((IkReal(-1.00000000000000))*(x3844)*(x3852)))+(((IkReal(-1.00000000000000))*(x3850)*(x3851)))+(((IkReal(-1.00000000000000))*(x3845)*(x3849)*(x3850))));
11769 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11770 {
11771 {
11772 IkReal dummyeval[1];
11773 IkReal gconst25;
11774 IkReal x3854=(cj6)*(cj6);
11775 IkReal x3855=(sj6)*(sj6);
11776 IkReal x3856=((IkReal(1.00000000000000))*(r01));
11777 IkReal x3857=((sj0)*(sj5));
11778 IkReal x3858=((cj6)*(r22));
11779 IkReal x3859=((r21)*(sj6));
11780 IkReal x3860=((r00)*(r21));
11781 IkReal x3861=((cj0)*(sj5));
11782 IkReal x3862=((cj6)*(r20));
11783 IkReal x3863=((r22)*(sj6));
11784 IkReal x3864=((cj0)*(cj5));
11785 IkReal x3865=((IkReal(1.00000000000000))*(r10));
11786 IkReal x3866=((cj5)*(sj0));
11787 IkReal x3867=((r20)*(x3855));
11788 IkReal x3868=((x3854)*(x3866));
11789 gconst25=IKsign(((((IkReal(-1.00000000000000))*(r02)*(x3857)*(x3862)))+(((r11)*(x3864)*(x3867)))+(((r00)*(x3857)*(x3858)))+(((IkReal(-1.00000000000000))*(x3856)*(x3857)*(x3863)))+(((x3855)*(x3860)*(x3866)))+(((r11)*(r20)*(x3854)*(x3864)))+(((IkReal(-1.00000000000000))*(x3856)*(x3866)*(x3867)))+(((r11)*(x3861)*(x3863)))+(((IkReal(-1.00000000000000))*(x3858)*(x3861)*(x3865)))+(((r02)*(x3857)*(x3859)))+(((IkReal(-1.00000000000000))*(r12)*(x3859)*(x3861)))+(((r12)*(x3861)*(x3862)))+(((IkReal(-1.00000000000000))*(r20)*(x3856)*(x3868)))+(((IkReal(-1.00000000000000))*(r21)*(x3855)*(x3864)*(x3865)))+(((x3860)*(x3868)))+(((IkReal(-1.00000000000000))*(r21)*(x3854)*(x3864)*(x3865)))));
11790 IkReal x3869=(cj6)*(cj6);
11791 IkReal x3870=(sj6)*(sj6);
11792 IkReal x3871=((IkReal(1.00000000000000))*(r01));
11793 IkReal x3872=((sj0)*(sj5));
11794 IkReal x3873=((cj6)*(r22));
11795 IkReal x3874=((r21)*(sj6));
11796 IkReal x3875=((r00)*(r21));
11797 IkReal x3876=((cj0)*(sj5));
11798 IkReal x3877=((cj6)*(r20));
11799 IkReal x3878=((r22)*(sj6));
11800 IkReal x3879=((cj0)*(cj5));
11801 IkReal x3880=((IkReal(1.00000000000000))*(r10));
11802 IkReal x3881=((cj5)*(sj0));
11803 IkReal x3882=((r20)*(x3870));
11804 IkReal x3883=((x3869)*(x3881));
11805 dummyeval[0]=((((x3870)*(x3875)*(x3881)))+(((r11)*(x3879)*(x3882)))+(((IkReal(-1.00000000000000))*(x3873)*(x3876)*(x3880)))+(((IkReal(-1.00000000000000))*(r21)*(x3869)*(x3879)*(x3880)))+(((r00)*(x3872)*(x3873)))+(((IkReal(-1.00000000000000))*(x3871)*(x3872)*(x3878)))+(((r11)*(x3876)*(x3878)))+(((IkReal(-1.00000000000000))*(r02)*(x3872)*(x3877)))+(((IkReal(-1.00000000000000))*(r20)*(x3871)*(x3883)))+(((r12)*(x3876)*(x3877)))+(((IkReal(-1.00000000000000))*(r21)*(x3870)*(x3879)*(x3880)))+(((x3875)*(x3883)))+(((IkReal(-1.00000000000000))*(x3871)*(x3881)*(x3882)))+(((r11)*(r20)*(x3869)*(x3879)))+(((IkReal(-1.00000000000000))*(r12)*(x3874)*(x3876)))+(((r02)*(x3872)*(x3874))));
11806 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11807 {
11808 continue;
11809 
11810 } else
11811 {
11812 {
11813 IkReal j4array[1], cj4array[1], sj4array[1];
11814 bool j4valid[1]={false};
11815 _nj4 = 1;
11816 IkReal x3884=((r01)*(sj0));
11817 IkReal x3885=((IkReal(1.00000000000000))*(cj5));
11818 IkReal x3886=((cj0)*(r10));
11819 IkReal x3887=((r00)*(sj0));
11820 IkReal x3888=((cj0)*(r11));
11821 if( IKabs(((gconst25)*(((((sj6)*(x3884)))+(((IkReal(-1.00000000000000))*(cj6)*(x3887)))+(((IkReal(-1.00000000000000))*(sj6)*(x3888)))+(((cj6)*(x3886))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((cj5)*(cj6)*(x3888)))+(((IkReal(-1.00000000000000))*(cj6)*(x3884)*(x3885)))+(((IkReal(-1.00000000000000))*(sj6)*(x3885)*(x3887)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(sj6)*(x3886))))))) < IKFAST_ATAN2_MAGTHRESH )
11822     continue;
11823 j4array[0]=IKatan2(((gconst25)*(((((sj6)*(x3884)))+(((IkReal(-1.00000000000000))*(cj6)*(x3887)))+(((IkReal(-1.00000000000000))*(sj6)*(x3888)))+(((cj6)*(x3886)))))), ((gconst25)*(((((cj5)*(cj6)*(x3888)))+(((IkReal(-1.00000000000000))*(cj6)*(x3884)*(x3885)))+(((IkReal(-1.00000000000000))*(sj6)*(x3885)*(x3887)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(sj6)*(x3886)))))));
11824 sj4array[0]=IKsin(j4array[0]);
11825 cj4array[0]=IKcos(j4array[0]);
11826 if( j4array[0] > IKPI )
11827 {
11828     j4array[0]-=IK2PI;
11829 }
11830 else if( j4array[0] < -IKPI )
11831 {    j4array[0]+=IK2PI;
11832 }
11833 j4valid[0] = true;
11834 for(int ij4 = 0; ij4 < 1; ++ij4)
11835 {
11836 if( !j4valid[ij4] )
11837 {
11838     continue;
11839 }
11840 _ij4[0] = ij4; _ij4[1] = -1;
11841 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11842 {
11843 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11844 {
11845     j4valid[iij4]=false; _ij4[1] = iij4; break; 
11846 }
11847 }
11848 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11849 {
11850 IkReal evalcond[6];
11851 IkReal x3889=IKsin(j4);
11852 IkReal x3890=IKcos(j4);
11853 IkReal x3891=((r22)*(sj5));
11854 IkReal x3892=((IkReal(1.00000000000000))*(cj6));
11855 IkReal x3893=((IkReal(1.00000000000000))*(cj0));
11856 IkReal x3894=((cj5)*(r11));
11857 IkReal x3895=((cj5)*(cj6));
11858 IkReal x3896=((r11)*(sj6));
11859 IkReal x3897=((IkReal(1.00000000000000))*(sj6));
11860 IkReal x3898=((cj6)*(r00));
11861 IkReal x3899=((r12)*(sj5));
11862 IkReal x3900=((r02)*(sj5));
11863 IkReal x3901=((cj6)*(r10));
11864 IkReal x3902=((cj5)*(sj6));
11865 IkReal x3903=((cj5)*(r01));
11866 IkReal x3904=((sj0)*(x3889));
11867 IkReal x3905=((r00)*(x3902));
11868 IkReal x3906=((cj0)*(x3889));
11869 IkReal x3907=((sj0)*(x3890));
11870 IkReal x3908=((r20)*(x3890));
11871 IkReal x3909=((cj0)*(x3890));
11872 IkReal x3910=((r21)*(x3889));
11873 IkReal x3911=((r21)*(x3890));
11874 IkReal x3912=((r20)*(x3889));
11875 IkReal x3913=((x3890)*(x3899));
11876 IkReal x3914=((r01)*(sj6)*(x3890));
11877 IkReal x3915=((cj5)*(r10)*(x3897));
11878 evalcond[0]=((IkReal(1.00000000000000))+(((x3902)*(x3912)))+(((IkReal(-1.00000000000000))*(x3892)*(x3908)))+(((x3889)*(x3891)))+(((x3895)*(x3910)))+(((sj6)*(x3911))));
11879 evalcond[1]=((((x3890)*(x3891)))+(((x3902)*(x3908)))+(((x3895)*(x3911)))+(((cj6)*(x3912)))+(((IkReal(-1.00000000000000))*(x3897)*(x3910))));
11880 evalcond[2]=((((IkReal(-1.00000000000000))*(x3890)*(x3893)*(x3896)))+(((x3904)*(x3905)))+(((x3900)*(x3904)))+(((IkReal(-1.00000000000000))*(r00)*(x3892)*(x3907)))+(((x3901)*(x3909)))+(((r01)*(sj6)*(x3907)))+(((IkReal(-1.00000000000000))*(x3889)*(x3893)*(x3899)))+(((r01)*(x3895)*(x3904)))+(((IkReal(-1.00000000000000))*(r10)*(x3889)*(x3893)*(x3902)))+(((IkReal(-1.00000000000000))*(x3892)*(x3894)*(x3906))));
11881 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3897)*(x3904)))+(((x3896)*(x3906)))+(((IkReal(-1.00000000000000))*(x3892)*(x3894)*(x3909)))+(((x3905)*(x3907)))+(((r01)*(x3895)*(x3907)))+(((IkReal(-1.00000000000000))*(r10)*(x3890)*(x3893)*(x3902)))+(cj3)+(((x3898)*(x3904)))+(((x3900)*(x3907)))+(((IkReal(-1.00000000000000))*(r10)*(x3892)*(x3906)))+(((IkReal(-1.00000000000000))*(x3893)*(x3913))));
11882 evalcond[4]=((((IkReal(-1.00000000000000))*(x3889)*(x3893)*(x3905)))+(((IkReal(-1.00000000000000))*(x3892)*(x3903)*(x3906)))+(((IkReal(-1.00000000000000))*(x3896)*(x3907)))+(((IkReal(-1.00000000000000))*(x3904)*(x3915)))+(((IkReal(-1.00000000000000))*(x3893)*(x3914)))+(((x3901)*(x3907)))+(((IkReal(-1.00000000000000))*(x3889)*(x3893)*(x3900)))+(((IkReal(-1.00000000000000))*(x3899)*(x3904)))+(((x3898)*(x3909)))+(((IkReal(-1.00000000000000))*(x3892)*(x3894)*(x3904))));
11883 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x3892)*(x3906)))+(((r01)*(sj6)*(x3906)))+(sj3)+(((IkReal(-1.00000000000000))*(x3892)*(x3903)*(x3909)))+(((IkReal(-1.00000000000000))*(x3890)*(x3893)*(x3900)))+(((IkReal(-1.00000000000000))*(x3892)*(x3894)*(x3907)))+(((IkReal(-1.00000000000000))*(x3899)*(x3907)))+(((x3896)*(x3904)))+(((IkReal(-1.00000000000000))*(r10)*(x3892)*(x3904)))+(((IkReal(-1.00000000000000))*(x3890)*(x3893)*(x3905)))+(((IkReal(-1.00000000000000))*(x3907)*(x3915))));
11884 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
11885 {
11886 continue;
11887 }
11888 }
11889 
11890 {
11891 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
11892 vinfos[0].jointtype = 1;
11893 vinfos[0].foffset = j0;
11894 vinfos[0].indices[0] = _ij0[0];
11895 vinfos[0].indices[1] = _ij0[1];
11896 vinfos[0].maxsolutions = _nj0;
11897 vinfos[1].jointtype = 1;
11898 vinfos[1].foffset = j1;
11899 vinfos[1].indices[0] = _ij1[0];
11900 vinfos[1].indices[1] = _ij1[1];
11901 vinfos[1].maxsolutions = _nj1;
11902 vinfos[2].jointtype = 1;
11903 vinfos[2].foffset = j2;
11904 vinfos[2].indices[0] = _ij2[0];
11905 vinfos[2].indices[1] = _ij2[1];
11906 vinfos[2].maxsolutions = _nj2;
11907 vinfos[3].jointtype = 1;
11908 vinfos[3].foffset = j3;
11909 vinfos[3].indices[0] = _ij3[0];
11910 vinfos[3].indices[1] = _ij3[1];
11911 vinfos[3].maxsolutions = _nj3;
11912 vinfos[4].jointtype = 1;
11913 vinfos[4].foffset = j4;
11914 vinfos[4].indices[0] = _ij4[0];
11915 vinfos[4].indices[1] = _ij4[1];
11916 vinfos[4].maxsolutions = _nj4;
11917 vinfos[5].jointtype = 1;
11918 vinfos[5].foffset = j5;
11919 vinfos[5].indices[0] = _ij5[0];
11920 vinfos[5].indices[1] = _ij5[1];
11921 vinfos[5].maxsolutions = _nj5;
11922 vinfos[6].jointtype = 1;
11923 vinfos[6].foffset = j6;
11924 vinfos[6].indices[0] = _ij6[0];
11925 vinfos[6].indices[1] = _ij6[1];
11926 vinfos[6].maxsolutions = _nj6;
11927 std::vector<int> vfree(0);
11928 solutions.AddSolution(vinfos,vfree);
11929 }
11930 }
11931 }
11932 
11933 }
11934 
11935 }
11936 
11937 } else
11938 {
11939 {
11940 IkReal j4array[1], cj4array[1], sj4array[1];
11941 bool j4valid[1]={false};
11942 _nj4 = 1;
11943 if( IKabs(((gconst24)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst24)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
11944     continue;
11945 j4array[0]=IKatan2(((gconst24)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst24)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
11946 sj4array[0]=IKsin(j4array[0]);
11947 cj4array[0]=IKcos(j4array[0]);
11948 if( j4array[0] > IKPI )
11949 {
11950     j4array[0]-=IK2PI;
11951 }
11952 else if( j4array[0] < -IKPI )
11953 {    j4array[0]+=IK2PI;
11954 }
11955 j4valid[0] = true;
11956 for(int ij4 = 0; ij4 < 1; ++ij4)
11957 {
11958 if( !j4valid[ij4] )
11959 {
11960     continue;
11961 }
11962 _ij4[0] = ij4; _ij4[1] = -1;
11963 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
11964 {
11965 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
11966 {
11967     j4valid[iij4]=false; _ij4[1] = iij4; break; 
11968 }
11969 }
11970 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
11971 {
11972 IkReal evalcond[6];
11973 IkReal x3916=IKsin(j4);
11974 IkReal x3917=IKcos(j4);
11975 IkReal x3918=((r22)*(sj5));
11976 IkReal x3919=((IkReal(1.00000000000000))*(cj6));
11977 IkReal x3920=((IkReal(1.00000000000000))*(cj0));
11978 IkReal x3921=((cj5)*(r11));
11979 IkReal x3922=((cj5)*(cj6));
11980 IkReal x3923=((r11)*(sj6));
11981 IkReal x3924=((IkReal(1.00000000000000))*(sj6));
11982 IkReal x3925=((cj6)*(r00));
11983 IkReal x3926=((r12)*(sj5));
11984 IkReal x3927=((r02)*(sj5));
11985 IkReal x3928=((cj6)*(r10));
11986 IkReal x3929=((cj5)*(sj6));
11987 IkReal x3930=((cj5)*(r01));
11988 IkReal x3931=((sj0)*(x3916));
11989 IkReal x3932=((r00)*(x3929));
11990 IkReal x3933=((cj0)*(x3916));
11991 IkReal x3934=((sj0)*(x3917));
11992 IkReal x3935=((r20)*(x3917));
11993 IkReal x3936=((cj0)*(x3917));
11994 IkReal x3937=((r21)*(x3916));
11995 IkReal x3938=((r21)*(x3917));
11996 IkReal x3939=((r20)*(x3916));
11997 IkReal x3940=((x3917)*(x3926));
11998 IkReal x3941=((r01)*(sj6)*(x3917));
11999 IkReal x3942=((cj5)*(r10)*(x3924));
12000 evalcond[0]=((IkReal(1.00000000000000))+(((x3929)*(x3939)))+(((x3922)*(x3937)))+(((sj6)*(x3938)))+(((x3916)*(x3918)))+(((IkReal(-1.00000000000000))*(x3919)*(x3935))));
12001 evalcond[1]=((((x3917)*(x3918)))+(((x3922)*(x3938)))+(((x3929)*(x3935)))+(((cj6)*(x3939)))+(((IkReal(-1.00000000000000))*(x3924)*(x3937))));
12002 evalcond[2]=((((IkReal(-1.00000000000000))*(x3916)*(x3920)*(x3926)))+(((IkReal(-1.00000000000000))*(r10)*(x3916)*(x3920)*(x3929)))+(((r01)*(x3922)*(x3931)))+(((r01)*(sj6)*(x3934)))+(((IkReal(-1.00000000000000))*(r00)*(x3919)*(x3934)))+(((IkReal(-1.00000000000000))*(x3917)*(x3920)*(x3923)))+(((x3931)*(x3932)))+(((IkReal(-1.00000000000000))*(x3919)*(x3921)*(x3933)))+(((x3928)*(x3936)))+(((x3927)*(x3931))));
12003 evalcond[3]=((((x3925)*(x3931)))+(((x3923)*(x3933)))+(((x3932)*(x3934)))+(((IkReal(-1.00000000000000))*(r01)*(x3924)*(x3931)))+(((r01)*(x3922)*(x3934)))+(((IkReal(-1.00000000000000))*(r10)*(x3919)*(x3933)))+(cj3)+(((IkReal(-1.00000000000000))*(x3919)*(x3921)*(x3936)))+(((x3927)*(x3934)))+(((IkReal(-1.00000000000000))*(r10)*(x3917)*(x3920)*(x3929)))+(((IkReal(-1.00000000000000))*(x3920)*(x3940))));
12004 evalcond[4]=((((IkReal(-1.00000000000000))*(x3920)*(x3941)))+(((IkReal(-1.00000000000000))*(x3923)*(x3934)))+(((IkReal(-1.00000000000000))*(x3916)*(x3920)*(x3932)))+(((IkReal(-1.00000000000000))*(x3919)*(x3930)*(x3933)))+(((x3925)*(x3936)))+(((IkReal(-1.00000000000000))*(x3919)*(x3921)*(x3931)))+(((IkReal(-1.00000000000000))*(x3926)*(x3931)))+(((IkReal(-1.00000000000000))*(x3916)*(x3920)*(x3927)))+(((x3928)*(x3934)))+(((IkReal(-1.00000000000000))*(x3931)*(x3942))));
12005 evalcond[5]=((((IkReal(-1.00000000000000))*(x3917)*(x3920)*(x3927)))+(((IkReal(-1.00000000000000))*(x3917)*(x3920)*(x3932)))+(sj3)+(((IkReal(-1.00000000000000))*(x3934)*(x3942)))+(((r01)*(sj6)*(x3933)))+(((IkReal(-1.00000000000000))*(x3919)*(x3921)*(x3934)))+(((IkReal(-1.00000000000000))*(r10)*(x3919)*(x3931)))+(((IkReal(-1.00000000000000))*(x3926)*(x3934)))+(((x3923)*(x3931)))+(((IkReal(-1.00000000000000))*(r00)*(x3919)*(x3933)))+(((IkReal(-1.00000000000000))*(x3919)*(x3930)*(x3936))));
12006 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
12007 {
12008 continue;
12009 }
12010 }
12011 
12012 {
12013 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12014 vinfos[0].jointtype = 1;
12015 vinfos[0].foffset = j0;
12016 vinfos[0].indices[0] = _ij0[0];
12017 vinfos[0].indices[1] = _ij0[1];
12018 vinfos[0].maxsolutions = _nj0;
12019 vinfos[1].jointtype = 1;
12020 vinfos[1].foffset = j1;
12021 vinfos[1].indices[0] = _ij1[0];
12022 vinfos[1].indices[1] = _ij1[1];
12023 vinfos[1].maxsolutions = _nj1;
12024 vinfos[2].jointtype = 1;
12025 vinfos[2].foffset = j2;
12026 vinfos[2].indices[0] = _ij2[0];
12027 vinfos[2].indices[1] = _ij2[1];
12028 vinfos[2].maxsolutions = _nj2;
12029 vinfos[3].jointtype = 1;
12030 vinfos[3].foffset = j3;
12031 vinfos[3].indices[0] = _ij3[0];
12032 vinfos[3].indices[1] = _ij3[1];
12033 vinfos[3].maxsolutions = _nj3;
12034 vinfos[4].jointtype = 1;
12035 vinfos[4].foffset = j4;
12036 vinfos[4].indices[0] = _ij4[0];
12037 vinfos[4].indices[1] = _ij4[1];
12038 vinfos[4].maxsolutions = _nj4;
12039 vinfos[5].jointtype = 1;
12040 vinfos[5].foffset = j5;
12041 vinfos[5].indices[0] = _ij5[0];
12042 vinfos[5].indices[1] = _ij5[1];
12043 vinfos[5].maxsolutions = _nj5;
12044 vinfos[6].jointtype = 1;
12045 vinfos[6].foffset = j6;
12046 vinfos[6].indices[0] = _ij6[0];
12047 vinfos[6].indices[1] = _ij6[1];
12048 vinfos[6].maxsolutions = _nj6;
12049 std::vector<int> vfree(0);
12050 solutions.AddSolution(vinfos,vfree);
12051 }
12052 }
12053 }
12054 
12055 }
12056 
12057 }
12058 }
12059 }
12060 
12061 } else
12062 {
12063 if( 1 )
12064 {
12065 continue;
12066 
12067 } else
12068 {
12069 }
12070 }
12071 }
12072 }
12073 
12074 } else
12075 {
12076 {
12077 IkReal j3array[1], cj3array[1], sj3array[1];
12078 bool j3valid[1]={false};
12079 _nj3 = 1;
12080 IkReal x3943=((sj5)*(sj6));
12081 IkReal x3944=((cj6)*(sj5));
12082 IkReal x3945=((IkReal(1.00000000000000))*(cj0));
12083 IkReal x3946=((IkReal(1.00000000000000))*(cj5));
12084 if( IKabs(((((r00)*(sj0)*(x3943)))+(((IkReal(-1.00000000000000))*(r10)*(x3943)*(x3945)))+(((r01)*(sj0)*(x3944)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x3944)*(x3945)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3946))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x3943)))+(((IkReal(-1.00000000000000))*(r22)*(x3946)))+(((r21)*(x3944))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r00)*(sj0)*(x3943)))+(((IkReal(-1.00000000000000))*(r10)*(x3943)*(x3945)))+(((r01)*(sj0)*(x3944)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x3944)*(x3945)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3946)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x3943)))+(((IkReal(-1.00000000000000))*(r22)*(x3946)))+(((r21)*(x3944)))))))-1) <= IKFAST_SINCOS_THRESH )
12085     continue;
12086 j3array[0]=IKatan2(((((r00)*(sj0)*(x3943)))+(((IkReal(-1.00000000000000))*(r10)*(x3943)*(x3945)))+(((r01)*(sj0)*(x3944)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x3944)*(x3945)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x3946)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x3943)))+(((IkReal(-1.00000000000000))*(r22)*(x3946)))+(((r21)*(x3944)))))));
12087 sj3array[0]=IKsin(j3array[0]);
12088 cj3array[0]=IKcos(j3array[0]);
12089 if( j3array[0] > IKPI )
12090 {
12091     j3array[0]-=IK2PI;
12092 }
12093 else if( j3array[0] < -IKPI )
12094 {    j3array[0]+=IK2PI;
12095 }
12096 j3valid[0] = true;
12097 for(int ij3 = 0; ij3 < 1; ++ij3)
12098 {
12099 if( !j3valid[ij3] )
12100 {
12101     continue;
12102 }
12103 _ij3[0] = ij3; _ij3[1] = -1;
12104 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12105 {
12106 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12107 {
12108     j3valid[iij3]=false; _ij3[1] = iij3; break; 
12109 }
12110 }
12111 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12112 {
12113 IkReal evalcond[3];
12114 IkReal x3947=IKcos(j3);
12115 IkReal x3948=((sj5)*(sj6));
12116 IkReal x3949=((cj0)*(cj5));
12117 IkReal x3950=((IkReal(1.00000000000000))*(cj0));
12118 IkReal x3951=((IkReal(1.00000000000000))*(sj0));
12119 IkReal x3952=((IkReal(1.00000000000000))*(x3947));
12120 IkReal x3953=((cj6)*(r01)*(sj5));
12121 IkReal x3954=((cj6)*(r11)*(sj5));
12122 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((r20)*(x3948)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x3952))));
12123 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r02)*(x3951)))+(((r12)*(x3949)))+(((IkReal(-1.00000000000000))*(r10)*(x3948)*(x3950)))+(((sj0)*(x3953)))+(((r00)*(sj0)*(x3948)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((IkReal(-1.00000000000000))*(x3950)*(x3954))));
12124 evalcond[2]=((((IkReal(-1.00000000000000))*(x3951)*(x3954)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(x3948)*(x3951)))+(((IkReal(-1.00000000000000))*(x3950)*(x3953)))+(((r02)*(x3949)))+(((IkReal(-1.00000000000000))*(r00)*(x3948)*(x3950)))+(((IkReal(-1.00000000000000))*(cj1)*(x3952))));
12125 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
12126 {
12127 continue;
12128 }
12129 }
12130 
12131 {
12132 IkReal dummyeval[1];
12133 IkReal gconst15;
12134 IkReal x3955=(r21)*(r21);
12135 IkReal x3956=(cj5)*(cj5);
12136 IkReal x3957=(sj6)*(sj6);
12137 IkReal x3958=(cj6)*(cj6);
12138 IkReal x3959=(r20)*(r20);
12139 IkReal x3960=((cj6)*(r21));
12140 IkReal x3961=((IkReal(2.00000000000000))*(r20)*(sj6));
12141 IkReal x3962=((cj5)*(r22)*(sj5));
12142 IkReal x3963=((IkReal(1.00000000000000))*(x3957));
12143 IkReal x3964=((IkReal(1.00000000000000))*(x3958));
12144 gconst15=IKsign(((((IkReal(-1.00000000000000))*(x3959)*(x3964)))+(((IkReal(-2.00000000000000))*(x3960)*(x3962)))+(((IkReal(-1.00000000000000))*(x3955)*(x3963)))+(((IkReal(-1.00000000000000))*(x3961)*(x3962)))+(((IkReal(-1.00000000000000))*(x3956)*(x3959)*(x3963)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((x3960)*(x3961)))+(((IkReal(-1.00000000000000))*(x3956)*(x3960)*(x3961)))+(((IkReal(-1.00000000000000))*(x3955)*(x3956)*(x3964)))));
12145 IkReal x3965=(r21)*(r21);
12146 IkReal x3966=(cj5)*(cj5);
12147 IkReal x3967=(sj6)*(sj6);
12148 IkReal x3968=(cj6)*(cj6);
12149 IkReal x3969=(r20)*(r20);
12150 IkReal x3970=((cj6)*(r21));
12151 IkReal x3971=((IkReal(2.00000000000000))*(r20)*(sj6));
12152 IkReal x3972=((cj5)*(r22)*(sj5));
12153 IkReal x3973=((IkReal(1.00000000000000))*(x3967));
12154 IkReal x3974=((IkReal(1.00000000000000))*(x3968));
12155 dummyeval[0]=((((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((x3970)*(x3971)))+(((IkReal(-1.00000000000000))*(x3966)*(x3970)*(x3971)))+(((IkReal(-1.00000000000000))*(x3966)*(x3969)*(x3973)))+(((IkReal(-1.00000000000000))*(x3971)*(x3972)))+(((IkReal(-2.00000000000000))*(x3970)*(x3972)))+(((IkReal(-1.00000000000000))*(x3965)*(x3973)))+(((IkReal(-1.00000000000000))*(x3965)*(x3966)*(x3974)))+(((IkReal(-1.00000000000000))*(x3969)*(x3974))));
12156 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12157 {
12158 {
12159 IkReal dummyeval[1];
12160 IkReal gconst16;
12161 IkReal x3975=(cj6)*(cj6);
12162 IkReal x3976=(sj6)*(sj6);
12163 IkReal x3977=((IkReal(1.00000000000000))*(r21));
12164 IkReal x3978=((cj6)*(r20));
12165 IkReal x3979=((r22)*(sj5));
12166 IkReal x3980=((r01)*(sj0));
12167 IkReal x3981=((r00)*(sj0));
12168 IkReal x3982=((cj0)*(r10));
12169 IkReal x3983=((r02)*(sj0)*(sj5));
12170 IkReal x3984=((cj5)*(x3975));
12171 IkReal x3985=((cj0)*(r12)*(sj5));
12172 IkReal x3986=((IkReal(1.00000000000000))*(cj0)*(r11));
12173 IkReal x3987=((cj5)*(x3976));
12174 IkReal x3988=((r20)*(x3987));
12175 gconst16=IKsign(((((x3978)*(x3983)))+(((IkReal(-1.00000000000000))*(x3977)*(x3981)*(x3987)))+(((IkReal(-1.00000000000000))*(sj6)*(x3977)*(x3983)))+(((r21)*(sj6)*(x3985)))+(((r21)*(x3982)*(x3984)))+(((r21)*(x3982)*(x3987)))+(((IkReal(-1.00000000000000))*(x3986)*(x3988)))+(((IkReal(-1.00000000000000))*(x3977)*(x3981)*(x3984)))+(((IkReal(-1.00000000000000))*(x3978)*(x3985)))+(((IkReal(-1.00000000000000))*(sj6)*(x3979)*(x3986)))+(((cj6)*(x3979)*(x3982)))+(((sj6)*(x3979)*(x3980)))+(((x3980)*(x3988)))+(((IkReal(-1.00000000000000))*(cj6)*(x3979)*(x3981)))+(((r20)*(x3980)*(x3984)))+(((IkReal(-1.00000000000000))*(r20)*(x3984)*(x3986)))));
12176 IkReal x3989=(cj6)*(cj6);
12177 IkReal x3990=(sj6)*(sj6);
12178 IkReal x3991=((IkReal(1.00000000000000))*(r21));
12179 IkReal x3992=((cj6)*(r20));
12180 IkReal x3993=((r22)*(sj5));
12181 IkReal x3994=((r01)*(sj0));
12182 IkReal x3995=((r00)*(sj0));
12183 IkReal x3996=((cj0)*(r10));
12184 IkReal x3997=((r02)*(sj0)*(sj5));
12185 IkReal x3998=((cj5)*(x3989));
12186 IkReal x3999=((cj0)*(r12)*(sj5));
12187 IkReal x4000=((IkReal(1.00000000000000))*(cj0)*(r11));
12188 IkReal x4001=((cj5)*(x3990));
12189 IkReal x4002=((r20)*(x4001));
12190 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj6)*(x3993)*(x3995)))+(((IkReal(-1.00000000000000))*(x3992)*(x3999)))+(((sj6)*(x3993)*(x3994)))+(((r21)*(x3996)*(x3998)))+(((IkReal(-1.00000000000000))*(x4000)*(x4002)))+(((r21)*(x3996)*(x4001)))+(((r20)*(x3994)*(x3998)))+(((IkReal(-1.00000000000000))*(sj6)*(x3991)*(x3997)))+(((cj6)*(x3993)*(x3996)))+(((IkReal(-1.00000000000000))*(r20)*(x3998)*(x4000)))+(((IkReal(-1.00000000000000))*(sj6)*(x3993)*(x4000)))+(((IkReal(-1.00000000000000))*(x3991)*(x3995)*(x4001)))+(((x3994)*(x4002)))+(((r21)*(sj6)*(x3999)))+(((x3992)*(x3997)))+(((IkReal(-1.00000000000000))*(x3991)*(x3995)*(x3998))));
12191 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12192 {
12193 continue;
12194 
12195 } else
12196 {
12197 {
12198 IkReal j4array[1], cj4array[1], sj4array[1];
12199 bool j4valid[1]={false};
12200 _nj4 = 1;
12201 IkReal x4003=((cj1)*(sj6));
12202 IkReal x4004=((r01)*(sj0));
12203 IkReal x4005=((cj0)*(r11));
12204 IkReal x4006=((cj1)*(cj6));
12205 IkReal x4007=((cj0)*(r10));
12206 IkReal x4008=((IkReal(1.00000000000000))*(sj0));
12207 IkReal x4009=((cj1)*(sj5));
12208 if( IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(r00)*(x4006)*(x4008)))+(((x4006)*(x4007)))+(((IkReal(-1.00000000000000))*(x4003)*(x4005)))+(((x4003)*(x4004))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(cj5)*(x4004)*(x4006)))+(((cj0)*(r12)*(x4009)))+(((IkReal(-1.00000000000000))*(r02)*(x4008)*(x4009)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4003)*(x4008)))+(((cj5)*(x4003)*(x4007)))+(((cj5)*(x4005)*(x4006))))))) < IKFAST_ATAN2_MAGTHRESH )
12209     continue;
12210 j4array[0]=IKatan2(((gconst16)*(((((IkReal(-1.00000000000000))*(r00)*(x4006)*(x4008)))+(((x4006)*(x4007)))+(((IkReal(-1.00000000000000))*(x4003)*(x4005)))+(((x4003)*(x4004)))))), ((gconst16)*(((((IkReal(-1.00000000000000))*(cj5)*(x4004)*(x4006)))+(((cj0)*(r12)*(x4009)))+(((IkReal(-1.00000000000000))*(r02)*(x4008)*(x4009)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4003)*(x4008)))+(((cj5)*(x4003)*(x4007)))+(((cj5)*(x4005)*(x4006)))))));
12211 sj4array[0]=IKsin(j4array[0]);
12212 cj4array[0]=IKcos(j4array[0]);
12213 if( j4array[0] > IKPI )
12214 {
12215     j4array[0]-=IK2PI;
12216 }
12217 else if( j4array[0] < -IKPI )
12218 {    j4array[0]+=IK2PI;
12219 }
12220 j4valid[0] = true;
12221 for(int ij4 = 0; ij4 < 1; ++ij4)
12222 {
12223 if( !j4valid[ij4] )
12224 {
12225     continue;
12226 }
12227 _ij4[0] = ij4; _ij4[1] = -1;
12228 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12229 {
12230 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12231 {
12232     j4valid[iij4]=false; _ij4[1] = iij4; break; 
12233 }
12234 }
12235 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12236 {
12237 IkReal evalcond[6];
12238 IkReal x4010=IKsin(j4);
12239 IkReal x4011=IKcos(j4);
12240 IkReal x4012=((r22)*(sj5));
12241 IkReal x4013=((IkReal(1.00000000000000))*(cj6));
12242 IkReal x4014=((IkReal(1.00000000000000))*(cj0));
12243 IkReal x4015=((cj5)*(r11));
12244 IkReal x4016=((cj5)*(cj6));
12245 IkReal x4017=((IkReal(1.00000000000000))*(sj3));
12246 IkReal x4018=((r11)*(sj6));
12247 IkReal x4019=((IkReal(1.00000000000000))*(sj6));
12248 IkReal x4020=((cj6)*(r00));
12249 IkReal x4021=((r12)*(sj5));
12250 IkReal x4022=((r02)*(sj5));
12251 IkReal x4023=((cj6)*(r10));
12252 IkReal x4024=((cj5)*(sj6));
12253 IkReal x4025=((cj5)*(r01));
12254 IkReal x4026=((sj0)*(x4010));
12255 IkReal x4027=((r00)*(x4024));
12256 IkReal x4028=((cj0)*(x4010));
12257 IkReal x4029=((sj0)*(x4011));
12258 IkReal x4030=((r20)*(x4011));
12259 IkReal x4031=((cj0)*(x4011));
12260 IkReal x4032=((r21)*(x4010));
12261 IkReal x4033=((r21)*(x4011));
12262 IkReal x4034=((r20)*(x4010));
12263 IkReal x4035=((x4011)*(x4021));
12264 IkReal x4036=((r01)*(sj6)*(x4011));
12265 IkReal x4037=((cj5)*(r10)*(x4019));
12266 evalcond[0]=((((IkReal(-1.00000000000000))*(x4013)*(x4030)))+(((IkReal(-1.00000000000000))*(cj1)))+(((x4024)*(x4034)))+(((sj6)*(x4033)))+(((x4010)*(x4012)))+(((x4016)*(x4032))));
12267 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x4017)))+(((x4024)*(x4030)))+(((x4016)*(x4033)))+(((cj6)*(x4034)))+(((IkReal(-1.00000000000000))*(x4019)*(x4032)))+(((x4011)*(x4012))));
12268 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x4013)*(x4029)))+(((r01)*(sj6)*(x4029)))+(((x4023)*(x4031)))+(((IkReal(-1.00000000000000))*(x4011)*(x4014)*(x4018)))+(((x4026)*(x4027)))+(((r01)*(x4016)*(x4026)))+(((IkReal(-1.00000000000000))*(x4010)*(x4014)*(x4021)))+(((IkReal(-1.00000000000000))*(x4013)*(x4015)*(x4028)))+(((IkReal(-1.00000000000000))*(r10)*(x4010)*(x4014)*(x4024)))+(((x4022)*(x4026))));
12269 evalcond[3]=((((x4020)*(x4026)))+(((x4018)*(x4028)))+(((x4027)*(x4029)))+(((IkReal(-1.00000000000000))*(x4014)*(x4035)))+(((IkReal(-1.00000000000000))*(x4013)*(x4015)*(x4031)))+(cj3)+(((IkReal(-1.00000000000000))*(r10)*(x4013)*(x4028)))+(((x4022)*(x4029)))+(((r01)*(x4016)*(x4029)))+(((IkReal(-1.00000000000000))*(r10)*(x4011)*(x4014)*(x4024)))+(((IkReal(-1.00000000000000))*(r01)*(x4019)*(x4026))));
12270 evalcond[4]=((((IkReal(-1.00000000000000))*(x4010)*(x4014)*(x4022)))+(((IkReal(-1.00000000000000))*(x4014)*(x4036)))+(((IkReal(-1.00000000000000))*(x4021)*(x4026)))+(((IkReal(-1.00000000000000))*(x4010)*(x4014)*(x4027)))+(sj1)+(((IkReal(-1.00000000000000))*(x4013)*(x4015)*(x4026)))+(((x4023)*(x4029)))+(((IkReal(-1.00000000000000))*(x4026)*(x4037)))+(((x4020)*(x4031)))+(((IkReal(-1.00000000000000))*(x4018)*(x4029)))+(((IkReal(-1.00000000000000))*(x4013)*(x4025)*(x4028))));
12271 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x4013)*(x4026)))+(((IkReal(-1.00000000000000))*(r00)*(x4013)*(x4028)))+(((IkReal(-1.00000000000000))*(x4013)*(x4025)*(x4031)))+(((IkReal(-1.00000000000000))*(x4011)*(x4014)*(x4022)))+(((IkReal(-1.00000000000000))*(x4011)*(x4014)*(x4027)))+(((IkReal(-1.00000000000000))*(cj1)*(x4017)))+(((IkReal(-1.00000000000000))*(x4029)*(x4037)))+(((x4018)*(x4026)))+(((r01)*(sj6)*(x4028)))+(((IkReal(-1.00000000000000))*(x4021)*(x4029)))+(((IkReal(-1.00000000000000))*(x4013)*(x4015)*(x4029))));
12272 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
12273 {
12274 continue;
12275 }
12276 }
12277 
12278 {
12279 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12280 vinfos[0].jointtype = 1;
12281 vinfos[0].foffset = j0;
12282 vinfos[0].indices[0] = _ij0[0];
12283 vinfos[0].indices[1] = _ij0[1];
12284 vinfos[0].maxsolutions = _nj0;
12285 vinfos[1].jointtype = 1;
12286 vinfos[1].foffset = j1;
12287 vinfos[1].indices[0] = _ij1[0];
12288 vinfos[1].indices[1] = _ij1[1];
12289 vinfos[1].maxsolutions = _nj1;
12290 vinfos[2].jointtype = 1;
12291 vinfos[2].foffset = j2;
12292 vinfos[2].indices[0] = _ij2[0];
12293 vinfos[2].indices[1] = _ij2[1];
12294 vinfos[2].maxsolutions = _nj2;
12295 vinfos[3].jointtype = 1;
12296 vinfos[3].foffset = j3;
12297 vinfos[3].indices[0] = _ij3[0];
12298 vinfos[3].indices[1] = _ij3[1];
12299 vinfos[3].maxsolutions = _nj3;
12300 vinfos[4].jointtype = 1;
12301 vinfos[4].foffset = j4;
12302 vinfos[4].indices[0] = _ij4[0];
12303 vinfos[4].indices[1] = _ij4[1];
12304 vinfos[4].maxsolutions = _nj4;
12305 vinfos[5].jointtype = 1;
12306 vinfos[5].foffset = j5;
12307 vinfos[5].indices[0] = _ij5[0];
12308 vinfos[5].indices[1] = _ij5[1];
12309 vinfos[5].maxsolutions = _nj5;
12310 vinfos[6].jointtype = 1;
12311 vinfos[6].foffset = j6;
12312 vinfos[6].indices[0] = _ij6[0];
12313 vinfos[6].indices[1] = _ij6[1];
12314 vinfos[6].maxsolutions = _nj6;
12315 std::vector<int> vfree(0);
12316 solutions.AddSolution(vinfos,vfree);
12317 }
12318 }
12319 }
12320 
12321 }
12322 
12323 }
12324 
12325 } else
12326 {
12327 {
12328 IkReal j4array[1], cj4array[1], sj4array[1];
12329 bool j4valid[1]={false};
12330 _nj4 = 1;
12331 IkReal x4038=((IkReal(1.00000000000000))*(cj1));
12332 IkReal x4039=((sj1)*(sj3));
12333 IkReal x4040=((r21)*(sj6));
12334 IkReal x4041=((r22)*(sj5));
12335 IkReal x4042=((cj6)*(r20));
12336 IkReal x4043=((cj5)*(r20)*(sj6));
12337 IkReal x4044=((cj5)*(cj6)*(r21));
12338 if( IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x4038)*(x4041)))+(((IkReal(-1.00000000000000))*(x4038)*(x4043)))+(((x4039)*(x4040)))+(((IkReal(-1.00000000000000))*(x4038)*(x4044)))+(((IkReal(-1.00000000000000))*(x4039)*(x4042))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((cj1)*(x4042)))+(((IkReal(-1.00000000000000))*(x4038)*(x4040)))+(((IkReal(-1.00000000000000))*(x4039)*(x4041)))+(((IkReal(-1.00000000000000))*(x4039)*(x4044)))+(((IkReal(-1.00000000000000))*(x4039)*(x4043))))))) < IKFAST_ATAN2_MAGTHRESH )
12339     continue;
12340 j4array[0]=IKatan2(((gconst15)*(((((IkReal(-1.00000000000000))*(x4038)*(x4041)))+(((IkReal(-1.00000000000000))*(x4038)*(x4043)))+(((x4039)*(x4040)))+(((IkReal(-1.00000000000000))*(x4038)*(x4044)))+(((IkReal(-1.00000000000000))*(x4039)*(x4042)))))), ((gconst15)*(((((cj1)*(x4042)))+(((IkReal(-1.00000000000000))*(x4038)*(x4040)))+(((IkReal(-1.00000000000000))*(x4039)*(x4041)))+(((IkReal(-1.00000000000000))*(x4039)*(x4044)))+(((IkReal(-1.00000000000000))*(x4039)*(x4043)))))));
12341 sj4array[0]=IKsin(j4array[0]);
12342 cj4array[0]=IKcos(j4array[0]);
12343 if( j4array[0] > IKPI )
12344 {
12345     j4array[0]-=IK2PI;
12346 }
12347 else if( j4array[0] < -IKPI )
12348 {    j4array[0]+=IK2PI;
12349 }
12350 j4valid[0] = true;
12351 for(int ij4 = 0; ij4 < 1; ++ij4)
12352 {
12353 if( !j4valid[ij4] )
12354 {
12355     continue;
12356 }
12357 _ij4[0] = ij4; _ij4[1] = -1;
12358 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12359 {
12360 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12361 {
12362     j4valid[iij4]=false; _ij4[1] = iij4; break; 
12363 }
12364 }
12365 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12366 {
12367 IkReal evalcond[6];
12368 IkReal x4045=IKsin(j4);
12369 IkReal x4046=IKcos(j4);
12370 IkReal x4047=((r22)*(sj5));
12371 IkReal x4048=((IkReal(1.00000000000000))*(cj6));
12372 IkReal x4049=((IkReal(1.00000000000000))*(cj0));
12373 IkReal x4050=((cj5)*(r11));
12374 IkReal x4051=((cj5)*(cj6));
12375 IkReal x4052=((IkReal(1.00000000000000))*(sj3));
12376 IkReal x4053=((r11)*(sj6));
12377 IkReal x4054=((IkReal(1.00000000000000))*(sj6));
12378 IkReal x4055=((cj6)*(r00));
12379 IkReal x4056=((r12)*(sj5));
12380 IkReal x4057=((r02)*(sj5));
12381 IkReal x4058=((cj6)*(r10));
12382 IkReal x4059=((cj5)*(sj6));
12383 IkReal x4060=((cj5)*(r01));
12384 IkReal x4061=((sj0)*(x4045));
12385 IkReal x4062=((r00)*(x4059));
12386 IkReal x4063=((cj0)*(x4045));
12387 IkReal x4064=((sj0)*(x4046));
12388 IkReal x4065=((r20)*(x4046));
12389 IkReal x4066=((cj0)*(x4046));
12390 IkReal x4067=((r21)*(x4045));
12391 IkReal x4068=((r21)*(x4046));
12392 IkReal x4069=((r20)*(x4045));
12393 IkReal x4070=((x4046)*(x4056));
12394 IkReal x4071=((r01)*(sj6)*(x4046));
12395 IkReal x4072=((cj5)*(r10)*(x4054));
12396 evalcond[0]=((((x4051)*(x4067)))+(((sj6)*(x4068)))+(((x4045)*(x4047)))+(((IkReal(-1.00000000000000))*(cj1)))+(((x4059)*(x4069)))+(((IkReal(-1.00000000000000))*(x4048)*(x4065))));
12397 evalcond[1]=((((x4059)*(x4065)))+(((IkReal(-1.00000000000000))*(x4054)*(x4067)))+(((IkReal(-1.00000000000000))*(sj1)*(x4052)))+(((cj6)*(x4069)))+(((x4051)*(x4068)))+(((x4046)*(x4047))));
12398 evalcond[2]=((((x4057)*(x4061)))+(((x4061)*(x4062)))+(((IkReal(-1.00000000000000))*(x4046)*(x4049)*(x4053)))+(((r01)*(x4051)*(x4061)))+(((r01)*(sj6)*(x4064)))+(((IkReal(-1.00000000000000))*(r00)*(x4048)*(x4064)))+(((IkReal(-1.00000000000000))*(x4048)*(x4050)*(x4063)))+(((IkReal(-1.00000000000000))*(r10)*(x4045)*(x4049)*(x4059)))+(((IkReal(-1.00000000000000))*(x4045)*(x4049)*(x4056)))+(((x4058)*(x4066))));
12399 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x4048)*(x4063)))+(((x4053)*(x4063)))+(((x4055)*(x4061)))+(((x4057)*(x4064)))+(((IkReal(-1.00000000000000))*(x4048)*(x4050)*(x4066)))+(cj3)+(((r01)*(x4051)*(x4064)))+(((x4062)*(x4064)))+(((IkReal(-1.00000000000000))*(r01)*(x4054)*(x4061)))+(((IkReal(-1.00000000000000))*(r10)*(x4046)*(x4049)*(x4059)))+(((IkReal(-1.00000000000000))*(x4049)*(x4070))));
12400 evalcond[4]=((sj1)+(((IkReal(-1.00000000000000))*(x4048)*(x4050)*(x4061)))+(((IkReal(-1.00000000000000))*(x4056)*(x4061)))+(((IkReal(-1.00000000000000))*(x4061)*(x4072)))+(((IkReal(-1.00000000000000))*(x4045)*(x4049)*(x4062)))+(((x4055)*(x4066)))+(((IkReal(-1.00000000000000))*(x4048)*(x4060)*(x4063)))+(((x4058)*(x4064)))+(((IkReal(-1.00000000000000))*(x4045)*(x4049)*(x4057)))+(((IkReal(-1.00000000000000))*(x4049)*(x4071)))+(((IkReal(-1.00000000000000))*(x4053)*(x4064))));
12401 evalcond[5]=((((IkReal(-1.00000000000000))*(cj1)*(x4052)))+(((IkReal(-1.00000000000000))*(x4048)*(x4050)*(x4064)))+(((IkReal(-1.00000000000000))*(x4048)*(x4060)*(x4066)))+(((IkReal(-1.00000000000000))*(x4046)*(x4049)*(x4057)))+(((IkReal(-1.00000000000000))*(r10)*(x4048)*(x4061)))+(((IkReal(-1.00000000000000))*(x4064)*(x4072)))+(((x4053)*(x4061)))+(((IkReal(-1.00000000000000))*(x4056)*(x4064)))+(((IkReal(-1.00000000000000))*(x4046)*(x4049)*(x4062)))+(((IkReal(-1.00000000000000))*(r00)*(x4048)*(x4063)))+(((r01)*(sj6)*(x4063))));
12402 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
12403 {
12404 continue;
12405 }
12406 }
12407 
12408 {
12409 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12410 vinfos[0].jointtype = 1;
12411 vinfos[0].foffset = j0;
12412 vinfos[0].indices[0] = _ij0[0];
12413 vinfos[0].indices[1] = _ij0[1];
12414 vinfos[0].maxsolutions = _nj0;
12415 vinfos[1].jointtype = 1;
12416 vinfos[1].foffset = j1;
12417 vinfos[1].indices[0] = _ij1[0];
12418 vinfos[1].indices[1] = _ij1[1];
12419 vinfos[1].maxsolutions = _nj1;
12420 vinfos[2].jointtype = 1;
12421 vinfos[2].foffset = j2;
12422 vinfos[2].indices[0] = _ij2[0];
12423 vinfos[2].indices[1] = _ij2[1];
12424 vinfos[2].maxsolutions = _nj2;
12425 vinfos[3].jointtype = 1;
12426 vinfos[3].foffset = j3;
12427 vinfos[3].indices[0] = _ij3[0];
12428 vinfos[3].indices[1] = _ij3[1];
12429 vinfos[3].maxsolutions = _nj3;
12430 vinfos[4].jointtype = 1;
12431 vinfos[4].foffset = j4;
12432 vinfos[4].indices[0] = _ij4[0];
12433 vinfos[4].indices[1] = _ij4[1];
12434 vinfos[4].maxsolutions = _nj4;
12435 vinfos[5].jointtype = 1;
12436 vinfos[5].foffset = j5;
12437 vinfos[5].indices[0] = _ij5[0];
12438 vinfos[5].indices[1] = _ij5[1];
12439 vinfos[5].maxsolutions = _nj5;
12440 vinfos[6].jointtype = 1;
12441 vinfos[6].foffset = j6;
12442 vinfos[6].indices[0] = _ij6[0];
12443 vinfos[6].indices[1] = _ij6[1];
12444 vinfos[6].maxsolutions = _nj6;
12445 std::vector<int> vfree(0);
12446 solutions.AddSolution(vinfos,vfree);
12447 }
12448 }
12449 }
12450 
12451 }
12452 
12453 }
12454 }
12455 }
12456 
12457 }
12458 
12459 }
12460 
12461 } else
12462 {
12463 {
12464 IkReal j4array[1], cj4array[1], sj4array[1];
12465 bool j4valid[1]={false};
12466 _nj4 = 1;
12467 IkReal x4073=((sj0)*(sj6));
12468 IkReal x4074=((cj0)*(cj6));
12469 IkReal x4075=((cj0)*(sj6));
12470 IkReal x4076=((IkReal(1.00000000000000))*(cj1));
12471 IkReal x4077=((r20)*(sj1));
12472 IkReal x4078=((cj6)*(sj0));
12473 IkReal x4079=((r21)*(sj1));
12474 IkReal x4080=((cj5)*(x4076));
12475 if( IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(sj6)*(x4079)))+(((cj6)*(x4077)))+(((cj1)*(r11)*(x4073)))+(((cj1)*(r01)*(x4075)))+(((IkReal(-1.00000000000000))*(r10)*(x4076)*(x4078)))+(((IkReal(-1.00000000000000))*(r00)*(x4074)*(x4076))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(r11)*(x4078)*(x4080)))+(((IkReal(-1.00000000000000))*(r00)*(x4075)*(x4080)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(sj5)*(x4076)))+(((cj5)*(sj6)*(x4077)))+(((IkReal(-1.00000000000000))*(r01)*(x4074)*(x4080)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x4076)))+(((IkReal(-1.00000000000000))*(r10)*(x4073)*(x4080)))+(((cj5)*(cj6)*(x4079)))+(((r22)*(sj1)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
12476     continue;
12477 j4array[0]=IKatan2(((gconst14)*(((((IkReal(-1.00000000000000))*(sj6)*(x4079)))+(((cj6)*(x4077)))+(((cj1)*(r11)*(x4073)))+(((cj1)*(r01)*(x4075)))+(((IkReal(-1.00000000000000))*(r10)*(x4076)*(x4078)))+(((IkReal(-1.00000000000000))*(r00)*(x4074)*(x4076)))))), ((gconst14)*(((((IkReal(-1.00000000000000))*(r11)*(x4078)*(x4080)))+(((IkReal(-1.00000000000000))*(r00)*(x4075)*(x4080)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(sj5)*(x4076)))+(((cj5)*(sj6)*(x4077)))+(((IkReal(-1.00000000000000))*(r01)*(x4074)*(x4080)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x4076)))+(((IkReal(-1.00000000000000))*(r10)*(x4073)*(x4080)))+(((cj5)*(cj6)*(x4079)))+(((r22)*(sj1)*(sj5)))))));
12478 sj4array[0]=IKsin(j4array[0]);
12479 cj4array[0]=IKcos(j4array[0]);
12480 if( j4array[0] > IKPI )
12481 {
12482     j4array[0]-=IK2PI;
12483 }
12484 else if( j4array[0] < -IKPI )
12485 {    j4array[0]+=IK2PI;
12486 }
12487 j4valid[0] = true;
12488 for(int ij4 = 0; ij4 < 1; ++ij4)
12489 {
12490 if( !j4valid[ij4] )
12491 {
12492     continue;
12493 }
12494 _ij4[0] = ij4; _ij4[1] = -1;
12495 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
12496 {
12497 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
12498 {
12499     j4valid[iij4]=false; _ij4[1] = iij4; break; 
12500 }
12501 }
12502 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
12503 {
12504 IkReal evalcond[3];
12505 IkReal x4081=IKsin(j4);
12506 IkReal x4082=IKcos(j4);
12507 IkReal x4083=((r00)*(sj6));
12508 IkReal x4084=((cj6)*(r01));
12509 IkReal x4085=((IkReal(1.00000000000000))*(cj0));
12510 IkReal x4086=((IkReal(1.00000000000000))*(sj0));
12511 IkReal x4087=((r10)*(sj6));
12512 IkReal x4088=((sj5)*(x4081));
12513 IkReal x4089=((IkReal(1.00000000000000))*(cj6)*(r11));
12514 IkReal x4090=((cj5)*(x4081));
12515 IkReal x4091=((cj6)*(x4082));
12516 IkReal x4092=((sj0)*(x4090));
12517 IkReal x4093=((r01)*(sj6)*(x4082));
12518 IkReal x4094=((r11)*(sj6)*(x4082));
12519 evalcond[0]=((((r20)*(sj6)*(x4090)))+(((r21)*(sj6)*(x4082)))+(((IkReal(-1.00000000000000))*(cj1)))+(((r22)*(x4088)))+(((cj6)*(r21)*(x4090)))+(((IkReal(-1.00000000000000))*(r20)*(x4091))));
12520 evalcond[1]=((((IkReal(-1.00000000000000))*(x4085)*(x4094)))+(((r02)*(sj0)*(x4088)))+(((x4084)*(x4092)))+(((IkReal(-1.00000000000000))*(r00)*(x4086)*(x4091)))+(((IkReal(-1.00000000000000))*(x4085)*(x4087)*(x4090)))+(((cj0)*(r10)*(x4091)))+(((x4083)*(x4092)))+(((IkReal(-1.00000000000000))*(r12)*(x4085)*(x4088)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x4085)*(x4090)))+(((sj0)*(x4093))));
12521 evalcond[2]=((((IkReal(-1.00000000000000))*(x4086)*(x4094)))+(((IkReal(-1.00000000000000))*(x4083)*(x4085)*(x4090)))+(((IkReal(-1.00000000000000))*(r02)*(x4085)*(x4088)))+(((IkReal(-1.00000000000000))*(x4086)*(x4087)*(x4090)))+(((cj0)*(r00)*(x4091)))+(sj1)+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x4086)*(x4090)))+(((r10)*(sj0)*(x4091)))+(((IkReal(-1.00000000000000))*(r12)*(x4086)*(x4088)))+(((IkReal(-1.00000000000000))*(x4085)*(x4093)))+(((IkReal(-1.00000000000000))*(x4084)*(x4085)*(x4090))));
12522 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
12523 {
12524 continue;
12525 }
12526 }
12527 
12528 {
12529 IkReal dummyeval[1];
12530 IkReal gconst17;
12531 gconst17=IKsign(sj1);
12532 dummyeval[0]=sj1;
12533 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12534 {
12535 {
12536 IkReal dummyeval[1];
12537 dummyeval[0]=sj1;
12538 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12539 {
12540 {
12541 IkReal dummyeval[1];
12542 dummyeval[0]=cj1;
12543 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12544 {
12545 {
12546 IkReal evalcond[9];
12547 IkReal x4095=((IkReal(1.00000000000000))*(cj0));
12548 IkReal x4096=((cj4)*(sj6));
12549 IkReal x4097=((sj0)*(sj6));
12550 IkReal x4098=((cj5)*(sj4));
12551 IkReal x4099=((IkReal(0.374290000000000))*(sj5));
12552 IkReal x4100=((sj4)*(sj5));
12553 IkReal x4101=((cj0)*(cj6));
12554 IkReal x4102=((IkReal(0.0100000000000000))*(cj5));
12555 IkReal x4103=((cj4)*(sj5));
12556 IkReal x4104=((cj5)*(sj0));
12557 IkReal x4105=((IkReal(0.374290000000000))*(r02));
12558 IkReal x4106=((r20)*(sj6));
12559 IkReal x4107=((cj6)*(r21));
12560 IkReal x4108=((IkReal(1.00000000000000))*(sj0));
12561 IkReal x4109=((cj0)*(sj6));
12562 IkReal x4110=((cj4)*(cj6));
12563 IkReal x4111=((IkReal(0.374290000000000))*(r12));
12564 IkReal x4112=((cj0)*(cj5));
12565 IkReal x4113=((cj6)*(sj5));
12566 IkReal x4114=((cj6)*(r01));
12567 IkReal x4115=((r00)*(sj6));
12568 IkReal x4116=((IkReal(0.0100000000000000))*(sj5));
12569 IkReal x4117=((cj6)*(r11));
12570 IkReal x4118=((IkReal(1.00000000000000))*(r10));
12571 IkReal x4119=((r02)*(sj0));
12572 IkReal x4120=((cj6)*(sj4));
12573 IkReal x4121=((r12)*(x4108));
12574 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
12575 evalcond[1]=((((r22)*(x4100)))+(((r21)*(x4096)))+(((x4098)*(x4107)))+(((IkReal(-1.00000000000000))*(r20)*(x4110)))+(((x4098)*(x4106))));
12576 evalcond[2]=((IkReal(0.364420000000000))+(((x4099)*(x4107)))+(((x4099)*(x4106)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x4116)))+(pz)+(((IkReal(-1.00000000000000))*(x4102)*(x4107)))+(((IkReal(-1.00000000000000))*(x4102)*(x4106))));
12577 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x4095)*(x4115)))+(((r12)*(x4104)))+(((IkReal(-1.00000000000000))*(r11)*(x4108)*(x4113)))+(((IkReal(-1.00000000000000))*(sj5)*(x4097)*(x4118)))+(((IkReal(-1.00000000000000))*(r01)*(x4095)*(x4113)))+(((r02)*(x4112))));
12578 evalcond[4]=((((sj0)*(x4098)*(x4114)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x4095)*(x4098)))+(((IkReal(-1.00000000000000))*(r12)*(x4095)*(x4100)))+(((IkReal(-1.00000000000000))*(r00)*(x4108)*(x4110)))+(((IkReal(-1.00000000000000))*(r11)*(x4095)*(x4096)))+(((r00)*(x4097)*(x4098)))+(((IkReal(-1.00000000000000))*(x4095)*(x4098)*(x4117)))+(((r01)*(sj0)*(x4096)))+(((x4100)*(x4119)))+(((cj4)*(r10)*(x4101))));
12579 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x4095)*(x4098)*(x4114)))+(((IkReal(-1.00000000000000))*(x4098)*(x4108)*(x4117)))+(((IkReal(-1.00000000000000))*(x4100)*(x4121)))+(((cj4)*(r00)*(x4101)))+(((IkReal(-1.00000000000000))*(x4097)*(x4098)*(x4118)))+(((IkReal(-1.00000000000000))*(r11)*(x4096)*(x4108)))+(((IkReal(-1.00000000000000))*(x4095)*(x4098)*(x4115)))+(((IkReal(-1.00000000000000))*(r02)*(x4095)*(x4100)))+(((IkReal(-1.00000000000000))*(r01)*(x4095)*(x4096)))+(((r10)*(sj0)*(x4110))));
12580 evalcond[6]=((IkReal(0.0690000000000000))+(((sj0)*(x4099)*(x4114)))+(((IkReal(-1.00000000000000))*(sj0)*(x4102)*(x4114)))+(((r11)*(x4101)*(x4102)))+(((r00)*(x4097)*(x4099)))+(((IkReal(-1.00000000000000))*(r11)*(x4099)*(x4101)))+(((IkReal(-1.00000000000000))*(r00)*(x4097)*(x4102)))+(((IkReal(-1.00000000000000))*(r10)*(x4099)*(x4109)))+(((IkReal(-1.00000000000000))*(x4116)*(x4119)))+(((IkReal(-1.00000000000000))*(py)*(x4095)))+(((IkReal(-1.00000000000000))*(x4104)*(x4105)))+(((r10)*(x4102)*(x4109)))+(((cj0)*(r12)*(x4116)))+(((px)*(sj0)))+(((x4111)*(x4112))));
12581 evalcond[7]=((((IkReal(-1.00000000000000))*(r02)*(x4095)*(x4103)))+(((r01)*(sj4)*(x4109)))+(((IkReal(-1.00000000000000))*(x4103)*(x4121)))+(((IkReal(-1.00000000000000))*(r00)*(x4095)*(x4120)))+(((r11)*(sj4)*(x4097)))+(((IkReal(-1.00000000000000))*(r10)*(x4108)*(x4120)))+(((IkReal(-1.00000000000000))*(x4096)*(x4104)*(x4118)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4095)*(x4110)))+(((IkReal(-1.00000000000000))*(r11)*(x4104)*(x4110)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4095)*(x4096))));
12582 evalcond[8]=((IkReal(0.0690000000000000))+(((r00)*(x4102)*(x4109)))+(((IkReal(-1.00000000000000))*(sj0)*(x4099)*(x4117)))+(((IkReal(-1.00000000000000))*(px)*(x4095)))+(((IkReal(-1.00000000000000))*(r01)*(x4099)*(x4101)))+(((r10)*(x4097)*(x4102)))+(((IkReal(-1.00000000000000))*(r10)*(x4097)*(x4099)))+(((cj0)*(r02)*(x4116)))+(((x4105)*(x4112)))+(((r01)*(x4101)*(x4102)))+(((IkReal(-1.00000000000000))*(r00)*(x4099)*(x4109)))+(((IkReal(-1.00000000000000))*(py)*(x4108)))+(((r12)*(sj0)*(x4116)))+(((x4104)*(x4111)))+(((sj0)*(x4102)*(x4117))));
12583 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
12584 {
12585 {
12586 IkReal j3array[1], cj3array[1], sj3array[1];
12587 bool j3valid[1]={false};
12588 _nj3 = 1;
12589 IkReal x4122=((r20)*(sj6));
12590 IkReal x4123=((cj4)*(cj5));
12591 IkReal x4124=((cj6)*(r21));
12592 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x4123)*(x4124)))+(((cj4)*(r22)*(sj5)))+(((x4122)*(x4123))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x4124)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4122))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x4123)*(x4124)))+(((cj4)*(r22)*(sj5)))+(((x4122)*(x4123)))))+IKsqr(((((sj5)*(x4124)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4122)))))-1) <= IKFAST_SINCOS_THRESH )
12593     continue;
12594 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x4123)*(x4124)))+(((cj4)*(r22)*(sj5)))+(((x4122)*(x4123)))), ((((sj5)*(x4124)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4122)))));
12595 sj3array[0]=IKsin(j3array[0]);
12596 cj3array[0]=IKcos(j3array[0]);
12597 if( j3array[0] > IKPI )
12598 {
12599     j3array[0]-=IK2PI;
12600 }
12601 else if( j3array[0] < -IKPI )
12602 {    j3array[0]+=IK2PI;
12603 }
12604 j3valid[0] = true;
12605 for(int ij3 = 0; ij3 < 1; ++ij3)
12606 {
12607 if( !j3valid[ij3] )
12608 {
12609     continue;
12610 }
12611 _ij3[0] = ij3; _ij3[1] = -1;
12612 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12613 {
12614 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12615 {
12616     j3valid[iij3]=false; _ij3[1] = iij3; break; 
12617 }
12618 }
12619 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12620 {
12621 IkReal evalcond[4];
12622 IkReal x4125=IKcos(j3);
12623 IkReal x4126=((sj0)*(sj5));
12624 IkReal x4127=((r00)*(sj6));
12625 IkReal x4128=((cj6)*(r01));
12626 IkReal x4129=((cj5)*(sj0));
12627 IkReal x4130=((cj0)*(cj5));
12628 IkReal x4131=((cj6)*(sj4));
12629 IkReal x4132=((sj4)*(sj6));
12630 IkReal x4133=((cj0)*(r11));
12631 IkReal x4134=((cj4)*(cj6));
12632 IkReal x4135=((cj4)*(sj6));
12633 IkReal x4136=((IkReal(1.00000000000000))*(cj0));
12634 IkReal x4137=((cj4)*(sj5));
12635 IkReal x4138=((sj5)*(sj6));
12636 IkReal x4139=((cj6)*(sj5));
12637 IkReal x4140=((IkReal(1.00000000000000))*(IKsin(j3)));
12638 evalcond[0]=((((r21)*(x4139)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4125)))+(((r20)*(x4138))));
12639 evalcond[1]=((((IkReal(-1.00000000000000))*(x4140)))+(((r20)*(x4131)))+(((IkReal(-1.00000000000000))*(r21)*(x4132)))+(((cj5)*(r21)*(x4134)))+(((r22)*(x4137)))+(((cj5)*(r20)*(x4135))));
12640 evalcond[2]=((((IkReal(-1.00000000000000))*(x4140)))+(((x4126)*(x4128)))+(((IkReal(-1.00000000000000))*(r02)*(x4129)))+(((IkReal(-1.00000000000000))*(x4133)*(x4139)))+(((r12)*(x4130)))+(((IkReal(-1.00000000000000))*(r10)*(x4136)*(x4138)))+(((x4126)*(x4127))));
12641 evalcond[3]=((((cj4)*(x4127)*(x4129)))+(((IkReal(-1.00000000000000))*(r10)*(x4130)*(x4135)))+(((x4132)*(x4133)))+(((cj4)*(r02)*(x4126)))+(((IkReal(-1.00000000000000))*(r12)*(x4136)*(x4137)))+(((IkReal(-1.00000000000000))*(r10)*(x4131)*(x4136)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x4132)))+(((IkReal(-1.00000000000000))*(r11)*(x4130)*(x4134)))+(((r00)*(sj0)*(x4131)))+(((cj4)*(x4128)*(x4129)))+(x4125));
12642 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12643 {
12644 continue;
12645 }
12646 }
12647 
12648 {
12649 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12650 vinfos[0].jointtype = 1;
12651 vinfos[0].foffset = j0;
12652 vinfos[0].indices[0] = _ij0[0];
12653 vinfos[0].indices[1] = _ij0[1];
12654 vinfos[0].maxsolutions = _nj0;
12655 vinfos[1].jointtype = 1;
12656 vinfos[1].foffset = j1;
12657 vinfos[1].indices[0] = _ij1[0];
12658 vinfos[1].indices[1] = _ij1[1];
12659 vinfos[1].maxsolutions = _nj1;
12660 vinfos[2].jointtype = 1;
12661 vinfos[2].foffset = j2;
12662 vinfos[2].indices[0] = _ij2[0];
12663 vinfos[2].indices[1] = _ij2[1];
12664 vinfos[2].maxsolutions = _nj2;
12665 vinfos[3].jointtype = 1;
12666 vinfos[3].foffset = j3;
12667 vinfos[3].indices[0] = _ij3[0];
12668 vinfos[3].indices[1] = _ij3[1];
12669 vinfos[3].maxsolutions = _nj3;
12670 vinfos[4].jointtype = 1;
12671 vinfos[4].foffset = j4;
12672 vinfos[4].indices[0] = _ij4[0];
12673 vinfos[4].indices[1] = _ij4[1];
12674 vinfos[4].maxsolutions = _nj4;
12675 vinfos[5].jointtype = 1;
12676 vinfos[5].foffset = j5;
12677 vinfos[5].indices[0] = _ij5[0];
12678 vinfos[5].indices[1] = _ij5[1];
12679 vinfos[5].maxsolutions = _nj5;
12680 vinfos[6].jointtype = 1;
12681 vinfos[6].foffset = j6;
12682 vinfos[6].indices[0] = _ij6[0];
12683 vinfos[6].indices[1] = _ij6[1];
12684 vinfos[6].maxsolutions = _nj6;
12685 std::vector<int> vfree(0);
12686 solutions.AddSolution(vinfos,vfree);
12687 }
12688 }
12689 }
12690 
12691 } else
12692 {
12693 IkReal x4141=((IkReal(1.00000000000000))*(cj0));
12694 IkReal x4142=((cj4)*(sj6));
12695 IkReal x4143=((sj0)*(sj6));
12696 IkReal x4144=((cj5)*(sj4));
12697 IkReal x4145=((IkReal(0.374290000000000))*(sj5));
12698 IkReal x4146=((sj4)*(sj5));
12699 IkReal x4147=((cj0)*(cj6));
12700 IkReal x4148=((IkReal(0.0100000000000000))*(cj5));
12701 IkReal x4149=((cj4)*(sj5));
12702 IkReal x4150=((cj5)*(sj0));
12703 IkReal x4151=((IkReal(0.374290000000000))*(r02));
12704 IkReal x4152=((r20)*(sj6));
12705 IkReal x4153=((cj6)*(r21));
12706 IkReal x4154=((IkReal(1.00000000000000))*(sj0));
12707 IkReal x4155=((cj0)*(sj6));
12708 IkReal x4156=((cj4)*(cj6));
12709 IkReal x4157=((IkReal(0.374290000000000))*(r12));
12710 IkReal x4158=((cj0)*(cj5));
12711 IkReal x4159=((cj6)*(sj5));
12712 IkReal x4160=((cj6)*(r01));
12713 IkReal x4161=((r00)*(sj6));
12714 IkReal x4162=((IkReal(0.0100000000000000))*(sj5));
12715 IkReal x4163=((cj6)*(r11));
12716 IkReal x4164=((IkReal(1.00000000000000))*(r10));
12717 IkReal x4165=((r02)*(sj0));
12718 IkReal x4166=((cj6)*(sj4));
12719 IkReal x4167=((r12)*(x4154));
12720 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
12721 evalcond[1]=((((x4144)*(x4153)))+(((x4144)*(x4152)))+(((r22)*(x4146)))+(((r21)*(x4142)))+(((IkReal(-1.00000000000000))*(r20)*(x4156))));
12722 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x4148)*(x4152)))+(((IkReal(-1.00000000000000))*(r22)*(x4162)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x4145)*(x4152)))+(((IkReal(-1.00000000000000))*(x4148)*(x4153)))+(((x4145)*(x4153))));
12723 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x4141)*(x4161)))+(((IkReal(-1.00000000000000))*(r11)*(x4154)*(x4159)))+(((IkReal(-1.00000000000000))*(r01)*(x4141)*(x4159)))+(((r12)*(x4150)))+(((r02)*(x4158)))+(((IkReal(-1.00000000000000))*(sj5)*(x4143)*(x4164))));
12724 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x4141)*(x4146)))+(((sj0)*(x4144)*(x4160)))+(((IkReal(-1.00000000000000))*(r11)*(x4141)*(x4142)))+(((r01)*(sj0)*(x4142)))+(((IkReal(-1.00000000000000))*(x4141)*(x4144)*(x4163)))+(((IkReal(-1.00000000000000))*(r00)*(x4154)*(x4156)))+(((cj4)*(r10)*(x4147)))+(((x4146)*(x4165)))+(((r00)*(x4143)*(x4144)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x4141)*(x4144))));
12725 evalcond[5]=((IkReal(-1.00000000000000))+(((r10)*(sj0)*(x4156)))+(((IkReal(-1.00000000000000))*(x4146)*(x4167)))+(((cj4)*(r00)*(x4147)))+(((IkReal(-1.00000000000000))*(x4141)*(x4144)*(x4161)))+(((IkReal(-1.00000000000000))*(r11)*(x4142)*(x4154)))+(((IkReal(-1.00000000000000))*(x4144)*(x4154)*(x4163)))+(((IkReal(-1.00000000000000))*(x4141)*(x4144)*(x4160)))+(((IkReal(-1.00000000000000))*(x4143)*(x4144)*(x4164)))+(((IkReal(-1.00000000000000))*(r01)*(x4141)*(x4142)))+(((IkReal(-1.00000000000000))*(r02)*(x4141)*(x4146))));
12726 evalcond[6]=((IkReal(0.0690000000000000))+(((r11)*(x4147)*(x4148)))+(((cj0)*(r12)*(x4162)))+(((IkReal(-1.00000000000000))*(x4162)*(x4165)))+(((r00)*(x4143)*(x4145)))+(((IkReal(-1.00000000000000))*(py)*(x4141)))+(((IkReal(-1.00000000000000))*(sj0)*(x4148)*(x4160)))+(((x4157)*(x4158)))+(((IkReal(-1.00000000000000))*(r00)*(x4143)*(x4148)))+(((r10)*(x4148)*(x4155)))+(((IkReal(-1.00000000000000))*(r10)*(x4145)*(x4155)))+(((IkReal(-1.00000000000000))*(x4150)*(x4151)))+(((sj0)*(x4145)*(x4160)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x4145)*(x4147))));
12727 evalcond[7]=((((r01)*(sj4)*(x4155)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4141)*(x4142)))+(((IkReal(-1.00000000000000))*(r11)*(x4150)*(x4156)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4141)*(x4156)))+(((IkReal(-1.00000000000000))*(r10)*(x4154)*(x4166)))+(((IkReal(-1.00000000000000))*(x4142)*(x4150)*(x4164)))+(((r11)*(sj4)*(x4143)))+(((IkReal(-1.00000000000000))*(r02)*(x4141)*(x4149)))+(((IkReal(-1.00000000000000))*(r00)*(x4141)*(x4166)))+(((IkReal(-1.00000000000000))*(x4149)*(x4167))));
12728 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x4143)*(x4145)))+(((r10)*(x4143)*(x4148)))+(((IkReal(-1.00000000000000))*(r00)*(x4145)*(x4155)))+(((r00)*(x4148)*(x4155)))+(((x4150)*(x4157)))+(((r12)*(sj0)*(x4162)))+(((IkReal(-1.00000000000000))*(sj0)*(x4145)*(x4163)))+(((sj0)*(x4148)*(x4163)))+(((IkReal(-1.00000000000000))*(r01)*(x4145)*(x4147)))+(((cj0)*(r02)*(x4162)))+(((r01)*(x4147)*(x4148)))+(((IkReal(-1.00000000000000))*(py)*(x4154)))+(((x4151)*(x4158)))+(((IkReal(-1.00000000000000))*(px)*(x4141))));
12729 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
12730 {
12731 {
12732 IkReal j3array[1], cj3array[1], sj3array[1];
12733 bool j3valid[1]={false};
12734 _nj3 = 1;
12735 IkReal x4168=((IkReal(1.00000000000000))*(sj5));
12736 IkReal x4169=((cj6)*(r21));
12737 IkReal x4170=((r20)*(sj6));
12738 IkReal x4171=((IkReal(1.00000000000000))*(cj4)*(cj5));
12739 if( IKabs(((((IkReal(-1.00000000000000))*(x4170)*(x4171)))+(((IkReal(-1.00000000000000))*(x4169)*(x4171)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4168)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x4168)*(x4170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4168)*(x4169))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x4170)*(x4171)))+(((IkReal(-1.00000000000000))*(x4169)*(x4171)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4168)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x4168)*(x4170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4168)*(x4169)))))-1) <= IKFAST_SINCOS_THRESH )
12740     continue;
12741 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x4170)*(x4171)))+(((IkReal(-1.00000000000000))*(x4169)*(x4171)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4168)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x4168)*(x4170)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4168)*(x4169)))));
12742 sj3array[0]=IKsin(j3array[0]);
12743 cj3array[0]=IKcos(j3array[0]);
12744 if( j3array[0] > IKPI )
12745 {
12746     j3array[0]-=IK2PI;
12747 }
12748 else if( j3array[0] < -IKPI )
12749 {    j3array[0]+=IK2PI;
12750 }
12751 j3valid[0] = true;
12752 for(int ij3 = 0; ij3 < 1; ++ij3)
12753 {
12754 if( !j3valid[ij3] )
12755 {
12756     continue;
12757 }
12758 _ij3[0] = ij3; _ij3[1] = -1;
12759 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12760 {
12761 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12762 {
12763     j3valid[iij3]=false; _ij3[1] = iij3; break; 
12764 }
12765 }
12766 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12767 {
12768 IkReal evalcond[4];
12769 IkReal x4172=IKsin(j3);
12770 IkReal x4173=IKcos(j3);
12771 IkReal x4174=((sj0)*(sj5));
12772 IkReal x4175=((r00)*(sj6));
12773 IkReal x4176=((cj6)*(r01));
12774 IkReal x4177=((cj5)*(sj0));
12775 IkReal x4178=((cj0)*(cj5));
12776 IkReal x4179=((cj6)*(sj4));
12777 IkReal x4180=((sj4)*(sj6));
12778 IkReal x4181=((cj0)*(r11));
12779 IkReal x4182=((cj4)*(cj6));
12780 IkReal x4183=((cj4)*(sj6));
12781 IkReal x4184=((IkReal(1.00000000000000))*(cj0));
12782 IkReal x4185=((cj4)*(sj5));
12783 IkReal x4186=((sj5)*(sj6));
12784 IkReal x4187=((cj6)*(sj5));
12785 evalcond[0]=((((r21)*(x4187)))+(x4173)+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x4186))));
12786 evalcond[1]=((x4172)+(((r22)*(x4185)))+(((cj5)*(r21)*(x4182)))+(((IkReal(-1.00000000000000))*(r21)*(x4180)))+(((r20)*(x4179)))+(((cj5)*(r20)*(x4183))));
12787 evalcond[2]=((((IkReal(-1.00000000000000))*(x4181)*(x4187)))+(((IkReal(-1.00000000000000))*(r02)*(x4177)))+(((r12)*(x4178)))+(((x4174)*(x4175)))+(((x4174)*(x4176)))+(((IkReal(-1.00000000000000))*(r10)*(x4184)*(x4186)))+(((IkReal(-1.00000000000000))*(x4172))));
12788 evalcond[3]=((((r00)*(sj0)*(x4179)))+(((x4180)*(x4181)))+(((cj4)*(r02)*(x4174)))+(x4173)+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x4180)))+(((cj4)*(x4176)*(x4177)))+(((cj4)*(x4175)*(x4177)))+(((IkReal(-1.00000000000000))*(r10)*(x4179)*(x4184)))+(((IkReal(-1.00000000000000))*(r10)*(x4178)*(x4183)))+(((IkReal(-1.00000000000000))*(r12)*(x4184)*(x4185)))+(((IkReal(-1.00000000000000))*(r11)*(x4178)*(x4182))));
12789 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12790 {
12791 continue;
12792 }
12793 }
12794 
12795 {
12796 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12797 vinfos[0].jointtype = 1;
12798 vinfos[0].foffset = j0;
12799 vinfos[0].indices[0] = _ij0[0];
12800 vinfos[0].indices[1] = _ij0[1];
12801 vinfos[0].maxsolutions = _nj0;
12802 vinfos[1].jointtype = 1;
12803 vinfos[1].foffset = j1;
12804 vinfos[1].indices[0] = _ij1[0];
12805 vinfos[1].indices[1] = _ij1[1];
12806 vinfos[1].maxsolutions = _nj1;
12807 vinfos[2].jointtype = 1;
12808 vinfos[2].foffset = j2;
12809 vinfos[2].indices[0] = _ij2[0];
12810 vinfos[2].indices[1] = _ij2[1];
12811 vinfos[2].maxsolutions = _nj2;
12812 vinfos[3].jointtype = 1;
12813 vinfos[3].foffset = j3;
12814 vinfos[3].indices[0] = _ij3[0];
12815 vinfos[3].indices[1] = _ij3[1];
12816 vinfos[3].maxsolutions = _nj3;
12817 vinfos[4].jointtype = 1;
12818 vinfos[4].foffset = j4;
12819 vinfos[4].indices[0] = _ij4[0];
12820 vinfos[4].indices[1] = _ij4[1];
12821 vinfos[4].maxsolutions = _nj4;
12822 vinfos[5].jointtype = 1;
12823 vinfos[5].foffset = j5;
12824 vinfos[5].indices[0] = _ij5[0];
12825 vinfos[5].indices[1] = _ij5[1];
12826 vinfos[5].maxsolutions = _nj5;
12827 vinfos[6].jointtype = 1;
12828 vinfos[6].foffset = j6;
12829 vinfos[6].indices[0] = _ij6[0];
12830 vinfos[6].indices[1] = _ij6[1];
12831 vinfos[6].maxsolutions = _nj6;
12832 std::vector<int> vfree(0);
12833 solutions.AddSolution(vinfos,vfree);
12834 }
12835 }
12836 }
12837 
12838 } else
12839 {
12840 IkReal x4188=((IkReal(1.00000000000000))*(cj0));
12841 IkReal x4189=((cj4)*(sj6));
12842 IkReal x4190=((sj0)*(sj4));
12843 IkReal x4191=((cj5)*(sj6));
12844 IkReal x4192=((sj4)*(sj5));
12845 IkReal x4193=((r12)*(sj5));
12846 IkReal x4194=((IkReal(0.374290000000000))*(cj5));
12847 IkReal x4195=((r02)*(sj0));
12848 IkReal x4196=((r20)*(sj4));
12849 IkReal x4197=((IkReal(1.00000000000000))*(sj0));
12850 IkReal x4198=((IkReal(1.00000000000000))*(cj5));
12851 IkReal x4199=((cj0)*(r10));
12852 IkReal x4200=((cj4)*(cj6));
12853 IkReal x4201=((r00)*(sj0));
12854 IkReal x4202=((cj6)*(r21));
12855 IkReal x4203=((IkReal(0.374290000000000))*(sj5));
12856 IkReal x4204=((cj0)*(r00));
12857 IkReal x4205=((IkReal(0.0100000000000000))*(sj5));
12858 IkReal x4206=((cj0)*(r02));
12859 IkReal x4207=((cj5)*(sj4));
12860 IkReal x4208=((cj6)*(r01));
12861 IkReal x4209=((cj6)*(r11));
12862 IkReal x4210=((r01)*(sj0));
12863 IkReal x4211=((r10)*(sj0));
12864 IkReal x4212=((IkReal(0.0100000000000000))*(cj5)*(cj6));
12865 IkReal x4213=((sj6)*(x4203));
12866 IkReal x4214=((cj0)*(cj6)*(x4203));
12867 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
12868 evalcond[1]=((((sj5)*(x4202)))+(((IkReal(-1.00000000000000))*(r22)*(x4198)))+(((r20)*(sj5)*(sj6))));
12869 evalcond[2]=((IkReal(-1.00000000000000))+(((x4202)*(x4207)))+(((x4191)*(x4196)))+(((r21)*(x4189)))+(((r22)*(x4192)))+(((IkReal(-1.00000000000000))*(r20)*(x4200))));
12870 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x4191)))+(((IkReal(-0.0100000000000000))*(cj5)*(x4202)))+(((x4202)*(x4203)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x4194)))+(((IkReal(-1.00000000000000))*(r22)*(x4205)))+(((r20)*(x4213))));
12871 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x4200)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x4189)))+(((cj6)*(x4196))));
12872 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x4188)*(x4191)))+(((r00)*(x4190)*(x4191)))+(((IkReal(-1.00000000000000))*(r00)*(x4197)*(x4200)))+(((IkReal(-1.00000000000000))*(r11)*(x4188)*(x4189)))+(((x4199)*(x4200)))+(((cj5)*(x4190)*(x4208)))+(((r02)*(sj5)*(x4190)))+(((IkReal(-1.00000000000000))*(r12)*(x4188)*(x4192)))+(((IkReal(-1.00000000000000))*(x4188)*(x4207)*(x4209)))+(((x4189)*(x4210))));
12873 evalcond[6]=((((x4200)*(x4204)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x4188)*(x4191)))+(((x4200)*(x4211)))+(((IkReal(-1.00000000000000))*(r01)*(x4188)*(x4189)))+(((IkReal(-1.00000000000000))*(x4188)*(x4207)*(x4208)))+(((IkReal(-1.00000000000000))*(r02)*(x4188)*(x4192)))+(((IkReal(-1.00000000000000))*(x4190)*(x4198)*(x4209)))+(((IkReal(-1.00000000000000))*(x4190)*(x4193)))+(((IkReal(-1.00000000000000))*(r11)*(x4189)*(x4197)))+(((IkReal(-1.00000000000000))*(r10)*(x4190)*(x4191))));
12874 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x4203)*(x4209)))+(((IkReal(-1.00000000000000))*(x4195)*(x4205)))+(((sj0)*(x4203)*(x4208)))+(((IkReal(-1.00000000000000))*(py)*(x4188)))+(((cj0)*(r12)*(x4194)))+(((x4201)*(x4213)))+(((IkReal(-1.00000000000000))*(x4194)*(x4195)))+(((IkReal(-1.00000000000000))*(x4199)*(x4213)))+(((IkReal(0.0100000000000000))*(x4191)*(x4199)))+(((IkReal(0.0100000000000000))*(cj0)*(x4193)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4209)))+(((IkReal(-0.0100000000000000))*(x4191)*(x4201)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x4208))));
12875 evalcond[8]=((IkReal(0.433420000000000))+(((r12)*(sj0)*(x4194)))+(((IkReal(0.0100000000000000))*(x4191)*(x4211)))+(((x4194)*(x4206)))+(((x4205)*(x4206)))+(((IkReal(-1.00000000000000))*(px)*(x4188)))+(((IkReal(-1.00000000000000))*(cj0)*(x4203)*(x4208)))+(((IkReal(0.0100000000000000))*(sj0)*(x4193)))+(((IkReal(-1.00000000000000))*(py)*(x4197)))+(((IkReal(-1.00000000000000))*(sj0)*(x4203)*(x4209)))+(((IkReal(0.0100000000000000))*(x4191)*(x4204)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4208)))+(((IkReal(-1.00000000000000))*(x4211)*(x4213)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x4209)))+(((IkReal(-1.00000000000000))*(x4204)*(x4213))));
12876 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
12877 {
12878 {
12879 IkReal j3array[1], cj3array[1], sj3array[1];
12880 bool j3valid[1]={false};
12881 _nj3 = 1;
12882 IkReal x4215=((cj0)*(cj5));
12883 IkReal x4216=((IkReal(1.00000000000000))*(cj0));
12884 IkReal x4217=((cj6)*(r11));
12885 IkReal x4218=((r10)*(sj6));
12886 IkReal x4219=((cj5)*(sj0));
12887 IkReal x4220=((r00)*(sj5)*(sj6));
12888 IkReal x4221=((cj6)*(r01)*(sj5));
12889 IkReal x4222=((IkReal(1.00000000000000))*(sj0)*(sj5));
12890 if( IKabs(((((sj0)*(x4221)))+(((IkReal(-1.00000000000000))*(r02)*(x4219)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4217)))+(((sj0)*(x4220)))+(((r12)*(x4215)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4218))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x4218)*(x4222)))+(((IkReal(-1.00000000000000))*(x4216)*(x4221)))+(((IkReal(-1.00000000000000))*(x4217)*(x4222)))+(((r02)*(x4215)))+(((r12)*(x4219)))+(((IkReal(-1.00000000000000))*(x4216)*(x4220))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x4221)))+(((IkReal(-1.00000000000000))*(r02)*(x4219)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4217)))+(((sj0)*(x4220)))+(((r12)*(x4215)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4218)))))+IKsqr(((((IkReal(-1.00000000000000))*(x4218)*(x4222)))+(((IkReal(-1.00000000000000))*(x4216)*(x4221)))+(((IkReal(-1.00000000000000))*(x4217)*(x4222)))+(((r02)*(x4215)))+(((r12)*(x4219)))+(((IkReal(-1.00000000000000))*(x4216)*(x4220)))))-1) <= IKFAST_SINCOS_THRESH )
12891     continue;
12892 j3array[0]=IKatan2(((((sj0)*(x4221)))+(((IkReal(-1.00000000000000))*(r02)*(x4219)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4217)))+(((sj0)*(x4220)))+(((r12)*(x4215)))+(((IkReal(-1.00000000000000))*(sj5)*(x4216)*(x4218)))), ((((IkReal(-1.00000000000000))*(x4218)*(x4222)))+(((IkReal(-1.00000000000000))*(x4216)*(x4221)))+(((IkReal(-1.00000000000000))*(x4217)*(x4222)))+(((r02)*(x4215)))+(((r12)*(x4219)))+(((IkReal(-1.00000000000000))*(x4216)*(x4220)))));
12893 sj3array[0]=IKsin(j3array[0]);
12894 cj3array[0]=IKcos(j3array[0]);
12895 if( j3array[0] > IKPI )
12896 {
12897     j3array[0]-=IK2PI;
12898 }
12899 else if( j3array[0] < -IKPI )
12900 {    j3array[0]+=IK2PI;
12901 }
12902 j3valid[0] = true;
12903 for(int ij3 = 0; ij3 < 1; ++ij3)
12904 {
12905 if( !j3valid[ij3] )
12906 {
12907     continue;
12908 }
12909 _ij3[0] = ij3; _ij3[1] = -1;
12910 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
12911 {
12912 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
12913 {
12914     j3valid[iij3]=false; _ij3[1] = iij3; break; 
12915 }
12916 }
12917 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
12918 {
12919 IkReal evalcond[4];
12920 IkReal x4223=IKcos(j3);
12921 IkReal x4224=((sj0)*(sj5));
12922 IkReal x4225=((r00)*(sj6));
12923 IkReal x4226=((cj6)*(sj0));
12924 IkReal x4227=((IkReal(1.00000000000000))*(cj4));
12925 IkReal x4228=((r00)*(sj4));
12926 IkReal x4229=((cj0)*(cj5));
12927 IkReal x4230=((cj5)*(sj0));
12928 IkReal x4231=((cj6)*(r11));
12929 IkReal x4232=((r10)*(sj6));
12930 IkReal x4233=((cj0)*(sj5));
12931 IkReal x4234=((r10)*(sj4));
12932 IkReal x4235=((IkReal(1.00000000000000))*(IKsin(j3)));
12933 IkReal x4236=((cj4)*(cj5)*(r01));
12934 IkReal x4237=((IkReal(1.00000000000000))*(cj0)*(cj6));
12935 IkReal x4238=((cj0)*(sj4)*(sj6));
12936 IkReal x4239=((sj0)*(sj4)*(sj6));
12937 evalcond[0]=((((cj6)*(r01)*(x4224)))+(((IkReal(-1.00000000000000))*(x4231)*(x4233)))+(((x4224)*(x4225)))+(((IkReal(-1.00000000000000))*(x4232)*(x4233)))+(((IkReal(-1.00000000000000))*(x4235)))+(((r12)*(x4229)))+(((IkReal(-1.00000000000000))*(r02)*(x4230))));
12938 evalcond[1]=((((r02)*(x4229)))+(((r12)*(x4230)))+(((IkReal(-1.00000000000000))*(x4225)*(x4233)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4233)))+(((IkReal(-1.00000000000000))*(x4223)))+(((IkReal(-1.00000000000000))*(x4224)*(x4232)))+(((IkReal(-1.00000000000000))*(x4224)*(x4231))));
12939 evalcond[2]=((((IkReal(-1.00000000000000))*(x4234)*(x4237)))+(((x4226)*(x4236)))+(((cj4)*(x4225)*(x4230)))+(((IkReal(-1.00000000000000))*(r12)*(x4227)*(x4233)))+(((cj4)*(r02)*(x4224)))+(x4223)+(((IkReal(-1.00000000000000))*(r01)*(x4239)))+(((x4226)*(x4228)))+(((IkReal(-1.00000000000000))*(x4227)*(x4229)*(x4232)))+(((IkReal(-1.00000000000000))*(x4227)*(x4229)*(x4231)))+(((r11)*(x4238))));
12940 evalcond[3]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4227)*(x4229)))+(((IkReal(-1.00000000000000))*(x4227)*(x4230)*(x4232)))+(((IkReal(-1.00000000000000))*(r12)*(x4224)*(x4227)))+(((IkReal(-1.00000000000000))*(x4228)*(x4237)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4226)*(x4227)))+(((r01)*(x4238)))+(((IkReal(-1.00000000000000))*(x4226)*(x4234)))+(((IkReal(-1.00000000000000))*(r02)*(x4227)*(x4233)))+(((r11)*(x4239)))+(((IkReal(-1.00000000000000))*(x4235)))+(((IkReal(-1.00000000000000))*(x4225)*(x4227)*(x4229))));
12941 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12942 {
12943 continue;
12944 }
12945 }
12946 
12947 {
12948 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
12949 vinfos[0].jointtype = 1;
12950 vinfos[0].foffset = j0;
12951 vinfos[0].indices[0] = _ij0[0];
12952 vinfos[0].indices[1] = _ij0[1];
12953 vinfos[0].maxsolutions = _nj0;
12954 vinfos[1].jointtype = 1;
12955 vinfos[1].foffset = j1;
12956 vinfos[1].indices[0] = _ij1[0];
12957 vinfos[1].indices[1] = _ij1[1];
12958 vinfos[1].maxsolutions = _nj1;
12959 vinfos[2].jointtype = 1;
12960 vinfos[2].foffset = j2;
12961 vinfos[2].indices[0] = _ij2[0];
12962 vinfos[2].indices[1] = _ij2[1];
12963 vinfos[2].maxsolutions = _nj2;
12964 vinfos[3].jointtype = 1;
12965 vinfos[3].foffset = j3;
12966 vinfos[3].indices[0] = _ij3[0];
12967 vinfos[3].indices[1] = _ij3[1];
12968 vinfos[3].maxsolutions = _nj3;
12969 vinfos[4].jointtype = 1;
12970 vinfos[4].foffset = j4;
12971 vinfos[4].indices[0] = _ij4[0];
12972 vinfos[4].indices[1] = _ij4[1];
12973 vinfos[4].maxsolutions = _nj4;
12974 vinfos[5].jointtype = 1;
12975 vinfos[5].foffset = j5;
12976 vinfos[5].indices[0] = _ij5[0];
12977 vinfos[5].indices[1] = _ij5[1];
12978 vinfos[5].maxsolutions = _nj5;
12979 vinfos[6].jointtype = 1;
12980 vinfos[6].foffset = j6;
12981 vinfos[6].indices[0] = _ij6[0];
12982 vinfos[6].indices[1] = _ij6[1];
12983 vinfos[6].maxsolutions = _nj6;
12984 std::vector<int> vfree(0);
12985 solutions.AddSolution(vinfos,vfree);
12986 }
12987 }
12988 }
12989 
12990 } else
12991 {
12992 IkReal x4240=((IkReal(1.00000000000000))*(cj0));
12993 IkReal x4241=((cj4)*(sj6));
12994 IkReal x4242=((sj0)*(sj4));
12995 IkReal x4243=((cj5)*(sj6));
12996 IkReal x4244=((sj4)*(sj5));
12997 IkReal x4245=((r12)*(sj5));
12998 IkReal x4246=((IkReal(0.374290000000000))*(cj5));
12999 IkReal x4247=((r02)*(sj0));
13000 IkReal x4248=((r20)*(sj4));
13001 IkReal x4249=((IkReal(1.00000000000000))*(sj0));
13002 IkReal x4250=((IkReal(1.00000000000000))*(cj5));
13003 IkReal x4251=((cj0)*(r10));
13004 IkReal x4252=((cj4)*(cj6));
13005 IkReal x4253=((r00)*(sj0));
13006 IkReal x4254=((cj6)*(r21));
13007 IkReal x4255=((IkReal(0.374290000000000))*(sj5));
13008 IkReal x4256=((cj0)*(r00));
13009 IkReal x4257=((IkReal(0.0100000000000000))*(sj5));
13010 IkReal x4258=((cj0)*(r02));
13011 IkReal x4259=((cj5)*(sj4));
13012 IkReal x4260=((cj6)*(r01));
13013 IkReal x4261=((cj6)*(r11));
13014 IkReal x4262=((r01)*(sj0));
13015 IkReal x4263=((r10)*(sj0));
13016 IkReal x4264=((IkReal(0.0100000000000000))*(cj5)*(cj6));
13017 IkReal x4265=((sj6)*(x4255));
13018 IkReal x4266=((cj0)*(cj6)*(x4255));
13019 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
13020 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x4250)))+(((sj5)*(x4254)))+(((r20)*(sj5)*(sj6))));
13021 evalcond[2]=((IkReal(1.00000000000000))+(((x4243)*(x4248)))+(((r21)*(x4241)))+(((IkReal(-1.00000000000000))*(r20)*(x4252)))+(((x4254)*(x4259)))+(((r22)*(x4244))));
13022 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x4246)))+(((x4254)*(x4255)))+(((IkReal(-0.0100000000000000))*(cj5)*(x4254)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x4243)))+(((IkReal(-1.00000000000000))*(r22)*(x4257)))+(((r20)*(x4265))));
13023 evalcond[4]=((((cj5)*(r21)*(x4252)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x4248)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x4241))));
13024 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x4240)*(x4243)))+(((r00)*(x4242)*(x4243)))+(((IkReal(-1.00000000000000))*(r12)*(x4240)*(x4244)))+(((IkReal(-1.00000000000000))*(r11)*(x4240)*(x4241)))+(((x4251)*(x4252)))+(((x4241)*(x4262)))+(((r02)*(sj5)*(x4242)))+(((IkReal(-1.00000000000000))*(x4240)*(x4259)*(x4261)))+(((IkReal(-1.00000000000000))*(r00)*(x4249)*(x4252)))+(((cj5)*(x4242)*(x4260))));
13025 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(sj4)*(x4240)*(x4243)))+(((IkReal(-1.00000000000000))*(x4242)*(x4250)*(x4261)))+(((IkReal(-1.00000000000000))*(r01)*(x4240)*(x4241)))+(((x4252)*(x4256)))+(((IkReal(-1.00000000000000))*(r11)*(x4241)*(x4249)))+(((IkReal(-1.00000000000000))*(r10)*(x4242)*(x4243)))+(((IkReal(-1.00000000000000))*(x4242)*(x4245)))+(((IkReal(-1.00000000000000))*(x4240)*(x4259)*(x4260)))+(((x4252)*(x4263)))+(((IkReal(-1.00000000000000))*(r02)*(x4240)*(x4244))));
13026 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(x4243)*(x4251)))+(((IkReal(-1.00000000000000))*(cj0)*(x4255)*(x4261)))+(((x4253)*(x4265)))+(((IkReal(-0.0100000000000000))*(x4243)*(x4253)))+(((IkReal(0.0100000000000000))*(cj0)*(x4245)))+(((IkReal(-1.00000000000000))*(x4246)*(x4247)))+(((cj0)*(r12)*(x4246)))+(((IkReal(-1.00000000000000))*(x4251)*(x4265)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4261)))+(((sj0)*(x4255)*(x4260)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x4260)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x4247)*(x4257)))+(((IkReal(-1.00000000000000))*(py)*(x4240))));
13027 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(x4256)*(x4265)))+(((IkReal(-1.00000000000000))*(py)*(x4249)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x4261)))+(((IkReal(-1.00000000000000))*(cj0)*(x4255)*(x4260)))+(((r12)*(sj0)*(x4246)))+(((IkReal(-1.00000000000000))*(sj0)*(x4255)*(x4261)))+(((IkReal(0.0100000000000000))*(x4243)*(x4256)))+(((IkReal(0.0100000000000000))*(x4243)*(x4263)))+(((IkReal(-1.00000000000000))*(px)*(x4240)))+(((IkReal(-1.00000000000000))*(x4263)*(x4265)))+(((x4257)*(x4258)))+(((x4246)*(x4258)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4260)))+(((IkReal(0.0100000000000000))*(sj0)*(x4245))));
13028 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
13029 {
13030 {
13031 IkReal j3array[1], cj3array[1], sj3array[1];
13032 bool j3valid[1]={false};
13033 _nj3 = 1;
13034 IkReal x4267=((sj0)*(sj5));
13035 IkReal x4268=((r00)*(sj6));
13036 IkReal x4269=((IkReal(1.00000000000000))*(cj5));
13037 IkReal x4270=((cj6)*(r11));
13038 IkReal x4271=((cj6)*(r01));
13039 IkReal x4272=((r10)*(sj6));
13040 IkReal x4273=((cj0)*(sj5));
13041 if( IKabs(((((IkReal(-1.00000000000000))*(x4272)*(x4273)))+(((cj0)*(cj5)*(r12)))+(((x4267)*(x4268)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4269)))+(((x4267)*(x4271)))+(((IkReal(-1.00000000000000))*(x4270)*(x4273))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x4271)*(x4273)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4269)))+(((x4267)*(x4270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4269)))+(((x4268)*(x4273)))+(((x4267)*(x4272))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x4272)*(x4273)))+(((cj0)*(cj5)*(r12)))+(((x4267)*(x4268)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4269)))+(((x4267)*(x4271)))+(((IkReal(-1.00000000000000))*(x4270)*(x4273)))))+IKsqr(((((x4271)*(x4273)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4269)))+(((x4267)*(x4270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4269)))+(((x4268)*(x4273)))+(((x4267)*(x4272)))))-1) <= IKFAST_SINCOS_THRESH )
13042     continue;
13043 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x4272)*(x4273)))+(((cj0)*(cj5)*(r12)))+(((x4267)*(x4268)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4269)))+(((x4267)*(x4271)))+(((IkReal(-1.00000000000000))*(x4270)*(x4273)))), ((((x4271)*(x4273)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4269)))+(((x4267)*(x4270)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4269)))+(((x4268)*(x4273)))+(((x4267)*(x4272)))));
13044 sj3array[0]=IKsin(j3array[0]);
13045 cj3array[0]=IKcos(j3array[0]);
13046 if( j3array[0] > IKPI )
13047 {
13048     j3array[0]-=IK2PI;
13049 }
13050 else if( j3array[0] < -IKPI )
13051 {    j3array[0]+=IK2PI;
13052 }
13053 j3valid[0] = true;
13054 for(int ij3 = 0; ij3 < 1; ++ij3)
13055 {
13056 if( !j3valid[ij3] )
13057 {
13058     continue;
13059 }
13060 _ij3[0] = ij3; _ij3[1] = -1;
13061 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13062 {
13063 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13064 {
13065     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13066 }
13067 }
13068 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13069 {
13070 IkReal evalcond[4];
13071 IkReal x4274=IKcos(j3);
13072 IkReal x4275=IKsin(j3);
13073 IkReal x4276=((sj0)*(sj5));
13074 IkReal x4277=((r00)*(sj6));
13075 IkReal x4278=((cj6)*(sj0));
13076 IkReal x4279=((IkReal(1.00000000000000))*(cj4));
13077 IkReal x4280=((r00)*(sj4));
13078 IkReal x4281=((cj0)*(cj5));
13079 IkReal x4282=((cj5)*(sj0));
13080 IkReal x4283=((cj6)*(r11));
13081 IkReal x4284=((r10)*(sj6));
13082 IkReal x4285=((cj0)*(sj5));
13083 IkReal x4286=((r10)*(sj4));
13084 IkReal x4287=((cj4)*(cj5)*(r01));
13085 IkReal x4288=((IkReal(1.00000000000000))*(cj0)*(cj6));
13086 IkReal x4289=((cj0)*(sj4)*(sj6));
13087 IkReal x4290=((sj0)*(sj4)*(sj6));
13088 evalcond[0]=((((cj6)*(r01)*(x4276)))+(((IkReal(-1.00000000000000))*(x4284)*(x4285)))+(((IkReal(-1.00000000000000))*(x4283)*(x4285)))+(((IkReal(-1.00000000000000))*(x4275)))+(((x4276)*(x4277)))+(((IkReal(-1.00000000000000))*(r02)*(x4282)))+(((r12)*(x4281))));
13089 evalcond[1]=((((r02)*(x4281)))+(((IkReal(-1.00000000000000))*(x4277)*(x4285)))+(((IkReal(-1.00000000000000))*(x4276)*(x4284)))+(x4274)+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4285)))+(((r12)*(x4282)))+(((IkReal(-1.00000000000000))*(x4276)*(x4283))));
13090 evalcond[2]=((((IkReal(-1.00000000000000))*(x4279)*(x4281)*(x4284)))+(((x4278)*(x4287)))+(((r11)*(x4289)))+(((x4278)*(x4280)))+(((IkReal(-1.00000000000000))*(r01)*(x4290)))+(x4274)+(((IkReal(-1.00000000000000))*(x4286)*(x4288)))+(((IkReal(-1.00000000000000))*(r12)*(x4279)*(x4285)))+(((cj4)*(r02)*(x4276)))+(((IkReal(-1.00000000000000))*(x4279)*(x4281)*(x4283)))+(((cj4)*(x4277)*(x4282))));
13091 evalcond[3]=((((IkReal(-1.00000000000000))*(r02)*(x4279)*(x4285)))+(((IkReal(-1.00000000000000))*(x4280)*(x4288)))+(x4275)+(((r01)*(x4289)))+(((r11)*(x4290)))+(((IkReal(-1.00000000000000))*(x4279)*(x4282)*(x4284)))+(((IkReal(-1.00000000000000))*(x4278)*(x4286)))+(((IkReal(-1.00000000000000))*(x4277)*(x4279)*(x4281)))+(((IkReal(-1.00000000000000))*(r12)*(x4276)*(x4279)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4279)*(x4281)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4278)*(x4279))));
13092 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13093 {
13094 continue;
13095 }
13096 }
13097 
13098 {
13099 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13100 vinfos[0].jointtype = 1;
13101 vinfos[0].foffset = j0;
13102 vinfos[0].indices[0] = _ij0[0];
13103 vinfos[0].indices[1] = _ij0[1];
13104 vinfos[0].maxsolutions = _nj0;
13105 vinfos[1].jointtype = 1;
13106 vinfos[1].foffset = j1;
13107 vinfos[1].indices[0] = _ij1[0];
13108 vinfos[1].indices[1] = _ij1[1];
13109 vinfos[1].maxsolutions = _nj1;
13110 vinfos[2].jointtype = 1;
13111 vinfos[2].foffset = j2;
13112 vinfos[2].indices[0] = _ij2[0];
13113 vinfos[2].indices[1] = _ij2[1];
13114 vinfos[2].maxsolutions = _nj2;
13115 vinfos[3].jointtype = 1;
13116 vinfos[3].foffset = j3;
13117 vinfos[3].indices[0] = _ij3[0];
13118 vinfos[3].indices[1] = _ij3[1];
13119 vinfos[3].maxsolutions = _nj3;
13120 vinfos[4].jointtype = 1;
13121 vinfos[4].foffset = j4;
13122 vinfos[4].indices[0] = _ij4[0];
13123 vinfos[4].indices[1] = _ij4[1];
13124 vinfos[4].maxsolutions = _nj4;
13125 vinfos[5].jointtype = 1;
13126 vinfos[5].foffset = j5;
13127 vinfos[5].indices[0] = _ij5[0];
13128 vinfos[5].indices[1] = _ij5[1];
13129 vinfos[5].maxsolutions = _nj5;
13130 vinfos[6].jointtype = 1;
13131 vinfos[6].foffset = j6;
13132 vinfos[6].indices[0] = _ij6[0];
13133 vinfos[6].indices[1] = _ij6[1];
13134 vinfos[6].maxsolutions = _nj6;
13135 std::vector<int> vfree(0);
13136 solutions.AddSolution(vinfos,vfree);
13137 }
13138 }
13139 }
13140 
13141 } else
13142 {
13143 if( 1 )
13144 {
13145 continue;
13146 
13147 } else
13148 {
13149 }
13150 }
13151 }
13152 }
13153 }
13154 }
13155 
13156 } else
13157 {
13158 {
13159 IkReal j3array[1], cj3array[1], sj3array[1];
13160 bool j3valid[1]={false};
13161 _nj3 = 1;
13162 IkReal x4291=((cj0)*(cj5));
13163 IkReal x4292=((IkReal(1.00000000000000))*(cj0));
13164 IkReal x4293=((cj6)*(r11));
13165 IkReal x4294=((r10)*(sj6));
13166 IkReal x4295=((cj5)*(sj0));
13167 IkReal x4296=((r00)*(sj5)*(sj6));
13168 IkReal x4297=((cj6)*(r01)*(sj5));
13169 IkReal x4298=((IkReal(1.00000000000000))*(sj0)*(sj5));
13170 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4294)))+(((sj0)*(x4296)))+(((sj0)*(x4297)))+(((IkReal(-1.00000000000000))*(r02)*(x4295)))+(((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4293)))+(((r12)*(x4291))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r12)*(x4295)))+(((IkReal(-1.00000000000000))*(x4293)*(x4298)))+(((r02)*(x4291)))+(((IkReal(-1.00000000000000))*(x4294)*(x4298)))+(((IkReal(-1.00000000000000))*(x4292)*(x4297)))+(((IkReal(-1.00000000000000))*(x4292)*(x4296))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4294)))+(((sj0)*(x4296)))+(((sj0)*(x4297)))+(((IkReal(-1.00000000000000))*(r02)*(x4295)))+(((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4293)))+(((r12)*(x4291)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r12)*(x4295)))+(((IkReal(-1.00000000000000))*(x4293)*(x4298)))+(((r02)*(x4291)))+(((IkReal(-1.00000000000000))*(x4294)*(x4298)))+(((IkReal(-1.00000000000000))*(x4292)*(x4297)))+(((IkReal(-1.00000000000000))*(x4292)*(x4296)))))))-1) <= IKFAST_SINCOS_THRESH )
13171     continue;
13172 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4294)))+(((sj0)*(x4296)))+(((sj0)*(x4297)))+(((IkReal(-1.00000000000000))*(r02)*(x4295)))+(((IkReal(-1.00000000000000))*(sj5)*(x4292)*(x4293)))+(((r12)*(x4291)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r12)*(x4295)))+(((IkReal(-1.00000000000000))*(x4293)*(x4298)))+(((r02)*(x4291)))+(((IkReal(-1.00000000000000))*(x4294)*(x4298)))+(((IkReal(-1.00000000000000))*(x4292)*(x4297)))+(((IkReal(-1.00000000000000))*(x4292)*(x4296)))))));
13173 sj3array[0]=IKsin(j3array[0]);
13174 cj3array[0]=IKcos(j3array[0]);
13175 if( j3array[0] > IKPI )
13176 {
13177     j3array[0]-=IK2PI;
13178 }
13179 else if( j3array[0] < -IKPI )
13180 {    j3array[0]+=IK2PI;
13181 }
13182 j3valid[0] = true;
13183 for(int ij3 = 0; ij3 < 1; ++ij3)
13184 {
13185 if( !j3valid[ij3] )
13186 {
13187     continue;
13188 }
13189 _ij3[0] = ij3; _ij3[1] = -1;
13190 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13191 {
13192 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13193 {
13194     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13195 }
13196 }
13197 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13198 {
13199 IkReal evalcond[6];
13200 IkReal x4299=IKsin(j3);
13201 IkReal x4300=IKcos(j3);
13202 IkReal x4301=((sj0)*(sj5));
13203 IkReal x4302=((r00)*(sj6));
13204 IkReal x4303=((cj6)*(r01));
13205 IkReal x4304=((cj4)*(cj5));
13206 IkReal x4305=((IkReal(1.00000000000000))*(cj0));
13207 IkReal x4306=((cj5)*(r12));
13208 IkReal x4307=((IkReal(1.00000000000000))*(sj0));
13209 IkReal x4308=((cj6)*(r11));
13210 IkReal x4309=((cj5)*(r02));
13211 IkReal x4310=((IkReal(1.00000000000000))*(cj1));
13212 IkReal x4311=((cj6)*(sj4));
13213 IkReal x4312=((cj6)*(r21));
13214 IkReal x4313=((r20)*(sj6));
13215 IkReal x4314=((r10)*(sj6));
13216 IkReal x4315=((sj4)*(sj6));
13217 IkReal x4316=((cj4)*(r02));
13218 IkReal x4317=((IkReal(1.00000000000000))*(cj4)*(r12));
13219 IkReal x4318=((IkReal(1.00000000000000))*(x4299));
13220 IkReal x4319=((cj0)*(x4315));
13221 evalcond[0]=((((sj5)*(x4313)))+(((IkReal(-1.00000000000000))*(sj1)*(x4300)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4312))));
13222 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x4318)))+(((x4304)*(x4313)))+(((IkReal(-1.00000000000000))*(r21)*(x4315)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x4311)))+(((x4304)*(x4312))));
13223 evalcond[2]=((((cj0)*(x4306)))+(((IkReal(-1.00000000000000))*(sj5)*(x4305)*(x4314)))+(((x4301)*(x4303)))+(((IkReal(-1.00000000000000))*(x4318)))+(((IkReal(-1.00000000000000))*(x4307)*(x4309)))+(((x4301)*(x4302)))+(((IkReal(-1.00000000000000))*(sj5)*(x4305)*(x4308))));
13224 evalcond[3]=((((sj0)*(x4306)))+(((IkReal(-1.00000000000000))*(x4301)*(x4308)))+(((IkReal(-1.00000000000000))*(sj5)*(x4302)*(x4305)))+(((IkReal(-1.00000000000000))*(x4301)*(x4314)))+(((IkReal(-1.00000000000000))*(x4300)*(x4310)))+(((IkReal(-1.00000000000000))*(sj5)*(x4303)*(x4305)))+(((cj0)*(x4309))));
13225 evalcond[4]=((((r11)*(x4319)))+(((x4301)*(x4316)))+(((IkReal(-1.00000000000000))*(x4304)*(x4305)*(x4308)))+(((IkReal(-1.00000000000000))*(x4304)*(x4305)*(x4314)))+(((IkReal(-1.00000000000000))*(r10)*(x4305)*(x4311)))+(((sj0)*(x4303)*(x4304)))+(((IkReal(-1.00000000000000))*(r01)*(x4307)*(x4315)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4305)))+(((sj0)*(x4302)*(x4304)))+(x4300)+(((r00)*(sj0)*(x4311))));
13226 evalcond[5]=((((r11)*(sj0)*(x4315)))+(((IkReal(-1.00000000000000))*(r00)*(x4305)*(x4311)))+(((IkReal(-1.00000000000000))*(r10)*(x4307)*(x4311)))+(((IkReal(-1.00000000000000))*(x4299)*(x4310)))+(((IkReal(-1.00000000000000))*(x4304)*(x4307)*(x4308)))+(((IkReal(-1.00000000000000))*(x4301)*(x4317)))+(((IkReal(-1.00000000000000))*(sj5)*(x4305)*(x4316)))+(((IkReal(-1.00000000000000))*(x4303)*(x4304)*(x4305)))+(((IkReal(-1.00000000000000))*(x4304)*(x4307)*(x4314)))+(((IkReal(-1.00000000000000))*(x4302)*(x4304)*(x4305)))+(((r01)*(x4319))));
13227 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
13228 {
13229 continue;
13230 }
13231 }
13232 
13233 {
13234 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13235 vinfos[0].jointtype = 1;
13236 vinfos[0].foffset = j0;
13237 vinfos[0].indices[0] = _ij0[0];
13238 vinfos[0].indices[1] = _ij0[1];
13239 vinfos[0].maxsolutions = _nj0;
13240 vinfos[1].jointtype = 1;
13241 vinfos[1].foffset = j1;
13242 vinfos[1].indices[0] = _ij1[0];
13243 vinfos[1].indices[1] = _ij1[1];
13244 vinfos[1].maxsolutions = _nj1;
13245 vinfos[2].jointtype = 1;
13246 vinfos[2].foffset = j2;
13247 vinfos[2].indices[0] = _ij2[0];
13248 vinfos[2].indices[1] = _ij2[1];
13249 vinfos[2].maxsolutions = _nj2;
13250 vinfos[3].jointtype = 1;
13251 vinfos[3].foffset = j3;
13252 vinfos[3].indices[0] = _ij3[0];
13253 vinfos[3].indices[1] = _ij3[1];
13254 vinfos[3].maxsolutions = _nj3;
13255 vinfos[4].jointtype = 1;
13256 vinfos[4].foffset = j4;
13257 vinfos[4].indices[0] = _ij4[0];
13258 vinfos[4].indices[1] = _ij4[1];
13259 vinfos[4].maxsolutions = _nj4;
13260 vinfos[5].jointtype = 1;
13261 vinfos[5].foffset = j5;
13262 vinfos[5].indices[0] = _ij5[0];
13263 vinfos[5].indices[1] = _ij5[1];
13264 vinfos[5].maxsolutions = _nj5;
13265 vinfos[6].jointtype = 1;
13266 vinfos[6].foffset = j6;
13267 vinfos[6].indices[0] = _ij6[0];
13268 vinfos[6].indices[1] = _ij6[1];
13269 vinfos[6].maxsolutions = _nj6;
13270 std::vector<int> vfree(0);
13271 solutions.AddSolution(vinfos,vfree);
13272 }
13273 }
13274 }
13275 
13276 }
13277 
13278 }
13279 
13280 } else
13281 {
13282 {
13283 IkReal j3array[1], cj3array[1], sj3array[1];
13284 bool j3valid[1]={false};
13285 _nj3 = 1;
13286 IkReal x4320=((sj5)*(sj6));
13287 IkReal x4321=((cj6)*(sj5));
13288 IkReal x4322=((IkReal(1.00000000000000))*(cj0));
13289 IkReal x4323=((IkReal(1.00000000000000))*(cj5));
13290 if( IKabs(((((IkReal(-1.00000000000000))*(r10)*(x4320)*(x4322)))+(((r01)*(sj0)*(x4321)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4323)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x4320)))+(((IkReal(-1.00000000000000))*(r11)*(x4321)*(x4322))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x4321)))+(((IkReal(-1.00000000000000))*(r22)*(x4323)))+(((r20)*(x4320))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r10)*(x4320)*(x4322)))+(((r01)*(sj0)*(x4321)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4323)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x4320)))+(((IkReal(-1.00000000000000))*(r11)*(x4321)*(x4322)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x4321)))+(((IkReal(-1.00000000000000))*(r22)*(x4323)))+(((r20)*(x4320)))))))-1) <= IKFAST_SINCOS_THRESH )
13291     continue;
13292 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r10)*(x4320)*(x4322)))+(((r01)*(sj0)*(x4321)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4323)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x4320)))+(((IkReal(-1.00000000000000))*(r11)*(x4321)*(x4322)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x4321)))+(((IkReal(-1.00000000000000))*(r22)*(x4323)))+(((r20)*(x4320)))))));
13293 sj3array[0]=IKsin(j3array[0]);
13294 cj3array[0]=IKcos(j3array[0]);
13295 if( j3array[0] > IKPI )
13296 {
13297     j3array[0]-=IK2PI;
13298 }
13299 else if( j3array[0] < -IKPI )
13300 {    j3array[0]+=IK2PI;
13301 }
13302 j3valid[0] = true;
13303 for(int ij3 = 0; ij3 < 1; ++ij3)
13304 {
13305 if( !j3valid[ij3] )
13306 {
13307     continue;
13308 }
13309 _ij3[0] = ij3; _ij3[1] = -1;
13310 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13311 {
13312 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13313 {
13314     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13315 }
13316 }
13317 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13318 {
13319 IkReal evalcond[6];
13320 IkReal x4324=IKsin(j3);
13321 IkReal x4325=IKcos(j3);
13322 IkReal x4326=((sj0)*(sj5));
13323 IkReal x4327=((r00)*(sj6));
13324 IkReal x4328=((cj6)*(r01));
13325 IkReal x4329=((cj4)*(cj5));
13326 IkReal x4330=((IkReal(1.00000000000000))*(cj0));
13327 IkReal x4331=((cj5)*(r12));
13328 IkReal x4332=((IkReal(1.00000000000000))*(sj0));
13329 IkReal x4333=((cj6)*(r11));
13330 IkReal x4334=((cj5)*(r02));
13331 IkReal x4335=((IkReal(1.00000000000000))*(cj1));
13332 IkReal x4336=((cj6)*(sj4));
13333 IkReal x4337=((cj6)*(r21));
13334 IkReal x4338=((r20)*(sj6));
13335 IkReal x4339=((r10)*(sj6));
13336 IkReal x4340=((sj4)*(sj6));
13337 IkReal x4341=((cj4)*(r02));
13338 IkReal x4342=((IkReal(1.00000000000000))*(cj4)*(r12));
13339 IkReal x4343=((IkReal(1.00000000000000))*(x4324));
13340 IkReal x4344=((cj0)*(x4340));
13341 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x4325)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4337)))+(((sj5)*(x4338))));
13342 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x4340)))+(((r20)*(x4336)))+(((x4329)*(x4337)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x4343)))+(((x4329)*(x4338))));
13343 evalcond[2]=((((IkReal(-1.00000000000000))*(x4343)))+(((cj0)*(x4331)))+(((x4326)*(x4328)))+(((x4326)*(x4327)))+(((IkReal(-1.00000000000000))*(x4332)*(x4334)))+(((IkReal(-1.00000000000000))*(sj5)*(x4330)*(x4339)))+(((IkReal(-1.00000000000000))*(sj5)*(x4330)*(x4333))));
13344 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x4327)*(x4330)))+(((IkReal(-1.00000000000000))*(x4325)*(x4335)))+(((cj0)*(x4334)))+(((IkReal(-1.00000000000000))*(x4326)*(x4339)))+(((sj0)*(x4331)))+(((IkReal(-1.00000000000000))*(sj5)*(x4328)*(x4330)))+(((IkReal(-1.00000000000000))*(x4326)*(x4333))));
13345 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4330)))+(((IkReal(-1.00000000000000))*(x4329)*(x4330)*(x4333)))+(((IkReal(-1.00000000000000))*(x4329)*(x4330)*(x4339)))+(((r00)*(sj0)*(x4336)))+(((r11)*(x4344)))+(((sj0)*(x4327)*(x4329)))+(((IkReal(-1.00000000000000))*(r01)*(x4332)*(x4340)))+(((IkReal(-1.00000000000000))*(r10)*(x4330)*(x4336)))+(((x4326)*(x4341)))+(((sj0)*(x4328)*(x4329)))+(x4325));
13346 evalcond[5]=((((r01)*(x4344)))+(((IkReal(-1.00000000000000))*(r00)*(x4330)*(x4336)))+(((IkReal(-1.00000000000000))*(x4326)*(x4342)))+(((IkReal(-1.00000000000000))*(x4328)*(x4329)*(x4330)))+(((IkReal(-1.00000000000000))*(r10)*(x4332)*(x4336)))+(((IkReal(-1.00000000000000))*(x4327)*(x4329)*(x4330)))+(((IkReal(-1.00000000000000))*(x4329)*(x4332)*(x4339)))+(((IkReal(-1.00000000000000))*(x4324)*(x4335)))+(((IkReal(-1.00000000000000))*(x4329)*(x4332)*(x4333)))+(((IkReal(-1.00000000000000))*(sj5)*(x4330)*(x4341)))+(((r11)*(sj0)*(x4340))));
13347 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
13348 {
13349 continue;
13350 }
13351 }
13352 
13353 {
13354 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13355 vinfos[0].jointtype = 1;
13356 vinfos[0].foffset = j0;
13357 vinfos[0].indices[0] = _ij0[0];
13358 vinfos[0].indices[1] = _ij0[1];
13359 vinfos[0].maxsolutions = _nj0;
13360 vinfos[1].jointtype = 1;
13361 vinfos[1].foffset = j1;
13362 vinfos[1].indices[0] = _ij1[0];
13363 vinfos[1].indices[1] = _ij1[1];
13364 vinfos[1].maxsolutions = _nj1;
13365 vinfos[2].jointtype = 1;
13366 vinfos[2].foffset = j2;
13367 vinfos[2].indices[0] = _ij2[0];
13368 vinfos[2].indices[1] = _ij2[1];
13369 vinfos[2].maxsolutions = _nj2;
13370 vinfos[3].jointtype = 1;
13371 vinfos[3].foffset = j3;
13372 vinfos[3].indices[0] = _ij3[0];
13373 vinfos[3].indices[1] = _ij3[1];
13374 vinfos[3].maxsolutions = _nj3;
13375 vinfos[4].jointtype = 1;
13376 vinfos[4].foffset = j4;
13377 vinfos[4].indices[0] = _ij4[0];
13378 vinfos[4].indices[1] = _ij4[1];
13379 vinfos[4].maxsolutions = _nj4;
13380 vinfos[5].jointtype = 1;
13381 vinfos[5].foffset = j5;
13382 vinfos[5].indices[0] = _ij5[0];
13383 vinfos[5].indices[1] = _ij5[1];
13384 vinfos[5].maxsolutions = _nj5;
13385 vinfos[6].jointtype = 1;
13386 vinfos[6].foffset = j6;
13387 vinfos[6].indices[0] = _ij6[0];
13388 vinfos[6].indices[1] = _ij6[1];
13389 vinfos[6].maxsolutions = _nj6;
13390 std::vector<int> vfree(0);
13391 solutions.AddSolution(vinfos,vfree);
13392 }
13393 }
13394 }
13395 
13396 }
13397 
13398 }
13399 
13400 } else
13401 {
13402 {
13403 IkReal j3array[1], cj3array[1], sj3array[1];
13404 bool j3valid[1]={false};
13405 _nj3 = 1;
13406 IkReal x4345=((r20)*(sj6));
13407 IkReal x4346=((cj4)*(cj5));
13408 IkReal x4347=((cj6)*(r21));
13409 if( IKabs(((gconst17)*(((((x4345)*(x4346)))+(((x4346)*(x4347)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((sj5)*(x4345)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4347))))))) < IKFAST_ATAN2_MAGTHRESH )
13410     continue;
13411 j3array[0]=IKatan2(((gconst17)*(((((x4345)*(x4346)))+(((x4346)*(x4347)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))), ((gconst17)*(((((sj5)*(x4345)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4347)))))));
13412 sj3array[0]=IKsin(j3array[0]);
13413 cj3array[0]=IKcos(j3array[0]);
13414 if( j3array[0] > IKPI )
13415 {
13416     j3array[0]-=IK2PI;
13417 }
13418 else if( j3array[0] < -IKPI )
13419 {    j3array[0]+=IK2PI;
13420 }
13421 j3valid[0] = true;
13422 for(int ij3 = 0; ij3 < 1; ++ij3)
13423 {
13424 if( !j3valid[ij3] )
13425 {
13426     continue;
13427 }
13428 _ij3[0] = ij3; _ij3[1] = -1;
13429 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13430 {
13431 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13432 {
13433     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13434 }
13435 }
13436 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13437 {
13438 IkReal evalcond[6];
13439 IkReal x4348=IKsin(j3);
13440 IkReal x4349=IKcos(j3);
13441 IkReal x4350=((sj0)*(sj5));
13442 IkReal x4351=((r00)*(sj6));
13443 IkReal x4352=((cj6)*(r01));
13444 IkReal x4353=((cj4)*(cj5));
13445 IkReal x4354=((IkReal(1.00000000000000))*(cj0));
13446 IkReal x4355=((cj5)*(r12));
13447 IkReal x4356=((IkReal(1.00000000000000))*(sj0));
13448 IkReal x4357=((cj6)*(r11));
13449 IkReal x4358=((cj5)*(r02));
13450 IkReal x4359=((IkReal(1.00000000000000))*(cj1));
13451 IkReal x4360=((cj6)*(sj4));
13452 IkReal x4361=((cj6)*(r21));
13453 IkReal x4362=((r20)*(sj6));
13454 IkReal x4363=((r10)*(sj6));
13455 IkReal x4364=((sj4)*(sj6));
13456 IkReal x4365=((cj4)*(r02));
13457 IkReal x4366=((IkReal(1.00000000000000))*(cj4)*(r12));
13458 IkReal x4367=((IkReal(1.00000000000000))*(x4348));
13459 IkReal x4368=((cj0)*(x4364));
13460 evalcond[0]=((((sj5)*(x4361)))+(((sj5)*(x4362)))+(((IkReal(-1.00000000000000))*(sj1)*(x4349)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
13461 evalcond[1]=((((x4353)*(x4362)))+(((x4353)*(x4361)))+(((IkReal(-1.00000000000000))*(r21)*(x4364)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x4360)))+(((IkReal(-1.00000000000000))*(sj1)*(x4367))));
13462 evalcond[2]=((((cj0)*(x4355)))+(((IkReal(-1.00000000000000))*(x4356)*(x4358)))+(((x4350)*(x4352)))+(((IkReal(-1.00000000000000))*(sj5)*(x4354)*(x4363)))+(((IkReal(-1.00000000000000))*(sj5)*(x4354)*(x4357)))+(((IkReal(-1.00000000000000))*(x4367)))+(((x4350)*(x4351))));
13463 evalcond[3]=((((cj0)*(x4358)))+(((IkReal(-1.00000000000000))*(x4349)*(x4359)))+(((IkReal(-1.00000000000000))*(sj5)*(x4352)*(x4354)))+(((IkReal(-1.00000000000000))*(sj5)*(x4351)*(x4354)))+(((IkReal(-1.00000000000000))*(x4350)*(x4357)))+(((sj0)*(x4355)))+(((IkReal(-1.00000000000000))*(x4350)*(x4363))));
13464 evalcond[4]=((((r00)*(sj0)*(x4360)))+(((IkReal(-1.00000000000000))*(r01)*(x4356)*(x4364)))+(((sj0)*(x4352)*(x4353)))+(((sj0)*(x4351)*(x4353)))+(((IkReal(-1.00000000000000))*(x4353)*(x4354)*(x4363)))+(((IkReal(-1.00000000000000))*(x4353)*(x4354)*(x4357)))+(x4349)+(((IkReal(-1.00000000000000))*(r10)*(x4354)*(x4360)))+(((x4350)*(x4365)))+(((r11)*(x4368)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4354))));
13465 evalcond[5]=((((r01)*(x4368)))+(((IkReal(-1.00000000000000))*(sj5)*(x4354)*(x4365)))+(((IkReal(-1.00000000000000))*(x4353)*(x4356)*(x4357)))+(((r11)*(sj0)*(x4364)))+(((IkReal(-1.00000000000000))*(x4350)*(x4366)))+(((IkReal(-1.00000000000000))*(x4353)*(x4356)*(x4363)))+(((IkReal(-1.00000000000000))*(x4351)*(x4353)*(x4354)))+(((IkReal(-1.00000000000000))*(x4348)*(x4359)))+(((IkReal(-1.00000000000000))*(r10)*(x4356)*(x4360)))+(((IkReal(-1.00000000000000))*(r00)*(x4354)*(x4360)))+(((IkReal(-1.00000000000000))*(x4352)*(x4353)*(x4354))));
13466 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
13467 {
13468 continue;
13469 }
13470 }
13471 
13472 {
13473 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13474 vinfos[0].jointtype = 1;
13475 vinfos[0].foffset = j0;
13476 vinfos[0].indices[0] = _ij0[0];
13477 vinfos[0].indices[1] = _ij0[1];
13478 vinfos[0].maxsolutions = _nj0;
13479 vinfos[1].jointtype = 1;
13480 vinfos[1].foffset = j1;
13481 vinfos[1].indices[0] = _ij1[0];
13482 vinfos[1].indices[1] = _ij1[1];
13483 vinfos[1].maxsolutions = _nj1;
13484 vinfos[2].jointtype = 1;
13485 vinfos[2].foffset = j2;
13486 vinfos[2].indices[0] = _ij2[0];
13487 vinfos[2].indices[1] = _ij2[1];
13488 vinfos[2].maxsolutions = _nj2;
13489 vinfos[3].jointtype = 1;
13490 vinfos[3].foffset = j3;
13491 vinfos[3].indices[0] = _ij3[0];
13492 vinfos[3].indices[1] = _ij3[1];
13493 vinfos[3].maxsolutions = _nj3;
13494 vinfos[4].jointtype = 1;
13495 vinfos[4].foffset = j4;
13496 vinfos[4].indices[0] = _ij4[0];
13497 vinfos[4].indices[1] = _ij4[1];
13498 vinfos[4].maxsolutions = _nj4;
13499 vinfos[5].jointtype = 1;
13500 vinfos[5].foffset = j5;
13501 vinfos[5].indices[0] = _ij5[0];
13502 vinfos[5].indices[1] = _ij5[1];
13503 vinfos[5].maxsolutions = _nj5;
13504 vinfos[6].jointtype = 1;
13505 vinfos[6].foffset = j6;
13506 vinfos[6].indices[0] = _ij6[0];
13507 vinfos[6].indices[1] = _ij6[1];
13508 vinfos[6].maxsolutions = _nj6;
13509 std::vector<int> vfree(0);
13510 solutions.AddSolution(vinfos,vfree);
13511 }
13512 }
13513 }
13514 
13515 }
13516 
13517 }
13518 }
13519 }
13520 
13521 }
13522 
13523 }
13524 
13525 } else
13526 {
13527 {
13528 IkReal j4array[1], cj4array[1], sj4array[1];
13529 bool j4valid[1]={false};
13530 _nj4 = 1;
13531 IkReal x4369=((cj1)*(sj6));
13532 IkReal x4370=((r01)*(sj0));
13533 IkReal x4371=((cj0)*(r11));
13534 IkReal x4372=((cj1)*(cj6));
13535 IkReal x4373=((cj0)*(r10));
13536 IkReal x4374=((IkReal(1.00000000000000))*(sj0));
13537 IkReal x4375=((cj1)*(sj5));
13538 if( IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(r00)*(x4372)*(x4374)))+(((x4372)*(x4373)))+(((x4369)*(x4370)))+(((IkReal(-1.00000000000000))*(x4369)*(x4371))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4369)*(x4374)))+(((IkReal(-1.00000000000000))*(r02)*(x4374)*(x4375)))+(((cj0)*(r12)*(x4375)))+(((cj5)*(x4369)*(x4373)))+(((IkReal(-1.00000000000000))*(cj5)*(x4370)*(x4372)))+(((cj5)*(x4371)*(x4372))))))) < IKFAST_ATAN2_MAGTHRESH )
13539     continue;
13540 j4array[0]=IKatan2(((gconst13)*(((((IkReal(-1.00000000000000))*(r00)*(x4372)*(x4374)))+(((x4372)*(x4373)))+(((x4369)*(x4370)))+(((IkReal(-1.00000000000000))*(x4369)*(x4371)))))), ((gconst13)*(((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4369)*(x4374)))+(((IkReal(-1.00000000000000))*(r02)*(x4374)*(x4375)))+(((cj0)*(r12)*(x4375)))+(((cj5)*(x4369)*(x4373)))+(((IkReal(-1.00000000000000))*(cj5)*(x4370)*(x4372)))+(((cj5)*(x4371)*(x4372)))))));
13541 sj4array[0]=IKsin(j4array[0]);
13542 cj4array[0]=IKcos(j4array[0]);
13543 if( j4array[0] > IKPI )
13544 {
13545     j4array[0]-=IK2PI;
13546 }
13547 else if( j4array[0] < -IKPI )
13548 {    j4array[0]+=IK2PI;
13549 }
13550 j4valid[0] = true;
13551 for(int ij4 = 0; ij4 < 1; ++ij4)
13552 {
13553 if( !j4valid[ij4] )
13554 {
13555     continue;
13556 }
13557 _ij4[0] = ij4; _ij4[1] = -1;
13558 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
13559 {
13560 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
13561 {
13562     j4valid[iij4]=false; _ij4[1] = iij4; break; 
13563 }
13564 }
13565 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
13566 {
13567 IkReal evalcond[3];
13568 IkReal x4376=IKsin(j4);
13569 IkReal x4377=IKcos(j4);
13570 IkReal x4378=((r00)*(sj6));
13571 IkReal x4379=((cj6)*(r01));
13572 IkReal x4380=((IkReal(1.00000000000000))*(cj0));
13573 IkReal x4381=((IkReal(1.00000000000000))*(sj0));
13574 IkReal x4382=((r10)*(sj6));
13575 IkReal x4383=((sj5)*(x4376));
13576 IkReal x4384=((IkReal(1.00000000000000))*(cj6)*(r11));
13577 IkReal x4385=((cj5)*(x4376));
13578 IkReal x4386=((cj6)*(x4377));
13579 IkReal x4387=((sj0)*(x4385));
13580 IkReal x4388=((r01)*(sj6)*(x4377));
13581 IkReal x4389=((r11)*(sj6)*(x4377));
13582 evalcond[0]=((((r22)*(x4383)))+(((r20)*(sj6)*(x4385)))+(((r21)*(sj6)*(x4377)))+(((IkReal(-1.00000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(r20)*(x4386)))+(((cj6)*(r21)*(x4385))));
13583 evalcond[1]=((((x4378)*(x4387)))+(((IkReal(-1.00000000000000))*(r12)*(x4380)*(x4383)))+(((cj0)*(r10)*(x4386)))+(((IkReal(-1.00000000000000))*(r00)*(x4381)*(x4386)))+(((r02)*(sj0)*(x4383)))+(((IkReal(-1.00000000000000))*(x4380)*(x4382)*(x4385)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x4380)*(x4385)))+(((IkReal(-1.00000000000000))*(x4380)*(x4389)))+(((x4379)*(x4387)))+(((sj0)*(x4388))));
13584 evalcond[2]=((((IkReal(-1.00000000000000))*(x4379)*(x4380)*(x4385)))+(((cj0)*(r00)*(x4386)))+(((IkReal(-1.00000000000000))*(r12)*(x4381)*(x4383)))+(sj1)+(((IkReal(-1.00000000000000))*(x4380)*(x4388)))+(((r10)*(sj0)*(x4386)))+(((IkReal(-1.00000000000000))*(x4381)*(x4389)))+(((IkReal(-1.00000000000000))*(r02)*(x4380)*(x4383)))+(((IkReal(-1.00000000000000))*(x4381)*(x4382)*(x4385)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x4381)*(x4385)))+(((IkReal(-1.00000000000000))*(x4378)*(x4380)*(x4385))));
13585 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
13586 {
13587 continue;
13588 }
13589 }
13590 
13591 {
13592 IkReal dummyeval[1];
13593 IkReal gconst17;
13594 gconst17=IKsign(sj1);
13595 dummyeval[0]=sj1;
13596 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13597 {
13598 {
13599 IkReal dummyeval[1];
13600 dummyeval[0]=sj1;
13601 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13602 {
13603 {
13604 IkReal dummyeval[1];
13605 dummyeval[0]=cj1;
13606 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13607 {
13608 {
13609 IkReal evalcond[9];
13610 IkReal x4390=((IkReal(1.00000000000000))*(cj0));
13611 IkReal x4391=((cj4)*(sj6));
13612 IkReal x4392=((sj0)*(sj6));
13613 IkReal x4393=((cj5)*(sj4));
13614 IkReal x4394=((IkReal(0.374290000000000))*(sj5));
13615 IkReal x4395=((sj4)*(sj5));
13616 IkReal x4396=((cj0)*(cj6));
13617 IkReal x4397=((IkReal(0.0100000000000000))*(cj5));
13618 IkReal x4398=((cj4)*(sj5));
13619 IkReal x4399=((cj5)*(sj0));
13620 IkReal x4400=((IkReal(0.374290000000000))*(r02));
13621 IkReal x4401=((r20)*(sj6));
13622 IkReal x4402=((cj6)*(r21));
13623 IkReal x4403=((IkReal(1.00000000000000))*(sj0));
13624 IkReal x4404=((cj0)*(sj6));
13625 IkReal x4405=((cj4)*(cj6));
13626 IkReal x4406=((IkReal(0.374290000000000))*(r12));
13627 IkReal x4407=((cj0)*(cj5));
13628 IkReal x4408=((cj6)*(sj5));
13629 IkReal x4409=((cj6)*(r01));
13630 IkReal x4410=((r00)*(sj6));
13631 IkReal x4411=((IkReal(0.0100000000000000))*(sj5));
13632 IkReal x4412=((cj6)*(r11));
13633 IkReal x4413=((IkReal(1.00000000000000))*(r10));
13634 IkReal x4414=((r02)*(sj0));
13635 IkReal x4415=((cj6)*(sj4));
13636 IkReal x4416=((r12)*(x4403));
13637 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
13638 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x4405)))+(((x4393)*(x4402)))+(((x4393)*(x4401)))+(((r21)*(x4391)))+(((r22)*(x4395))));
13639 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(r22)*(x4411)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4397)*(x4402)))+(((IkReal(-1.00000000000000))*(x4397)*(x4401)))+(((x4394)*(x4401)))+(pz)+(((x4394)*(x4402))));
13640 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x4403)*(x4408)))+(((r12)*(x4399)))+(((IkReal(-1.00000000000000))*(r01)*(x4390)*(x4408)))+(((IkReal(-1.00000000000000))*(sj5)*(x4392)*(x4413)))+(((IkReal(-1.00000000000000))*(sj5)*(x4390)*(x4410)))+(((r02)*(x4407))));
13641 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x4390)*(x4391)))+(((r01)*(sj0)*(x4391)))+(((IkReal(-1.00000000000000))*(r00)*(x4403)*(x4405)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x4390)*(x4393)))+(((IkReal(-1.00000000000000))*(r12)*(x4390)*(x4395)))+(((x4395)*(x4414)))+(((IkReal(-1.00000000000000))*(x4390)*(x4393)*(x4412)))+(((r00)*(x4392)*(x4393)))+(((sj0)*(x4393)*(x4409)))+(((cj4)*(r10)*(x4396))));
13642 evalcond[5]=((IkReal(1.00000000000000))+(((r10)*(sj0)*(x4405)))+(((IkReal(-1.00000000000000))*(x4390)*(x4393)*(x4410)))+(((IkReal(-1.00000000000000))*(x4393)*(x4403)*(x4412)))+(((IkReal(-1.00000000000000))*(r11)*(x4391)*(x4403)))+(((cj4)*(r00)*(x4396)))+(((IkReal(-1.00000000000000))*(x4390)*(x4393)*(x4409)))+(((IkReal(-1.00000000000000))*(r01)*(x4390)*(x4391)))+(((IkReal(-1.00000000000000))*(x4395)*(x4416)))+(((IkReal(-1.00000000000000))*(r02)*(x4390)*(x4395)))+(((IkReal(-1.00000000000000))*(x4392)*(x4393)*(x4413))));
13643 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x4411)*(x4414)))+(((IkReal(-1.00000000000000))*(r00)*(x4392)*(x4397)))+(((IkReal(-1.00000000000000))*(x4399)*(x4400)))+(((r11)*(x4396)*(x4397)))+(((IkReal(-1.00000000000000))*(sj0)*(x4397)*(x4409)))+(((IkReal(-1.00000000000000))*(py)*(x4390)))+(((r10)*(x4397)*(x4404)))+(((x4406)*(x4407)))+(((cj0)*(r12)*(x4411)))+(((IkReal(-1.00000000000000))*(r11)*(x4394)*(x4396)))+(((IkReal(-1.00000000000000))*(r10)*(x4394)*(x4404)))+(((px)*(sj0)))+(((r00)*(x4392)*(x4394)))+(((sj0)*(x4394)*(x4409))));
13644 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4390)*(x4391)))+(((IkReal(-1.00000000000000))*(x4398)*(x4416)))+(((r01)*(sj4)*(x4404)))+(((IkReal(-1.00000000000000))*(r02)*(x4390)*(x4398)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4390)*(x4405)))+(((IkReal(-1.00000000000000))*(r00)*(x4390)*(x4415)))+(((IkReal(-1.00000000000000))*(r10)*(x4403)*(x4415)))+(((IkReal(-1.00000000000000))*(r11)*(x4399)*(x4405)))+(((r11)*(sj4)*(x4392)))+(((IkReal(-1.00000000000000))*(x4391)*(x4399)*(x4413))));
13645 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x4390)))+(((r01)*(x4396)*(x4397)))+(((r12)*(sj0)*(x4411)))+(((x4399)*(x4406)))+(((IkReal(-1.00000000000000))*(r01)*(x4394)*(x4396)))+(((IkReal(-1.00000000000000))*(r00)*(x4394)*(x4404)))+(((IkReal(-1.00000000000000))*(sj0)*(x4394)*(x4412)))+(((IkReal(-1.00000000000000))*(r10)*(x4392)*(x4394)))+(((cj0)*(r02)*(x4411)))+(((r10)*(x4392)*(x4397)))+(((IkReal(-1.00000000000000))*(py)*(x4403)))+(((r00)*(x4397)*(x4404)))+(((sj0)*(x4397)*(x4412)))+(((x4400)*(x4407))));
13646 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
13647 {
13648 {
13649 IkReal j3array[1], cj3array[1], sj3array[1];
13650 bool j3valid[1]={false};
13651 _nj3 = 1;
13652 IkReal x4417=((r20)*(sj6));
13653 IkReal x4418=((cj4)*(cj5));
13654 IkReal x4419=((cj6)*(r21));
13655 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x4417)*(x4418)))+(((x4418)*(x4419))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x4419)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4417))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x4417)*(x4418)))+(((x4418)*(x4419)))))+IKsqr(((((sj5)*(x4419)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4417)))))-1) <= IKFAST_SINCOS_THRESH )
13656     continue;
13657 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x4417)*(x4418)))+(((x4418)*(x4419)))), ((((sj5)*(x4419)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4417)))));
13658 sj3array[0]=IKsin(j3array[0]);
13659 cj3array[0]=IKcos(j3array[0]);
13660 if( j3array[0] > IKPI )
13661 {
13662     j3array[0]-=IK2PI;
13663 }
13664 else if( j3array[0] < -IKPI )
13665 {    j3array[0]+=IK2PI;
13666 }
13667 j3valid[0] = true;
13668 for(int ij3 = 0; ij3 < 1; ++ij3)
13669 {
13670 if( !j3valid[ij3] )
13671 {
13672     continue;
13673 }
13674 _ij3[0] = ij3; _ij3[1] = -1;
13675 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13676 {
13677 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13678 {
13679     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13680 }
13681 }
13682 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13683 {
13684 IkReal evalcond[4];
13685 IkReal x4420=IKcos(j3);
13686 IkReal x4421=((sj0)*(sj5));
13687 IkReal x4422=((r00)*(sj6));
13688 IkReal x4423=((cj6)*(r01));
13689 IkReal x4424=((cj5)*(sj0));
13690 IkReal x4425=((cj0)*(cj5));
13691 IkReal x4426=((cj6)*(sj4));
13692 IkReal x4427=((sj4)*(sj6));
13693 IkReal x4428=((cj0)*(r11));
13694 IkReal x4429=((cj4)*(cj6));
13695 IkReal x4430=((cj4)*(sj6));
13696 IkReal x4431=((IkReal(1.00000000000000))*(cj0));
13697 IkReal x4432=((cj4)*(sj5));
13698 IkReal x4433=((sj5)*(sj6));
13699 IkReal x4434=((cj6)*(sj5));
13700 IkReal x4435=((IkReal(1.00000000000000))*(IKsin(j3)));
13701 evalcond[0]=((((r21)*(x4434)))+(((r20)*(x4433)))+(((IkReal(-1.00000000000000))*(x4420)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
13702 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x4427)))+(((r20)*(x4426)))+(((r22)*(x4432)))+(((cj5)*(r20)*(x4430)))+(((IkReal(-1.00000000000000))*(x4435)))+(((cj5)*(r21)*(x4429))));
13703 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x4424)))+(((r12)*(x4425)))+(((IkReal(-1.00000000000000))*(x4428)*(x4434)))+(((x4421)*(x4422)))+(((x4421)*(x4423)))+(((IkReal(-1.00000000000000))*(r10)*(x4431)*(x4433)))+(((IkReal(-1.00000000000000))*(x4435))));
13704 evalcond[3]=((((cj4)*(r02)*(x4421)))+(((cj4)*(x4423)*(x4424)))+(((IkReal(-1.00000000000000))*(r11)*(x4425)*(x4429)))+(((IkReal(-1.00000000000000))*(r12)*(x4431)*(x4432)))+(x4420)+(((x4427)*(x4428)))+(((cj4)*(x4422)*(x4424)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x4427)))+(((IkReal(-1.00000000000000))*(r10)*(x4425)*(x4430)))+(((r00)*(sj0)*(x4426)))+(((IkReal(-1.00000000000000))*(r10)*(x4426)*(x4431))));
13705 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13706 {
13707 continue;
13708 }
13709 }
13710 
13711 {
13712 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13713 vinfos[0].jointtype = 1;
13714 vinfos[0].foffset = j0;
13715 vinfos[0].indices[0] = _ij0[0];
13716 vinfos[0].indices[1] = _ij0[1];
13717 vinfos[0].maxsolutions = _nj0;
13718 vinfos[1].jointtype = 1;
13719 vinfos[1].foffset = j1;
13720 vinfos[1].indices[0] = _ij1[0];
13721 vinfos[1].indices[1] = _ij1[1];
13722 vinfos[1].maxsolutions = _nj1;
13723 vinfos[2].jointtype = 1;
13724 vinfos[2].foffset = j2;
13725 vinfos[2].indices[0] = _ij2[0];
13726 vinfos[2].indices[1] = _ij2[1];
13727 vinfos[2].maxsolutions = _nj2;
13728 vinfos[3].jointtype = 1;
13729 vinfos[3].foffset = j3;
13730 vinfos[3].indices[0] = _ij3[0];
13731 vinfos[3].indices[1] = _ij3[1];
13732 vinfos[3].maxsolutions = _nj3;
13733 vinfos[4].jointtype = 1;
13734 vinfos[4].foffset = j4;
13735 vinfos[4].indices[0] = _ij4[0];
13736 vinfos[4].indices[1] = _ij4[1];
13737 vinfos[4].maxsolutions = _nj4;
13738 vinfos[5].jointtype = 1;
13739 vinfos[5].foffset = j5;
13740 vinfos[5].indices[0] = _ij5[0];
13741 vinfos[5].indices[1] = _ij5[1];
13742 vinfos[5].maxsolutions = _nj5;
13743 vinfos[6].jointtype = 1;
13744 vinfos[6].foffset = j6;
13745 vinfos[6].indices[0] = _ij6[0];
13746 vinfos[6].indices[1] = _ij6[1];
13747 vinfos[6].maxsolutions = _nj6;
13748 std::vector<int> vfree(0);
13749 solutions.AddSolution(vinfos,vfree);
13750 }
13751 }
13752 }
13753 
13754 } else
13755 {
13756 IkReal x4436=((IkReal(1.00000000000000))*(cj0));
13757 IkReal x4437=((cj4)*(sj6));
13758 IkReal x4438=((sj0)*(sj6));
13759 IkReal x4439=((cj5)*(sj4));
13760 IkReal x4440=((IkReal(0.374290000000000))*(sj5));
13761 IkReal x4441=((sj4)*(sj5));
13762 IkReal x4442=((cj0)*(cj6));
13763 IkReal x4443=((IkReal(0.0100000000000000))*(cj5));
13764 IkReal x4444=((cj4)*(sj5));
13765 IkReal x4445=((cj5)*(sj0));
13766 IkReal x4446=((IkReal(0.374290000000000))*(r02));
13767 IkReal x4447=((r20)*(sj6));
13768 IkReal x4448=((cj6)*(r21));
13769 IkReal x4449=((IkReal(1.00000000000000))*(sj0));
13770 IkReal x4450=((cj0)*(sj6));
13771 IkReal x4451=((cj4)*(cj6));
13772 IkReal x4452=((IkReal(0.374290000000000))*(r12));
13773 IkReal x4453=((cj0)*(cj5));
13774 IkReal x4454=((cj6)*(sj5));
13775 IkReal x4455=((cj6)*(r01));
13776 IkReal x4456=((r00)*(sj6));
13777 IkReal x4457=((IkReal(0.0100000000000000))*(sj5));
13778 IkReal x4458=((cj6)*(r11));
13779 IkReal x4459=((IkReal(1.00000000000000))*(r10));
13780 IkReal x4460=((r02)*(sj0));
13781 IkReal x4461=((cj6)*(sj4));
13782 IkReal x4462=((r12)*(x4449));
13783 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
13784 evalcond[1]=((((r21)*(x4437)))+(((x4439)*(x4448)))+(((x4439)*(x4447)))+(((r22)*(x4441)))+(((IkReal(-1.00000000000000))*(r20)*(x4451))));
13785 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x4443)*(x4447)))+(((x4440)*(x4447)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x4443)*(x4448)))+(((IkReal(-1.00000000000000))*(r22)*(x4457)))+(pz)+(((x4440)*(x4448))));
13786 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x4436)*(x4456)))+(((IkReal(-1.00000000000000))*(r11)*(x4449)*(x4454)))+(((r12)*(x4445)))+(((IkReal(-1.00000000000000))*(r01)*(x4436)*(x4454)))+(((r02)*(x4453)))+(((IkReal(-1.00000000000000))*(sj5)*(x4438)*(x4459))));
13787 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(sj6)*(x4436)*(x4439)))+(((IkReal(-1.00000000000000))*(r11)*(x4436)*(x4437)))+(((IkReal(-1.00000000000000))*(r00)*(x4449)*(x4451)))+(((IkReal(-1.00000000000000))*(x4436)*(x4439)*(x4458)))+(((sj0)*(x4439)*(x4455)))+(((IkReal(-1.00000000000000))*(r12)*(x4436)*(x4441)))+(((r01)*(sj0)*(x4437)))+(((x4441)*(x4460)))+(((cj4)*(r10)*(x4442)))+(((r00)*(x4438)*(x4439))));
13788 evalcond[5]=((IkReal(-1.00000000000000))+(((r10)*(sj0)*(x4451)))+(((cj4)*(r00)*(x4442)))+(((IkReal(-1.00000000000000))*(x4439)*(x4449)*(x4458)))+(((IkReal(-1.00000000000000))*(r02)*(x4436)*(x4441)))+(((IkReal(-1.00000000000000))*(x4441)*(x4462)))+(((IkReal(-1.00000000000000))*(x4436)*(x4439)*(x4455)))+(((IkReal(-1.00000000000000))*(x4436)*(x4439)*(x4456)))+(((IkReal(-1.00000000000000))*(r11)*(x4437)*(x4449)))+(((IkReal(-1.00000000000000))*(x4438)*(x4439)*(x4459)))+(((IkReal(-1.00000000000000))*(r01)*(x4436)*(x4437))));
13789 evalcond[6]=((IkReal(0.0690000000000000))+(((r10)*(x4443)*(x4450)))+(((IkReal(-1.00000000000000))*(r11)*(x4440)*(x4442)))+(((x4452)*(x4453)))+(((cj0)*(r12)*(x4457)))+(((r00)*(x4438)*(x4440)))+(((IkReal(-1.00000000000000))*(x4445)*(x4446)))+(((r11)*(x4442)*(x4443)))+(((IkReal(-1.00000000000000))*(sj0)*(x4443)*(x4455)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x4436)))+(((IkReal(-1.00000000000000))*(r00)*(x4438)*(x4443)))+(((IkReal(-1.00000000000000))*(x4457)*(x4460)))+(((IkReal(-1.00000000000000))*(r10)*(x4440)*(x4450)))+(((sj0)*(x4440)*(x4455))));
13790 evalcond[7]=((((IkReal(-1.00000000000000))*(x4437)*(x4445)*(x4459)))+(((r11)*(sj4)*(x4438)))+(((IkReal(-1.00000000000000))*(r11)*(x4445)*(x4451)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4436)*(x4437)))+(((IkReal(-1.00000000000000))*(x4444)*(x4462)))+(((r01)*(sj4)*(x4450)))+(((IkReal(-1.00000000000000))*(r00)*(x4436)*(x4461)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4436)*(x4451)))+(((IkReal(-1.00000000000000))*(r02)*(x4436)*(x4444)))+(((IkReal(-1.00000000000000))*(r10)*(x4449)*(x4461))));
13791 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x4440)*(x4450)))+(((r01)*(x4442)*(x4443)))+(((r10)*(x4438)*(x4443)))+(((x4445)*(x4452)))+(((r12)*(sj0)*(x4457)))+(((IkReal(-1.00000000000000))*(px)*(x4436)))+(((IkReal(-1.00000000000000))*(py)*(x4449)))+(((cj0)*(r02)*(x4457)))+(((IkReal(-1.00000000000000))*(r01)*(x4440)*(x4442)))+(((IkReal(-1.00000000000000))*(r10)*(x4438)*(x4440)))+(((r00)*(x4443)*(x4450)))+(((sj0)*(x4443)*(x4458)))+(((x4446)*(x4453)))+(((IkReal(-1.00000000000000))*(sj0)*(x4440)*(x4458))));
13792 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
13793 {
13794 {
13795 IkReal j3array[1], cj3array[1], sj3array[1];
13796 bool j3valid[1]={false};
13797 _nj3 = 1;
13798 IkReal x4463=((IkReal(1.00000000000000))*(sj5));
13799 IkReal x4464=((cj6)*(r21));
13800 IkReal x4465=((r20)*(sj6));
13801 IkReal x4466=((IkReal(1.00000000000000))*(cj4)*(cj5));
13802 if( IKabs(((((IkReal(-1.00000000000000))*(x4464)*(x4466)))+(((IkReal(-1.00000000000000))*(x4465)*(x4466)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x4463)*(x4465)))+(((IkReal(-1.00000000000000))*(x4463)*(x4464)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x4464)*(x4466)))+(((IkReal(-1.00000000000000))*(x4465)*(x4466)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x4463)*(x4465)))+(((IkReal(-1.00000000000000))*(x4463)*(x4464)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
13803     continue;
13804 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x4464)*(x4466)))+(((IkReal(-1.00000000000000))*(x4465)*(x4466)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x4463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x4463)*(x4465)))+(((IkReal(-1.00000000000000))*(x4463)*(x4464)))+(((cj5)*(r22)))));
13805 sj3array[0]=IKsin(j3array[0]);
13806 cj3array[0]=IKcos(j3array[0]);
13807 if( j3array[0] > IKPI )
13808 {
13809     j3array[0]-=IK2PI;
13810 }
13811 else if( j3array[0] < -IKPI )
13812 {    j3array[0]+=IK2PI;
13813 }
13814 j3valid[0] = true;
13815 for(int ij3 = 0; ij3 < 1; ++ij3)
13816 {
13817 if( !j3valid[ij3] )
13818 {
13819     continue;
13820 }
13821 _ij3[0] = ij3; _ij3[1] = -1;
13822 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13823 {
13824 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13825 {
13826     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13827 }
13828 }
13829 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13830 {
13831 IkReal evalcond[4];
13832 IkReal x4467=IKsin(j3);
13833 IkReal x4468=IKcos(j3);
13834 IkReal x4469=((sj0)*(sj5));
13835 IkReal x4470=((r00)*(sj6));
13836 IkReal x4471=((cj6)*(r01));
13837 IkReal x4472=((cj5)*(sj0));
13838 IkReal x4473=((cj0)*(cj5));
13839 IkReal x4474=((cj6)*(sj4));
13840 IkReal x4475=((sj4)*(sj6));
13841 IkReal x4476=((cj0)*(r11));
13842 IkReal x4477=((cj4)*(cj6));
13843 IkReal x4478=((cj4)*(sj6));
13844 IkReal x4479=((IkReal(1.00000000000000))*(cj0));
13845 IkReal x4480=((cj4)*(sj5));
13846 IkReal x4481=((sj5)*(sj6));
13847 IkReal x4482=((cj6)*(sj5));
13848 evalcond[0]=((x4468)+(((r21)*(x4482)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x4481))));
13849 evalcond[1]=((x4467)+(((r22)*(x4480)))+(((cj5)*(r20)*(x4478)))+(((cj5)*(r21)*(x4477)))+(((IkReal(-1.00000000000000))*(r21)*(x4475)))+(((r20)*(x4474))));
13850 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4479)*(x4481)))+(((r12)*(x4473)))+(((x4469)*(x4471)))+(((IkReal(-1.00000000000000))*(x4476)*(x4482)))+(((x4469)*(x4470)))+(((IkReal(-1.00000000000000))*(r02)*(x4472)))+(((IkReal(-1.00000000000000))*(x4467))));
13851 evalcond[3]=((x4468)+(((r00)*(sj0)*(x4474)))+(((IkReal(-1.00000000000000))*(r10)*(x4474)*(x4479)))+(((cj4)*(x4471)*(x4472)))+(((cj4)*(r02)*(x4469)))+(((x4475)*(x4476)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x4475)))+(((IkReal(-1.00000000000000))*(r11)*(x4473)*(x4477)))+(((IkReal(-1.00000000000000))*(r10)*(x4473)*(x4478)))+(((IkReal(-1.00000000000000))*(r12)*(x4479)*(x4480)))+(((cj4)*(x4470)*(x4472))));
13852 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13853 {
13854 continue;
13855 }
13856 }
13857 
13858 {
13859 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
13860 vinfos[0].jointtype = 1;
13861 vinfos[0].foffset = j0;
13862 vinfos[0].indices[0] = _ij0[0];
13863 vinfos[0].indices[1] = _ij0[1];
13864 vinfos[0].maxsolutions = _nj0;
13865 vinfos[1].jointtype = 1;
13866 vinfos[1].foffset = j1;
13867 vinfos[1].indices[0] = _ij1[0];
13868 vinfos[1].indices[1] = _ij1[1];
13869 vinfos[1].maxsolutions = _nj1;
13870 vinfos[2].jointtype = 1;
13871 vinfos[2].foffset = j2;
13872 vinfos[2].indices[0] = _ij2[0];
13873 vinfos[2].indices[1] = _ij2[1];
13874 vinfos[2].maxsolutions = _nj2;
13875 vinfos[3].jointtype = 1;
13876 vinfos[3].foffset = j3;
13877 vinfos[3].indices[0] = _ij3[0];
13878 vinfos[3].indices[1] = _ij3[1];
13879 vinfos[3].maxsolutions = _nj3;
13880 vinfos[4].jointtype = 1;
13881 vinfos[4].foffset = j4;
13882 vinfos[4].indices[0] = _ij4[0];
13883 vinfos[4].indices[1] = _ij4[1];
13884 vinfos[4].maxsolutions = _nj4;
13885 vinfos[5].jointtype = 1;
13886 vinfos[5].foffset = j5;
13887 vinfos[5].indices[0] = _ij5[0];
13888 vinfos[5].indices[1] = _ij5[1];
13889 vinfos[5].maxsolutions = _nj5;
13890 vinfos[6].jointtype = 1;
13891 vinfos[6].foffset = j6;
13892 vinfos[6].indices[0] = _ij6[0];
13893 vinfos[6].indices[1] = _ij6[1];
13894 vinfos[6].maxsolutions = _nj6;
13895 std::vector<int> vfree(0);
13896 solutions.AddSolution(vinfos,vfree);
13897 }
13898 }
13899 }
13900 
13901 } else
13902 {
13903 IkReal x4483=((IkReal(1.00000000000000))*(cj0));
13904 IkReal x4484=((cj4)*(sj6));
13905 IkReal x4485=((sj0)*(sj4));
13906 IkReal x4486=((cj5)*(sj6));
13907 IkReal x4487=((sj4)*(sj5));
13908 IkReal x4488=((r12)*(sj5));
13909 IkReal x4489=((IkReal(0.374290000000000))*(cj5));
13910 IkReal x4490=((r02)*(sj0));
13911 IkReal x4491=((r20)*(sj4));
13912 IkReal x4492=((IkReal(1.00000000000000))*(sj0));
13913 IkReal x4493=((IkReal(1.00000000000000))*(cj5));
13914 IkReal x4494=((cj0)*(r10));
13915 IkReal x4495=((cj4)*(cj6));
13916 IkReal x4496=((r00)*(sj0));
13917 IkReal x4497=((cj6)*(r21));
13918 IkReal x4498=((IkReal(0.374290000000000))*(sj5));
13919 IkReal x4499=((cj0)*(r00));
13920 IkReal x4500=((IkReal(0.0100000000000000))*(sj5));
13921 IkReal x4501=((cj0)*(r02));
13922 IkReal x4502=((cj5)*(sj4));
13923 IkReal x4503=((cj6)*(r01));
13924 IkReal x4504=((cj6)*(r11));
13925 IkReal x4505=((r01)*(sj0));
13926 IkReal x4506=((r10)*(sj0));
13927 IkReal x4507=((IkReal(0.0100000000000000))*(cj5)*(cj6));
13928 IkReal x4508=((sj6)*(x4498));
13929 IkReal x4509=((cj0)*(cj6)*(x4498));
13930 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
13931 evalcond[1]=((((sj5)*(x4497)))+(((IkReal(-1.00000000000000))*(r22)*(x4493)))+(((r20)*(sj5)*(sj6))));
13932 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x4495)))+(((x4486)*(x4491)))+(((r22)*(x4487)))+(((r21)*(x4484)))+(((x4497)*(x4502))));
13933 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x4489)))+(((IkReal(-1.00000000000000))*(r22)*(x4500)))+(((IkReal(-0.0100000000000000))*(cj5)*(x4497)))+(((IkReal(-0.0100000000000000))*(r20)*(x4486)))+(pz)+(((r20)*(x4508)))+(((x4497)*(x4498))));
13934 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x4491)))+(((cj5)*(r20)*(x4484)))+(((cj5)*(r21)*(x4495))));
13935 evalcond[5]=((((x4494)*(x4495)))+(((x4484)*(x4505)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x4483)*(x4486)))+(((r02)*(sj5)*(x4485)))+(((r00)*(x4485)*(x4486)))+(((IkReal(-1.00000000000000))*(r12)*(x4483)*(x4487)))+(((IkReal(-1.00000000000000))*(r00)*(x4492)*(x4495)))+(((IkReal(-1.00000000000000))*(r11)*(x4483)*(x4484)))+(((IkReal(-1.00000000000000))*(x4483)*(x4502)*(x4504)))+(((cj5)*(x4485)*(x4503))));
13936 evalcond[6]=((((x4495)*(x4506)))+(((x4495)*(x4499)))+(((IkReal(-1.00000000000000))*(x4483)*(x4502)*(x4503)))+(((IkReal(-1.00000000000000))*(r11)*(x4484)*(x4492)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x4483)*(x4486)))+(((IkReal(-1.00000000000000))*(r02)*(x4483)*(x4487)))+(((IkReal(-1.00000000000000))*(x4485)*(x4493)*(x4504)))+(((IkReal(-1.00000000000000))*(r10)*(x4485)*(x4486)))+(((IkReal(-1.00000000000000))*(x4485)*(x4488)))+(((IkReal(-1.00000000000000))*(r01)*(x4483)*(x4484))));
13937 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-0.0100000000000000))*(x4486)*(x4496)))+(((IkReal(-1.00000000000000))*(x4490)*(x4500)))+(((IkReal(-1.00000000000000))*(py)*(x4483)))+(((IkReal(-1.00000000000000))*(cj0)*(x4498)*(x4504)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x4503)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4504)))+(((sj0)*(x4498)*(x4503)))+(((x4496)*(x4508)))+(((IkReal(0.0100000000000000))*(cj0)*(x4488)))+(((IkReal(0.0100000000000000))*(x4486)*(x4494)))+(((cj0)*(r12)*(x4489)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x4489)*(x4490)))+(((IkReal(-1.00000000000000))*(x4494)*(x4508))));
13938 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4503)))+(((x4500)*(x4501)))+(((x4489)*(x4501)))+(((r12)*(sj0)*(x4489)))+(((IkReal(0.0100000000000000))*(sj0)*(x4488)))+(((IkReal(-1.00000000000000))*(sj0)*(x4498)*(x4504)))+(((IkReal(-1.00000000000000))*(py)*(x4492)))+(((IkReal(-1.00000000000000))*(x4506)*(x4508)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x4504)))+(((IkReal(0.0100000000000000))*(x4486)*(x4506)))+(((IkReal(-1.00000000000000))*(x4499)*(x4508)))+(((IkReal(0.0100000000000000))*(x4486)*(x4499)))+(((IkReal(-1.00000000000000))*(px)*(x4483)))+(((IkReal(-1.00000000000000))*(cj0)*(x4498)*(x4503))));
13939 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
13940 {
13941 {
13942 IkReal j3array[1], cj3array[1], sj3array[1];
13943 bool j3valid[1]={false};
13944 _nj3 = 1;
13945 IkReal x4510=((cj0)*(cj5));
13946 IkReal x4511=((IkReal(1.00000000000000))*(cj0));
13947 IkReal x4512=((cj6)*(r11));
13948 IkReal x4513=((r10)*(sj6));
13949 IkReal x4514=((cj5)*(sj0));
13950 IkReal x4515=((r00)*(sj5)*(sj6));
13951 IkReal x4516=((cj6)*(r01)*(sj5));
13952 IkReal x4517=((IkReal(1.00000000000000))*(sj0)*(sj5));
13953 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4512)))+(((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4513)))+(((r12)*(x4510)))+(((IkReal(-1.00000000000000))*(r02)*(x4514)))+(((sj0)*(x4515)))+(((sj0)*(x4516))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r02)*(x4510)))+(((r12)*(x4514)))+(((IkReal(-1.00000000000000))*(x4513)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4516)))+(((IkReal(-1.00000000000000))*(x4512)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4515))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4512)))+(((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4513)))+(((r12)*(x4510)))+(((IkReal(-1.00000000000000))*(r02)*(x4514)))+(((sj0)*(x4515)))+(((sj0)*(x4516)))))+IKsqr(((((r02)*(x4510)))+(((r12)*(x4514)))+(((IkReal(-1.00000000000000))*(x4513)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4516)))+(((IkReal(-1.00000000000000))*(x4512)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4515)))))-1) <= IKFAST_SINCOS_THRESH )
13954     continue;
13955 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4512)))+(((IkReal(-1.00000000000000))*(sj5)*(x4511)*(x4513)))+(((r12)*(x4510)))+(((IkReal(-1.00000000000000))*(r02)*(x4514)))+(((sj0)*(x4515)))+(((sj0)*(x4516)))), ((((r02)*(x4510)))+(((r12)*(x4514)))+(((IkReal(-1.00000000000000))*(x4513)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4516)))+(((IkReal(-1.00000000000000))*(x4512)*(x4517)))+(((IkReal(-1.00000000000000))*(x4511)*(x4515)))));
13956 sj3array[0]=IKsin(j3array[0]);
13957 cj3array[0]=IKcos(j3array[0]);
13958 if( j3array[0] > IKPI )
13959 {
13960     j3array[0]-=IK2PI;
13961 }
13962 else if( j3array[0] < -IKPI )
13963 {    j3array[0]+=IK2PI;
13964 }
13965 j3valid[0] = true;
13966 for(int ij3 = 0; ij3 < 1; ++ij3)
13967 {
13968 if( !j3valid[ij3] )
13969 {
13970     continue;
13971 }
13972 _ij3[0] = ij3; _ij3[1] = -1;
13973 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
13974 {
13975 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
13976 {
13977     j3valid[iij3]=false; _ij3[1] = iij3; break; 
13978 }
13979 }
13980 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
13981 {
13982 IkReal evalcond[4];
13983 IkReal x4518=IKcos(j3);
13984 IkReal x4519=((sj0)*(sj5));
13985 IkReal x4520=((r00)*(sj6));
13986 IkReal x4521=((cj6)*(sj0));
13987 IkReal x4522=((IkReal(1.00000000000000))*(cj4));
13988 IkReal x4523=((r00)*(sj4));
13989 IkReal x4524=((cj0)*(cj5));
13990 IkReal x4525=((cj5)*(sj0));
13991 IkReal x4526=((cj6)*(r11));
13992 IkReal x4527=((r10)*(sj6));
13993 IkReal x4528=((cj0)*(sj5));
13994 IkReal x4529=((r10)*(sj4));
13995 IkReal x4530=((IkReal(1.00000000000000))*(IKsin(j3)));
13996 IkReal x4531=((cj4)*(cj5)*(r01));
13997 IkReal x4532=((IkReal(1.00000000000000))*(cj0)*(cj6));
13998 IkReal x4533=((cj0)*(sj4)*(sj6));
13999 IkReal x4534=((sj0)*(sj4)*(sj6));
14000 evalcond[0]=((((x4519)*(x4520)))+(((IkReal(-1.00000000000000))*(x4526)*(x4528)))+(((r12)*(x4524)))+(((IkReal(-1.00000000000000))*(r02)*(x4525)))+(((cj6)*(r01)*(x4519)))+(((IkReal(-1.00000000000000))*(x4530)))+(((IkReal(-1.00000000000000))*(x4527)*(x4528))));
14001 evalcond[1]=((((r02)*(x4524)))+(((IkReal(-1.00000000000000))*(x4518)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4528)))+(((IkReal(-1.00000000000000))*(x4519)*(x4526)))+(((IkReal(-1.00000000000000))*(x4520)*(x4528)))+(((r12)*(x4525)))+(((IkReal(-1.00000000000000))*(x4519)*(x4527))));
14002 evalcond[2]=((x4518)+(((x4521)*(x4523)))+(((IkReal(-1.00000000000000))*(x4522)*(x4524)*(x4527)))+(((IkReal(-1.00000000000000))*(r12)*(x4522)*(x4528)))+(((IkReal(-1.00000000000000))*(x4522)*(x4524)*(x4526)))+(((IkReal(-1.00000000000000))*(r01)*(x4534)))+(((IkReal(-1.00000000000000))*(x4529)*(x4532)))+(((cj4)*(r02)*(x4519)))+(((r11)*(x4533)))+(((x4521)*(x4531)))+(((cj4)*(x4520)*(x4525))));
14003 evalcond[3]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4522)*(x4524)))+(((IkReal(-1.00000000000000))*(x4521)*(x4529)))+(((IkReal(-1.00000000000000))*(x4522)*(x4525)*(x4527)))+(((IkReal(-1.00000000000000))*(x4520)*(x4522)*(x4524)))+(((IkReal(-1.00000000000000))*(x4523)*(x4532)))+(((r11)*(x4534)))+(((r01)*(x4533)))+(((IkReal(-1.00000000000000))*(r12)*(x4519)*(x4522)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4521)*(x4522)))+(((IkReal(-1.00000000000000))*(x4530)))+(((IkReal(-1.00000000000000))*(r02)*(x4522)*(x4528))));
14004 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14005 {
14006 continue;
14007 }
14008 }
14009 
14010 {
14011 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14012 vinfos[0].jointtype = 1;
14013 vinfos[0].foffset = j0;
14014 vinfos[0].indices[0] = _ij0[0];
14015 vinfos[0].indices[1] = _ij0[1];
14016 vinfos[0].maxsolutions = _nj0;
14017 vinfos[1].jointtype = 1;
14018 vinfos[1].foffset = j1;
14019 vinfos[1].indices[0] = _ij1[0];
14020 vinfos[1].indices[1] = _ij1[1];
14021 vinfos[1].maxsolutions = _nj1;
14022 vinfos[2].jointtype = 1;
14023 vinfos[2].foffset = j2;
14024 vinfos[2].indices[0] = _ij2[0];
14025 vinfos[2].indices[1] = _ij2[1];
14026 vinfos[2].maxsolutions = _nj2;
14027 vinfos[3].jointtype = 1;
14028 vinfos[3].foffset = j3;
14029 vinfos[3].indices[0] = _ij3[0];
14030 vinfos[3].indices[1] = _ij3[1];
14031 vinfos[3].maxsolutions = _nj3;
14032 vinfos[4].jointtype = 1;
14033 vinfos[4].foffset = j4;
14034 vinfos[4].indices[0] = _ij4[0];
14035 vinfos[4].indices[1] = _ij4[1];
14036 vinfos[4].maxsolutions = _nj4;
14037 vinfos[5].jointtype = 1;
14038 vinfos[5].foffset = j5;
14039 vinfos[5].indices[0] = _ij5[0];
14040 vinfos[5].indices[1] = _ij5[1];
14041 vinfos[5].maxsolutions = _nj5;
14042 vinfos[6].jointtype = 1;
14043 vinfos[6].foffset = j6;
14044 vinfos[6].indices[0] = _ij6[0];
14045 vinfos[6].indices[1] = _ij6[1];
14046 vinfos[6].maxsolutions = _nj6;
14047 std::vector<int> vfree(0);
14048 solutions.AddSolution(vinfos,vfree);
14049 }
14050 }
14051 }
14052 
14053 } else
14054 {
14055 IkReal x4535=((IkReal(1.00000000000000))*(cj0));
14056 IkReal x4536=((cj4)*(sj6));
14057 IkReal x4537=((sj0)*(sj4));
14058 IkReal x4538=((cj5)*(sj6));
14059 IkReal x4539=((sj4)*(sj5));
14060 IkReal x4540=((r12)*(sj5));
14061 IkReal x4541=((IkReal(0.374290000000000))*(cj5));
14062 IkReal x4542=((r02)*(sj0));
14063 IkReal x4543=((r20)*(sj4));
14064 IkReal x4544=((IkReal(1.00000000000000))*(sj0));
14065 IkReal x4545=((IkReal(1.00000000000000))*(cj5));
14066 IkReal x4546=((cj0)*(r10));
14067 IkReal x4547=((cj4)*(cj6));
14068 IkReal x4548=((r00)*(sj0));
14069 IkReal x4549=((cj6)*(r21));
14070 IkReal x4550=((IkReal(0.374290000000000))*(sj5));
14071 IkReal x4551=((cj0)*(r00));
14072 IkReal x4552=((IkReal(0.0100000000000000))*(sj5));
14073 IkReal x4553=((cj0)*(r02));
14074 IkReal x4554=((cj5)*(sj4));
14075 IkReal x4555=((cj6)*(r01));
14076 IkReal x4556=((cj6)*(r11));
14077 IkReal x4557=((r01)*(sj0));
14078 IkReal x4558=((r10)*(sj0));
14079 IkReal x4559=((IkReal(0.0100000000000000))*(cj5)*(cj6));
14080 IkReal x4560=((sj6)*(x4550));
14081 IkReal x4561=((cj0)*(cj6)*(x4550));
14082 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
14083 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x4545)))+(((sj5)*(x4549)))+(((r20)*(sj5)*(sj6))));
14084 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x4547)))+(((r21)*(x4536)))+(((x4538)*(x4543)))+(((r22)*(x4539)))+(((x4549)*(x4554))));
14085 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x4541)))+(((IkReal(-0.0100000000000000))*(r20)*(x4538)))+(((x4549)*(x4550)))+(pz)+(((r20)*(x4560)))+(((IkReal(-1.00000000000000))*(r22)*(x4552)))+(((IkReal(-0.0100000000000000))*(cj5)*(x4549))));
14086 evalcond[4]=((((cj5)*(r21)*(x4547)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x4536)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x4543))));
14087 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x4535)*(x4538)))+(((cj5)*(x4537)*(x4555)))+(((IkReal(-1.00000000000000))*(r12)*(x4535)*(x4539)))+(((IkReal(-1.00000000000000))*(x4535)*(x4554)*(x4556)))+(((r00)*(x4537)*(x4538)))+(((r02)*(sj5)*(x4537)))+(((IkReal(-1.00000000000000))*(r00)*(x4544)*(x4547)))+(((IkReal(-1.00000000000000))*(r11)*(x4535)*(x4536)))+(((x4536)*(x4557)))+(((x4546)*(x4547))));
14088 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(x4537)*(x4538)))+(((IkReal(-1.00000000000000))*(x4537)*(x4545)*(x4556)))+(((x4547)*(x4558)))+(((x4547)*(x4551)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x4535)*(x4538)))+(((IkReal(-1.00000000000000))*(x4537)*(x4540)))+(((IkReal(-1.00000000000000))*(r01)*(x4535)*(x4536)))+(((IkReal(-1.00000000000000))*(r02)*(x4535)*(x4539)))+(((IkReal(-1.00000000000000))*(r11)*(x4536)*(x4544)))+(((IkReal(-1.00000000000000))*(x4535)*(x4554)*(x4555))));
14089 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x4550)*(x4556)))+(((IkReal(0.0100000000000000))*(cj0)*(x4540)))+(((IkReal(-1.00000000000000))*(py)*(x4535)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x4555)))+(((IkReal(-1.00000000000000))*(x4546)*(x4560)))+(((IkReal(-0.0100000000000000))*(x4538)*(x4548)))+(((x4548)*(x4560)))+(((IkReal(-1.00000000000000))*(x4542)*(x4552)))+(((IkReal(0.0100000000000000))*(x4538)*(x4546)))+(((cj0)*(r12)*(x4541)))+(((px)*(sj0)))+(((sj0)*(x4550)*(x4555)))+(((IkReal(-1.00000000000000))*(x4541)*(x4542)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4556))));
14090 evalcond[8]=((IkReal(-0.295420000000000))+(((x4552)*(x4553)))+(((IkReal(-1.00000000000000))*(x4558)*(x4560)))+(((IkReal(-1.00000000000000))*(py)*(x4544)))+(((x4541)*(x4553)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x4555)))+(((IkReal(-1.00000000000000))*(px)*(x4535)))+(((IkReal(-1.00000000000000))*(sj0)*(x4550)*(x4556)))+(((IkReal(-1.00000000000000))*(cj0)*(x4550)*(x4555)))+(((r12)*(sj0)*(x4541)))+(((IkReal(0.0100000000000000))*(x4538)*(x4551)))+(((IkReal(-1.00000000000000))*(x4551)*(x4560)))+(((IkReal(0.0100000000000000))*(sj0)*(x4540)))+(((IkReal(0.0100000000000000))*(x4538)*(x4558)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x4556))));
14091 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
14092 {
14093 {
14094 IkReal j3array[1], cj3array[1], sj3array[1];
14095 bool j3valid[1]={false};
14096 _nj3 = 1;
14097 IkReal x4562=((sj0)*(sj5));
14098 IkReal x4563=((r00)*(sj6));
14099 IkReal x4564=((IkReal(1.00000000000000))*(cj5));
14100 IkReal x4565=((cj6)*(r11));
14101 IkReal x4566=((cj6)*(r01));
14102 IkReal x4567=((r10)*(sj6));
14103 IkReal x4568=((cj0)*(sj5));
14104 if( IKabs(((((IkReal(-1.00000000000000))*(x4565)*(x4568)))+(((x4562)*(x4563)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4564)))+(((IkReal(-1.00000000000000))*(x4567)*(x4568)))+(((cj0)*(cj5)*(r12)))+(((x4562)*(x4566))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x4563)*(x4568)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4564)))+(((x4562)*(x4567)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4564)))+(((x4562)*(x4565)))+(((x4566)*(x4568))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x4565)*(x4568)))+(((x4562)*(x4563)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4564)))+(((IkReal(-1.00000000000000))*(x4567)*(x4568)))+(((cj0)*(cj5)*(r12)))+(((x4562)*(x4566)))))+IKsqr(((((x4563)*(x4568)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4564)))+(((x4562)*(x4567)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4564)))+(((x4562)*(x4565)))+(((x4566)*(x4568)))))-1) <= IKFAST_SINCOS_THRESH )
14105     continue;
14106 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x4565)*(x4568)))+(((x4562)*(x4563)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4564)))+(((IkReal(-1.00000000000000))*(x4567)*(x4568)))+(((cj0)*(cj5)*(r12)))+(((x4562)*(x4566)))), ((((x4563)*(x4568)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4564)))+(((x4562)*(x4567)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4564)))+(((x4562)*(x4565)))+(((x4566)*(x4568)))));
14107 sj3array[0]=IKsin(j3array[0]);
14108 cj3array[0]=IKcos(j3array[0]);
14109 if( j3array[0] > IKPI )
14110 {
14111     j3array[0]-=IK2PI;
14112 }
14113 else if( j3array[0] < -IKPI )
14114 {    j3array[0]+=IK2PI;
14115 }
14116 j3valid[0] = true;
14117 for(int ij3 = 0; ij3 < 1; ++ij3)
14118 {
14119 if( !j3valid[ij3] )
14120 {
14121     continue;
14122 }
14123 _ij3[0] = ij3; _ij3[1] = -1;
14124 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14125 {
14126 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14127 {
14128     j3valid[iij3]=false; _ij3[1] = iij3; break; 
14129 }
14130 }
14131 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14132 {
14133 IkReal evalcond[4];
14134 IkReal x4569=IKcos(j3);
14135 IkReal x4570=IKsin(j3);
14136 IkReal x4571=((sj0)*(sj5));
14137 IkReal x4572=((r00)*(sj6));
14138 IkReal x4573=((cj6)*(sj0));
14139 IkReal x4574=((IkReal(1.00000000000000))*(cj4));
14140 IkReal x4575=((r00)*(sj4));
14141 IkReal x4576=((cj0)*(cj5));
14142 IkReal x4577=((cj5)*(sj0));
14143 IkReal x4578=((cj6)*(r11));
14144 IkReal x4579=((r10)*(sj6));
14145 IkReal x4580=((cj0)*(sj5));
14146 IkReal x4581=((r10)*(sj4));
14147 IkReal x4582=((cj4)*(cj5)*(r01));
14148 IkReal x4583=((IkReal(1.00000000000000))*(cj0)*(cj6));
14149 IkReal x4584=((cj0)*(sj4)*(sj6));
14150 IkReal x4585=((sj0)*(sj4)*(sj6));
14151 evalcond[0]=((((r12)*(x4576)))+(((cj6)*(r01)*(x4571)))+(((IkReal(-1.00000000000000))*(x4579)*(x4580)))+(((x4571)*(x4572)))+(((IkReal(-1.00000000000000))*(x4578)*(x4580)))+(((IkReal(-1.00000000000000))*(x4570)))+(((IkReal(-1.00000000000000))*(r02)*(x4577))));
14152 evalcond[1]=((((IkReal(-1.00000000000000))*(x4571)*(x4579)))+(((IkReal(-1.00000000000000))*(x4571)*(x4578)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4580)))+(((r12)*(x4577)))+(((IkReal(-1.00000000000000))*(x4572)*(x4580)))+(x4569)+(((r02)*(x4576))));
14153 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x4585)))+(((IkReal(-1.00000000000000))*(x4574)*(x4576)*(x4579)))+(((IkReal(-1.00000000000000))*(x4574)*(x4576)*(x4578)))+(((cj4)*(x4572)*(x4577)))+(((r11)*(x4584)))+(((IkReal(-1.00000000000000))*(x4581)*(x4583)))+(((cj4)*(r02)*(x4571)))+(x4569)+(((x4573)*(x4575)))+(((x4573)*(x4582)))+(((IkReal(-1.00000000000000))*(r12)*(x4574)*(x4580))));
14154 evalcond[3]=((x4570)+(((IkReal(-1.00000000000000))*(x4574)*(x4577)*(x4579)))+(((IkReal(-1.00000000000000))*(r02)*(x4574)*(x4580)))+(((r11)*(x4585)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x4574)*(x4576)))+(((IkReal(-1.00000000000000))*(x4573)*(x4581)))+(((IkReal(-1.00000000000000))*(x4575)*(x4583)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4573)*(x4574)))+(((r01)*(x4584)))+(((IkReal(-1.00000000000000))*(r12)*(x4571)*(x4574)))+(((IkReal(-1.00000000000000))*(x4572)*(x4574)*(x4576))));
14155 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14156 {
14157 continue;
14158 }
14159 }
14160 
14161 {
14162 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14163 vinfos[0].jointtype = 1;
14164 vinfos[0].foffset = j0;
14165 vinfos[0].indices[0] = _ij0[0];
14166 vinfos[0].indices[1] = _ij0[1];
14167 vinfos[0].maxsolutions = _nj0;
14168 vinfos[1].jointtype = 1;
14169 vinfos[1].foffset = j1;
14170 vinfos[1].indices[0] = _ij1[0];
14171 vinfos[1].indices[1] = _ij1[1];
14172 vinfos[1].maxsolutions = _nj1;
14173 vinfos[2].jointtype = 1;
14174 vinfos[2].foffset = j2;
14175 vinfos[2].indices[0] = _ij2[0];
14176 vinfos[2].indices[1] = _ij2[1];
14177 vinfos[2].maxsolutions = _nj2;
14178 vinfos[3].jointtype = 1;
14179 vinfos[3].foffset = j3;
14180 vinfos[3].indices[0] = _ij3[0];
14181 vinfos[3].indices[1] = _ij3[1];
14182 vinfos[3].maxsolutions = _nj3;
14183 vinfos[4].jointtype = 1;
14184 vinfos[4].foffset = j4;
14185 vinfos[4].indices[0] = _ij4[0];
14186 vinfos[4].indices[1] = _ij4[1];
14187 vinfos[4].maxsolutions = _nj4;
14188 vinfos[5].jointtype = 1;
14189 vinfos[5].foffset = j5;
14190 vinfos[5].indices[0] = _ij5[0];
14191 vinfos[5].indices[1] = _ij5[1];
14192 vinfos[5].maxsolutions = _nj5;
14193 vinfos[6].jointtype = 1;
14194 vinfos[6].foffset = j6;
14195 vinfos[6].indices[0] = _ij6[0];
14196 vinfos[6].indices[1] = _ij6[1];
14197 vinfos[6].maxsolutions = _nj6;
14198 std::vector<int> vfree(0);
14199 solutions.AddSolution(vinfos,vfree);
14200 }
14201 }
14202 }
14203 
14204 } else
14205 {
14206 if( 1 )
14207 {
14208 continue;
14209 
14210 } else
14211 {
14212 }
14213 }
14214 }
14215 }
14216 }
14217 }
14218 
14219 } else
14220 {
14221 {
14222 IkReal j3array[1], cj3array[1], sj3array[1];
14223 bool j3valid[1]={false};
14224 _nj3 = 1;
14225 IkReal x4586=((cj0)*(cj5));
14226 IkReal x4587=((IkReal(1.00000000000000))*(cj0));
14227 IkReal x4588=((cj6)*(r11));
14228 IkReal x4589=((r10)*(sj6));
14229 IkReal x4590=((cj5)*(sj0));
14230 IkReal x4591=((r00)*(sj5)*(sj6));
14231 IkReal x4592=((cj6)*(r01)*(sj5));
14232 IkReal x4593=((IkReal(1.00000000000000))*(sj0)*(sj5));
14233 if( IKabs(((((sj0)*(x4592)))+(((sj0)*(x4591)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4588)))+(((IkReal(-1.00000000000000))*(r02)*(x4590)))+(((r12)*(x4586)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4589))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x4587)*(x4592)))+(((IkReal(-1.00000000000000))*(x4588)*(x4593)))+(((IkReal(-1.00000000000000))*(x4589)*(x4593)))+(((IkReal(-1.00000000000000))*(x4587)*(x4591)))+(((r12)*(x4590)))+(((r02)*(x4586))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x4592)))+(((sj0)*(x4591)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4588)))+(((IkReal(-1.00000000000000))*(r02)*(x4590)))+(((r12)*(x4586)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4589)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x4587)*(x4592)))+(((IkReal(-1.00000000000000))*(x4588)*(x4593)))+(((IkReal(-1.00000000000000))*(x4589)*(x4593)))+(((IkReal(-1.00000000000000))*(x4587)*(x4591)))+(((r12)*(x4590)))+(((r02)*(x4586)))))))-1) <= IKFAST_SINCOS_THRESH )
14234     continue;
14235 j3array[0]=IKatan2(((((sj0)*(x4592)))+(((sj0)*(x4591)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4588)))+(((IkReal(-1.00000000000000))*(r02)*(x4590)))+(((r12)*(x4586)))+(((IkReal(-1.00000000000000))*(sj5)*(x4587)*(x4589)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x4587)*(x4592)))+(((IkReal(-1.00000000000000))*(x4588)*(x4593)))+(((IkReal(-1.00000000000000))*(x4589)*(x4593)))+(((IkReal(-1.00000000000000))*(x4587)*(x4591)))+(((r12)*(x4590)))+(((r02)*(x4586)))))));
14236 sj3array[0]=IKsin(j3array[0]);
14237 cj3array[0]=IKcos(j3array[0]);
14238 if( j3array[0] > IKPI )
14239 {
14240     j3array[0]-=IK2PI;
14241 }
14242 else if( j3array[0] < -IKPI )
14243 {    j3array[0]+=IK2PI;
14244 }
14245 j3valid[0] = true;
14246 for(int ij3 = 0; ij3 < 1; ++ij3)
14247 {
14248 if( !j3valid[ij3] )
14249 {
14250     continue;
14251 }
14252 _ij3[0] = ij3; _ij3[1] = -1;
14253 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14254 {
14255 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14256 {
14257     j3valid[iij3]=false; _ij3[1] = iij3; break; 
14258 }
14259 }
14260 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14261 {
14262 IkReal evalcond[6];
14263 IkReal x4594=IKsin(j3);
14264 IkReal x4595=IKcos(j3);
14265 IkReal x4596=((sj0)*(sj5));
14266 IkReal x4597=((r00)*(sj6));
14267 IkReal x4598=((cj6)*(r01));
14268 IkReal x4599=((cj4)*(cj5));
14269 IkReal x4600=((IkReal(1.00000000000000))*(cj0));
14270 IkReal x4601=((cj5)*(r12));
14271 IkReal x4602=((IkReal(1.00000000000000))*(sj0));
14272 IkReal x4603=((cj6)*(r11));
14273 IkReal x4604=((cj5)*(r02));
14274 IkReal x4605=((IkReal(1.00000000000000))*(cj1));
14275 IkReal x4606=((cj6)*(sj4));
14276 IkReal x4607=((cj6)*(r21));
14277 IkReal x4608=((r20)*(sj6));
14278 IkReal x4609=((r10)*(sj6));
14279 IkReal x4610=((sj4)*(sj6));
14280 IkReal x4611=((cj4)*(r02));
14281 IkReal x4612=((IkReal(1.00000000000000))*(cj4)*(r12));
14282 IkReal x4613=((IkReal(1.00000000000000))*(x4594));
14283 IkReal x4614=((cj0)*(x4610));
14284 evalcond[0]=((((sj5)*(x4608)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x4595)))+(((sj5)*(x4607))));
14285 evalcond[1]=((((r20)*(x4606)))+(((cj4)*(r22)*(sj5)))+(((x4599)*(x4607)))+(((IkReal(-1.00000000000000))*(sj1)*(x4613)))+(((IkReal(-1.00000000000000))*(r21)*(x4610)))+(((x4599)*(x4608))));
14286 evalcond[2]=((((cj0)*(x4601)))+(((IkReal(-1.00000000000000))*(sj5)*(x4600)*(x4609)))+(((IkReal(-1.00000000000000))*(x4613)))+(((IkReal(-1.00000000000000))*(sj5)*(x4600)*(x4603)))+(((x4596)*(x4597)))+(((x4596)*(x4598)))+(((IkReal(-1.00000000000000))*(x4602)*(x4604))));
14287 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x4598)*(x4600)))+(((IkReal(-1.00000000000000))*(x4595)*(x4605)))+(((sj0)*(x4601)))+(((IkReal(-1.00000000000000))*(x4596)*(x4603)))+(((cj0)*(x4604)))+(((IkReal(-1.00000000000000))*(sj5)*(x4597)*(x4600)))+(((IkReal(-1.00000000000000))*(x4596)*(x4609))));
14288 evalcond[4]=((x4595)+(((r11)*(x4614)))+(((sj0)*(x4598)*(x4599)))+(((sj0)*(x4597)*(x4599)))+(((IkReal(-1.00000000000000))*(x4599)*(x4600)*(x4609)))+(((x4596)*(x4611)))+(((IkReal(-1.00000000000000))*(r01)*(x4602)*(x4610)))+(((IkReal(-1.00000000000000))*(x4599)*(x4600)*(x4603)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4600)))+(((IkReal(-1.00000000000000))*(r10)*(x4600)*(x4606)))+(((r00)*(sj0)*(x4606))));
14289 evalcond[5]=((((IkReal(-1.00000000000000))*(x4594)*(x4605)))+(((IkReal(-1.00000000000000))*(x4599)*(x4602)*(x4603)))+(((IkReal(-1.00000000000000))*(r00)*(x4600)*(x4606)))+(((r01)*(x4614)))+(((IkReal(-1.00000000000000))*(x4597)*(x4599)*(x4600)))+(((IkReal(-1.00000000000000))*(x4599)*(x4602)*(x4609)))+(((IkReal(-1.00000000000000))*(x4598)*(x4599)*(x4600)))+(((IkReal(-1.00000000000000))*(sj5)*(x4600)*(x4611)))+(((r11)*(sj0)*(x4610)))+(((IkReal(-1.00000000000000))*(r10)*(x4602)*(x4606)))+(((IkReal(-1.00000000000000))*(x4596)*(x4612))));
14290 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
14291 {
14292 continue;
14293 }
14294 }
14295 
14296 {
14297 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14298 vinfos[0].jointtype = 1;
14299 vinfos[0].foffset = j0;
14300 vinfos[0].indices[0] = _ij0[0];
14301 vinfos[0].indices[1] = _ij0[1];
14302 vinfos[0].maxsolutions = _nj0;
14303 vinfos[1].jointtype = 1;
14304 vinfos[1].foffset = j1;
14305 vinfos[1].indices[0] = _ij1[0];
14306 vinfos[1].indices[1] = _ij1[1];
14307 vinfos[1].maxsolutions = _nj1;
14308 vinfos[2].jointtype = 1;
14309 vinfos[2].foffset = j2;
14310 vinfos[2].indices[0] = _ij2[0];
14311 vinfos[2].indices[1] = _ij2[1];
14312 vinfos[2].maxsolutions = _nj2;
14313 vinfos[3].jointtype = 1;
14314 vinfos[3].foffset = j3;
14315 vinfos[3].indices[0] = _ij3[0];
14316 vinfos[3].indices[1] = _ij3[1];
14317 vinfos[3].maxsolutions = _nj3;
14318 vinfos[4].jointtype = 1;
14319 vinfos[4].foffset = j4;
14320 vinfos[4].indices[0] = _ij4[0];
14321 vinfos[4].indices[1] = _ij4[1];
14322 vinfos[4].maxsolutions = _nj4;
14323 vinfos[5].jointtype = 1;
14324 vinfos[5].foffset = j5;
14325 vinfos[5].indices[0] = _ij5[0];
14326 vinfos[5].indices[1] = _ij5[1];
14327 vinfos[5].maxsolutions = _nj5;
14328 vinfos[6].jointtype = 1;
14329 vinfos[6].foffset = j6;
14330 vinfos[6].indices[0] = _ij6[0];
14331 vinfos[6].indices[1] = _ij6[1];
14332 vinfos[6].maxsolutions = _nj6;
14333 std::vector<int> vfree(0);
14334 solutions.AddSolution(vinfos,vfree);
14335 }
14336 }
14337 }
14338 
14339 }
14340 
14341 }
14342 
14343 } else
14344 {
14345 {
14346 IkReal j3array[1], cj3array[1], sj3array[1];
14347 bool j3valid[1]={false};
14348 _nj3 = 1;
14349 IkReal x4615=((sj5)*(sj6));
14350 IkReal x4616=((cj6)*(sj5));
14351 IkReal x4617=((IkReal(1.00000000000000))*(cj0));
14352 IkReal x4618=((IkReal(1.00000000000000))*(cj5));
14353 if( IKabs(((((r01)*(sj0)*(x4616)))+(((r00)*(sj0)*(x4615)))+(((IkReal(-1.00000000000000))*(r10)*(x4615)*(x4617)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4618)))+(((IkReal(-1.00000000000000))*(r11)*(x4616)*(x4617))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x4618)))+(((r20)*(x4615)))+(((r21)*(x4616))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r01)*(sj0)*(x4616)))+(((r00)*(sj0)*(x4615)))+(((IkReal(-1.00000000000000))*(r10)*(x4615)*(x4617)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4618)))+(((IkReal(-1.00000000000000))*(r11)*(x4616)*(x4617)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x4618)))+(((r20)*(x4615)))+(((r21)*(x4616)))))))-1) <= IKFAST_SINCOS_THRESH )
14354     continue;
14355 j3array[0]=IKatan2(((((r01)*(sj0)*(x4616)))+(((r00)*(sj0)*(x4615)))+(((IkReal(-1.00000000000000))*(r10)*(x4615)*(x4617)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4618)))+(((IkReal(-1.00000000000000))*(r11)*(x4616)*(x4617)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x4618)))+(((r20)*(x4615)))+(((r21)*(x4616)))))));
14356 sj3array[0]=IKsin(j3array[0]);
14357 cj3array[0]=IKcos(j3array[0]);
14358 if( j3array[0] > IKPI )
14359 {
14360     j3array[0]-=IK2PI;
14361 }
14362 else if( j3array[0] < -IKPI )
14363 {    j3array[0]+=IK2PI;
14364 }
14365 j3valid[0] = true;
14366 for(int ij3 = 0; ij3 < 1; ++ij3)
14367 {
14368 if( !j3valid[ij3] )
14369 {
14370     continue;
14371 }
14372 _ij3[0] = ij3; _ij3[1] = -1;
14373 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14374 {
14375 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14376 {
14377     j3valid[iij3]=false; _ij3[1] = iij3; break; 
14378 }
14379 }
14380 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14381 {
14382 IkReal evalcond[6];
14383 IkReal x4619=IKsin(j3);
14384 IkReal x4620=IKcos(j3);
14385 IkReal x4621=((sj0)*(sj5));
14386 IkReal x4622=((r00)*(sj6));
14387 IkReal x4623=((cj6)*(r01));
14388 IkReal x4624=((cj4)*(cj5));
14389 IkReal x4625=((IkReal(1.00000000000000))*(cj0));
14390 IkReal x4626=((cj5)*(r12));
14391 IkReal x4627=((IkReal(1.00000000000000))*(sj0));
14392 IkReal x4628=((cj6)*(r11));
14393 IkReal x4629=((cj5)*(r02));
14394 IkReal x4630=((IkReal(1.00000000000000))*(cj1));
14395 IkReal x4631=((cj6)*(sj4));
14396 IkReal x4632=((cj6)*(r21));
14397 IkReal x4633=((r20)*(sj6));
14398 IkReal x4634=((r10)*(sj6));
14399 IkReal x4635=((sj4)*(sj6));
14400 IkReal x4636=((cj4)*(r02));
14401 IkReal x4637=((IkReal(1.00000000000000))*(cj4)*(r12));
14402 IkReal x4638=((IkReal(1.00000000000000))*(x4619));
14403 IkReal x4639=((cj0)*(x4635));
14404 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x4620)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4632)))+(((sj5)*(x4633))));
14405 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x4638)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x4631)))+(((x4624)*(x4633)))+(((x4624)*(x4632)))+(((IkReal(-1.00000000000000))*(r21)*(x4635))));
14406 evalcond[2]=((((IkReal(-1.00000000000000))*(x4627)*(x4629)))+(((IkReal(-1.00000000000000))*(x4638)))+(((IkReal(-1.00000000000000))*(sj5)*(x4625)*(x4634)))+(((x4621)*(x4623)))+(((x4621)*(x4622)))+(((cj0)*(x4626)))+(((IkReal(-1.00000000000000))*(sj5)*(x4625)*(x4628))));
14407 evalcond[3]=((((IkReal(-1.00000000000000))*(x4621)*(x4628)))+(((cj0)*(x4629)))+(((IkReal(-1.00000000000000))*(sj5)*(x4622)*(x4625)))+(((IkReal(-1.00000000000000))*(sj5)*(x4623)*(x4625)))+(((IkReal(-1.00000000000000))*(x4620)*(x4630)))+(((IkReal(-1.00000000000000))*(x4621)*(x4634)))+(((sj0)*(x4626))));
14408 evalcond[4]=((((sj0)*(x4623)*(x4624)))+(((IkReal(-1.00000000000000))*(x4624)*(x4625)*(x4634)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4625)))+(((x4621)*(x4636)))+(((r11)*(x4639)))+(((IkReal(-1.00000000000000))*(r10)*(x4625)*(x4631)))+(((IkReal(-1.00000000000000))*(r01)*(x4627)*(x4635)))+(((r00)*(sj0)*(x4631)))+(((sj0)*(x4622)*(x4624)))+(((IkReal(-1.00000000000000))*(x4624)*(x4625)*(x4628)))+(x4620));
14409 evalcond[5]=((((IkReal(-1.00000000000000))*(x4624)*(x4627)*(x4628)))+(((IkReal(-1.00000000000000))*(x4624)*(x4627)*(x4634)))+(((IkReal(-1.00000000000000))*(r00)*(x4625)*(x4631)))+(((IkReal(-1.00000000000000))*(r10)*(x4627)*(x4631)))+(((IkReal(-1.00000000000000))*(x4622)*(x4624)*(x4625)))+(((IkReal(-1.00000000000000))*(x4619)*(x4630)))+(((r11)*(sj0)*(x4635)))+(((IkReal(-1.00000000000000))*(x4621)*(x4637)))+(((IkReal(-1.00000000000000))*(sj5)*(x4625)*(x4636)))+(((r01)*(x4639)))+(((IkReal(-1.00000000000000))*(x4623)*(x4624)*(x4625))));
14410 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
14411 {
14412 continue;
14413 }
14414 }
14415 
14416 {
14417 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14418 vinfos[0].jointtype = 1;
14419 vinfos[0].foffset = j0;
14420 vinfos[0].indices[0] = _ij0[0];
14421 vinfos[0].indices[1] = _ij0[1];
14422 vinfos[0].maxsolutions = _nj0;
14423 vinfos[1].jointtype = 1;
14424 vinfos[1].foffset = j1;
14425 vinfos[1].indices[0] = _ij1[0];
14426 vinfos[1].indices[1] = _ij1[1];
14427 vinfos[1].maxsolutions = _nj1;
14428 vinfos[2].jointtype = 1;
14429 vinfos[2].foffset = j2;
14430 vinfos[2].indices[0] = _ij2[0];
14431 vinfos[2].indices[1] = _ij2[1];
14432 vinfos[2].maxsolutions = _nj2;
14433 vinfos[3].jointtype = 1;
14434 vinfos[3].foffset = j3;
14435 vinfos[3].indices[0] = _ij3[0];
14436 vinfos[3].indices[1] = _ij3[1];
14437 vinfos[3].maxsolutions = _nj3;
14438 vinfos[4].jointtype = 1;
14439 vinfos[4].foffset = j4;
14440 vinfos[4].indices[0] = _ij4[0];
14441 vinfos[4].indices[1] = _ij4[1];
14442 vinfos[4].maxsolutions = _nj4;
14443 vinfos[5].jointtype = 1;
14444 vinfos[5].foffset = j5;
14445 vinfos[5].indices[0] = _ij5[0];
14446 vinfos[5].indices[1] = _ij5[1];
14447 vinfos[5].maxsolutions = _nj5;
14448 vinfos[6].jointtype = 1;
14449 vinfos[6].foffset = j6;
14450 vinfos[6].indices[0] = _ij6[0];
14451 vinfos[6].indices[1] = _ij6[1];
14452 vinfos[6].maxsolutions = _nj6;
14453 std::vector<int> vfree(0);
14454 solutions.AddSolution(vinfos,vfree);
14455 }
14456 }
14457 }
14458 
14459 }
14460 
14461 }
14462 
14463 } else
14464 {
14465 {
14466 IkReal j3array[1], cj3array[1], sj3array[1];
14467 bool j3valid[1]={false};
14468 _nj3 = 1;
14469 IkReal x4640=((r20)*(sj6));
14470 IkReal x4641=((cj4)*(cj5));
14471 IkReal x4642=((cj6)*(r21));
14472 if( IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x4641)*(x4642)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x4640)*(x4641))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4640)))+(((sj5)*(x4642))))))) < IKFAST_ATAN2_MAGTHRESH )
14473     continue;
14474 j3array[0]=IKatan2(((gconst17)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x4641)*(x4642)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x4640)*(x4641)))))), ((gconst17)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4640)))+(((sj5)*(x4642)))))));
14475 sj3array[0]=IKsin(j3array[0]);
14476 cj3array[0]=IKcos(j3array[0]);
14477 if( j3array[0] > IKPI )
14478 {
14479     j3array[0]-=IK2PI;
14480 }
14481 else if( j3array[0] < -IKPI )
14482 {    j3array[0]+=IK2PI;
14483 }
14484 j3valid[0] = true;
14485 for(int ij3 = 0; ij3 < 1; ++ij3)
14486 {
14487 if( !j3valid[ij3] )
14488 {
14489     continue;
14490 }
14491 _ij3[0] = ij3; _ij3[1] = -1;
14492 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14493 {
14494 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14495 {
14496     j3valid[iij3]=false; _ij3[1] = iij3; break; 
14497 }
14498 }
14499 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14500 {
14501 IkReal evalcond[6];
14502 IkReal x4643=IKsin(j3);
14503 IkReal x4644=IKcos(j3);
14504 IkReal x4645=((sj0)*(sj5));
14505 IkReal x4646=((r00)*(sj6));
14506 IkReal x4647=((cj6)*(r01));
14507 IkReal x4648=((cj4)*(cj5));
14508 IkReal x4649=((IkReal(1.00000000000000))*(cj0));
14509 IkReal x4650=((cj5)*(r12));
14510 IkReal x4651=((IkReal(1.00000000000000))*(sj0));
14511 IkReal x4652=((cj6)*(r11));
14512 IkReal x4653=((cj5)*(r02));
14513 IkReal x4654=((IkReal(1.00000000000000))*(cj1));
14514 IkReal x4655=((cj6)*(sj4));
14515 IkReal x4656=((cj6)*(r21));
14516 IkReal x4657=((r20)*(sj6));
14517 IkReal x4658=((r10)*(sj6));
14518 IkReal x4659=((sj4)*(sj6));
14519 IkReal x4660=((cj4)*(r02));
14520 IkReal x4661=((IkReal(1.00000000000000))*(cj4)*(r12));
14521 IkReal x4662=((IkReal(1.00000000000000))*(x4643));
14522 IkReal x4663=((cj0)*(x4659));
14523 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x4656)))+(((sj5)*(x4657)))+(((IkReal(-1.00000000000000))*(sj1)*(x4644))));
14524 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x4662)))+(((r20)*(x4655)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x4659)))+(((x4648)*(x4657)))+(((x4648)*(x4656))));
14525 evalcond[2]=((((x4645)*(x4646)))+(((IkReal(-1.00000000000000))*(sj5)*(x4649)*(x4658)))+(((cj0)*(x4650)))+(((x4645)*(x4647)))+(((IkReal(-1.00000000000000))*(x4662)))+(((IkReal(-1.00000000000000))*(sj5)*(x4649)*(x4652)))+(((IkReal(-1.00000000000000))*(x4651)*(x4653))));
14526 evalcond[3]=((((IkReal(-1.00000000000000))*(x4645)*(x4658)))+(((IkReal(-1.00000000000000))*(sj5)*(x4647)*(x4649)))+(((IkReal(-1.00000000000000))*(x4644)*(x4654)))+(((cj0)*(x4653)))+(((sj0)*(x4650)))+(((IkReal(-1.00000000000000))*(x4645)*(x4652)))+(((IkReal(-1.00000000000000))*(sj5)*(x4646)*(x4649))));
14527 evalcond[4]=((((r11)*(x4663)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x4649)))+(((sj0)*(x4647)*(x4648)))+(((x4645)*(x4660)))+(((sj0)*(x4646)*(x4648)))+(((IkReal(-1.00000000000000))*(r01)*(x4651)*(x4659)))+(((IkReal(-1.00000000000000))*(x4648)*(x4649)*(x4658)))+(((r00)*(sj0)*(x4655)))+(((IkReal(-1.00000000000000))*(x4648)*(x4649)*(x4652)))+(x4644)+(((IkReal(-1.00000000000000))*(r10)*(x4649)*(x4655))));
14528 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x4649)*(x4660)))+(((r01)*(x4663)))+(((IkReal(-1.00000000000000))*(r10)*(x4651)*(x4655)))+(((IkReal(-1.00000000000000))*(x4648)*(x4651)*(x4658)))+(((IkReal(-1.00000000000000))*(x4643)*(x4654)))+(((IkReal(-1.00000000000000))*(x4648)*(x4651)*(x4652)))+(((IkReal(-1.00000000000000))*(r00)*(x4649)*(x4655)))+(((r11)*(sj0)*(x4659)))+(((IkReal(-1.00000000000000))*(x4647)*(x4648)*(x4649)))+(((IkReal(-1.00000000000000))*(x4645)*(x4661)))+(((IkReal(-1.00000000000000))*(x4646)*(x4648)*(x4649))));
14529 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
14530 {
14531 continue;
14532 }
14533 }
14534 
14535 {
14536 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14537 vinfos[0].jointtype = 1;
14538 vinfos[0].foffset = j0;
14539 vinfos[0].indices[0] = _ij0[0];
14540 vinfos[0].indices[1] = _ij0[1];
14541 vinfos[0].maxsolutions = _nj0;
14542 vinfos[1].jointtype = 1;
14543 vinfos[1].foffset = j1;
14544 vinfos[1].indices[0] = _ij1[0];
14545 vinfos[1].indices[1] = _ij1[1];
14546 vinfos[1].maxsolutions = _nj1;
14547 vinfos[2].jointtype = 1;
14548 vinfos[2].foffset = j2;
14549 vinfos[2].indices[0] = _ij2[0];
14550 vinfos[2].indices[1] = _ij2[1];
14551 vinfos[2].maxsolutions = _nj2;
14552 vinfos[3].jointtype = 1;
14553 vinfos[3].foffset = j3;
14554 vinfos[3].indices[0] = _ij3[0];
14555 vinfos[3].indices[1] = _ij3[1];
14556 vinfos[3].maxsolutions = _nj3;
14557 vinfos[4].jointtype = 1;
14558 vinfos[4].foffset = j4;
14559 vinfos[4].indices[0] = _ij4[0];
14560 vinfos[4].indices[1] = _ij4[1];
14561 vinfos[4].maxsolutions = _nj4;
14562 vinfos[5].jointtype = 1;
14563 vinfos[5].foffset = j5;
14564 vinfos[5].indices[0] = _ij5[0];
14565 vinfos[5].indices[1] = _ij5[1];
14566 vinfos[5].maxsolutions = _nj5;
14567 vinfos[6].jointtype = 1;
14568 vinfos[6].foffset = j6;
14569 vinfos[6].indices[0] = _ij6[0];
14570 vinfos[6].indices[1] = _ij6[1];
14571 vinfos[6].maxsolutions = _nj6;
14572 std::vector<int> vfree(0);
14573 solutions.AddSolution(vinfos,vfree);
14574 }
14575 }
14576 }
14577 
14578 }
14579 
14580 }
14581 }
14582 }
14583 
14584 }
14585 
14586 }
14587 
14588 } else
14589 {
14590 IkReal x4664=((IkReal(0.374290000000000))*(sj5));
14591 IkReal x4665=((cj0)*(sj6));
14592 IkReal x4666=((IkReal(0.0100000000000000))*(sj5));
14593 IkReal x4667=((cj0)*(r02));
14594 IkReal x4668=((IkReal(0.0100000000000000))*(cj5));
14595 IkReal x4669=((IkReal(1.00000000000000))*(py));
14596 IkReal x4670=((r01)*(sj0));
14597 IkReal x4671=((r20)*(sj6));
14598 IkReal x4672=((r11)*(sj0));
14599 IkReal x4673=((IkReal(0.374290000000000))*(cj5));
14600 IkReal x4674=((cj0)*(r12));
14601 IkReal x4675=((sj0)*(x4673));
14602 IkReal x4676=((cj6)*(x4668));
14603 IkReal x4677=((r10)*(sj0)*(sj6));
14604 IkReal x4678=((r00)*(sj0)*(sj6));
14605 IkReal x4679=((cj0)*(cj6)*(x4664));
14606 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
14607 evalcond[1]=((((IkReal(0.364420000000000))*(sj1)))+(((x4664)*(x4671)))+(((IkReal(-1.00000000000000))*(r22)*(x4673)))+(((cj6)*(r21)*(x4664)))+(((IkReal(-1.00000000000000))*(r21)*(x4676)))+(pz)+(((IkReal(-1.00000000000000))*(x4668)*(x4671)))+(((IkReal(-1.00000000000000))*(r22)*(x4666))));
14608 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x4679)))+(((IkReal(-1.00000000000000))*(x4670)*(x4676)))+(((x4664)*(x4678)))+(((IkReal(-1.00000000000000))*(x4668)*(x4678)))+(((x4666)*(x4674)))+(((cj0)*(r11)*(x4676)))+(((IkReal(-1.00000000000000))*(r10)*(x4664)*(x4665)))+(((cj6)*(x4664)*(x4670)))+(((r10)*(x4665)*(x4668)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4666)))+(((px)*(sj0)))+(((x4673)*(x4674)))+(((IkReal(-1.00000000000000))*(r02)*(x4675)))+(((IkReal(-1.00000000000000))*(cj0)*(x4669))));
14609 evalcond[3]=((IkReal(0.0690000000000000))+(((x4667)*(x4673)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(cj6)*(x4664)*(x4672)))+(((r00)*(x4665)*(x4668)))+(((r12)*(sj0)*(x4666)))+(((cj0)*(r01)*(x4676)))+(((IkReal(-1.00000000000000))*(r00)*(x4664)*(x4665)))+(((x4666)*(x4667)))+(((IkReal(-1.00000000000000))*(sj0)*(x4669)))+(((IkReal(-1.00000000000000))*(r01)*(x4679)))+(((r12)*(x4675)))+(((x4668)*(x4677)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x4664)*(x4677)))+(((x4672)*(x4676))));
14610 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  )
14611 {
14612 {
14613 IkReal dummyeval[1];
14614 IkReal gconst26;
14615 IkReal x4680=(cj6)*(cj6);
14616 IkReal x4681=(sj6)*(sj6);
14617 IkReal x4682=((IkReal(1.00000000000000))*(r01));
14618 IkReal x4683=((sj0)*(sj5));
14619 IkReal x4684=((cj6)*(r22));
14620 IkReal x4685=((r21)*(sj6));
14621 IkReal x4686=((r00)*(r21));
14622 IkReal x4687=((cj0)*(sj5));
14623 IkReal x4688=((cj6)*(r20));
14624 IkReal x4689=((r22)*(sj6));
14625 IkReal x4690=((cj0)*(cj5));
14626 IkReal x4691=((IkReal(1.00000000000000))*(r10));
14627 IkReal x4692=((cj5)*(sj0));
14628 IkReal x4693=((r20)*(x4681));
14629 IkReal x4694=((x4680)*(x4692));
14630 gconst26=IKsign(((((r00)*(x4683)*(x4684)))+(((r11)*(x4690)*(x4693)))+(((x4686)*(x4694)))+(((IkReal(-1.00000000000000))*(x4682)*(x4683)*(x4689)))+(((IkReal(-1.00000000000000))*(r02)*(x4683)*(x4688)))+(((IkReal(-1.00000000000000))*(x4682)*(x4692)*(x4693)))+(((r11)*(x4687)*(x4689)))+(((IkReal(-1.00000000000000))*(r21)*(x4681)*(x4690)*(x4691)))+(((r11)*(r20)*(x4680)*(x4690)))+(((IkReal(-1.00000000000000))*(r12)*(x4685)*(x4687)))+(((IkReal(-1.00000000000000))*(x4684)*(x4687)*(x4691)))+(((r12)*(x4687)*(x4688)))+(((IkReal(-1.00000000000000))*(r21)*(x4680)*(x4690)*(x4691)))+(((x4681)*(x4686)*(x4692)))+(((r02)*(x4683)*(x4685)))+(((IkReal(-1.00000000000000))*(r20)*(x4682)*(x4694)))));
14631 IkReal x4695=(cj6)*(cj6);
14632 IkReal x4696=(sj6)*(sj6);
14633 IkReal x4697=((IkReal(1.00000000000000))*(r01));
14634 IkReal x4698=((sj0)*(sj5));
14635 IkReal x4699=((cj6)*(r22));
14636 IkReal x4700=((r21)*(sj6));
14637 IkReal x4701=((r00)*(r21));
14638 IkReal x4702=((cj0)*(sj5));
14639 IkReal x4703=((cj6)*(r20));
14640 IkReal x4704=((r22)*(sj6));
14641 IkReal x4705=((cj0)*(cj5));
14642 IkReal x4706=((IkReal(1.00000000000000))*(r10));
14643 IkReal x4707=((cj5)*(sj0));
14644 IkReal x4708=((r20)*(x4696));
14645 IkReal x4709=((x4695)*(x4707));
14646 dummyeval[0]=((((r11)*(x4705)*(x4708)))+(((IkReal(-1.00000000000000))*(x4697)*(x4698)*(x4704)))+(((IkReal(-1.00000000000000))*(r20)*(x4697)*(x4709)))+(((r11)*(x4702)*(x4704)))+(((IkReal(-1.00000000000000))*(r21)*(x4696)*(x4705)*(x4706)))+(((IkReal(-1.00000000000000))*(r21)*(x4695)*(x4705)*(x4706)))+(((r00)*(x4698)*(x4699)))+(((r11)*(r20)*(x4695)*(x4705)))+(((IkReal(-1.00000000000000))*(r12)*(x4700)*(x4702)))+(((r12)*(x4702)*(x4703)))+(((r02)*(x4698)*(x4700)))+(((IkReal(-1.00000000000000))*(x4699)*(x4702)*(x4706)))+(((x4701)*(x4709)))+(((x4696)*(x4701)*(x4707)))+(((IkReal(-1.00000000000000))*(x4697)*(x4707)*(x4708)))+(((IkReal(-1.00000000000000))*(r02)*(x4698)*(x4703))));
14647 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14648 {
14649 {
14650 IkReal dummyeval[1];
14651 IkReal gconst27;
14652 IkReal x4710=(cj6)*(cj6);
14653 IkReal x4711=(sj6)*(sj6);
14654 IkReal x4712=((sj5)*(sj6));
14655 IkReal x4713=((IkReal(1.00000000000000))*(cj0));
14656 IkReal x4714=((cj6)*(sj5));
14657 IkReal x4715=((r20)*(sj0));
14658 IkReal x4716=((cj0)*(r20));
14659 IkReal x4717=((r00)*(r21));
14660 IkReal x4718=((r22)*(sj0));
14661 IkReal x4719=((IkReal(1.00000000000000))*(r21)*(sj0));
14662 IkReal x4720=((cj5)*(x4711));
14663 IkReal x4721=((cj5)*(x4710));
14664 gconst27=IKsign(((((IkReal(-1.00000000000000))*(r10)*(x4719)*(x4721)))+(((r11)*(x4715)*(x4720)))+(((r01)*(x4716)*(x4720)))+(((r11)*(x4712)*(x4718)))+(((IkReal(-1.00000000000000))*(x4713)*(x4717)*(x4721)))+(((r01)*(x4716)*(x4721)))+(((IkReal(-1.00000000000000))*(r10)*(x4719)*(x4720)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x4713)*(x4714)))+(((r12)*(x4714)*(x4715)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x4712)*(x4713)))+(((cj0)*(r01)*(r22)*(x4712)))+(((r11)*(x4715)*(x4721)))+(((r02)*(x4714)*(x4716)))+(((IkReal(-1.00000000000000))*(x4713)*(x4717)*(x4720)))+(((IkReal(-1.00000000000000))*(r12)*(x4712)*(x4719)))+(((IkReal(-1.00000000000000))*(r10)*(x4714)*(x4718)))));
14665 IkReal x4722=(cj6)*(cj6);
14666 IkReal x4723=(sj6)*(sj6);
14667 IkReal x4724=((sj5)*(sj6));
14668 IkReal x4725=((IkReal(1.00000000000000))*(cj0));
14669 IkReal x4726=((cj6)*(sj5));
14670 IkReal x4727=((r20)*(sj0));
14671 IkReal x4728=((cj0)*(r20));
14672 IkReal x4729=((r00)*(r21));
14673 IkReal x4730=((r22)*(sj0));
14674 IkReal x4731=((IkReal(1.00000000000000))*(r21)*(sj0));
14675 IkReal x4732=((cj5)*(x4723));
14676 IkReal x4733=((cj5)*(x4722));
14677 dummyeval[0]=((((cj0)*(r01)*(r22)*(x4724)))+(((IkReal(-1.00000000000000))*(r12)*(x4724)*(x4731)))+(((r02)*(x4726)*(x4728)))+(((IkReal(-1.00000000000000))*(r10)*(x4731)*(x4733)))+(((IkReal(-1.00000000000000))*(x4725)*(x4729)*(x4733)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x4724)*(x4725)))+(((r01)*(x4728)*(x4733)))+(((IkReal(-1.00000000000000))*(r10)*(x4731)*(x4732)))+(((r11)*(x4727)*(x4732)))+(((r01)*(x4728)*(x4732)))+(((IkReal(-1.00000000000000))*(r10)*(x4726)*(x4730)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x4725)*(x4726)))+(((r11)*(x4724)*(x4730)))+(((r12)*(x4726)*(x4727)))+(((r11)*(x4727)*(x4733)))+(((IkReal(-1.00000000000000))*(x4725)*(x4729)*(x4732))));
14678 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14679 {
14680 {
14681 IkReal dummyeval[1];
14682 dummyeval[0]=sj1;
14683 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14684 {
14685 {
14686 IkReal evalcond[5];
14687 IkReal x4734=((cj5)*(r22));
14688 IkReal x4735=((IkReal(0.374290000000000))*(sj5));
14689 IkReal x4736=((cj0)*(sj6));
14690 IkReal x4737=((cj6)*(r21));
14691 IkReal x4738=((IkReal(0.0100000000000000))*(sj5));
14692 IkReal x4739=((cj0)*(r02));
14693 IkReal x4740=((IkReal(0.0100000000000000))*(cj5));
14694 IkReal x4741=((IkReal(1.00000000000000))*(py));
14695 IkReal x4742=((r01)*(sj0));
14696 IkReal x4743=((r20)*(sj6));
14697 IkReal x4744=((r11)*(sj0));
14698 IkReal x4745=((IkReal(0.374290000000000))*(cj5));
14699 IkReal x4746=((cj0)*(r12));
14700 IkReal x4747=((sj0)*(x4745));
14701 IkReal x4748=((cj6)*(x4740));
14702 IkReal x4749=((r10)*(sj0)*(sj6));
14703 IkReal x4750=((r00)*(sj0)*(sj6));
14704 IkReal x4751=((cj0)*(cj6)*(x4735));
14705 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
14706 evalcond[1]=((((IkReal(-1.00000000000000))*(x4734)))+(((sj5)*(x4737)))+(((sj5)*(x4743))));
14707 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x4738)))+(((x4735)*(x4737)))+(pz)+(((IkReal(-1.00000000000000))*(x4740)*(x4743)))+(((IkReal(-0.374290000000000))*(x4734)))+(((IkReal(-1.00000000000000))*(x4737)*(x4740)))+(((x4735)*(x4743))));
14708 evalcond[3]=((IkReal(-0.0690000000000000))+(((x4738)*(x4746)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4738)))+(((x4735)*(x4750)))+(((IkReal(-1.00000000000000))*(x4742)*(x4748)))+(((r10)*(x4736)*(x4740)))+(((cj0)*(r11)*(x4748)))+(((IkReal(-1.00000000000000))*(r11)*(x4751)))+(((IkReal(-1.00000000000000))*(r10)*(x4735)*(x4736)))+(((x4745)*(x4746)))+(((IkReal(-1.00000000000000))*(x4740)*(x4750)))+(((IkReal(-1.00000000000000))*(r02)*(x4747)))+(((cj6)*(x4735)*(x4742)))+(((IkReal(-1.00000000000000))*(cj0)*(x4741)))+(((px)*(sj0))));
14709 evalcond[4]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((IkReal(-1.00000000000000))*(r01)*(x4751)))+(((IkReal(-1.00000000000000))*(x4735)*(x4749)))+(((r12)*(x4747)))+(((cj0)*(r01)*(x4748)))+(((r00)*(x4736)*(x4740)))+(((IkReal(-1.00000000000000))*(sj0)*(x4741)))+(((IkReal(-1.00000000000000))*(r00)*(x4735)*(x4736)))+(((x4738)*(x4739)))+(((x4739)*(x4745)))+(((r12)*(sj0)*(x4738)))+(((IkReal(-1.00000000000000))*(cj6)*(x4735)*(x4744)))+(((x4744)*(x4748)))+(((x4740)*(x4749))));
14710 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
14711 {
14712 {
14713 IkReal j3array[1], cj3array[1], sj3array[1];
14714 bool j3valid[1]={false};
14715 _nj3 = 1;
14716 IkReal x4752=((cj5)*(r02));
14717 IkReal x4753=((cj0)*(sj5));
14718 IkReal x4754=((r10)*(sj6));
14719 IkReal x4755=((IkReal(1.00000000000000))*(cj6));
14720 IkReal x4756=((sj0)*(sj5));
14721 IkReal x4757=((cj5)*(r12));
14722 IkReal x4758=((IkReal(1.00000000000000))*(r00)*(sj6));
14723 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x4757)))+(((IkReal(-1.00000000000000))*(r01)*(x4755)*(x4756)))+(((x4753)*(x4754)))+(((IkReal(-1.00000000000000))*(x4756)*(x4758)))+(((cj6)*(r11)*(x4753)))+(((sj0)*(x4752))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj0)*(x4757)))+(((cj0)*(x4752)))+(((IkReal(-1.00000000000000))*(x4754)*(x4756)))+(((IkReal(-1.00000000000000))*(x4753)*(x4758)))+(((IkReal(-1.00000000000000))*(r11)*(x4755)*(x4756)))+(((IkReal(-1.00000000000000))*(r01)*(x4753)*(x4755))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x4757)))+(((IkReal(-1.00000000000000))*(r01)*(x4755)*(x4756)))+(((x4753)*(x4754)))+(((IkReal(-1.00000000000000))*(x4756)*(x4758)))+(((cj6)*(r11)*(x4753)))+(((sj0)*(x4752)))))+IKsqr(((((sj0)*(x4757)))+(((cj0)*(x4752)))+(((IkReal(-1.00000000000000))*(x4754)*(x4756)))+(((IkReal(-1.00000000000000))*(x4753)*(x4758)))+(((IkReal(-1.00000000000000))*(r11)*(x4755)*(x4756)))+(((IkReal(-1.00000000000000))*(r01)*(x4753)*(x4755)))))-1) <= IKFAST_SINCOS_THRESH )
14724     continue;
14725 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x4757)))+(((IkReal(-1.00000000000000))*(r01)*(x4755)*(x4756)))+(((x4753)*(x4754)))+(((IkReal(-1.00000000000000))*(x4756)*(x4758)))+(((cj6)*(r11)*(x4753)))+(((sj0)*(x4752)))), ((((sj0)*(x4757)))+(((cj0)*(x4752)))+(((IkReal(-1.00000000000000))*(x4754)*(x4756)))+(((IkReal(-1.00000000000000))*(x4753)*(x4758)))+(((IkReal(-1.00000000000000))*(r11)*(x4755)*(x4756)))+(((IkReal(-1.00000000000000))*(r01)*(x4753)*(x4755)))));
14726 sj3array[0]=IKsin(j3array[0]);
14727 cj3array[0]=IKcos(j3array[0]);
14728 if( j3array[0] > IKPI )
14729 {
14730     j3array[0]-=IK2PI;
14731 }
14732 else if( j3array[0] < -IKPI )
14733 {    j3array[0]+=IK2PI;
14734 }
14735 j3valid[0] = true;
14736 for(int ij3 = 0; ij3 < 1; ++ij3)
14737 {
14738 if( !j3valid[ij3] )
14739 {
14740     continue;
14741 }
14742 _ij3[0] = ij3; _ij3[1] = -1;
14743 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
14744 {
14745 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
14746 {
14747     j3valid[iij3]=false; _ij3[1] = iij3; break; 
14748 }
14749 }
14750 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
14751 {
14752 IkReal evalcond[2];
14753 IkReal x4759=((cj0)*(cj5));
14754 IkReal x4760=((IkReal(1.00000000000000))*(cj0));
14755 IkReal x4761=((cj6)*(r11));
14756 IkReal x4762=((r10)*(sj6));
14757 IkReal x4763=((cj5)*(sj0));
14758 IkReal x4764=((r00)*(sj5)*(sj6));
14759 IkReal x4765=((cj6)*(r01)*(sj5));
14760 IkReal x4766=((IkReal(1.00000000000000))*(sj0)*(sj5));
14761 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x4763)))+(((sj0)*(x4765)))+(((r12)*(x4759)))+(((sj0)*(x4764)))+(((IkReal(-1.00000000000000))*(sj5)*(x4760)*(x4761)))+(IKsin(j3))+(((IkReal(-1.00000000000000))*(sj5)*(x4760)*(x4762))));
14762 evalcond[1]=((((IkReal(-1.00000000000000))*(x4760)*(x4765)))+(((IkReal(-1.00000000000000))*(x4761)*(x4766)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((r02)*(x4759)))+(((IkReal(-1.00000000000000))*(x4760)*(x4764)))+(((r12)*(x4763)))+(((IkReal(-1.00000000000000))*(x4762)*(x4766))));
14763 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
14764 {
14765 continue;
14766 }
14767 }
14768 
14769 {
14770 IkReal dummyeval[1];
14771 IkReal gconst33;
14772 IkReal x4767=(r21)*(r21);
14773 IkReal x4768=(cj5)*(cj5);
14774 IkReal x4769=(sj6)*(sj6);
14775 IkReal x4770=(cj6)*(cj6);
14776 IkReal x4771=(r20)*(r20);
14777 IkReal x4772=((cj6)*(r21));
14778 IkReal x4773=((IkReal(2.00000000000000))*(r20)*(sj6));
14779 IkReal x4774=((cj5)*(r22)*(sj5));
14780 IkReal x4775=((IkReal(1.00000000000000))*(x4769));
14781 IkReal x4776=((IkReal(1.00000000000000))*(x4770));
14782 gconst33=IKsign(((((IkReal(-1.00000000000000))*(x4771)*(x4776)))+(((IkReal(-1.00000000000000))*(x4767)*(x4775)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x4767)*(x4768)*(x4776)))+(((IkReal(-1.00000000000000))*(x4768)*(x4771)*(x4775)))+(((IkReal(-1.00000000000000))*(x4768)*(x4772)*(x4773)))+(((x4772)*(x4773)))+(((IkReal(-1.00000000000000))*(x4773)*(x4774)))+(((IkReal(-2.00000000000000))*(x4772)*(x4774)))));
14783 IkReal x4777=(r21)*(r21);
14784 IkReal x4778=(cj5)*(cj5);
14785 IkReal x4779=(sj6)*(sj6);
14786 IkReal x4780=(cj6)*(cj6);
14787 IkReal x4781=(r20)*(r20);
14788 IkReal x4782=((cj6)*(r21));
14789 IkReal x4783=((IkReal(2.00000000000000))*(r20)*(sj6));
14790 IkReal x4784=((cj5)*(r22)*(sj5));
14791 IkReal x4785=((IkReal(1.00000000000000))*(x4779));
14792 IkReal x4786=((IkReal(1.00000000000000))*(x4780));
14793 dummyeval[0]=((((IkReal(-1.00000000000000))*(x4777)*(x4785)))+(((IkReal(-1.00000000000000))*(x4783)*(x4784)))+(((IkReal(-1.00000000000000))*(x4778)*(x4782)*(x4783)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x4777)*(x4778)*(x4786)))+(((x4782)*(x4783)))+(((IkReal(-1.00000000000000))*(x4781)*(x4786)))+(((IkReal(-1.00000000000000))*(x4778)*(x4781)*(x4785)))+(((IkReal(-2.00000000000000))*(x4782)*(x4784))));
14794 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14795 {
14796 {
14797 IkReal dummyeval[1];
14798 IkReal gconst34;
14799 IkReal x4787=(cj6)*(cj6);
14800 IkReal x4788=(sj6)*(sj6);
14801 IkReal x4789=((IkReal(1.00000000000000))*(r01));
14802 IkReal x4790=((sj0)*(sj5));
14803 IkReal x4791=((cj6)*(r22));
14804 IkReal x4792=((r21)*(sj6));
14805 IkReal x4793=((r00)*(r21));
14806 IkReal x4794=((cj0)*(sj5));
14807 IkReal x4795=((cj6)*(r20));
14808 IkReal x4796=((r22)*(sj6));
14809 IkReal x4797=((cj0)*(cj5));
14810 IkReal x4798=((IkReal(1.00000000000000))*(r10));
14811 IkReal x4799=((cj5)*(sj0));
14812 IkReal x4800=((r20)*(x4788));
14813 IkReal x4801=((x4787)*(x4799));
14814 gconst34=IKsign(((((r02)*(x4790)*(x4792)))+(((IkReal(-1.00000000000000))*(r20)*(x4789)*(x4801)))+(((r12)*(x4794)*(x4795)))+(((r11)*(x4794)*(x4796)))+(((IkReal(-1.00000000000000))*(x4789)*(x4799)*(x4800)))+(((x4788)*(x4793)*(x4799)))+(((x4793)*(x4801)))+(((IkReal(-1.00000000000000))*(r21)*(x4787)*(x4797)*(x4798)))+(((r11)*(r20)*(x4787)*(x4797)))+(((IkReal(-1.00000000000000))*(r21)*(x4788)*(x4797)*(x4798)))+(((r00)*(x4790)*(x4791)))+(((IkReal(-1.00000000000000))*(r02)*(x4790)*(x4795)))+(((IkReal(-1.00000000000000))*(x4791)*(x4794)*(x4798)))+(((IkReal(-1.00000000000000))*(x4789)*(x4790)*(x4796)))+(((r11)*(x4797)*(x4800)))+(((IkReal(-1.00000000000000))*(r12)*(x4792)*(x4794)))));
14815 IkReal x4802=(cj6)*(cj6);
14816 IkReal x4803=(sj6)*(sj6);
14817 IkReal x4804=((IkReal(1.00000000000000))*(r01));
14818 IkReal x4805=((sj0)*(sj5));
14819 IkReal x4806=((cj6)*(r22));
14820 IkReal x4807=((r21)*(sj6));
14821 IkReal x4808=((r00)*(r21));
14822 IkReal x4809=((cj0)*(sj5));
14823 IkReal x4810=((cj6)*(r20));
14824 IkReal x4811=((r22)*(sj6));
14825 IkReal x4812=((cj0)*(cj5));
14826 IkReal x4813=((IkReal(1.00000000000000))*(r10));
14827 IkReal x4814=((cj5)*(sj0));
14828 IkReal x4815=((r20)*(x4803));
14829 IkReal x4816=((x4802)*(x4814));
14830 dummyeval[0]=((((r11)*(r20)*(x4802)*(x4812)))+(((IkReal(-1.00000000000000))*(r21)*(x4803)*(x4812)*(x4813)))+(((r12)*(x4809)*(x4810)))+(((IkReal(-1.00000000000000))*(x4804)*(x4805)*(x4811)))+(((IkReal(-1.00000000000000))*(r21)*(x4802)*(x4812)*(x4813)))+(((IkReal(-1.00000000000000))*(r20)*(x4804)*(x4816)))+(((x4803)*(x4808)*(x4814)))+(((IkReal(-1.00000000000000))*(x4806)*(x4809)*(x4813)))+(((IkReal(-1.00000000000000))*(r12)*(x4807)*(x4809)))+(((r00)*(x4805)*(x4806)))+(((r11)*(x4809)*(x4811)))+(((IkReal(-1.00000000000000))*(r02)*(x4805)*(x4810)))+(((x4808)*(x4816)))+(((r11)*(x4812)*(x4815)))+(((IkReal(-1.00000000000000))*(x4804)*(x4814)*(x4815)))+(((r02)*(x4805)*(x4807))));
14831 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14832 {
14833 continue;
14834 
14835 } else
14836 {
14837 {
14838 IkReal j4array[1], cj4array[1], sj4array[1];
14839 bool j4valid[1]={false};
14840 _nj4 = 1;
14841 IkReal x4817=((sj0)*(sj6));
14842 IkReal x4818=((cj0)*(r10));
14843 IkReal x4819=((IkReal(1.00000000000000))*(cj5));
14844 IkReal x4820=((cj6)*(sj0));
14845 IkReal x4821=((cj0)*(r11));
14846 if( IKabs(((gconst34)*(((((r01)*(x4817)))+(((IkReal(-1.00000000000000))*(r00)*(x4820)))+(((cj6)*(x4818)))+(((IkReal(-1.00000000000000))*(sj6)*(x4821))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((((IkReal(-1.00000000000000))*(r00)*(x4817)*(x4819)))+(((cj0)*(r12)*(sj5)))+(((cj5)*(cj6)*(x4821)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r01)*(x4819)*(x4820)))+(((cj5)*(sj6)*(x4818))))))) < IKFAST_ATAN2_MAGTHRESH )
14847     continue;
14848 j4array[0]=IKatan2(((gconst34)*(((((r01)*(x4817)))+(((IkReal(-1.00000000000000))*(r00)*(x4820)))+(((cj6)*(x4818)))+(((IkReal(-1.00000000000000))*(sj6)*(x4821)))))), ((gconst34)*(((((IkReal(-1.00000000000000))*(r00)*(x4817)*(x4819)))+(((cj0)*(r12)*(sj5)))+(((cj5)*(cj6)*(x4821)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r01)*(x4819)*(x4820)))+(((cj5)*(sj6)*(x4818)))))));
14849 sj4array[0]=IKsin(j4array[0]);
14850 cj4array[0]=IKcos(j4array[0]);
14851 if( j4array[0] > IKPI )
14852 {
14853     j4array[0]-=IK2PI;
14854 }
14855 else if( j4array[0] < -IKPI )
14856 {    j4array[0]+=IK2PI;
14857 }
14858 j4valid[0] = true;
14859 for(int ij4 = 0; ij4 < 1; ++ij4)
14860 {
14861 if( !j4valid[ij4] )
14862 {
14863     continue;
14864 }
14865 _ij4[0] = ij4; _ij4[1] = -1;
14866 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14867 {
14868 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14869 {
14870     j4valid[iij4]=false; _ij4[1] = iij4; break; 
14871 }
14872 }
14873 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14874 {
14875 IkReal evalcond[6];
14876 IkReal x4822=IKsin(j4);
14877 IkReal x4823=IKcos(j4);
14878 IkReal x4824=((r22)*(sj5));
14879 IkReal x4825=((IkReal(1.00000000000000))*(cj6));
14880 IkReal x4826=((IkReal(1.00000000000000))*(cj0));
14881 IkReal x4827=((cj5)*(r11));
14882 IkReal x4828=((cj5)*(cj6));
14883 IkReal x4829=((r11)*(sj6));
14884 IkReal x4830=((IkReal(1.00000000000000))*(sj6));
14885 IkReal x4831=((cj6)*(r00));
14886 IkReal x4832=((r12)*(sj5));
14887 IkReal x4833=((r02)*(sj5));
14888 IkReal x4834=((cj6)*(r10));
14889 IkReal x4835=((cj5)*(sj6));
14890 IkReal x4836=((cj5)*(r01));
14891 IkReal x4837=((sj0)*(x4822));
14892 IkReal x4838=((r00)*(x4835));
14893 IkReal x4839=((cj0)*(x4822));
14894 IkReal x4840=((sj0)*(x4823));
14895 IkReal x4841=((r20)*(x4823));
14896 IkReal x4842=((cj0)*(x4823));
14897 IkReal x4843=((r21)*(x4822));
14898 IkReal x4844=((r21)*(x4823));
14899 IkReal x4845=((r20)*(x4822));
14900 IkReal x4846=((x4823)*(x4832));
14901 IkReal x4847=((r01)*(sj6)*(x4823));
14902 IkReal x4848=((cj5)*(r10)*(x4830));
14903 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x4825)*(x4841)))+(((x4835)*(x4845)))+(((sj6)*(x4844)))+(((x4828)*(x4843)))+(((x4822)*(x4824))));
14904 evalcond[1]=((((x4828)*(x4844)))+(((x4835)*(x4841)))+(((cj6)*(x4845)))+(((IkReal(-1.00000000000000))*(x4830)*(x4843)))+(((x4823)*(x4824))));
14905 evalcond[2]=((((r01)*(x4828)*(x4837)))+(((IkReal(-1.00000000000000))*(r10)*(x4822)*(x4826)*(x4835)))+(((IkReal(-1.00000000000000))*(x4822)*(x4826)*(x4832)))+(((IkReal(-1.00000000000000))*(x4825)*(x4827)*(x4839)))+(((IkReal(-1.00000000000000))*(r00)*(x4825)*(x4840)))+(((x4833)*(x4837)))+(((x4837)*(x4838)))+(((IkReal(-1.00000000000000))*(x4823)*(x4826)*(x4829)))+(((r01)*(sj6)*(x4840)))+(((x4834)*(x4842))));
14906 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x4825)*(x4839)))+(((IkReal(-1.00000000000000))*(r01)*(x4830)*(x4837)))+(((IkReal(-1.00000000000000))*(x4825)*(x4827)*(x4842)))+(((x4838)*(x4840)))+(((x4829)*(x4839)))+(((IkReal(-1.00000000000000))*(r10)*(x4823)*(x4826)*(x4835)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x4831)*(x4837)))+(((r01)*(x4828)*(x4840)))+(((x4833)*(x4840)))+(((IkReal(-1.00000000000000))*(x4826)*(x4846))));
14907 evalcond[4]=((((IkReal(-1.00000000000000))*(x4837)*(x4848)))+(((x4831)*(x4842)))+(((IkReal(-1.00000000000000))*(x4822)*(x4826)*(x4838)))+(((IkReal(-1.00000000000000))*(x4822)*(x4826)*(x4833)))+(((IkReal(-1.00000000000000))*(x4829)*(x4840)))+(((x4834)*(x4840)))+(((IkReal(-1.00000000000000))*(x4825)*(x4827)*(x4837)))+(((IkReal(-1.00000000000000))*(x4826)*(x4847)))+(((IkReal(-1.00000000000000))*(x4825)*(x4836)*(x4839)))+(((IkReal(-1.00000000000000))*(x4832)*(x4837))));
14908 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x4825)*(x4837)))+(((r01)*(sj6)*(x4839)))+(((IkReal(-1.00000000000000))*(x4825)*(x4836)*(x4842)))+(((x4829)*(x4837)))+(((IkReal(-1.00000000000000))*(x4825)*(x4827)*(x4840)))+(((IkReal(-1.00000000000000))*(x4840)*(x4848)))+(((IkReal(-1.00000000000000))*(x4832)*(x4840)))+(((IkReal(-1.00000000000000))*(x4823)*(x4826)*(x4833)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r00)*(x4825)*(x4839)))+(((IkReal(-1.00000000000000))*(x4823)*(x4826)*(x4838))));
14909 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
14910 {
14911 continue;
14912 }
14913 }
14914 
14915 {
14916 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
14917 vinfos[0].jointtype = 1;
14918 vinfos[0].foffset = j0;
14919 vinfos[0].indices[0] = _ij0[0];
14920 vinfos[0].indices[1] = _ij0[1];
14921 vinfos[0].maxsolutions = _nj0;
14922 vinfos[1].jointtype = 1;
14923 vinfos[1].foffset = j1;
14924 vinfos[1].indices[0] = _ij1[0];
14925 vinfos[1].indices[1] = _ij1[1];
14926 vinfos[1].maxsolutions = _nj1;
14927 vinfos[2].jointtype = 1;
14928 vinfos[2].foffset = j2;
14929 vinfos[2].indices[0] = _ij2[0];
14930 vinfos[2].indices[1] = _ij2[1];
14931 vinfos[2].maxsolutions = _nj2;
14932 vinfos[3].jointtype = 1;
14933 vinfos[3].foffset = j3;
14934 vinfos[3].indices[0] = _ij3[0];
14935 vinfos[3].indices[1] = _ij3[1];
14936 vinfos[3].maxsolutions = _nj3;
14937 vinfos[4].jointtype = 1;
14938 vinfos[4].foffset = j4;
14939 vinfos[4].indices[0] = _ij4[0];
14940 vinfos[4].indices[1] = _ij4[1];
14941 vinfos[4].maxsolutions = _nj4;
14942 vinfos[5].jointtype = 1;
14943 vinfos[5].foffset = j5;
14944 vinfos[5].indices[0] = _ij5[0];
14945 vinfos[5].indices[1] = _ij5[1];
14946 vinfos[5].maxsolutions = _nj5;
14947 vinfos[6].jointtype = 1;
14948 vinfos[6].foffset = j6;
14949 vinfos[6].indices[0] = _ij6[0];
14950 vinfos[6].indices[1] = _ij6[1];
14951 vinfos[6].maxsolutions = _nj6;
14952 std::vector<int> vfree(0);
14953 solutions.AddSolution(vinfos,vfree);
14954 }
14955 }
14956 }
14957 
14958 }
14959 
14960 }
14961 
14962 } else
14963 {
14964 {
14965 IkReal j4array[1], cj4array[1], sj4array[1];
14966 bool j4valid[1]={false};
14967 _nj4 = 1;
14968 if( IKabs(((gconst33)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
14969     continue;
14970 j4array[0]=IKatan2(((gconst33)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst33)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
14971 sj4array[0]=IKsin(j4array[0]);
14972 cj4array[0]=IKcos(j4array[0]);
14973 if( j4array[0] > IKPI )
14974 {
14975     j4array[0]-=IK2PI;
14976 }
14977 else if( j4array[0] < -IKPI )
14978 {    j4array[0]+=IK2PI;
14979 }
14980 j4valid[0] = true;
14981 for(int ij4 = 0; ij4 < 1; ++ij4)
14982 {
14983 if( !j4valid[ij4] )
14984 {
14985     continue;
14986 }
14987 _ij4[0] = ij4; _ij4[1] = -1;
14988 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
14989 {
14990 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
14991 {
14992     j4valid[iij4]=false; _ij4[1] = iij4; break; 
14993 }
14994 }
14995 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
14996 {
14997 IkReal evalcond[6];
14998 IkReal x4849=IKsin(j4);
14999 IkReal x4850=IKcos(j4);
15000 IkReal x4851=((r22)*(sj5));
15001 IkReal x4852=((IkReal(1.00000000000000))*(cj6));
15002 IkReal x4853=((IkReal(1.00000000000000))*(cj0));
15003 IkReal x4854=((cj5)*(r11));
15004 IkReal x4855=((cj5)*(cj6));
15005 IkReal x4856=((r11)*(sj6));
15006 IkReal x4857=((IkReal(1.00000000000000))*(sj6));
15007 IkReal x4858=((cj6)*(r00));
15008 IkReal x4859=((r12)*(sj5));
15009 IkReal x4860=((r02)*(sj5));
15010 IkReal x4861=((cj6)*(r10));
15011 IkReal x4862=((cj5)*(sj6));
15012 IkReal x4863=((cj5)*(r01));
15013 IkReal x4864=((sj0)*(x4849));
15014 IkReal x4865=((r00)*(x4862));
15015 IkReal x4866=((cj0)*(x4849));
15016 IkReal x4867=((sj0)*(x4850));
15017 IkReal x4868=((r20)*(x4850));
15018 IkReal x4869=((cj0)*(x4850));
15019 IkReal x4870=((r21)*(x4849));
15020 IkReal x4871=((r21)*(x4850));
15021 IkReal x4872=((r20)*(x4849));
15022 IkReal x4873=((x4850)*(x4859));
15023 IkReal x4874=((r01)*(sj6)*(x4850));
15024 IkReal x4875=((cj5)*(r10)*(x4857));
15025 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x4852)*(x4868)))+(((sj6)*(x4871)))+(((x4849)*(x4851)))+(((x4855)*(x4870)))+(((x4862)*(x4872))));
15026 evalcond[1]=((((x4850)*(x4851)))+(((IkReal(-1.00000000000000))*(x4857)*(x4870)))+(((x4862)*(x4868)))+(((cj6)*(x4872)))+(((x4855)*(x4871))));
15027 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x4852)*(x4867)))+(((IkReal(-1.00000000000000))*(x4852)*(x4854)*(x4866)))+(((x4861)*(x4869)))+(((x4864)*(x4865)))+(((IkReal(-1.00000000000000))*(r10)*(x4849)*(x4853)*(x4862)))+(((IkReal(-1.00000000000000))*(x4849)*(x4853)*(x4859)))+(((IkReal(-1.00000000000000))*(x4850)*(x4853)*(x4856)))+(((x4860)*(x4864)))+(((r01)*(x4855)*(x4864)))+(((r01)*(sj6)*(x4867))));
15028 evalcond[3]=((((x4858)*(x4864)))+(((IkReal(-1.00000000000000))*(r10)*(x4852)*(x4866)))+(((x4856)*(x4866)))+(((IkReal(-1.00000000000000))*(r10)*(x4850)*(x4853)*(x4862)))+(((r01)*(x4855)*(x4867)))+(((IkReal(-1.00000000000000))*(r01)*(x4857)*(x4864)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x4853)*(x4873)))+(((x4865)*(x4867)))+(((IkReal(-1.00000000000000))*(x4852)*(x4854)*(x4869)))+(((x4860)*(x4867))));
15029 evalcond[4]=((((x4858)*(x4869)))+(((IkReal(-1.00000000000000))*(x4849)*(x4853)*(x4865)))+(((IkReal(-1.00000000000000))*(x4864)*(x4875)))+(((IkReal(-1.00000000000000))*(x4852)*(x4863)*(x4866)))+(((IkReal(-1.00000000000000))*(x4859)*(x4864)))+(((IkReal(-1.00000000000000))*(x4853)*(x4874)))+(((IkReal(-1.00000000000000))*(x4849)*(x4853)*(x4860)))+(((IkReal(-1.00000000000000))*(x4856)*(x4867)))+(((x4861)*(x4867)))+(((IkReal(-1.00000000000000))*(x4852)*(x4854)*(x4864))));
15030 evalcond[5]=((((IkReal(-1.00000000000000))*(x4850)*(x4853)*(x4860)))+(((IkReal(-1.00000000000000))*(r00)*(x4852)*(x4866)))+(((x4856)*(x4864)))+(((IkReal(-1.00000000000000))*(x4852)*(x4854)*(x4867)))+(((r01)*(sj6)*(x4866)))+(((IkReal(-1.00000000000000))*(x4852)*(x4863)*(x4869)))+(((IkReal(-1.00000000000000))*(x4867)*(x4875)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r10)*(x4852)*(x4864)))+(((IkReal(-1.00000000000000))*(x4859)*(x4867)))+(((IkReal(-1.00000000000000))*(x4850)*(x4853)*(x4865))));
15031 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
15032 {
15033 continue;
15034 }
15035 }
15036 
15037 {
15038 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
15039 vinfos[0].jointtype = 1;
15040 vinfos[0].foffset = j0;
15041 vinfos[0].indices[0] = _ij0[0];
15042 vinfos[0].indices[1] = _ij0[1];
15043 vinfos[0].maxsolutions = _nj0;
15044 vinfos[1].jointtype = 1;
15045 vinfos[1].foffset = j1;
15046 vinfos[1].indices[0] = _ij1[0];
15047 vinfos[1].indices[1] = _ij1[1];
15048 vinfos[1].maxsolutions = _nj1;
15049 vinfos[2].jointtype = 1;
15050 vinfos[2].foffset = j2;
15051 vinfos[2].indices[0] = _ij2[0];
15052 vinfos[2].indices[1] = _ij2[1];
15053 vinfos[2].maxsolutions = _nj2;
15054 vinfos[3].jointtype = 1;
15055 vinfos[3].foffset = j3;
15056 vinfos[3].indices[0] = _ij3[0];
15057 vinfos[3].indices[1] = _ij3[1];
15058 vinfos[3].maxsolutions = _nj3;
15059 vinfos[4].jointtype = 1;
15060 vinfos[4].foffset = j4;
15061 vinfos[4].indices[0] = _ij4[0];
15062 vinfos[4].indices[1] = _ij4[1];
15063 vinfos[4].maxsolutions = _nj4;
15064 vinfos[5].jointtype = 1;
15065 vinfos[5].foffset = j5;
15066 vinfos[5].indices[0] = _ij5[0];
15067 vinfos[5].indices[1] = _ij5[1];
15068 vinfos[5].maxsolutions = _nj5;
15069 vinfos[6].jointtype = 1;
15070 vinfos[6].foffset = j6;
15071 vinfos[6].indices[0] = _ij6[0];
15072 vinfos[6].indices[1] = _ij6[1];
15073 vinfos[6].maxsolutions = _nj6;
15074 std::vector<int> vfree(0);
15075 solutions.AddSolution(vinfos,vfree);
15076 }
15077 }
15078 }
15079 
15080 }
15081 
15082 }
15083 }
15084 }
15085 
15086 } else
15087 {
15088 IkReal x4876=((cj5)*(r22));
15089 IkReal x4877=((IkReal(0.374290000000000))*(sj5));
15090 IkReal x4878=((cj0)*(sj6));
15091 IkReal x4879=((cj6)*(r21));
15092 IkReal x4880=((IkReal(0.0100000000000000))*(sj5));
15093 IkReal x4881=((cj0)*(r02));
15094 IkReal x4882=((IkReal(0.0100000000000000))*(cj5));
15095 IkReal x4883=((IkReal(1.00000000000000))*(py));
15096 IkReal x4884=((r01)*(sj0));
15097 IkReal x4885=((r20)*(sj6));
15098 IkReal x4886=((r11)*(sj0));
15099 IkReal x4887=((IkReal(0.374290000000000))*(cj5));
15100 IkReal x4888=((cj0)*(r12));
15101 IkReal x4889=((sj0)*(x4887));
15102 IkReal x4890=((cj6)*(x4882));
15103 IkReal x4891=((r10)*(sj0)*(sj6));
15104 IkReal x4892=((r00)*(sj0)*(sj6));
15105 IkReal x4893=((cj0)*(cj6)*(x4877));
15106 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
15107 evalcond[1]=((((IkReal(-1.00000000000000))*(x4876)))+(((sj5)*(x4879)))+(((sj5)*(x4885))));
15108 evalcond[2]=((((IkReal(-1.00000000000000))*(x4879)*(x4882)))+(((IkReal(-0.374290000000000))*(x4876)))+(((x4877)*(x4879)))+(((IkReal(-1.00000000000000))*(r22)*(x4880)))+(((IkReal(-1.00000000000000))*(x4882)*(x4885)))+(pz)+(((x4877)*(x4885))));
15109 evalcond[3]=((IkReal(-0.0690000000000000))+(((cj0)*(r11)*(x4890)))+(((x4880)*(x4888)))+(((IkReal(-1.00000000000000))*(x4884)*(x4890)))+(((x4877)*(x4892)))+(((r10)*(x4878)*(x4882)))+(((IkReal(-1.00000000000000))*(r10)*(x4877)*(x4878)))+(((IkReal(-1.00000000000000))*(r02)*(x4889)))+(((cj6)*(x4877)*(x4884)))+(((x4887)*(x4888)))+(((IkReal(-1.00000000000000))*(x4882)*(x4892)))+(((IkReal(-1.00000000000000))*(cj0)*(x4883)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x4880)))+(((IkReal(-1.00000000000000))*(r11)*(x4893))));
15110 evalcond[4]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((cj0)*(r01)*(x4890)))+(((IkReal(-1.00000000000000))*(r00)*(x4877)*(x4878)))+(((r12)*(x4889)))+(((IkReal(-1.00000000000000))*(cj6)*(x4877)*(x4886)))+(((x4882)*(x4891)))+(((r12)*(sj0)*(x4880)))+(((IkReal(-1.00000000000000))*(x4877)*(x4891)))+(((x4881)*(x4887)))+(((IkReal(-1.00000000000000))*(sj0)*(x4883)))+(((r00)*(x4878)*(x4882)))+(((x4880)*(x4881)))+(((IkReal(-1.00000000000000))*(r01)*(x4893)))+(((x4886)*(x4890))));
15111 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
15112 {
15113 {
15114 IkReal j3array[1], cj3array[1], sj3array[1];
15115 bool j3valid[1]={false};
15116 _nj3 = 1;
15117 IkReal x4894=((IkReal(1.00000000000000))*(cj5));
15118 IkReal x4895=((r10)*(sj5)*(sj6));
15119 IkReal x4896=((cj6)*(sj0)*(sj5));
15120 IkReal x4897=((r00)*(sj5)*(sj6));
15121 IkReal x4898=((cj0)*(cj6)*(sj5));
15122 if( IKabs(((((r11)*(x4898)))+(((cj0)*(x4895)))+(((IkReal(-1.00000000000000))*(sj0)*(x4897)))+(((IkReal(-1.00000000000000))*(r01)*(x4896)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x4894)))+(((cj5)*(r02)*(sj0))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r01)*(x4898)))+(((cj0)*(x4897)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4894)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4894)))+(((r11)*(x4896)))+(((sj0)*(x4895))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r11)*(x4898)))+(((cj0)*(x4895)))+(((IkReal(-1.00000000000000))*(sj0)*(x4897)))+(((IkReal(-1.00000000000000))*(r01)*(x4896)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x4894)))+(((cj5)*(r02)*(sj0)))))+IKsqr(((((r01)*(x4898)))+(((cj0)*(x4897)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4894)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4894)))+(((r11)*(x4896)))+(((sj0)*(x4895)))))-1) <= IKFAST_SINCOS_THRESH )
15123     continue;
15124 j3array[0]=IKatan2(((((r11)*(x4898)))+(((cj0)*(x4895)))+(((IkReal(-1.00000000000000))*(sj0)*(x4897)))+(((IkReal(-1.00000000000000))*(r01)*(x4896)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x4894)))+(((cj5)*(r02)*(sj0)))), ((((r01)*(x4898)))+(((cj0)*(x4897)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x4894)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x4894)))+(((r11)*(x4896)))+(((sj0)*(x4895)))));
15125 sj3array[0]=IKsin(j3array[0]);
15126 cj3array[0]=IKcos(j3array[0]);
15127 if( j3array[0] > IKPI )
15128 {
15129     j3array[0]-=IK2PI;
15130 }
15131 else if( j3array[0] < -IKPI )
15132 {    j3array[0]+=IK2PI;
15133 }
15134 j3valid[0] = true;
15135 for(int ij3 = 0; ij3 < 1; ++ij3)
15136 {
15137 if( !j3valid[ij3] )
15138 {
15139     continue;
15140 }
15141 _ij3[0] = ij3; _ij3[1] = -1;
15142 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15143 {
15144 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15145 {
15146     j3valid[iij3]=false; _ij3[1] = iij3; break; 
15147 }
15148 }
15149 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15150 {
15151 IkReal evalcond[2];
15152 IkReal x4899=((cj0)*(cj5));
15153 IkReal x4900=((IkReal(1.00000000000000))*(cj0));
15154 IkReal x4901=((cj6)*(r11));
15155 IkReal x4902=((r10)*(sj6));
15156 IkReal x4903=((cj5)*(sj0));
15157 IkReal x4904=((r00)*(sj5)*(sj6));
15158 IkReal x4905=((cj6)*(r01)*(sj5));
15159 IkReal x4906=((IkReal(1.00000000000000))*(sj0)*(sj5));
15160 evalcond[0]=((((sj0)*(x4904)))+(((r12)*(x4899)))+(IKsin(j3))+(((IkReal(-1.00000000000000))*(sj5)*(x4900)*(x4901)))+(((IkReal(-1.00000000000000))*(sj5)*(x4900)*(x4902)))+(((sj0)*(x4905)))+(((IkReal(-1.00000000000000))*(r02)*(x4903))));
15161 evalcond[1]=((((r02)*(x4899)))+(((IkReal(-1.00000000000000))*(x4902)*(x4906)))+(((IkReal(-1.00000000000000))*(x4900)*(x4905)))+(((IkReal(-1.00000000000000))*(x4900)*(x4904)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x4901)*(x4906)))+(((r12)*(x4903))));
15162 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
15163 {
15164 continue;
15165 }
15166 }
15167 
15168 {
15169 IkReal dummyeval[1];
15170 IkReal gconst37;
15171 IkReal x4907=(cj5)*(cj5);
15172 IkReal x4908=(r20)*(r20);
15173 IkReal x4909=(sj6)*(sj6);
15174 IkReal x4910=(cj6)*(cj6);
15175 IkReal x4911=(r21)*(r21);
15176 IkReal x4912=((cj6)*(r21));
15177 IkReal x4913=((IkReal(2.00000000000000))*(r20)*(sj6));
15178 IkReal x4914=((cj5)*(r22)*(sj5));
15179 gconst37=IKsign(((((x4907)*(x4910)*(x4911)))+(((x4907)*(x4908)*(x4909)))+(((x4913)*(x4914)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x4907)*(x4912)*(x4913)))+(((IkReal(-1.00000000000000))*(x4912)*(x4913)))+(((IkReal(2.00000000000000))*(x4912)*(x4914)))+(((x4908)*(x4910)))+(((x4909)*(x4911)))));
15180 IkReal x4915=(cj5)*(cj5);
15181 IkReal x4916=(r20)*(r20);
15182 IkReal x4917=(sj6)*(sj6);
15183 IkReal x4918=(cj6)*(cj6);
15184 IkReal x4919=(r21)*(r21);
15185 IkReal x4920=((cj6)*(r21));
15186 IkReal x4921=((IkReal(2.00000000000000))*(r20)*(sj6));
15187 IkReal x4922=((cj5)*(r22)*(sj5));
15188 dummyeval[0]=((((IkReal(2.00000000000000))*(x4920)*(x4922)))+(((x4915)*(x4916)*(x4917)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x4917)*(x4919)))+(((IkReal(-1.00000000000000))*(x4920)*(x4921)))+(((x4915)*(x4920)*(x4921)))+(((x4921)*(x4922)))+(((x4915)*(x4918)*(x4919)))+(((x4916)*(x4918))));
15189 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15190 {
15191 {
15192 IkReal dummyeval[1];
15193 IkReal gconst38;
15194 IkReal x4923=(cj6)*(cj6);
15195 IkReal x4924=(sj6)*(sj6);
15196 IkReal x4925=((IkReal(1.00000000000000))*(r21));
15197 IkReal x4926=((cj6)*(r20));
15198 IkReal x4927=((r22)*(sj5));
15199 IkReal x4928=((r01)*(sj0));
15200 IkReal x4929=((r00)*(sj0));
15201 IkReal x4930=((cj0)*(r10));
15202 IkReal x4931=((r02)*(sj0)*(sj5));
15203 IkReal x4932=((cj5)*(x4923));
15204 IkReal x4933=((cj0)*(r12)*(sj5));
15205 IkReal x4934=((IkReal(1.00000000000000))*(cj0)*(r11));
15206 IkReal x4935=((cj5)*(x4924));
15207 IkReal x4936=((r20)*(x4935));
15208 gconst38=IKsign(((((x4928)*(x4936)))+(((IkReal(-1.00000000000000))*(cj6)*(x4927)*(x4929)))+(((IkReal(-1.00000000000000))*(sj6)*(x4927)*(x4934)))+(((IkReal(-1.00000000000000))*(sj6)*(x4925)*(x4931)))+(((r21)*(sj6)*(x4933)))+(((r21)*(x4930)*(x4935)))+(((IkReal(-1.00000000000000))*(x4925)*(x4929)*(x4935)))+(((x4926)*(x4931)))+(((IkReal(-1.00000000000000))*(r20)*(x4932)*(x4934)))+(((IkReal(-1.00000000000000))*(x4925)*(x4929)*(x4932)))+(((IkReal(-1.00000000000000))*(x4926)*(x4933)))+(((r21)*(x4930)*(x4932)))+(((IkReal(-1.00000000000000))*(x4934)*(x4936)))+(((r20)*(x4928)*(x4932)))+(((cj6)*(x4927)*(x4930)))+(((sj6)*(x4927)*(x4928)))));
15209 IkReal x4937=(cj6)*(cj6);
15210 IkReal x4938=(sj6)*(sj6);
15211 IkReal x4939=((IkReal(1.00000000000000))*(r21));
15212 IkReal x4940=((cj6)*(r20));
15213 IkReal x4941=((r22)*(sj5));
15214 IkReal x4942=((r01)*(sj0));
15215 IkReal x4943=((r00)*(sj0));
15216 IkReal x4944=((cj0)*(r10));
15217 IkReal x4945=((r02)*(sj0)*(sj5));
15218 IkReal x4946=((cj5)*(x4937));
15219 IkReal x4947=((cj0)*(r12)*(sj5));
15220 IkReal x4948=((IkReal(1.00000000000000))*(cj0)*(r11));
15221 IkReal x4949=((cj5)*(x4938));
15222 IkReal x4950=((r20)*(x4949));
15223 dummyeval[0]=((((IkReal(-1.00000000000000))*(x4939)*(x4943)*(x4946)))+(((r21)*(x4944)*(x4949)))+(((r21)*(x4944)*(x4946)))+(((r20)*(x4942)*(x4946)))+(((IkReal(-1.00000000000000))*(cj6)*(x4941)*(x4943)))+(((sj6)*(x4941)*(x4942)))+(((IkReal(-1.00000000000000))*(sj6)*(x4939)*(x4945)))+(((x4940)*(x4945)))+(((IkReal(-1.00000000000000))*(x4940)*(x4947)))+(((IkReal(-1.00000000000000))*(x4948)*(x4950)))+(((IkReal(-1.00000000000000))*(x4939)*(x4943)*(x4949)))+(((IkReal(-1.00000000000000))*(sj6)*(x4941)*(x4948)))+(((x4942)*(x4950)))+(((cj6)*(x4941)*(x4944)))+(((r21)*(sj6)*(x4947)))+(((IkReal(-1.00000000000000))*(r20)*(x4946)*(x4948))));
15224 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15225 {
15226 continue;
15227 
15228 } else
15229 {
15230 {
15231 IkReal j4array[1], cj4array[1], sj4array[1];
15232 bool j4valid[1]={false};
15233 _nj4 = 1;
15234 IkReal x4951=((sj0)*(sj6));
15235 IkReal x4952=((cj0)*(r10));
15236 IkReal x4953=((IkReal(1.00000000000000))*(cj5));
15237 IkReal x4954=((cj6)*(sj0));
15238 IkReal x4955=((cj0)*(r11));
15239 if( IKabs(((gconst38)*(((((cj6)*(x4952)))+(((r01)*(x4951)))+(((IkReal(-1.00000000000000))*(r00)*(x4954)))+(((IkReal(-1.00000000000000))*(sj6)*(x4955))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((cj5)*(sj6)*(x4952)))+(((IkReal(-1.00000000000000))*(r01)*(x4953)*(x4954)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x4951)*(x4953)))+(((cj5)*(cj6)*(x4955))))))) < IKFAST_ATAN2_MAGTHRESH )
15240     continue;
15241 j4array[0]=IKatan2(((gconst38)*(((((cj6)*(x4952)))+(((r01)*(x4951)))+(((IkReal(-1.00000000000000))*(r00)*(x4954)))+(((IkReal(-1.00000000000000))*(sj6)*(x4955)))))), ((gconst38)*(((((cj5)*(sj6)*(x4952)))+(((IkReal(-1.00000000000000))*(r01)*(x4953)*(x4954)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r00)*(x4951)*(x4953)))+(((cj5)*(cj6)*(x4955)))))));
15242 sj4array[0]=IKsin(j4array[0]);
15243 cj4array[0]=IKcos(j4array[0]);
15244 if( j4array[0] > IKPI )
15245 {
15246     j4array[0]-=IK2PI;
15247 }
15248 else if( j4array[0] < -IKPI )
15249 {    j4array[0]+=IK2PI;
15250 }
15251 j4valid[0] = true;
15252 for(int ij4 = 0; ij4 < 1; ++ij4)
15253 {
15254 if( !j4valid[ij4] )
15255 {
15256     continue;
15257 }
15258 _ij4[0] = ij4; _ij4[1] = -1;
15259 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15260 {
15261 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15262 {
15263     j4valid[iij4]=false; _ij4[1] = iij4; break; 
15264 }
15265 }
15266 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15267 {
15268 IkReal evalcond[6];
15269 IkReal x4956=IKsin(j4);
15270 IkReal x4957=IKcos(j4);
15271 IkReal x4958=((r22)*(sj5));
15272 IkReal x4959=((IkReal(1.00000000000000))*(cj6));
15273 IkReal x4960=((IkReal(1.00000000000000))*(cj0));
15274 IkReal x4961=((cj5)*(r11));
15275 IkReal x4962=((cj5)*(cj6));
15276 IkReal x4963=((r11)*(sj6));
15277 IkReal x4964=((IkReal(1.00000000000000))*(sj6));
15278 IkReal x4965=((cj6)*(r00));
15279 IkReal x4966=((r12)*(sj5));
15280 IkReal x4967=((r02)*(sj5));
15281 IkReal x4968=((cj6)*(r10));
15282 IkReal x4969=((cj5)*(sj6));
15283 IkReal x4970=((cj5)*(r01));
15284 IkReal x4971=((sj0)*(x4956));
15285 IkReal x4972=((r00)*(x4969));
15286 IkReal x4973=((cj0)*(x4956));
15287 IkReal x4974=((sj0)*(x4957));
15288 IkReal x4975=((r20)*(x4957));
15289 IkReal x4976=((cj0)*(x4957));
15290 IkReal x4977=((r21)*(x4956));
15291 IkReal x4978=((r21)*(x4957));
15292 IkReal x4979=((r20)*(x4956));
15293 IkReal x4980=((x4957)*(x4966));
15294 IkReal x4981=((r01)*(sj6)*(x4957));
15295 IkReal x4982=((cj5)*(r10)*(x4964));
15296 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x4959)*(x4975)))+(((x4969)*(x4979)))+(((sj6)*(x4978)))+(((x4956)*(x4958)))+(((x4962)*(x4977))));
15297 evalcond[1]=((((x4969)*(x4975)))+(((IkReal(-1.00000000000000))*(x4964)*(x4977)))+(((x4962)*(x4978)))+(((x4957)*(x4958)))+(((cj6)*(x4979))));
15298 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4956)*(x4960)*(x4969)))+(((x4967)*(x4971)))+(((IkReal(-1.00000000000000))*(x4956)*(x4960)*(x4966)))+(((IkReal(-1.00000000000000))*(x4957)*(x4960)*(x4963)))+(((r01)*(x4962)*(x4971)))+(((r01)*(sj6)*(x4974)))+(((x4971)*(x4972)))+(((IkReal(-1.00000000000000))*(r00)*(x4959)*(x4974)))+(((x4968)*(x4976)))+(((IkReal(-1.00000000000000))*(x4959)*(x4961)*(x4973))));
15299 evalcond[3]=((((r01)*(x4962)*(x4974)))+(((x4965)*(x4971)))+(((IkReal(-1.00000000000000))*(r10)*(x4959)*(x4973)))+(((x4963)*(x4973)))+(((IkReal(-1.00000000000000))*(r01)*(x4964)*(x4971)))+(((IkReal(-1.00000000000000))*(r10)*(x4957)*(x4960)*(x4969)))+(((IkReal(-1.00000000000000))*(x4959)*(x4961)*(x4976)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x4972)*(x4974)))+(((x4967)*(x4974)))+(((IkReal(-1.00000000000000))*(x4960)*(x4980))));
15300 evalcond[4]=((((x4968)*(x4974)))+(((IkReal(-1.00000000000000))*(x4956)*(x4960)*(x4967)))+(((IkReal(-1.00000000000000))*(x4959)*(x4970)*(x4973)))+(((IkReal(-1.00000000000000))*(x4956)*(x4960)*(x4972)))+(((IkReal(-1.00000000000000))*(x4960)*(x4981)))+(((IkReal(-1.00000000000000))*(x4963)*(x4974)))+(((IkReal(-1.00000000000000))*(x4959)*(x4961)*(x4971)))+(((IkReal(-1.00000000000000))*(x4966)*(x4971)))+(((x4965)*(x4976)))+(((IkReal(-1.00000000000000))*(x4971)*(x4982))));
15301 evalcond[5]=((((IkReal(-1.00000000000000))*(x4959)*(x4970)*(x4976)))+(sj3)+(((IkReal(-1.00000000000000))*(r00)*(x4959)*(x4973)))+(((IkReal(-1.00000000000000))*(x4959)*(x4961)*(x4974)))+(((r01)*(sj6)*(x4973)))+(((IkReal(-1.00000000000000))*(x4966)*(x4974)))+(((x4963)*(x4971)))+(((IkReal(-1.00000000000000))*(x4957)*(x4960)*(x4972)))+(((IkReal(-1.00000000000000))*(r10)*(x4959)*(x4971)))+(((IkReal(-1.00000000000000))*(x4974)*(x4982)))+(((IkReal(-1.00000000000000))*(x4957)*(x4960)*(x4967))));
15302 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
15303 {
15304 continue;
15305 }
15306 }
15307 
15308 {
15309 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
15310 vinfos[0].jointtype = 1;
15311 vinfos[0].foffset = j0;
15312 vinfos[0].indices[0] = _ij0[0];
15313 vinfos[0].indices[1] = _ij0[1];
15314 vinfos[0].maxsolutions = _nj0;
15315 vinfos[1].jointtype = 1;
15316 vinfos[1].foffset = j1;
15317 vinfos[1].indices[0] = _ij1[0];
15318 vinfos[1].indices[1] = _ij1[1];
15319 vinfos[1].maxsolutions = _nj1;
15320 vinfos[2].jointtype = 1;
15321 vinfos[2].foffset = j2;
15322 vinfos[2].indices[0] = _ij2[0];
15323 vinfos[2].indices[1] = _ij2[1];
15324 vinfos[2].maxsolutions = _nj2;
15325 vinfos[3].jointtype = 1;
15326 vinfos[3].foffset = j3;
15327 vinfos[3].indices[0] = _ij3[0];
15328 vinfos[3].indices[1] = _ij3[1];
15329 vinfos[3].maxsolutions = _nj3;
15330 vinfos[4].jointtype = 1;
15331 vinfos[4].foffset = j4;
15332 vinfos[4].indices[0] = _ij4[0];
15333 vinfos[4].indices[1] = _ij4[1];
15334 vinfos[4].maxsolutions = _nj4;
15335 vinfos[5].jointtype = 1;
15336 vinfos[5].foffset = j5;
15337 vinfos[5].indices[0] = _ij5[0];
15338 vinfos[5].indices[1] = _ij5[1];
15339 vinfos[5].maxsolutions = _nj5;
15340 vinfos[6].jointtype = 1;
15341 vinfos[6].foffset = j6;
15342 vinfos[6].indices[0] = _ij6[0];
15343 vinfos[6].indices[1] = _ij6[1];
15344 vinfos[6].maxsolutions = _nj6;
15345 std::vector<int> vfree(0);
15346 solutions.AddSolution(vinfos,vfree);
15347 }
15348 }
15349 }
15350 
15351 }
15352 
15353 }
15354 
15355 } else
15356 {
15357 {
15358 IkReal j4array[1], cj4array[1], sj4array[1];
15359 bool j4valid[1]={false};
15360 _nj4 = 1;
15361 if( IKabs(((gconst37)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
15362     continue;
15363 j4array[0]=IKatan2(((gconst37)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst37)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
15364 sj4array[0]=IKsin(j4array[0]);
15365 cj4array[0]=IKcos(j4array[0]);
15366 if( j4array[0] > IKPI )
15367 {
15368     j4array[0]-=IK2PI;
15369 }
15370 else if( j4array[0] < -IKPI )
15371 {    j4array[0]+=IK2PI;
15372 }
15373 j4valid[0] = true;
15374 for(int ij4 = 0; ij4 < 1; ++ij4)
15375 {
15376 if( !j4valid[ij4] )
15377 {
15378     continue;
15379 }
15380 _ij4[0] = ij4; _ij4[1] = -1;
15381 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15382 {
15383 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15384 {
15385     j4valid[iij4]=false; _ij4[1] = iij4; break; 
15386 }
15387 }
15388 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15389 {
15390 IkReal evalcond[6];
15391 IkReal x4983=IKsin(j4);
15392 IkReal x4984=IKcos(j4);
15393 IkReal x4985=((r22)*(sj5));
15394 IkReal x4986=((IkReal(1.00000000000000))*(cj6));
15395 IkReal x4987=((IkReal(1.00000000000000))*(cj0));
15396 IkReal x4988=((cj5)*(r11));
15397 IkReal x4989=((cj5)*(cj6));
15398 IkReal x4990=((r11)*(sj6));
15399 IkReal x4991=((IkReal(1.00000000000000))*(sj6));
15400 IkReal x4992=((cj6)*(r00));
15401 IkReal x4993=((r12)*(sj5));
15402 IkReal x4994=((r02)*(sj5));
15403 IkReal x4995=((cj6)*(r10));
15404 IkReal x4996=((cj5)*(sj6));
15405 IkReal x4997=((cj5)*(r01));
15406 IkReal x4998=((sj0)*(x4983));
15407 IkReal x4999=((r00)*(x4996));
15408 IkReal x5000=((cj0)*(x4983));
15409 IkReal x5001=((sj0)*(x4984));
15410 IkReal x5002=((r20)*(x4984));
15411 IkReal x5003=((cj0)*(x4984));
15412 IkReal x5004=((r21)*(x4983));
15413 IkReal x5005=((r21)*(x4984));
15414 IkReal x5006=((r20)*(x4983));
15415 IkReal x5007=((x4984)*(x4993));
15416 IkReal x5008=((r01)*(sj6)*(x4984));
15417 IkReal x5009=((cj5)*(r10)*(x4991));
15418 evalcond[0]=((IkReal(-1.00000000000000))+(((sj6)*(x5005)))+(((x4996)*(x5006)))+(((x4983)*(x4985)))+(((x4989)*(x5004)))+(((IkReal(-1.00000000000000))*(x4986)*(x5002))));
15419 evalcond[1]=((((x4989)*(x5005)))+(((x4984)*(x4985)))+(((IkReal(-1.00000000000000))*(x4991)*(x5004)))+(((cj6)*(x5006)))+(((x4996)*(x5002))));
15420 evalcond[2]=((((r01)*(x4989)*(x4998)))+(((IkReal(-1.00000000000000))*(x4986)*(x4988)*(x5000)))+(((x4994)*(x4998)))+(((x4998)*(x4999)))+(((IkReal(-1.00000000000000))*(r10)*(x4983)*(x4987)*(x4996)))+(((IkReal(-1.00000000000000))*(x4984)*(x4987)*(x4990)))+(((IkReal(-1.00000000000000))*(x4983)*(x4987)*(x4993)))+(((x4995)*(x5003)))+(((IkReal(-1.00000000000000))*(r00)*(x4986)*(x5001)))+(((r01)*(sj6)*(x5001))));
15421 evalcond[3]=((((x4994)*(x5001)))+(((IkReal(-1.00000000000000))*(r10)*(x4986)*(x5000)))+(((IkReal(-1.00000000000000))*(r10)*(x4984)*(x4987)*(x4996)))+(((IkReal(-1.00000000000000))*(x4987)*(x5007)))+(((x4990)*(x5000)))+(((r01)*(x4989)*(x5001)))+(((IkReal(-1.00000000000000))*(r01)*(x4991)*(x4998)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x4986)*(x4988)*(x5003)))+(((x4999)*(x5001)))+(((x4992)*(x4998))));
15422 evalcond[4]=((((IkReal(-1.00000000000000))*(x4993)*(x4998)))+(((IkReal(-1.00000000000000))*(x4983)*(x4987)*(x4999)))+(((IkReal(-1.00000000000000))*(x4987)*(x5008)))+(((IkReal(-1.00000000000000))*(x4986)*(x4988)*(x4998)))+(((IkReal(-1.00000000000000))*(x4990)*(x5001)))+(((IkReal(-1.00000000000000))*(x4983)*(x4987)*(x4994)))+(((x4992)*(x5003)))+(((IkReal(-1.00000000000000))*(x4998)*(x5009)))+(((x4995)*(x5001)))+(((IkReal(-1.00000000000000))*(x4986)*(x4997)*(x5000))));
15423 evalcond[5]=((((IkReal(-1.00000000000000))*(x4984)*(x4987)*(x4999)))+(sj3)+(((IkReal(-1.00000000000000))*(x5001)*(x5009)))+(((r01)*(sj6)*(x5000)))+(((IkReal(-1.00000000000000))*(x4993)*(x5001)))+(((IkReal(-1.00000000000000))*(x4986)*(x4997)*(x5003)))+(((IkReal(-1.00000000000000))*(x4984)*(x4987)*(x4994)))+(((IkReal(-1.00000000000000))*(x4986)*(x4988)*(x5001)))+(((IkReal(-1.00000000000000))*(r10)*(x4986)*(x4998)))+(((x4990)*(x4998)))+(((IkReal(-1.00000000000000))*(r00)*(x4986)*(x5000))));
15424 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
15425 {
15426 continue;
15427 }
15428 }
15429 
15430 {
15431 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
15432 vinfos[0].jointtype = 1;
15433 vinfos[0].foffset = j0;
15434 vinfos[0].indices[0] = _ij0[0];
15435 vinfos[0].indices[1] = _ij0[1];
15436 vinfos[0].maxsolutions = _nj0;
15437 vinfos[1].jointtype = 1;
15438 vinfos[1].foffset = j1;
15439 vinfos[1].indices[0] = _ij1[0];
15440 vinfos[1].indices[1] = _ij1[1];
15441 vinfos[1].maxsolutions = _nj1;
15442 vinfos[2].jointtype = 1;
15443 vinfos[2].foffset = j2;
15444 vinfos[2].indices[0] = _ij2[0];
15445 vinfos[2].indices[1] = _ij2[1];
15446 vinfos[2].maxsolutions = _nj2;
15447 vinfos[3].jointtype = 1;
15448 vinfos[3].foffset = j3;
15449 vinfos[3].indices[0] = _ij3[0];
15450 vinfos[3].indices[1] = _ij3[1];
15451 vinfos[3].maxsolutions = _nj3;
15452 vinfos[4].jointtype = 1;
15453 vinfos[4].foffset = j4;
15454 vinfos[4].indices[0] = _ij4[0];
15455 vinfos[4].indices[1] = _ij4[1];
15456 vinfos[4].maxsolutions = _nj4;
15457 vinfos[5].jointtype = 1;
15458 vinfos[5].foffset = j5;
15459 vinfos[5].indices[0] = _ij5[0];
15460 vinfos[5].indices[1] = _ij5[1];
15461 vinfos[5].maxsolutions = _nj5;
15462 vinfos[6].jointtype = 1;
15463 vinfos[6].foffset = j6;
15464 vinfos[6].indices[0] = _ij6[0];
15465 vinfos[6].indices[1] = _ij6[1];
15466 vinfos[6].maxsolutions = _nj6;
15467 std::vector<int> vfree(0);
15468 solutions.AddSolution(vinfos,vfree);
15469 }
15470 }
15471 }
15472 
15473 }
15474 
15475 }
15476 }
15477 }
15478 
15479 } else
15480 {
15481 if( 1 )
15482 {
15483 continue;
15484 
15485 } else
15486 {
15487 }
15488 }
15489 }
15490 }
15491 
15492 } else
15493 {
15494 {
15495 IkReal j3array[1], cj3array[1], sj3array[1];
15496 bool j3valid[1]={false};
15497 _nj3 = 1;
15498 IkReal x5010=((sj5)*(sj6));
15499 IkReal x5011=((IkReal(1.00000000000000))*(sj0));
15500 IkReal x5012=((cj6)*(sj5));
15501 IkReal x5013=((IkReal(1.00000000000000))*(cj5));
15502 if( IKabs(((((IkReal(-1.00000000000000))*(r01)*(x5011)*(x5012)))+(((IkReal(-1.00000000000000))*(r00)*(x5010)*(x5011)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5013)))+(((cj0)*(r11)*(x5012)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x5010))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5012)))+(((IkReal(-1.00000000000000))*(r22)*(x5013)))+(((r20)*(x5010))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x5011)*(x5012)))+(((IkReal(-1.00000000000000))*(r00)*(x5010)*(x5011)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5013)))+(((cj0)*(r11)*(x5012)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x5010)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5012)))+(((IkReal(-1.00000000000000))*(r22)*(x5013)))+(((r20)*(x5010)))))))-1) <= IKFAST_SINCOS_THRESH )
15503     continue;
15504 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r01)*(x5011)*(x5012)))+(((IkReal(-1.00000000000000))*(r00)*(x5010)*(x5011)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5013)))+(((cj0)*(r11)*(x5012)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x5010)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5012)))+(((IkReal(-1.00000000000000))*(r22)*(x5013)))+(((r20)*(x5010)))))));
15505 sj3array[0]=IKsin(j3array[0]);
15506 cj3array[0]=IKcos(j3array[0]);
15507 if( j3array[0] > IKPI )
15508 {
15509     j3array[0]-=IK2PI;
15510 }
15511 else if( j3array[0] < -IKPI )
15512 {    j3array[0]+=IK2PI;
15513 }
15514 j3valid[0] = true;
15515 for(int ij3 = 0; ij3 < 1; ++ij3)
15516 {
15517 if( !j3valid[ij3] )
15518 {
15519     continue;
15520 }
15521 _ij3[0] = ij3; _ij3[1] = -1;
15522 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
15523 {
15524 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
15525 {
15526     j3valid[iij3]=false; _ij3[1] = iij3; break; 
15527 }
15528 }
15529 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
15530 {
15531 IkReal evalcond[3];
15532 IkReal x5014=IKcos(j3);
15533 IkReal x5015=((sj5)*(sj6));
15534 IkReal x5016=((cj0)*(cj5));
15535 IkReal x5017=((IkReal(1.00000000000000))*(cj0));
15536 IkReal x5018=((IkReal(1.00000000000000))*(sj0));
15537 IkReal x5019=((IkReal(1.00000000000000))*(x5014));
15538 IkReal x5020=((cj6)*(r01)*(sj5));
15539 IkReal x5021=((cj6)*(r11)*(sj5));
15540 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x5019)))+(((r20)*(x5015)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
15541 evalcond[1]=((((sj0)*(x5020)))+(((IkReal(-1.00000000000000))*(x5017)*(x5021)))+(((r12)*(x5016)))+(((r00)*(sj0)*(x5015)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x5018)))+(((IkReal(-1.00000000000000))*(r10)*(x5015)*(x5017)))+(IKsin(j3)));
15542 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x5015)*(x5017)))+(((cj5)*(r12)*(sj0)))+(((r02)*(x5016)))+(((IkReal(-1.00000000000000))*(x5018)*(x5021)))+(((IkReal(-1.00000000000000))*(cj1)*(x5019)))+(((IkReal(-1.00000000000000))*(r10)*(x5015)*(x5018)))+(((IkReal(-1.00000000000000))*(x5017)*(x5020))));
15543 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
15544 {
15545 continue;
15546 }
15547 }
15548 
15549 {
15550 IkReal dummyeval[1];
15551 IkReal gconst28;
15552 IkReal x5022=(r21)*(r21);
15553 IkReal x5023=(cj5)*(cj5);
15554 IkReal x5024=(sj6)*(sj6);
15555 IkReal x5025=(cj6)*(cj6);
15556 IkReal x5026=(r20)*(r20);
15557 IkReal x5027=((cj6)*(r21));
15558 IkReal x5028=((IkReal(2.00000000000000))*(r20)*(sj6));
15559 IkReal x5029=((cj5)*(r22)*(sj5));
15560 IkReal x5030=((IkReal(1.00000000000000))*(x5024));
15561 IkReal x5031=((IkReal(1.00000000000000))*(x5025));
15562 gconst28=IKsign(((((IkReal(-1.00000000000000))*(x5026)*(x5031)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x5022)*(x5030)))+(((IkReal(-1.00000000000000))*(x5023)*(x5026)*(x5030)))+(((IkReal(-2.00000000000000))*(x5027)*(x5029)))+(((x5027)*(x5028)))+(((IkReal(-1.00000000000000))*(x5022)*(x5023)*(x5031)))+(((IkReal(-1.00000000000000))*(x5023)*(x5027)*(x5028)))+(((IkReal(-1.00000000000000))*(x5028)*(x5029)))));
15563 IkReal x5032=(r21)*(r21);
15564 IkReal x5033=(cj5)*(cj5);
15565 IkReal x5034=(sj6)*(sj6);
15566 IkReal x5035=(cj6)*(cj6);
15567 IkReal x5036=(r20)*(r20);
15568 IkReal x5037=((cj6)*(r21));
15569 IkReal x5038=((IkReal(2.00000000000000))*(r20)*(sj6));
15570 IkReal x5039=((cj5)*(r22)*(sj5));
15571 IkReal x5040=((IkReal(1.00000000000000))*(x5034));
15572 IkReal x5041=((IkReal(1.00000000000000))*(x5035));
15573 dummyeval[0]=((((x5037)*(x5038)))+(((IkReal(-1.00000000000000))*(x5038)*(x5039)))+(((IkReal(-1.00000000000000))*(x5036)*(x5041)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x5032)*(x5033)*(x5041)))+(((IkReal(-1.00000000000000))*(x5033)*(x5037)*(x5038)))+(((IkReal(-2.00000000000000))*(x5037)*(x5039)))+(((IkReal(-1.00000000000000))*(x5032)*(x5040)))+(((IkReal(-1.00000000000000))*(x5033)*(x5036)*(x5040))));
15574 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15575 {
15576 {
15577 IkReal dummyeval[1];
15578 IkReal gconst29;
15579 IkReal x5042=(cj6)*(cj6);
15580 IkReal x5043=(sj6)*(sj6);
15581 IkReal x5044=((IkReal(1.00000000000000))*(r01));
15582 IkReal x5045=((sj0)*(sj5));
15583 IkReal x5046=((cj6)*(r22));
15584 IkReal x5047=((r21)*(sj6));
15585 IkReal x5048=((r00)*(r21));
15586 IkReal x5049=((cj0)*(sj5));
15587 IkReal x5050=((cj6)*(r20));
15588 IkReal x5051=((r22)*(sj6));
15589 IkReal x5052=((cj0)*(cj5));
15590 IkReal x5053=((IkReal(1.00000000000000))*(r10));
15591 IkReal x5054=((cj5)*(sj0));
15592 IkReal x5055=((r20)*(x5043));
15593 IkReal x5056=((x5042)*(x5054));
15594 gconst29=IKsign(((((r11)*(r20)*(x5042)*(x5052)))+(((r00)*(x5045)*(x5046)))+(((IkReal(-1.00000000000000))*(x5046)*(x5049)*(x5053)))+(((IkReal(-1.00000000000000))*(r12)*(x5047)*(x5049)))+(((r11)*(x5052)*(x5055)))+(((IkReal(-1.00000000000000))*(r20)*(x5044)*(x5056)))+(((r02)*(x5045)*(x5047)))+(((IkReal(-1.00000000000000))*(r21)*(x5042)*(x5052)*(x5053)))+(((IkReal(-1.00000000000000))*(x5044)*(x5045)*(x5051)))+(((IkReal(-1.00000000000000))*(r21)*(x5043)*(x5052)*(x5053)))+(((r12)*(x5049)*(x5050)))+(((IkReal(-1.00000000000000))*(r02)*(x5045)*(x5050)))+(((x5043)*(x5048)*(x5054)))+(((x5048)*(x5056)))+(((IkReal(-1.00000000000000))*(x5044)*(x5054)*(x5055)))+(((r11)*(x5049)*(x5051)))));
15595 IkReal x5057=(cj6)*(cj6);
15596 IkReal x5058=(sj6)*(sj6);
15597 IkReal x5059=((IkReal(1.00000000000000))*(r01));
15598 IkReal x5060=((sj0)*(sj5));
15599 IkReal x5061=((cj6)*(r22));
15600 IkReal x5062=((r21)*(sj6));
15601 IkReal x5063=((r00)*(r21));
15602 IkReal x5064=((cj0)*(sj5));
15603 IkReal x5065=((cj6)*(r20));
15604 IkReal x5066=((r22)*(sj6));
15605 IkReal x5067=((cj0)*(cj5));
15606 IkReal x5068=((IkReal(1.00000000000000))*(r10));
15607 IkReal x5069=((cj5)*(sj0));
15608 IkReal x5070=((r20)*(x5058));
15609 IkReal x5071=((x5057)*(x5069));
15610 dummyeval[0]=((((r02)*(x5060)*(x5062)))+(((x5058)*(x5063)*(x5069)))+(((IkReal(-1.00000000000000))*(x5061)*(x5064)*(x5068)))+(((r11)*(r20)*(x5057)*(x5067)))+(((IkReal(-1.00000000000000))*(r12)*(x5062)*(x5064)))+(((r11)*(x5064)*(x5066)))+(((r11)*(x5067)*(x5070)))+(((IkReal(-1.00000000000000))*(r02)*(x5060)*(x5065)))+(((x5063)*(x5071)))+(((r00)*(x5060)*(x5061)))+(((r12)*(x5064)*(x5065)))+(((IkReal(-1.00000000000000))*(r21)*(x5058)*(x5067)*(x5068)))+(((IkReal(-1.00000000000000))*(x5059)*(x5069)*(x5070)))+(((IkReal(-1.00000000000000))*(x5059)*(x5060)*(x5066)))+(((IkReal(-1.00000000000000))*(r21)*(x5057)*(x5067)*(x5068)))+(((IkReal(-1.00000000000000))*(r20)*(x5059)*(x5071))));
15611 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15612 {
15613 continue;
15614 
15615 } else
15616 {
15617 {
15618 IkReal j4array[1], cj4array[1], sj4array[1];
15619 bool j4valid[1]={false};
15620 _nj4 = 1;
15621 IkReal x5072=((cj1)*(cj6));
15622 IkReal x5073=((IkReal(1.00000000000000))*(sj0));
15623 IkReal x5074=((cj0)*(r10));
15624 IkReal x5075=((cj1)*(sj5));
15625 IkReal x5076=((cj1)*(sj6));
15626 IkReal x5077=((cj0)*(r11));
15627 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(x5076)*(x5077)))+(((x5072)*(x5074)))+(((r01)*(sj0)*(x5076)))+(((IkReal(-1.00000000000000))*(r00)*(x5072)*(x5073))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((cj5)*(x5074)*(x5076)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5073)*(x5076)))+(((cj5)*(x5072)*(x5077)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5072)*(x5073)))+(((IkReal(-1.00000000000000))*(r02)*(x5073)*(x5075)))+(((cj0)*(r12)*(x5075))))))) < IKFAST_ATAN2_MAGTHRESH )
15628     continue;
15629 j4array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(x5076)*(x5077)))+(((x5072)*(x5074)))+(((r01)*(sj0)*(x5076)))+(((IkReal(-1.00000000000000))*(r00)*(x5072)*(x5073)))))), ((gconst29)*(((((cj5)*(x5074)*(x5076)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5073)*(x5076)))+(((cj5)*(x5072)*(x5077)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5072)*(x5073)))+(((IkReal(-1.00000000000000))*(r02)*(x5073)*(x5075)))+(((cj0)*(r12)*(x5075)))))));
15630 sj4array[0]=IKsin(j4array[0]);
15631 cj4array[0]=IKcos(j4array[0]);
15632 if( j4array[0] > IKPI )
15633 {
15634     j4array[0]-=IK2PI;
15635 }
15636 else if( j4array[0] < -IKPI )
15637 {    j4array[0]+=IK2PI;
15638 }
15639 j4valid[0] = true;
15640 for(int ij4 = 0; ij4 < 1; ++ij4)
15641 {
15642 if( !j4valid[ij4] )
15643 {
15644     continue;
15645 }
15646 _ij4[0] = ij4; _ij4[1] = -1;
15647 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15648 {
15649 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15650 {
15651     j4valid[iij4]=false; _ij4[1] = iij4; break; 
15652 }
15653 }
15654 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15655 {
15656 IkReal evalcond[6];
15657 IkReal x5078=IKsin(j4);
15658 IkReal x5079=IKcos(j4);
15659 IkReal x5080=((r22)*(sj5));
15660 IkReal x5081=((IkReal(1.00000000000000))*(cj6));
15661 IkReal x5082=((IkReal(1.00000000000000))*(cj0));
15662 IkReal x5083=((IkReal(1.00000000000000))*(sj1));
15663 IkReal x5084=((cj5)*(r11));
15664 IkReal x5085=((cj5)*(cj6));
15665 IkReal x5086=((r11)*(sj6));
15666 IkReal x5087=((IkReal(1.00000000000000))*(sj6));
15667 IkReal x5088=((cj6)*(r00));
15668 IkReal x5089=((r12)*(sj5));
15669 IkReal x5090=((r02)*(sj5));
15670 IkReal x5091=((cj6)*(r10));
15671 IkReal x5092=((cj5)*(sj6));
15672 IkReal x5093=((cj5)*(r01));
15673 IkReal x5094=((sj0)*(x5078));
15674 IkReal x5095=((r00)*(x5092));
15675 IkReal x5096=((cj0)*(x5078));
15676 IkReal x5097=((sj0)*(x5079));
15677 IkReal x5098=((r20)*(x5079));
15678 IkReal x5099=((cj0)*(x5079));
15679 IkReal x5100=((r21)*(x5078));
15680 IkReal x5101=((r21)*(x5079));
15681 IkReal x5102=((r20)*(x5078));
15682 IkReal x5103=((x5079)*(x5089));
15683 IkReal x5104=((r01)*(sj6)*(x5079));
15684 IkReal x5105=((cj5)*(r10)*(x5087));
15685 evalcond[0]=((((IkReal(-1.00000000000000))*(x5081)*(x5098)))+(((x5085)*(x5100)))+(((x5092)*(x5102)))+(cj1)+(((sj6)*(x5101)))+(((x5078)*(x5080))));
15686 evalcond[1]=((((x5085)*(x5101)))+(((x5079)*(x5080)))+(((x5092)*(x5098)))+(((IkReal(-1.00000000000000))*(sj3)*(x5083)))+(((IkReal(-1.00000000000000))*(x5087)*(x5100)))+(((cj6)*(x5102))));
15687 evalcond[2]=((((x5090)*(x5094)))+(((x5091)*(x5099)))+(((r01)*(sj6)*(x5097)))+(((IkReal(-1.00000000000000))*(x5078)*(x5082)*(x5089)))+(((IkReal(-1.00000000000000))*(x5079)*(x5082)*(x5086)))+(((IkReal(-1.00000000000000))*(r00)*(x5081)*(x5097)))+(((r01)*(x5085)*(x5094)))+(((IkReal(-1.00000000000000))*(r10)*(x5078)*(x5082)*(x5092)))+(((IkReal(-1.00000000000000))*(x5081)*(x5084)*(x5096)))+(((x5094)*(x5095))));
15688 evalcond[3]=((((IkReal(-1.00000000000000))*(x5082)*(x5103)))+(((IkReal(-1.00000000000000))*(r10)*(x5081)*(x5096)))+(((IkReal(-1.00000000000000))*(x5081)*(x5084)*(x5099)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x5095)*(x5097)))+(((x5086)*(x5096)))+(((IkReal(-1.00000000000000))*(r01)*(x5087)*(x5094)))+(((r01)*(x5085)*(x5097)))+(((x5090)*(x5097)))+(((x5088)*(x5094)))+(((IkReal(-1.00000000000000))*(r10)*(x5079)*(x5082)*(x5092))));
15689 evalcond[4]=((((IkReal(-1.00000000000000))*(x5094)*(x5105)))+(((IkReal(-1.00000000000000))*(x5082)*(x5104)))+(((IkReal(-1.00000000000000))*(x5086)*(x5097)))+(((IkReal(-1.00000000000000))*(x5081)*(x5093)*(x5096)))+(((IkReal(-1.00000000000000))*(x5089)*(x5094)))+(((IkReal(-1.00000000000000))*(x5081)*(x5084)*(x5094)))+(((x5091)*(x5097)))+(((x5088)*(x5099)))+(((IkReal(-1.00000000000000))*(x5078)*(x5082)*(x5090)))+(((IkReal(-1.00000000000000))*(x5078)*(x5082)*(x5095)))+(((IkReal(-1.00000000000000))*(x5083))));
15690 evalcond[5]=((((x5086)*(x5094)))+(((IkReal(-1.00000000000000))*(r00)*(x5081)*(x5096)))+(((IkReal(-1.00000000000000))*(r10)*(x5081)*(x5094)))+(((r01)*(sj6)*(x5096)))+(((IkReal(-1.00000000000000))*(cj1)*(sj3)))+(((IkReal(-1.00000000000000))*(x5081)*(x5093)*(x5099)))+(((IkReal(-1.00000000000000))*(x5079)*(x5082)*(x5090)))+(((IkReal(-1.00000000000000))*(x5079)*(x5082)*(x5095)))+(((IkReal(-1.00000000000000))*(x5081)*(x5084)*(x5097)))+(((IkReal(-1.00000000000000))*(x5097)*(x5105)))+(((IkReal(-1.00000000000000))*(x5089)*(x5097))));
15691 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
15692 {
15693 continue;
15694 }
15695 }
15696 
15697 {
15698 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
15699 vinfos[0].jointtype = 1;
15700 vinfos[0].foffset = j0;
15701 vinfos[0].indices[0] = _ij0[0];
15702 vinfos[0].indices[1] = _ij0[1];
15703 vinfos[0].maxsolutions = _nj0;
15704 vinfos[1].jointtype = 1;
15705 vinfos[1].foffset = j1;
15706 vinfos[1].indices[0] = _ij1[0];
15707 vinfos[1].indices[1] = _ij1[1];
15708 vinfos[1].maxsolutions = _nj1;
15709 vinfos[2].jointtype = 1;
15710 vinfos[2].foffset = j2;
15711 vinfos[2].indices[0] = _ij2[0];
15712 vinfos[2].indices[1] = _ij2[1];
15713 vinfos[2].maxsolutions = _nj2;
15714 vinfos[3].jointtype = 1;
15715 vinfos[3].foffset = j3;
15716 vinfos[3].indices[0] = _ij3[0];
15717 vinfos[3].indices[1] = _ij3[1];
15718 vinfos[3].maxsolutions = _nj3;
15719 vinfos[4].jointtype = 1;
15720 vinfos[4].foffset = j4;
15721 vinfos[4].indices[0] = _ij4[0];
15722 vinfos[4].indices[1] = _ij4[1];
15723 vinfos[4].maxsolutions = _nj4;
15724 vinfos[5].jointtype = 1;
15725 vinfos[5].foffset = j5;
15726 vinfos[5].indices[0] = _ij5[0];
15727 vinfos[5].indices[1] = _ij5[1];
15728 vinfos[5].maxsolutions = _nj5;
15729 vinfos[6].jointtype = 1;
15730 vinfos[6].foffset = j6;
15731 vinfos[6].indices[0] = _ij6[0];
15732 vinfos[6].indices[1] = _ij6[1];
15733 vinfos[6].maxsolutions = _nj6;
15734 std::vector<int> vfree(0);
15735 solutions.AddSolution(vinfos,vfree);
15736 }
15737 }
15738 }
15739 
15740 }
15741 
15742 }
15743 
15744 } else
15745 {
15746 {
15747 IkReal j4array[1], cj4array[1], sj4array[1];
15748 bool j4valid[1]={false};
15749 _nj4 = 1;
15750 IkReal x5106=((cj1)*(r20));
15751 IkReal x5107=((cj5)*(sj6));
15752 IkReal x5108=((sj1)*(sj3));
15753 IkReal x5109=((r21)*(sj6));
15754 IkReal x5110=((r22)*(sj5));
15755 IkReal x5111=((IkReal(1.00000000000000))*(cj6));
15756 IkReal x5112=((cj5)*(r21));
15757 if( IKabs(((gconst28)*(((((cj1)*(x5110)))+(((x5106)*(x5107)))+(((IkReal(-1.00000000000000))*(r20)*(x5108)*(x5111)))+(((x5108)*(x5109)))+(((cj1)*(cj6)*(x5112))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(r20)*(x5107)*(x5108)))+(((IkReal(-1.00000000000000))*(x5108)*(x5111)*(x5112)))+(((IkReal(-1.00000000000000))*(x5108)*(x5110)))+(((cj1)*(x5109)))+(((IkReal(-1.00000000000000))*(x5106)*(x5111))))))) < IKFAST_ATAN2_MAGTHRESH )
15758     continue;
15759 j4array[0]=IKatan2(((gconst28)*(((((cj1)*(x5110)))+(((x5106)*(x5107)))+(((IkReal(-1.00000000000000))*(r20)*(x5108)*(x5111)))+(((x5108)*(x5109)))+(((cj1)*(cj6)*(x5112)))))), ((gconst28)*(((((IkReal(-1.00000000000000))*(r20)*(x5107)*(x5108)))+(((IkReal(-1.00000000000000))*(x5108)*(x5111)*(x5112)))+(((IkReal(-1.00000000000000))*(x5108)*(x5110)))+(((cj1)*(x5109)))+(((IkReal(-1.00000000000000))*(x5106)*(x5111)))))));
15760 sj4array[0]=IKsin(j4array[0]);
15761 cj4array[0]=IKcos(j4array[0]);
15762 if( j4array[0] > IKPI )
15763 {
15764     j4array[0]-=IK2PI;
15765 }
15766 else if( j4array[0] < -IKPI )
15767 {    j4array[0]+=IK2PI;
15768 }
15769 j4valid[0] = true;
15770 for(int ij4 = 0; ij4 < 1; ++ij4)
15771 {
15772 if( !j4valid[ij4] )
15773 {
15774     continue;
15775 }
15776 _ij4[0] = ij4; _ij4[1] = -1;
15777 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15778 {
15779 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15780 {
15781     j4valid[iij4]=false; _ij4[1] = iij4; break; 
15782 }
15783 }
15784 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15785 {
15786 IkReal evalcond[6];
15787 IkReal x5113=IKsin(j4);
15788 IkReal x5114=IKcos(j4);
15789 IkReal x5115=((r22)*(sj5));
15790 IkReal x5116=((IkReal(1.00000000000000))*(cj6));
15791 IkReal x5117=((IkReal(1.00000000000000))*(cj0));
15792 IkReal x5118=((IkReal(1.00000000000000))*(sj1));
15793 IkReal x5119=((cj5)*(r11));
15794 IkReal x5120=((cj5)*(cj6));
15795 IkReal x5121=((r11)*(sj6));
15796 IkReal x5122=((IkReal(1.00000000000000))*(sj6));
15797 IkReal x5123=((cj6)*(r00));
15798 IkReal x5124=((r12)*(sj5));
15799 IkReal x5125=((r02)*(sj5));
15800 IkReal x5126=((cj6)*(r10));
15801 IkReal x5127=((cj5)*(sj6));
15802 IkReal x5128=((cj5)*(r01));
15803 IkReal x5129=((sj0)*(x5113));
15804 IkReal x5130=((r00)*(x5127));
15805 IkReal x5131=((cj0)*(x5113));
15806 IkReal x5132=((sj0)*(x5114));
15807 IkReal x5133=((r20)*(x5114));
15808 IkReal x5134=((cj0)*(x5114));
15809 IkReal x5135=((r21)*(x5113));
15810 IkReal x5136=((r21)*(x5114));
15811 IkReal x5137=((r20)*(x5113));
15812 IkReal x5138=((x5114)*(x5124));
15813 IkReal x5139=((r01)*(sj6)*(x5114));
15814 IkReal x5140=((cj5)*(r10)*(x5122));
15815 evalcond[0]=((((x5127)*(x5137)))+(((x5113)*(x5115)))+(((x5120)*(x5135)))+(cj1)+(((IkReal(-1.00000000000000))*(x5116)*(x5133)))+(((sj6)*(x5136))));
15816 evalcond[1]=((((cj6)*(x5137)))+(((x5114)*(x5115)))+(((x5127)*(x5133)))+(((IkReal(-1.00000000000000))*(x5122)*(x5135)))+(((x5120)*(x5136)))+(((IkReal(-1.00000000000000))*(sj3)*(x5118))));
15817 evalcond[2]=((((IkReal(-1.00000000000000))*(x5113)*(x5117)*(x5124)))+(((IkReal(-1.00000000000000))*(x5116)*(x5119)*(x5131)))+(((x5125)*(x5129)))+(((x5129)*(x5130)))+(((IkReal(-1.00000000000000))*(x5114)*(x5117)*(x5121)))+(((x5126)*(x5134)))+(((r01)*(sj6)*(x5132)))+(((IkReal(-1.00000000000000))*(r10)*(x5113)*(x5117)*(x5127)))+(((r01)*(x5120)*(x5129)))+(((IkReal(-1.00000000000000))*(r00)*(x5116)*(x5132))));
15818 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x5116)*(x5131)))+(((IkReal(-1.00000000000000))*(r10)*(x5114)*(x5117)*(x5127)))+(((x5130)*(x5132)))+(((IkReal(-1.00000000000000))*(x5117)*(x5138)))+(((IkReal(-1.00000000000000))*(x5116)*(x5119)*(x5134)))+(((x5123)*(x5129)))+(((r01)*(x5120)*(x5132)))+(((x5121)*(x5131)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(r01)*(x5122)*(x5129)))+(((x5125)*(x5132))));
15819 evalcond[4]=((((IkReal(-1.00000000000000))*(x5116)*(x5119)*(x5129)))+(((IkReal(-1.00000000000000))*(x5129)*(x5140)))+(((IkReal(-1.00000000000000))*(x5113)*(x5117)*(x5125)))+(((x5126)*(x5132)))+(((IkReal(-1.00000000000000))*(x5117)*(x5139)))+(((IkReal(-1.00000000000000))*(x5113)*(x5117)*(x5130)))+(((IkReal(-1.00000000000000))*(x5124)*(x5129)))+(((IkReal(-1.00000000000000))*(x5121)*(x5132)))+(((IkReal(-1.00000000000000))*(x5118)))+(((x5123)*(x5134)))+(((IkReal(-1.00000000000000))*(x5116)*(x5128)*(x5131))));
15820 evalcond[5]=((((IkReal(-1.00000000000000))*(x5116)*(x5128)*(x5134)))+(((IkReal(-1.00000000000000))*(x5114)*(x5117)*(x5125)))+(((IkReal(-1.00000000000000))*(x5114)*(x5117)*(x5130)))+(((IkReal(-1.00000000000000))*(x5116)*(x5119)*(x5132)))+(((IkReal(-1.00000000000000))*(r00)*(x5116)*(x5131)))+(((x5121)*(x5129)))+(((IkReal(-1.00000000000000))*(r10)*(x5116)*(x5129)))+(((IkReal(-1.00000000000000))*(cj1)*(sj3)))+(((IkReal(-1.00000000000000))*(x5132)*(x5140)))+(((r01)*(sj6)*(x5131)))+(((IkReal(-1.00000000000000))*(x5124)*(x5132))));
15821 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
15822 {
15823 continue;
15824 }
15825 }
15826 
15827 {
15828 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
15829 vinfos[0].jointtype = 1;
15830 vinfos[0].foffset = j0;
15831 vinfos[0].indices[0] = _ij0[0];
15832 vinfos[0].indices[1] = _ij0[1];
15833 vinfos[0].maxsolutions = _nj0;
15834 vinfos[1].jointtype = 1;
15835 vinfos[1].foffset = j1;
15836 vinfos[1].indices[0] = _ij1[0];
15837 vinfos[1].indices[1] = _ij1[1];
15838 vinfos[1].maxsolutions = _nj1;
15839 vinfos[2].jointtype = 1;
15840 vinfos[2].foffset = j2;
15841 vinfos[2].indices[0] = _ij2[0];
15842 vinfos[2].indices[1] = _ij2[1];
15843 vinfos[2].maxsolutions = _nj2;
15844 vinfos[3].jointtype = 1;
15845 vinfos[3].foffset = j3;
15846 vinfos[3].indices[0] = _ij3[0];
15847 vinfos[3].indices[1] = _ij3[1];
15848 vinfos[3].maxsolutions = _nj3;
15849 vinfos[4].jointtype = 1;
15850 vinfos[4].foffset = j4;
15851 vinfos[4].indices[0] = _ij4[0];
15852 vinfos[4].indices[1] = _ij4[1];
15853 vinfos[4].maxsolutions = _nj4;
15854 vinfos[5].jointtype = 1;
15855 vinfos[5].foffset = j5;
15856 vinfos[5].indices[0] = _ij5[0];
15857 vinfos[5].indices[1] = _ij5[1];
15858 vinfos[5].maxsolutions = _nj5;
15859 vinfos[6].jointtype = 1;
15860 vinfos[6].foffset = j6;
15861 vinfos[6].indices[0] = _ij6[0];
15862 vinfos[6].indices[1] = _ij6[1];
15863 vinfos[6].maxsolutions = _nj6;
15864 std::vector<int> vfree(0);
15865 solutions.AddSolution(vinfos,vfree);
15866 }
15867 }
15868 }
15869 
15870 }
15871 
15872 }
15873 }
15874 }
15875 
15876 }
15877 
15878 }
15879 
15880 } else
15881 {
15882 {
15883 IkReal j4array[1], cj4array[1], sj4array[1];
15884 bool j4valid[1]={false};
15885 _nj4 = 1;
15886 IkReal x5141=((IkReal(1.00000000000000))*(sj1));
15887 IkReal x5142=((cj0)*(cj1));
15888 IkReal x5143=((cj1)*(sj0));
15889 IkReal x5144=((cj5)*(sj6));
15890 IkReal x5145=((cj5)*(cj6));
15891 IkReal x5146=((sj6)*(x5142));
15892 IkReal x5147=((cj6)*(x5143));
15893 if( IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(r11)*(sj6)*(x5143)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(x5141)))+(((r10)*(x5147)))+(((IkReal(-1.00000000000000))*(r01)*(x5146)))+(((cj6)*(r00)*(x5142)))+(((r21)*(sj1)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x5141)))+(((r01)*(x5142)*(x5145)))+(((r12)*(sj5)*(x5143)))+(((IkReal(-1.00000000000000))*(r20)*(x5141)*(x5144)))+(((r11)*(x5143)*(x5145)))+(((r00)*(x5142)*(x5144)))+(((r02)*(sj5)*(x5142)))+(((IkReal(-1.00000000000000))*(r21)*(x5141)*(x5145)))+(((r10)*(x5143)*(x5144))))))) < IKFAST_ATAN2_MAGTHRESH )
15894     continue;
15895 j4array[0]=IKatan2(((gconst27)*(((((IkReal(-1.00000000000000))*(r11)*(sj6)*(x5143)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(x5141)))+(((r10)*(x5147)))+(((IkReal(-1.00000000000000))*(r01)*(x5146)))+(((cj6)*(r00)*(x5142)))+(((r21)*(sj1)*(sj6)))))), ((gconst27)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x5141)))+(((r01)*(x5142)*(x5145)))+(((r12)*(sj5)*(x5143)))+(((IkReal(-1.00000000000000))*(r20)*(x5141)*(x5144)))+(((r11)*(x5143)*(x5145)))+(((r00)*(x5142)*(x5144)))+(((r02)*(sj5)*(x5142)))+(((IkReal(-1.00000000000000))*(r21)*(x5141)*(x5145)))+(((r10)*(x5143)*(x5144)))))));
15896 sj4array[0]=IKsin(j4array[0]);
15897 cj4array[0]=IKcos(j4array[0]);
15898 if( j4array[0] > IKPI )
15899 {
15900     j4array[0]-=IK2PI;
15901 }
15902 else if( j4array[0] < -IKPI )
15903 {    j4array[0]+=IK2PI;
15904 }
15905 j4valid[0] = true;
15906 for(int ij4 = 0; ij4 < 1; ++ij4)
15907 {
15908 if( !j4valid[ij4] )
15909 {
15910     continue;
15911 }
15912 _ij4[0] = ij4; _ij4[1] = -1;
15913 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
15914 {
15915 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
15916 {
15917     j4valid[iij4]=false; _ij4[1] = iij4; break; 
15918 }
15919 }
15920 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
15921 {
15922 IkReal evalcond[3];
15923 IkReal x5148=IKsin(j4);
15924 IkReal x5149=IKcos(j4);
15925 IkReal x5150=((r00)*(sj6));
15926 IkReal x5151=((cj6)*(r01));
15927 IkReal x5152=((IkReal(1.00000000000000))*(cj0));
15928 IkReal x5153=((IkReal(1.00000000000000))*(sj0));
15929 IkReal x5154=((r10)*(sj6));
15930 IkReal x5155=((sj5)*(x5148));
15931 IkReal x5156=((IkReal(1.00000000000000))*(cj6)*(r11));
15932 IkReal x5157=((cj5)*(x5148));
15933 IkReal x5158=((cj6)*(x5149));
15934 IkReal x5159=((sj0)*(x5157));
15935 IkReal x5160=((r01)*(sj6)*(x5149));
15936 IkReal x5161=((r11)*(sj6)*(x5149));
15937 evalcond[0]=((((IkReal(-1.00000000000000))*(r20)*(x5158)))+(((r21)*(sj6)*(x5149)))+(((r20)*(sj6)*(x5157)))+(cj1)+(((r22)*(x5155)))+(((cj6)*(r21)*(x5157))));
15938 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x5153)*(x5158)))+(((IkReal(-1.00000000000000))*(r12)*(x5152)*(x5155)))+(((IkReal(-1.00000000000000))*(x5152)*(x5154)*(x5157)))+(((x5150)*(x5159)))+(((x5151)*(x5159)))+(((cj0)*(r10)*(x5158)))+(((r02)*(sj0)*(x5155)))+(((sj0)*(x5160)))+(((IkReal(-1.00000000000000))*(x5152)*(x5161)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5152)*(x5157))));
15939 evalcond[2]=((((r10)*(sj0)*(x5158)))+(((cj0)*(r00)*(x5158)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5153)*(x5157)))+(((IkReal(-1.00000000000000))*(x5151)*(x5152)*(x5157)))+(((IkReal(-1.00000000000000))*(x5152)*(x5160)))+(((IkReal(-1.00000000000000))*(x5153)*(x5154)*(x5157)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x5150)*(x5152)*(x5157)))+(((IkReal(-1.00000000000000))*(r02)*(x5152)*(x5155)))+(((IkReal(-1.00000000000000))*(r12)*(x5153)*(x5155)))+(((IkReal(-1.00000000000000))*(x5153)*(x5161))));
15940 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
15941 {
15942 continue;
15943 }
15944 }
15945 
15946 {
15947 IkReal dummyeval[1];
15948 IkReal gconst30;
15949 gconst30=IKsign(sj1);
15950 dummyeval[0]=sj1;
15951 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15952 {
15953 {
15954 IkReal dummyeval[1];
15955 dummyeval[0]=sj1;
15956 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15957 {
15958 {
15959 IkReal dummyeval[1];
15960 dummyeval[0]=cj1;
15961 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15962 {
15963 {
15964 IkReal evalcond[9];
15965 IkReal x5162=((IkReal(1.00000000000000))*(cj0));
15966 IkReal x5163=((cj4)*(sj6));
15967 IkReal x5164=((sj0)*(sj6));
15968 IkReal x5165=((cj5)*(sj4));
15969 IkReal x5166=((IkReal(0.374290000000000))*(sj5));
15970 IkReal x5167=((sj4)*(sj5));
15971 IkReal x5168=((cj0)*(cj6));
15972 IkReal x5169=((IkReal(0.0100000000000000))*(cj5));
15973 IkReal x5170=((cj4)*(sj5));
15974 IkReal x5171=((cj5)*(sj0));
15975 IkReal x5172=((IkReal(0.374290000000000))*(r02));
15976 IkReal x5173=((r20)*(sj6));
15977 IkReal x5174=((cj6)*(r21));
15978 IkReal x5175=((IkReal(1.00000000000000))*(sj0));
15979 IkReal x5176=((cj0)*(sj6));
15980 IkReal x5177=((cj4)*(cj6));
15981 IkReal x5178=((IkReal(0.374290000000000))*(r12));
15982 IkReal x5179=((cj0)*(cj5));
15983 IkReal x5180=((cj6)*(sj5));
15984 IkReal x5181=((cj6)*(r01));
15985 IkReal x5182=((r00)*(sj6));
15986 IkReal x5183=((IkReal(0.0100000000000000))*(sj5));
15987 IkReal x5184=((cj6)*(r11));
15988 IkReal x5185=((IkReal(1.00000000000000))*(r10));
15989 IkReal x5186=((r02)*(sj0));
15990 IkReal x5187=((cj6)*(sj4));
15991 IkReal x5188=((r12)*(x5175));
15992 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
15993 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x5177)))+(((r21)*(x5163)))+(((x5165)*(x5173)))+(((r22)*(x5167)))+(((x5165)*(x5174))));
15994 evalcond[2]=((IkReal(0.364420000000000))+(((x5166)*(x5174)))+(((IkReal(-1.00000000000000))*(x5169)*(x5174)))+(((IkReal(-1.00000000000000))*(x5169)*(x5173)))+(((IkReal(-1.00000000000000))*(r22)*(x5183)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x5166)*(x5173))));
15995 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x5164)*(x5185)))+(((IkReal(-1.00000000000000))*(sj5)*(x5162)*(x5182)))+(((r02)*(x5179)))+(((IkReal(-1.00000000000000))*(r01)*(x5162)*(x5180)))+(((IkReal(-1.00000000000000))*(r11)*(x5175)*(x5180)))+(((r12)*(x5171))));
15996 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x5162)*(x5163)))+(((cj4)*(r10)*(x5168)))+(((x5167)*(x5186)))+(((IkReal(-1.00000000000000))*(x5162)*(x5165)*(x5184)))+(((r00)*(x5164)*(x5165)))+(((IkReal(-1.00000000000000))*(r00)*(x5175)*(x5177)))+(((r01)*(sj0)*(x5163)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x5162)*(x5165)))+(((sj0)*(x5165)*(x5181)))+(((IkReal(-1.00000000000000))*(r12)*(x5162)*(x5167))));
15997 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x5162)*(x5163)))+(((IkReal(-1.00000000000000))*(x5162)*(x5165)*(x5181)))+(((IkReal(-1.00000000000000))*(r02)*(x5162)*(x5167)))+(((r10)*(sj0)*(x5177)))+(((IkReal(-1.00000000000000))*(x5165)*(x5175)*(x5184)))+(((IkReal(-1.00000000000000))*(x5167)*(x5188)))+(((IkReal(-1.00000000000000))*(x5162)*(x5165)*(x5182)))+(((cj4)*(r00)*(x5168)))+(((IkReal(-1.00000000000000))*(r11)*(x5163)*(x5175)))+(((IkReal(-1.00000000000000))*(x5164)*(x5165)*(x5185))));
15998 evalcond[6]=((IkReal(-0.0690000000000000))+(((r11)*(x5168)*(x5169)))+(((r10)*(x5169)*(x5176)))+(((IkReal(-1.00000000000000))*(py)*(x5162)))+(((IkReal(-1.00000000000000))*(r10)*(x5166)*(x5176)))+(((r00)*(x5164)*(x5166)))+(((x5178)*(x5179)))+(((IkReal(-1.00000000000000))*(x5171)*(x5172)))+(((cj0)*(r12)*(x5183)))+(((IkReal(-1.00000000000000))*(r11)*(x5166)*(x5168)))+(((IkReal(-1.00000000000000))*(r00)*(x5164)*(x5169)))+(((IkReal(-1.00000000000000))*(x5183)*(x5186)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x5169)*(x5181)))+(((sj0)*(x5166)*(x5181))));
15999 evalcond[7]=((((r01)*(sj4)*(x5176)))+(((IkReal(-1.00000000000000))*(r10)*(x5175)*(x5187)))+(((IkReal(-1.00000000000000))*(x5170)*(x5188)))+(((IkReal(-1.00000000000000))*(r11)*(x5171)*(x5177)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5162)*(x5163)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5162)*(x5177)))+(((IkReal(-1.00000000000000))*(x5163)*(x5171)*(x5185)))+(((IkReal(-1.00000000000000))*(r00)*(x5162)*(x5187)))+(((r11)*(sj4)*(x5164)))+(((IkReal(-1.00000000000000))*(r02)*(x5162)*(x5170))));
16000 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x5166)*(x5168)))+(((r12)*(sj0)*(x5183)))+(((IkReal(-1.00000000000000))*(r00)*(x5166)*(x5176)))+(((r00)*(x5169)*(x5176)))+(((r01)*(x5168)*(x5169)))+(((r10)*(x5164)*(x5169)))+(((IkReal(-1.00000000000000))*(px)*(x5162)))+(((sj0)*(x5169)*(x5184)))+(((cj0)*(r02)*(x5183)))+(((IkReal(-1.00000000000000))*(r10)*(x5164)*(x5166)))+(((IkReal(-1.00000000000000))*(py)*(x5175)))+(((IkReal(-1.00000000000000))*(sj0)*(x5166)*(x5184)))+(((x5172)*(x5179)))+(((x5171)*(x5178))));
16001 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
16002 {
16003 {
16004 IkReal j3array[1], cj3array[1], sj3array[1];
16005 bool j3valid[1]={false};
16006 _nj3 = 1;
16007 IkReal x5189=((r20)*(sj6));
16008 IkReal x5190=((cj4)*(cj5));
16009 IkReal x5191=((cj6)*(r21));
16010 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5189)*(x5190)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5190)*(x5191))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x5189)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5191))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5189)*(x5190)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5190)*(x5191)))))+IKsqr(((((sj5)*(x5189)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5191)))))-1) <= IKFAST_SINCOS_THRESH )
16011     continue;
16012 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5189)*(x5190)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5190)*(x5191)))), ((((sj5)*(x5189)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5191)))));
16013 sj3array[0]=IKsin(j3array[0]);
16014 cj3array[0]=IKcos(j3array[0]);
16015 if( j3array[0] > IKPI )
16016 {
16017     j3array[0]-=IK2PI;
16018 }
16019 else if( j3array[0] < -IKPI )
16020 {    j3array[0]+=IK2PI;
16021 }
16022 j3valid[0] = true;
16023 for(int ij3 = 0; ij3 < 1; ++ij3)
16024 {
16025 if( !j3valid[ij3] )
16026 {
16027     continue;
16028 }
16029 _ij3[0] = ij3; _ij3[1] = -1;
16030 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16031 {
16032 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16033 {
16034     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16035 }
16036 }
16037 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16038 {
16039 IkReal evalcond[4];
16040 IkReal x5192=IKsin(j3);
16041 IkReal x5193=((sj0)*(sj5));
16042 IkReal x5194=((r00)*(sj6));
16043 IkReal x5195=((cj6)*(r01));
16044 IkReal x5196=((cj5)*(sj0));
16045 IkReal x5197=((cj0)*(cj5));
16046 IkReal x5198=((cj6)*(sj4));
16047 IkReal x5199=((sj4)*(sj6));
16048 IkReal x5200=((cj0)*(r11));
16049 IkReal x5201=((cj4)*(cj6));
16050 IkReal x5202=((cj4)*(sj6));
16051 IkReal x5203=((IkReal(1.00000000000000))*(cj0));
16052 IkReal x5204=((cj4)*(sj5));
16053 IkReal x5205=((sj5)*(sj6));
16054 IkReal x5206=((cj6)*(sj5));
16055 IkReal x5207=((IkReal(1.00000000000000))*(IKcos(j3)));
16056 evalcond[0]=((((IkReal(-1.00000000000000))*(x5207)))+(((r21)*(x5206)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x5205))));
16057 evalcond[1]=((((cj5)*(r21)*(x5201)))+(((cj5)*(r20)*(x5202)))+(((IkReal(-1.00000000000000))*(r21)*(x5199)))+(((r22)*(x5204)))+(((IkReal(-1.00000000000000))*(x5192)))+(((r20)*(x5198))));
16058 evalcond[2]=((((IkReal(-1.00000000000000))*(x5200)*(x5206)))+(x5192)+(((r12)*(x5197)))+(((IkReal(-1.00000000000000))*(r10)*(x5203)*(x5205)))+(((x5193)*(x5194)))+(((IkReal(-1.00000000000000))*(r02)*(x5196)))+(((x5193)*(x5195))));
16059 evalcond[3]=((((x5199)*(x5200)))+(((cj4)*(x5195)*(x5196)))+(((IkReal(-1.00000000000000))*(r11)*(x5197)*(x5201)))+(((IkReal(-1.00000000000000))*(r10)*(x5197)*(x5202)))+(((IkReal(-1.00000000000000))*(x5207)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x5199)))+(((IkReal(-1.00000000000000))*(r10)*(x5198)*(x5203)))+(((cj4)*(r02)*(x5193)))+(((IkReal(-1.00000000000000))*(r12)*(x5203)*(x5204)))+(((cj4)*(x5194)*(x5196)))+(((r00)*(sj0)*(x5198))));
16060 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16061 {
16062 continue;
16063 }
16064 }
16065 
16066 {
16067 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16068 vinfos[0].jointtype = 1;
16069 vinfos[0].foffset = j0;
16070 vinfos[0].indices[0] = _ij0[0];
16071 vinfos[0].indices[1] = _ij0[1];
16072 vinfos[0].maxsolutions = _nj0;
16073 vinfos[1].jointtype = 1;
16074 vinfos[1].foffset = j1;
16075 vinfos[1].indices[0] = _ij1[0];
16076 vinfos[1].indices[1] = _ij1[1];
16077 vinfos[1].maxsolutions = _nj1;
16078 vinfos[2].jointtype = 1;
16079 vinfos[2].foffset = j2;
16080 vinfos[2].indices[0] = _ij2[0];
16081 vinfos[2].indices[1] = _ij2[1];
16082 vinfos[2].maxsolutions = _nj2;
16083 vinfos[3].jointtype = 1;
16084 vinfos[3].foffset = j3;
16085 vinfos[3].indices[0] = _ij3[0];
16086 vinfos[3].indices[1] = _ij3[1];
16087 vinfos[3].maxsolutions = _nj3;
16088 vinfos[4].jointtype = 1;
16089 vinfos[4].foffset = j4;
16090 vinfos[4].indices[0] = _ij4[0];
16091 vinfos[4].indices[1] = _ij4[1];
16092 vinfos[4].maxsolutions = _nj4;
16093 vinfos[5].jointtype = 1;
16094 vinfos[5].foffset = j5;
16095 vinfos[5].indices[0] = _ij5[0];
16096 vinfos[5].indices[1] = _ij5[1];
16097 vinfos[5].maxsolutions = _nj5;
16098 vinfos[6].jointtype = 1;
16099 vinfos[6].foffset = j6;
16100 vinfos[6].indices[0] = _ij6[0];
16101 vinfos[6].indices[1] = _ij6[1];
16102 vinfos[6].maxsolutions = _nj6;
16103 std::vector<int> vfree(0);
16104 solutions.AddSolution(vinfos,vfree);
16105 }
16106 }
16107 }
16108 
16109 } else
16110 {
16111 IkReal x5208=((IkReal(1.00000000000000))*(cj0));
16112 IkReal x5209=((cj4)*(sj6));
16113 IkReal x5210=((sj0)*(sj6));
16114 IkReal x5211=((cj5)*(sj4));
16115 IkReal x5212=((IkReal(0.374290000000000))*(sj5));
16116 IkReal x5213=((sj4)*(sj5));
16117 IkReal x5214=((cj0)*(cj6));
16118 IkReal x5215=((IkReal(0.0100000000000000))*(cj5));
16119 IkReal x5216=((cj4)*(sj5));
16120 IkReal x5217=((cj5)*(sj0));
16121 IkReal x5218=((IkReal(0.374290000000000))*(r02));
16122 IkReal x5219=((r20)*(sj6));
16123 IkReal x5220=((cj6)*(r21));
16124 IkReal x5221=((IkReal(1.00000000000000))*(sj0));
16125 IkReal x5222=((cj0)*(sj6));
16126 IkReal x5223=((cj4)*(cj6));
16127 IkReal x5224=((IkReal(0.374290000000000))*(r12));
16128 IkReal x5225=((cj0)*(cj5));
16129 IkReal x5226=((cj6)*(sj5));
16130 IkReal x5227=((cj6)*(r01));
16131 IkReal x5228=((r00)*(sj6));
16132 IkReal x5229=((IkReal(0.0100000000000000))*(sj5));
16133 IkReal x5230=((cj6)*(r11));
16134 IkReal x5231=((IkReal(1.00000000000000))*(r10));
16135 IkReal x5232=((r02)*(sj0));
16136 IkReal x5233=((cj6)*(sj4));
16137 IkReal x5234=((r12)*(x5221));
16138 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
16139 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x5223)))+(((x5211)*(x5220)))+(((r22)*(x5213)))+(((r21)*(x5209)))+(((x5211)*(x5219))));
16140 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(r22)*(x5229)))+(((IkReal(-1.00000000000000))*(x5215)*(x5220)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x5215)*(x5219)))+(pz)+(((x5212)*(x5219)))+(((x5212)*(x5220))));
16141 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x5210)*(x5231)))+(((IkReal(-1.00000000000000))*(r01)*(x5208)*(x5226)))+(((IkReal(-1.00000000000000))*(r11)*(x5221)*(x5226)))+(((r12)*(x5217)))+(((r02)*(x5225)))+(((IkReal(-1.00000000000000))*(sj5)*(x5208)*(x5228))));
16142 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x5208)*(x5213)))+(((r01)*(sj0)*(x5209)))+(((IkReal(-1.00000000000000))*(x5208)*(x5211)*(x5230)))+(((sj0)*(x5211)*(x5227)))+(((IkReal(-1.00000000000000))*(r00)*(x5221)*(x5223)))+(((IkReal(-1.00000000000000))*(r11)*(x5208)*(x5209)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x5208)*(x5211)))+(((cj4)*(r10)*(x5214)))+(((r00)*(x5210)*(x5211)))+(((x5213)*(x5232))));
16143 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x5208)*(x5211)*(x5228)))+(((IkReal(-1.00000000000000))*(r01)*(x5208)*(x5209)))+(((IkReal(-1.00000000000000))*(r02)*(x5208)*(x5213)))+(((IkReal(-1.00000000000000))*(r11)*(x5209)*(x5221)))+(((IkReal(-1.00000000000000))*(x5210)*(x5211)*(x5231)))+(((IkReal(-1.00000000000000))*(x5208)*(x5211)*(x5227)))+(((IkReal(-1.00000000000000))*(x5211)*(x5221)*(x5230)))+(((r10)*(sj0)*(x5223)))+(((cj4)*(r00)*(x5214)))+(((IkReal(-1.00000000000000))*(x5213)*(x5234))));
16144 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x5208)))+(((r11)*(x5214)*(x5215)))+(((IkReal(-1.00000000000000))*(r00)*(x5210)*(x5215)))+(((IkReal(-1.00000000000000))*(x5229)*(x5232)))+(((IkReal(-1.00000000000000))*(x5217)*(x5218)))+(((IkReal(-1.00000000000000))*(sj0)*(x5215)*(x5227)))+(((r00)*(x5210)*(x5212)))+(((cj0)*(r12)*(x5229)))+(((IkReal(-1.00000000000000))*(r11)*(x5212)*(x5214)))+(((IkReal(-1.00000000000000))*(r10)*(x5212)*(x5222)))+(((x5224)*(x5225)))+(((px)*(sj0)))+(((sj0)*(x5212)*(x5227)))+(((r10)*(x5215)*(x5222))));
16145 evalcond[7]=((((r11)*(sj4)*(x5210)))+(((IkReal(-1.00000000000000))*(r11)*(x5217)*(x5223)))+(((IkReal(-1.00000000000000))*(r10)*(x5221)*(x5233)))+(((IkReal(-1.00000000000000))*(r02)*(x5208)*(x5216)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5208)*(x5223)))+(((r01)*(sj4)*(x5222)))+(((IkReal(-1.00000000000000))*(x5216)*(x5234)))+(((IkReal(-1.00000000000000))*(x5209)*(x5217)*(x5231)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5208)*(x5209)))+(((IkReal(-1.00000000000000))*(r00)*(x5208)*(x5233))));
16146 evalcond[8]=((IkReal(0.0690000000000000))+(((r01)*(x5214)*(x5215)))+(((IkReal(-1.00000000000000))*(r01)*(x5212)*(x5214)))+(((sj0)*(x5215)*(x5230)))+(((r10)*(x5210)*(x5215)))+(((IkReal(-1.00000000000000))*(px)*(x5208)))+(((IkReal(-1.00000000000000))*(sj0)*(x5212)*(x5230)))+(((r00)*(x5215)*(x5222)))+(((IkReal(-1.00000000000000))*(r00)*(x5212)*(x5222)))+(((cj0)*(r02)*(x5229)))+(((r12)*(sj0)*(x5229)))+(((IkReal(-1.00000000000000))*(py)*(x5221)))+(((x5217)*(x5224)))+(((IkReal(-1.00000000000000))*(r10)*(x5210)*(x5212)))+(((x5218)*(x5225))));
16147 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
16148 {
16149 {
16150 IkReal j3array[1], cj3array[1], sj3array[1];
16151 bool j3valid[1]={false};
16152 _nj3 = 1;
16153 IkReal x5235=((IkReal(1.00000000000000))*(sj5));
16154 IkReal x5236=((cj6)*(r21));
16155 IkReal x5237=((r20)*(sj6));
16156 IkReal x5238=((IkReal(1.00000000000000))*(cj4)*(cj5));
16157 if( IKabs(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5235)))+(((IkReal(-1.00000000000000))*(x5237)*(x5238)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5236)*(x5238)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x5235)*(x5236)))+(((IkReal(-1.00000000000000))*(x5235)*(x5237)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5235)))+(((IkReal(-1.00000000000000))*(x5237)*(x5238)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5236)*(x5238)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x5235)*(x5236)))+(((IkReal(-1.00000000000000))*(x5235)*(x5237)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
16158     continue;
16159 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5235)))+(((IkReal(-1.00000000000000))*(x5237)*(x5238)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5236)*(x5238)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x5235)*(x5236)))+(((IkReal(-1.00000000000000))*(x5235)*(x5237)))+(((cj5)*(r22)))));
16160 sj3array[0]=IKsin(j3array[0]);
16161 cj3array[0]=IKcos(j3array[0]);
16162 if( j3array[0] > IKPI )
16163 {
16164     j3array[0]-=IK2PI;
16165 }
16166 else if( j3array[0] < -IKPI )
16167 {    j3array[0]+=IK2PI;
16168 }
16169 j3valid[0] = true;
16170 for(int ij3 = 0; ij3 < 1; ++ij3)
16171 {
16172 if( !j3valid[ij3] )
16173 {
16174     continue;
16175 }
16176 _ij3[0] = ij3; _ij3[1] = -1;
16177 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16178 {
16179 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16180 {
16181     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16182 }
16183 }
16184 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16185 {
16186 IkReal evalcond[4];
16187 IkReal x5239=IKsin(j3);
16188 IkReal x5240=IKcos(j3);
16189 IkReal x5241=((sj0)*(sj5));
16190 IkReal x5242=((r00)*(sj6));
16191 IkReal x5243=((cj6)*(r01));
16192 IkReal x5244=((cj0)*(cj5));
16193 IkReal x5245=((IkReal(1.00000000000000))*(cj5));
16194 IkReal x5246=((cj4)*(cj5));
16195 IkReal x5247=((cj6)*(sj4));
16196 IkReal x5248=((sj4)*(sj6));
16197 IkReal x5249=((cj0)*(r11));
16198 IkReal x5250=((IkReal(1.00000000000000))*(cj4));
16199 IkReal x5251=((cj6)*(r21));
16200 IkReal x5252=((r20)*(sj6));
16201 IkReal x5253=((cj0)*(sj5));
16202 IkReal x5254=((r10)*(sj6));
16203 evalcond[0]=((x5240)+(((IkReal(-1.00000000000000))*(r22)*(x5245)))+(((sj5)*(x5251)))+(((sj5)*(x5252))));
16204 evalcond[1]=((((x5246)*(x5252)))+(x5239)+(((cj4)*(r22)*(sj5)))+(((r20)*(x5247)))+(((x5246)*(x5251)))+(((IkReal(-1.00000000000000))*(r21)*(x5248))));
16205 evalcond[2]=((x5239)+(((r12)*(x5244)))+(((IkReal(-1.00000000000000))*(x5253)*(x5254)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x5249)))+(((x5241)*(x5242)))+(((x5241)*(x5243)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x5245))));
16206 evalcond[3]=((((sj0)*(x5242)*(x5246)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x5248)))+(((r00)*(sj0)*(x5247)))+(((IkReal(-1.00000000000000))*(x5244)*(x5250)*(x5254)))+(((sj0)*(x5243)*(x5246)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x5247)))+(((IkReal(-1.00000000000000))*(r12)*(x5250)*(x5253)))+(((x5248)*(x5249)))+(((IkReal(-1.00000000000000))*(x5240)))+(((cj4)*(r02)*(x5241)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5244)*(x5250))));
16207 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16208 {
16209 continue;
16210 }
16211 }
16212 
16213 {
16214 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16215 vinfos[0].jointtype = 1;
16216 vinfos[0].foffset = j0;
16217 vinfos[0].indices[0] = _ij0[0];
16218 vinfos[0].indices[1] = _ij0[1];
16219 vinfos[0].maxsolutions = _nj0;
16220 vinfos[1].jointtype = 1;
16221 vinfos[1].foffset = j1;
16222 vinfos[1].indices[0] = _ij1[0];
16223 vinfos[1].indices[1] = _ij1[1];
16224 vinfos[1].maxsolutions = _nj1;
16225 vinfos[2].jointtype = 1;
16226 vinfos[2].foffset = j2;
16227 vinfos[2].indices[0] = _ij2[0];
16228 vinfos[2].indices[1] = _ij2[1];
16229 vinfos[2].maxsolutions = _nj2;
16230 vinfos[3].jointtype = 1;
16231 vinfos[3].foffset = j3;
16232 vinfos[3].indices[0] = _ij3[0];
16233 vinfos[3].indices[1] = _ij3[1];
16234 vinfos[3].maxsolutions = _nj3;
16235 vinfos[4].jointtype = 1;
16236 vinfos[4].foffset = j4;
16237 vinfos[4].indices[0] = _ij4[0];
16238 vinfos[4].indices[1] = _ij4[1];
16239 vinfos[4].maxsolutions = _nj4;
16240 vinfos[5].jointtype = 1;
16241 vinfos[5].foffset = j5;
16242 vinfos[5].indices[0] = _ij5[0];
16243 vinfos[5].indices[1] = _ij5[1];
16244 vinfos[5].maxsolutions = _nj5;
16245 vinfos[6].jointtype = 1;
16246 vinfos[6].foffset = j6;
16247 vinfos[6].indices[0] = _ij6[0];
16248 vinfos[6].indices[1] = _ij6[1];
16249 vinfos[6].maxsolutions = _nj6;
16250 std::vector<int> vfree(0);
16251 solutions.AddSolution(vinfos,vfree);
16252 }
16253 }
16254 }
16255 
16256 } else
16257 {
16258 IkReal x5255=((IkReal(1.00000000000000))*(cj0));
16259 IkReal x5256=((cj4)*(sj6));
16260 IkReal x5257=((sj0)*(sj4));
16261 IkReal x5258=((cj5)*(sj6));
16262 IkReal x5259=((sj4)*(sj5));
16263 IkReal x5260=((r12)*(sj5));
16264 IkReal x5261=((IkReal(0.374290000000000))*(cj5));
16265 IkReal x5262=((r02)*(sj0));
16266 IkReal x5263=((r20)*(sj4));
16267 IkReal x5264=((IkReal(1.00000000000000))*(sj0));
16268 IkReal x5265=((IkReal(1.00000000000000))*(cj5));
16269 IkReal x5266=((cj0)*(r10));
16270 IkReal x5267=((cj4)*(cj6));
16271 IkReal x5268=((r00)*(sj0));
16272 IkReal x5269=((cj6)*(r21));
16273 IkReal x5270=((IkReal(0.374290000000000))*(sj5));
16274 IkReal x5271=((cj0)*(r00));
16275 IkReal x5272=((IkReal(0.0100000000000000))*(sj5));
16276 IkReal x5273=((cj0)*(r02));
16277 IkReal x5274=((cj5)*(sj4));
16278 IkReal x5275=((cj6)*(r01));
16279 IkReal x5276=((cj6)*(r11));
16280 IkReal x5277=((r01)*(sj0));
16281 IkReal x5278=((r10)*(sj0));
16282 IkReal x5279=((IkReal(0.0100000000000000))*(cj5)*(cj6));
16283 IkReal x5280=((sj6)*(x5270));
16284 IkReal x5281=((cj0)*(cj6)*(x5270));
16285 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
16286 evalcond[1]=((((sj5)*(x5269)))+(((r20)*(sj5)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(x5265))));
16287 evalcond[2]=((IkReal(1.00000000000000))+(((x5258)*(x5263)))+(((IkReal(-1.00000000000000))*(r20)*(x5267)))+(((x5269)*(x5274)))+(((r21)*(x5256)))+(((r22)*(x5259))));
16288 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x5272)))+(((r20)*(x5280)))+(((IkReal(-0.0100000000000000))*(r20)*(x5258)))+(((IkReal(-0.0100000000000000))*(cj5)*(x5269)))+(pz)+(((x5269)*(x5270)))+(((IkReal(-1.00000000000000))*(r22)*(x5261))));
16289 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x5263)))+(((cj5)*(r21)*(x5267)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x5256))));
16290 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x5255)*(x5259)))+(((r02)*(sj5)*(x5257)))+(((x5266)*(x5267)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x5255)*(x5258)))+(((r00)*(x5257)*(x5258)))+(((IkReal(-1.00000000000000))*(r11)*(x5255)*(x5256)))+(((cj5)*(x5257)*(x5275)))+(((x5256)*(x5277)))+(((IkReal(-1.00000000000000))*(r00)*(x5264)*(x5267)))+(((IkReal(-1.00000000000000))*(x5255)*(x5274)*(x5276))));
16291 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x5256)*(x5264)))+(((IkReal(-1.00000000000000))*(r10)*(x5257)*(x5258)))+(((IkReal(-1.00000000000000))*(x5257)*(x5260)))+(((IkReal(-1.00000000000000))*(r02)*(x5255)*(x5259)))+(((IkReal(-1.00000000000000))*(x5257)*(x5265)*(x5276)))+(((x5267)*(x5271)))+(((IkReal(-1.00000000000000))*(x5255)*(x5274)*(x5275)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x5255)*(x5258)))+(((IkReal(-1.00000000000000))*(r01)*(x5255)*(x5256)))+(((x5267)*(x5278))));
16292 evalcond[7]=((IkReal(-0.0690000000000000))+(((cj0)*(r12)*(x5261)))+(((IkReal(-0.0100000000000000))*(x5258)*(x5268)))+(((IkReal(-1.00000000000000))*(x5266)*(x5280)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5276)))+(((x5268)*(x5280)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x5275)))+(((sj0)*(x5270)*(x5275)))+(((IkReal(0.0100000000000000))*(x5258)*(x5266)))+(((IkReal(-1.00000000000000))*(py)*(x5255)))+(((IkReal(-1.00000000000000))*(cj0)*(x5270)*(x5276)))+(((IkReal(-1.00000000000000))*(x5262)*(x5272)))+(((IkReal(0.0100000000000000))*(cj0)*(x5260)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x5261)*(x5262))));
16293 evalcond[8]=((IkReal(0.433420000000000))+(((r12)*(sj0)*(x5261)))+(((IkReal(0.0100000000000000))*(x5258)*(x5278)))+(((IkReal(-1.00000000000000))*(sj0)*(x5270)*(x5276)))+(((IkReal(-1.00000000000000))*(py)*(x5264)))+(((IkReal(-1.00000000000000))*(px)*(x5255)))+(((x5272)*(x5273)))+(((IkReal(-1.00000000000000))*(x5271)*(x5280)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x5276)))+(((x5261)*(x5273)))+(((IkReal(-1.00000000000000))*(x5278)*(x5280)))+(((IkReal(-1.00000000000000))*(cj0)*(x5270)*(x5275)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5275)))+(((IkReal(0.0100000000000000))*(sj0)*(x5260)))+(((IkReal(0.0100000000000000))*(x5258)*(x5271))));
16294 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
16295 {
16296 {
16297 IkReal j3array[1], cj3array[1], sj3array[1];
16298 bool j3valid[1]={false};
16299 _nj3 = 1;
16300 IkReal x5282=((cj5)*(r02));
16301 IkReal x5283=((cj0)*(sj5));
16302 IkReal x5284=((r10)*(sj6));
16303 IkReal x5285=((IkReal(1.00000000000000))*(cj6));
16304 IkReal x5286=((sj0)*(sj5));
16305 IkReal x5287=((cj5)*(r12));
16306 IkReal x5288=((IkReal(1.00000000000000))*(r00)*(sj6));
16307 if( IKabs(((((IkReal(-1.00000000000000))*(x5286)*(x5288)))+(((IkReal(-1.00000000000000))*(cj0)*(x5287)))+(((sj0)*(x5282)))+(((IkReal(-1.00000000000000))*(r01)*(x5285)*(x5286)))+(((cj6)*(r11)*(x5283)))+(((x5283)*(x5284))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x5283)*(x5288)))+(((sj0)*(x5287)))+(((IkReal(-1.00000000000000))*(r11)*(x5285)*(x5286)))+(((IkReal(-1.00000000000000))*(r01)*(x5283)*(x5285)))+(((cj0)*(x5282)))+(((IkReal(-1.00000000000000))*(x5284)*(x5286))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x5286)*(x5288)))+(((IkReal(-1.00000000000000))*(cj0)*(x5287)))+(((sj0)*(x5282)))+(((IkReal(-1.00000000000000))*(r01)*(x5285)*(x5286)))+(((cj6)*(r11)*(x5283)))+(((x5283)*(x5284)))))+IKsqr(((((IkReal(-1.00000000000000))*(x5283)*(x5288)))+(((sj0)*(x5287)))+(((IkReal(-1.00000000000000))*(r11)*(x5285)*(x5286)))+(((IkReal(-1.00000000000000))*(r01)*(x5283)*(x5285)))+(((cj0)*(x5282)))+(((IkReal(-1.00000000000000))*(x5284)*(x5286)))))-1) <= IKFAST_SINCOS_THRESH )
16308     continue;
16309 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x5286)*(x5288)))+(((IkReal(-1.00000000000000))*(cj0)*(x5287)))+(((sj0)*(x5282)))+(((IkReal(-1.00000000000000))*(r01)*(x5285)*(x5286)))+(((cj6)*(r11)*(x5283)))+(((x5283)*(x5284)))), ((((IkReal(-1.00000000000000))*(x5283)*(x5288)))+(((sj0)*(x5287)))+(((IkReal(-1.00000000000000))*(r11)*(x5285)*(x5286)))+(((IkReal(-1.00000000000000))*(r01)*(x5283)*(x5285)))+(((cj0)*(x5282)))+(((IkReal(-1.00000000000000))*(x5284)*(x5286)))));
16310 sj3array[0]=IKsin(j3array[0]);
16311 cj3array[0]=IKcos(j3array[0]);
16312 if( j3array[0] > IKPI )
16313 {
16314     j3array[0]-=IK2PI;
16315 }
16316 else if( j3array[0] < -IKPI )
16317 {    j3array[0]+=IK2PI;
16318 }
16319 j3valid[0] = true;
16320 for(int ij3 = 0; ij3 < 1; ++ij3)
16321 {
16322 if( !j3valid[ij3] )
16323 {
16324     continue;
16325 }
16326 _ij3[0] = ij3; _ij3[1] = -1;
16327 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16328 {
16329 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16330 {
16331     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16332 }
16333 }
16334 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16335 {
16336 IkReal evalcond[4];
16337 IkReal x5289=IKsin(j3);
16338 IkReal x5290=((sj0)*(sj5));
16339 IkReal x5291=((r00)*(sj6));
16340 IkReal x5292=((IkReal(1.00000000000000))*(cj4));
16341 IkReal x5293=((cj6)*(sj0));
16342 IkReal x5294=((r00)*(sj4));
16343 IkReal x5295=((cj0)*(cj5));
16344 IkReal x5296=((cj6)*(r01));
16345 IkReal x5297=((cj5)*(sj0));
16346 IkReal x5298=((cj0)*(sj5));
16347 IkReal x5299=((cj6)*(r11));
16348 IkReal x5300=((r10)*(sj6));
16349 IkReal x5301=((r10)*(sj4));
16350 IkReal x5302=((IkReal(1.00000000000000))*(IKcos(j3)));
16351 IkReal x5303=((cj0)*(sj4)*(sj6));
16352 IkReal x5304=((sj0)*(sj4)*(sj6));
16353 IkReal x5305=((IkReal(1.00000000000000))*(cj0)*(cj6));
16354 evalcond[0]=((x5289)+(((r12)*(x5295)))+(((x5290)*(x5296)))+(((IkReal(-1.00000000000000))*(r02)*(x5297)))+(((IkReal(-1.00000000000000))*(x5298)*(x5299)))+(((IkReal(-1.00000000000000))*(x5298)*(x5300)))+(((x5290)*(x5291))));
16355 evalcond[1]=((((IkReal(-1.00000000000000))*(x5296)*(x5298)))+(((r12)*(x5297)))+(((IkReal(-1.00000000000000))*(x5290)*(x5300)))+(((IkReal(-1.00000000000000))*(x5290)*(x5299)))+(((IkReal(-1.00000000000000))*(x5302)))+(((IkReal(-1.00000000000000))*(x5291)*(x5298)))+(((r02)*(x5295))));
16356 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x5292)*(x5298)))+(((cj4)*(cj5)*(r01)*(x5293)))+(((IkReal(-1.00000000000000))*(x5301)*(x5305)))+(((cj4)*(r02)*(x5290)))+(((cj4)*(x5291)*(x5297)))+(((x5293)*(x5294)))+(((IkReal(-1.00000000000000))*(x5302)))+(((r11)*(x5303)))+(((IkReal(-1.00000000000000))*(x5292)*(x5295)*(x5300)))+(((IkReal(-1.00000000000000))*(r01)*(x5304)))+(((IkReal(-1.00000000000000))*(x5292)*(x5295)*(x5299))));
16357 evalcond[3]=((((IkReal(-1.00000000000000))*(x5292)*(x5297)*(x5300)))+(((IkReal(-1.00000000000000))*(x5291)*(x5292)*(x5295)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x5292)*(x5293)))+(((r11)*(x5304)))+(((r01)*(x5303)))+(((IkReal(-1.00000000000000))*(x5294)*(x5305)))+(((IkReal(-1.00000000000000))*(x5293)*(x5301)))+(((IkReal(-1.00000000000000))*(r12)*(x5290)*(x5292)))+(((IkReal(-1.00000000000000))*(x5289)))+(((IkReal(-1.00000000000000))*(x5292)*(x5295)*(x5296)))+(((IkReal(-1.00000000000000))*(r02)*(x5292)*(x5298))));
16358 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16359 {
16360 continue;
16361 }
16362 }
16363 
16364 {
16365 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16366 vinfos[0].jointtype = 1;
16367 vinfos[0].foffset = j0;
16368 vinfos[0].indices[0] = _ij0[0];
16369 vinfos[0].indices[1] = _ij0[1];
16370 vinfos[0].maxsolutions = _nj0;
16371 vinfos[1].jointtype = 1;
16372 vinfos[1].foffset = j1;
16373 vinfos[1].indices[0] = _ij1[0];
16374 vinfos[1].indices[1] = _ij1[1];
16375 vinfos[1].maxsolutions = _nj1;
16376 vinfos[2].jointtype = 1;
16377 vinfos[2].foffset = j2;
16378 vinfos[2].indices[0] = _ij2[0];
16379 vinfos[2].indices[1] = _ij2[1];
16380 vinfos[2].maxsolutions = _nj2;
16381 vinfos[3].jointtype = 1;
16382 vinfos[3].foffset = j3;
16383 vinfos[3].indices[0] = _ij3[0];
16384 vinfos[3].indices[1] = _ij3[1];
16385 vinfos[3].maxsolutions = _nj3;
16386 vinfos[4].jointtype = 1;
16387 vinfos[4].foffset = j4;
16388 vinfos[4].indices[0] = _ij4[0];
16389 vinfos[4].indices[1] = _ij4[1];
16390 vinfos[4].maxsolutions = _nj4;
16391 vinfos[5].jointtype = 1;
16392 vinfos[5].foffset = j5;
16393 vinfos[5].indices[0] = _ij5[0];
16394 vinfos[5].indices[1] = _ij5[1];
16395 vinfos[5].maxsolutions = _nj5;
16396 vinfos[6].jointtype = 1;
16397 vinfos[6].foffset = j6;
16398 vinfos[6].indices[0] = _ij6[0];
16399 vinfos[6].indices[1] = _ij6[1];
16400 vinfos[6].maxsolutions = _nj6;
16401 std::vector<int> vfree(0);
16402 solutions.AddSolution(vinfos,vfree);
16403 }
16404 }
16405 }
16406 
16407 } else
16408 {
16409 IkReal x5306=((IkReal(1.00000000000000))*(cj0));
16410 IkReal x5307=((cj4)*(sj6));
16411 IkReal x5308=((sj0)*(sj4));
16412 IkReal x5309=((cj5)*(sj6));
16413 IkReal x5310=((sj4)*(sj5));
16414 IkReal x5311=((r12)*(sj5));
16415 IkReal x5312=((IkReal(0.374290000000000))*(cj5));
16416 IkReal x5313=((r02)*(sj0));
16417 IkReal x5314=((r20)*(sj4));
16418 IkReal x5315=((IkReal(1.00000000000000))*(sj0));
16419 IkReal x5316=((IkReal(1.00000000000000))*(cj5));
16420 IkReal x5317=((cj0)*(r10));
16421 IkReal x5318=((cj4)*(cj6));
16422 IkReal x5319=((r00)*(sj0));
16423 IkReal x5320=((cj6)*(r21));
16424 IkReal x5321=((IkReal(0.374290000000000))*(sj5));
16425 IkReal x5322=((cj0)*(r00));
16426 IkReal x5323=((IkReal(0.0100000000000000))*(sj5));
16427 IkReal x5324=((cj0)*(r02));
16428 IkReal x5325=((cj5)*(sj4));
16429 IkReal x5326=((cj6)*(r01));
16430 IkReal x5327=((cj6)*(r11));
16431 IkReal x5328=((r01)*(sj0));
16432 IkReal x5329=((r10)*(sj0));
16433 IkReal x5330=((IkReal(0.0100000000000000))*(cj5)*(cj6));
16434 IkReal x5331=((sj6)*(x5321));
16435 IkReal x5332=((cj0)*(cj6)*(x5321));
16436 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
16437 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x5316)))+(((sj5)*(x5320)))+(((r20)*(sj5)*(sj6))));
16438 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x5318)))+(((r21)*(x5307)))+(((x5320)*(x5325)))+(((r22)*(x5310)))+(((x5309)*(x5314))));
16439 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x5323)))+(((IkReal(-1.00000000000000))*(r22)*(x5312)))+(((IkReal(-0.0100000000000000))*(r20)*(x5309)))+(((IkReal(-0.0100000000000000))*(cj5)*(x5320)))+(((x5320)*(x5321)))+(pz)+(((r20)*(x5331))));
16440 evalcond[4]=((((cj5)*(r20)*(x5307)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x5314)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x5318))));
16441 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x5306)*(x5310)))+(((IkReal(-1.00000000000000))*(r11)*(x5306)*(x5307)))+(((r02)*(sj5)*(x5308)))+(((IkReal(-1.00000000000000))*(r00)*(x5315)*(x5318)))+(((x5307)*(x5328)))+(((r00)*(x5308)*(x5309)))+(((IkReal(-1.00000000000000))*(x5306)*(x5325)*(x5327)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x5306)*(x5309)))+(((x5317)*(x5318)))+(((cj5)*(x5308)*(x5326))));
16442 evalcond[6]=((((x5318)*(x5322)))+(((IkReal(-1.00000000000000))*(x5308)*(x5311)))+(((IkReal(-1.00000000000000))*(x5308)*(x5316)*(x5327)))+(((IkReal(-1.00000000000000))*(r10)*(x5308)*(x5309)))+(((IkReal(-1.00000000000000))*(r02)*(x5306)*(x5310)))+(((IkReal(-1.00000000000000))*(x5306)*(x5325)*(x5326)))+(((IkReal(-1.00000000000000))*(r11)*(x5307)*(x5315)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x5306)*(x5309)))+(((IkReal(-1.00000000000000))*(r01)*(x5306)*(x5307)))+(((x5318)*(x5329))));
16443 evalcond[7]=((IkReal(-0.0690000000000000))+(((sj0)*(x5321)*(x5326)))+(((x5319)*(x5331)))+(((cj0)*(r12)*(x5312)))+(((IkReal(-1.00000000000000))*(x5312)*(x5313)))+(((IkReal(0.0100000000000000))*(x5309)*(x5317)))+(((IkReal(-1.00000000000000))*(x5313)*(x5323)))+(((IkReal(-0.0100000000000000))*(x5309)*(x5319)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5327)))+(((IkReal(-1.00000000000000))*(py)*(x5306)))+(((IkReal(0.0100000000000000))*(cj0)*(x5311)))+(((IkReal(-1.00000000000000))*(x5317)*(x5331)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x5326)))+(((IkReal(-1.00000000000000))*(cj0)*(x5321)*(x5327))));
16444 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(x5309)*(x5322)))+(((IkReal(-1.00000000000000))*(cj0)*(x5321)*(x5326)))+(((x5312)*(x5324)))+(((IkReal(-1.00000000000000))*(py)*(x5315)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x5327)))+(((IkReal(-1.00000000000000))*(sj0)*(x5321)*(x5327)))+(((IkReal(-1.00000000000000))*(x5329)*(x5331)))+(((x5323)*(x5324)))+(((IkReal(-1.00000000000000))*(x5322)*(x5331)))+(((IkReal(0.0100000000000000))*(sj0)*(x5311)))+(((IkReal(-1.00000000000000))*(px)*(x5306)))+(((r12)*(sj0)*(x5312)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5326)))+(((IkReal(0.0100000000000000))*(x5309)*(x5329))));
16445 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
16446 {
16447 {
16448 IkReal j3array[1], cj3array[1], sj3array[1];
16449 bool j3valid[1]={false};
16450 _nj3 = 1;
16451 IkReal x5333=((IkReal(1.00000000000000))*(cj5));
16452 IkReal x5334=((r10)*(sj5)*(sj6));
16453 IkReal x5335=((cj6)*(sj0)*(sj5));
16454 IkReal x5336=((r00)*(sj5)*(sj6));
16455 IkReal x5337=((cj0)*(cj6)*(sj5));
16456 if( IKabs(((((cj0)*(x5334)))+(((IkReal(-1.00000000000000))*(sj0)*(x5336)))+(((IkReal(-1.00000000000000))*(r01)*(x5335)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5333)))+(((r11)*(x5337))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj0)*(x5334)))+(((cj0)*(x5336)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5333)))+(((r01)*(x5337)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5333)))+(((r11)*(x5335))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(x5334)))+(((IkReal(-1.00000000000000))*(sj0)*(x5336)))+(((IkReal(-1.00000000000000))*(r01)*(x5335)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5333)))+(((r11)*(x5337)))))+IKsqr(((((sj0)*(x5334)))+(((cj0)*(x5336)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5333)))+(((r01)*(x5337)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5333)))+(((r11)*(x5335)))))-1) <= IKFAST_SINCOS_THRESH )
16457     continue;
16458 j3array[0]=IKatan2(((((cj0)*(x5334)))+(((IkReal(-1.00000000000000))*(sj0)*(x5336)))+(((IkReal(-1.00000000000000))*(r01)*(x5335)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5333)))+(((r11)*(x5337)))), ((((sj0)*(x5334)))+(((cj0)*(x5336)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5333)))+(((r01)*(x5337)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5333)))+(((r11)*(x5335)))));
16459 sj3array[0]=IKsin(j3array[0]);
16460 cj3array[0]=IKcos(j3array[0]);
16461 if( j3array[0] > IKPI )
16462 {
16463     j3array[0]-=IK2PI;
16464 }
16465 else if( j3array[0] < -IKPI )
16466 {    j3array[0]+=IK2PI;
16467 }
16468 j3valid[0] = true;
16469 for(int ij3 = 0; ij3 < 1; ++ij3)
16470 {
16471 if( !j3valid[ij3] )
16472 {
16473     continue;
16474 }
16475 _ij3[0] = ij3; _ij3[1] = -1;
16476 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16477 {
16478 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16479 {
16480     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16481 }
16482 }
16483 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16484 {
16485 IkReal evalcond[4];
16486 IkReal x5338=IKcos(j3);
16487 IkReal x5339=IKsin(j3);
16488 IkReal x5340=((sj0)*(sj5));
16489 IkReal x5341=((r00)*(sj6));
16490 IkReal x5342=((IkReal(1.00000000000000))*(cj4));
16491 IkReal x5343=((cj6)*(sj0));
16492 IkReal x5344=((r00)*(sj4));
16493 IkReal x5345=((cj0)*(cj5));
16494 IkReal x5346=((cj6)*(r01));
16495 IkReal x5347=((cj5)*(sj0));
16496 IkReal x5348=((cj0)*(sj5));
16497 IkReal x5349=((cj6)*(r11));
16498 IkReal x5350=((r10)*(sj6));
16499 IkReal x5351=((r10)*(sj4));
16500 IkReal x5352=((cj0)*(sj4)*(sj6));
16501 IkReal x5353=((sj0)*(sj4)*(sj6));
16502 IkReal x5354=((IkReal(1.00000000000000))*(cj0)*(cj6));
16503 evalcond[0]=((((r12)*(x5345)))+(((IkReal(-1.00000000000000))*(x5348)*(x5350)))+(((IkReal(-1.00000000000000))*(x5348)*(x5349)))+(((IkReal(-1.00000000000000))*(r02)*(x5347)))+(((x5340)*(x5346)))+(((x5340)*(x5341)))+(x5339));
16504 evalcond[1]=((((IkReal(-1.00000000000000))*(x5340)*(x5349)))+(((IkReal(-1.00000000000000))*(x5340)*(x5350)))+(((IkReal(-1.00000000000000))*(x5346)*(x5348)))+(((r02)*(x5345)))+(((IkReal(-1.00000000000000))*(x5341)*(x5348)))+(((r12)*(x5347)))+(x5338));
16505 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x5353)))+(((IkReal(-1.00000000000000))*(r12)*(x5342)*(x5348)))+(((IkReal(-1.00000000000000))*(x5342)*(x5345)*(x5350)))+(((cj4)*(x5341)*(x5347)))+(((IkReal(-1.00000000000000))*(x5342)*(x5345)*(x5349)))+(((cj4)*(cj5)*(r01)*(x5343)))+(((IkReal(-1.00000000000000))*(x5338)))+(((x5343)*(x5344)))+(((r11)*(x5352)))+(((IkReal(-1.00000000000000))*(x5351)*(x5354)))+(((cj4)*(r02)*(x5340))));
16506 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x5340)*(x5342)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x5342)*(x5343)))+(((IkReal(-1.00000000000000))*(x5343)*(x5351)))+(((IkReal(-1.00000000000000))*(x5341)*(x5342)*(x5345)))+(((IkReal(-1.00000000000000))*(x5342)*(x5345)*(x5346)))+(((IkReal(-1.00000000000000))*(x5344)*(x5354)))+(((IkReal(-1.00000000000000))*(r02)*(x5342)*(x5348)))+(((r11)*(x5353)))+(((r01)*(x5352)))+(((IkReal(-1.00000000000000))*(x5342)*(x5347)*(x5350)))+(x5339));
16507 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16508 {
16509 continue;
16510 }
16511 }
16512 
16513 {
16514 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16515 vinfos[0].jointtype = 1;
16516 vinfos[0].foffset = j0;
16517 vinfos[0].indices[0] = _ij0[0];
16518 vinfos[0].indices[1] = _ij0[1];
16519 vinfos[0].maxsolutions = _nj0;
16520 vinfos[1].jointtype = 1;
16521 vinfos[1].foffset = j1;
16522 vinfos[1].indices[0] = _ij1[0];
16523 vinfos[1].indices[1] = _ij1[1];
16524 vinfos[1].maxsolutions = _nj1;
16525 vinfos[2].jointtype = 1;
16526 vinfos[2].foffset = j2;
16527 vinfos[2].indices[0] = _ij2[0];
16528 vinfos[2].indices[1] = _ij2[1];
16529 vinfos[2].maxsolutions = _nj2;
16530 vinfos[3].jointtype = 1;
16531 vinfos[3].foffset = j3;
16532 vinfos[3].indices[0] = _ij3[0];
16533 vinfos[3].indices[1] = _ij3[1];
16534 vinfos[3].maxsolutions = _nj3;
16535 vinfos[4].jointtype = 1;
16536 vinfos[4].foffset = j4;
16537 vinfos[4].indices[0] = _ij4[0];
16538 vinfos[4].indices[1] = _ij4[1];
16539 vinfos[4].maxsolutions = _nj4;
16540 vinfos[5].jointtype = 1;
16541 vinfos[5].foffset = j5;
16542 vinfos[5].indices[0] = _ij5[0];
16543 vinfos[5].indices[1] = _ij5[1];
16544 vinfos[5].maxsolutions = _nj5;
16545 vinfos[6].jointtype = 1;
16546 vinfos[6].foffset = j6;
16547 vinfos[6].indices[0] = _ij6[0];
16548 vinfos[6].indices[1] = _ij6[1];
16549 vinfos[6].maxsolutions = _nj6;
16550 std::vector<int> vfree(0);
16551 solutions.AddSolution(vinfos,vfree);
16552 }
16553 }
16554 }
16555 
16556 } else
16557 {
16558 if( 1 )
16559 {
16560 continue;
16561 
16562 } else
16563 {
16564 }
16565 }
16566 }
16567 }
16568 }
16569 }
16570 
16571 } else
16572 {
16573 {
16574 IkReal j3array[1], cj3array[1], sj3array[1];
16575 bool j3valid[1]={false};
16576 _nj3 = 1;
16577 IkReal x5355=((cj5)*(r02));
16578 IkReal x5356=((cj0)*(sj5));
16579 IkReal x5357=((r10)*(sj6));
16580 IkReal x5358=((IkReal(1.00000000000000))*(cj6));
16581 IkReal x5359=((sj0)*(sj5));
16582 IkReal x5360=((cj5)*(r12));
16583 IkReal x5361=((IkReal(1.00000000000000))*(r00)*(sj6));
16584 if( IKabs(((((x5356)*(x5357)))+(((cj6)*(r11)*(x5356)))+(((IkReal(-1.00000000000000))*(r01)*(x5358)*(x5359)))+(((sj0)*(x5355)))+(((IkReal(-1.00000000000000))*(x5359)*(x5361)))+(((IkReal(-1.00000000000000))*(cj0)*(x5360))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x5357)*(x5359)))+(((sj0)*(x5360)))+(((IkReal(-1.00000000000000))*(r01)*(x5356)*(x5358)))+(((IkReal(-1.00000000000000))*(r11)*(x5358)*(x5359)))+(((IkReal(-1.00000000000000))*(x5356)*(x5361)))+(((cj0)*(x5355))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x5356)*(x5357)))+(((cj6)*(r11)*(x5356)))+(((IkReal(-1.00000000000000))*(r01)*(x5358)*(x5359)))+(((sj0)*(x5355)))+(((IkReal(-1.00000000000000))*(x5359)*(x5361)))+(((IkReal(-1.00000000000000))*(cj0)*(x5360)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x5357)*(x5359)))+(((sj0)*(x5360)))+(((IkReal(-1.00000000000000))*(r01)*(x5356)*(x5358)))+(((IkReal(-1.00000000000000))*(r11)*(x5358)*(x5359)))+(((IkReal(-1.00000000000000))*(x5356)*(x5361)))+(((cj0)*(x5355)))))))-1) <= IKFAST_SINCOS_THRESH )
16585     continue;
16586 j3array[0]=IKatan2(((((x5356)*(x5357)))+(((cj6)*(r11)*(x5356)))+(((IkReal(-1.00000000000000))*(r01)*(x5358)*(x5359)))+(((sj0)*(x5355)))+(((IkReal(-1.00000000000000))*(x5359)*(x5361)))+(((IkReal(-1.00000000000000))*(cj0)*(x5360)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x5357)*(x5359)))+(((sj0)*(x5360)))+(((IkReal(-1.00000000000000))*(r01)*(x5356)*(x5358)))+(((IkReal(-1.00000000000000))*(r11)*(x5358)*(x5359)))+(((IkReal(-1.00000000000000))*(x5356)*(x5361)))+(((cj0)*(x5355)))))));
16587 sj3array[0]=IKsin(j3array[0]);
16588 cj3array[0]=IKcos(j3array[0]);
16589 if( j3array[0] > IKPI )
16590 {
16591     j3array[0]-=IK2PI;
16592 }
16593 else if( j3array[0] < -IKPI )
16594 {    j3array[0]+=IK2PI;
16595 }
16596 j3valid[0] = true;
16597 for(int ij3 = 0; ij3 < 1; ++ij3)
16598 {
16599 if( !j3valid[ij3] )
16600 {
16601     continue;
16602 }
16603 _ij3[0] = ij3; _ij3[1] = -1;
16604 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16605 {
16606 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16607 {
16608     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16609 }
16610 }
16611 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16612 {
16613 IkReal evalcond[6];
16614 IkReal x5362=IKsin(j3);
16615 IkReal x5363=IKcos(j3);
16616 IkReal x5364=((sj0)*(sj5));
16617 IkReal x5365=((r00)*(sj6));
16618 IkReal x5366=((IkReal(1.00000000000000))*(cj4));
16619 IkReal x5367=((cj6)*(r01));
16620 IkReal x5368=((cj0)*(cj5));
16621 IkReal x5369=((cj5)*(sj0));
16622 IkReal x5370=((cj6)*(r11));
16623 IkReal x5371=((cj0)*(sj5));
16624 IkReal x5372=((IkReal(1.00000000000000))*(cj1));
16625 IkReal x5373=((cj6)*(sj4));
16626 IkReal x5374=((IkReal(1.00000000000000))*(sj1));
16627 IkReal x5375=((cj4)*(cj5));
16628 IkReal x5376=((cj6)*(r21));
16629 IkReal x5377=((r20)*(sj6));
16630 IkReal x5378=((r10)*(sj6));
16631 IkReal x5379=((IkReal(1.00000000000000))*(cj0));
16632 IkReal x5380=((cj0)*(sj4)*(sj6));
16633 IkReal x5381=((sj0)*(sj4)*(sj6));
16634 evalcond[0]=((((sj5)*(x5377)))+(((sj5)*(x5376)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x5363)*(x5374))));
16635 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5362)*(x5374)))+(((cj4)*(r22)*(sj5)))+(((x5375)*(x5376)))+(((r20)*(x5373)))+(((x5375)*(x5377))));
16636 evalcond[2]=((((IkReal(-1.00000000000000))*(x5371)*(x5378)))+(((x5364)*(x5367)))+(((r12)*(x5368)))+(((IkReal(-1.00000000000000))*(x5370)*(x5371)))+(((IkReal(-1.00000000000000))*(r02)*(x5369)))+(x5362)+(((x5364)*(x5365))));
16637 evalcond[3]=((((IkReal(-1.00000000000000))*(x5363)*(x5372)))+(((r12)*(x5369)))+(((IkReal(-1.00000000000000))*(x5365)*(x5371)))+(((IkReal(-1.00000000000000))*(x5364)*(x5378)))+(((r02)*(x5368)))+(((IkReal(-1.00000000000000))*(x5367)*(x5371)))+(((IkReal(-1.00000000000000))*(x5364)*(x5370))));
16638 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x5366)*(x5371)))+(((cj4)*(x5367)*(x5369)))+(((r00)*(sj0)*(x5373)))+(((IkReal(-1.00000000000000))*(r01)*(x5381)))+(((IkReal(-1.00000000000000))*(r10)*(x5373)*(x5379)))+(((IkReal(-1.00000000000000))*(x5363)))+(((r11)*(x5380)))+(((cj4)*(x5365)*(x5369)))+(((IkReal(-1.00000000000000))*(x5366)*(x5368)*(x5370)))+(((cj4)*(r02)*(x5364)))+(((IkReal(-1.00000000000000))*(x5366)*(x5368)*(x5378))));
16639 evalcond[5]=((((IkReal(-1.00000000000000))*(x5362)*(x5372)))+(((IkReal(-1.00000000000000))*(r02)*(x5366)*(x5371)))+(((IkReal(-1.00000000000000))*(x5366)*(x5367)*(x5368)))+(((IkReal(-1.00000000000000))*(x5366)*(x5369)*(x5378)))+(((r01)*(x5380)))+(((r11)*(x5381)))+(((IkReal(-1.00000000000000))*(x5365)*(x5366)*(x5368)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5373)))+(((IkReal(-1.00000000000000))*(r12)*(x5364)*(x5366)))+(((IkReal(-1.00000000000000))*(x5366)*(x5369)*(x5370)))+(((IkReal(-1.00000000000000))*(r00)*(x5373)*(x5379))));
16640 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
16641 {
16642 continue;
16643 }
16644 }
16645 
16646 {
16647 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16648 vinfos[0].jointtype = 1;
16649 vinfos[0].foffset = j0;
16650 vinfos[0].indices[0] = _ij0[0];
16651 vinfos[0].indices[1] = _ij0[1];
16652 vinfos[0].maxsolutions = _nj0;
16653 vinfos[1].jointtype = 1;
16654 vinfos[1].foffset = j1;
16655 vinfos[1].indices[0] = _ij1[0];
16656 vinfos[1].indices[1] = _ij1[1];
16657 vinfos[1].maxsolutions = _nj1;
16658 vinfos[2].jointtype = 1;
16659 vinfos[2].foffset = j2;
16660 vinfos[2].indices[0] = _ij2[0];
16661 vinfos[2].indices[1] = _ij2[1];
16662 vinfos[2].maxsolutions = _nj2;
16663 vinfos[3].jointtype = 1;
16664 vinfos[3].foffset = j3;
16665 vinfos[3].indices[0] = _ij3[0];
16666 vinfos[3].indices[1] = _ij3[1];
16667 vinfos[3].maxsolutions = _nj3;
16668 vinfos[4].jointtype = 1;
16669 vinfos[4].foffset = j4;
16670 vinfos[4].indices[0] = _ij4[0];
16671 vinfos[4].indices[1] = _ij4[1];
16672 vinfos[4].maxsolutions = _nj4;
16673 vinfos[5].jointtype = 1;
16674 vinfos[5].foffset = j5;
16675 vinfos[5].indices[0] = _ij5[0];
16676 vinfos[5].indices[1] = _ij5[1];
16677 vinfos[5].maxsolutions = _nj5;
16678 vinfos[6].jointtype = 1;
16679 vinfos[6].foffset = j6;
16680 vinfos[6].indices[0] = _ij6[0];
16681 vinfos[6].indices[1] = _ij6[1];
16682 vinfos[6].maxsolutions = _nj6;
16683 std::vector<int> vfree(0);
16684 solutions.AddSolution(vinfos,vfree);
16685 }
16686 }
16687 }
16688 
16689 }
16690 
16691 }
16692 
16693 } else
16694 {
16695 {
16696 IkReal j3array[1], cj3array[1], sj3array[1];
16697 bool j3valid[1]={false};
16698 _nj3 = 1;
16699 IkReal x5382=((sj5)*(sj6));
16700 IkReal x5383=((IkReal(1.00000000000000))*(sj0));
16701 IkReal x5384=((cj6)*(sj5));
16702 IkReal x5385=((IkReal(1.00000000000000))*(cj5));
16703 if( IKabs(((((cj0)*(r10)*(x5382)))+(((cj0)*(r11)*(x5384)))+(((IkReal(-1.00000000000000))*(r01)*(x5383)*(x5384)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x5382)*(x5383)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5385))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x5385)))+(((r21)*(x5384)))+(((r20)*(x5382))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r10)*(x5382)))+(((cj0)*(r11)*(x5384)))+(((IkReal(-1.00000000000000))*(r01)*(x5383)*(x5384)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x5382)*(x5383)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5385)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x5385)))+(((r21)*(x5384)))+(((r20)*(x5382)))))))-1) <= IKFAST_SINCOS_THRESH )
16704     continue;
16705 j3array[0]=IKatan2(((((cj0)*(r10)*(x5382)))+(((cj0)*(r11)*(x5384)))+(((IkReal(-1.00000000000000))*(r01)*(x5383)*(x5384)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x5382)*(x5383)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5385)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x5385)))+(((r21)*(x5384)))+(((r20)*(x5382)))))));
16706 sj3array[0]=IKsin(j3array[0]);
16707 cj3array[0]=IKcos(j3array[0]);
16708 if( j3array[0] > IKPI )
16709 {
16710     j3array[0]-=IK2PI;
16711 }
16712 else if( j3array[0] < -IKPI )
16713 {    j3array[0]+=IK2PI;
16714 }
16715 j3valid[0] = true;
16716 for(int ij3 = 0; ij3 < 1; ++ij3)
16717 {
16718 if( !j3valid[ij3] )
16719 {
16720     continue;
16721 }
16722 _ij3[0] = ij3; _ij3[1] = -1;
16723 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16724 {
16725 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16726 {
16727     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16728 }
16729 }
16730 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16731 {
16732 IkReal evalcond[6];
16733 IkReal x5386=IKsin(j3);
16734 IkReal x5387=IKcos(j3);
16735 IkReal x5388=((sj0)*(sj5));
16736 IkReal x5389=((r00)*(sj6));
16737 IkReal x5390=((IkReal(1.00000000000000))*(cj4));
16738 IkReal x5391=((cj6)*(r01));
16739 IkReal x5392=((cj0)*(cj5));
16740 IkReal x5393=((cj5)*(sj0));
16741 IkReal x5394=((cj6)*(r11));
16742 IkReal x5395=((cj0)*(sj5));
16743 IkReal x5396=((IkReal(1.00000000000000))*(cj1));
16744 IkReal x5397=((cj6)*(sj4));
16745 IkReal x5398=((IkReal(1.00000000000000))*(sj1));
16746 IkReal x5399=((cj4)*(cj5));
16747 IkReal x5400=((cj6)*(r21));
16748 IkReal x5401=((r20)*(sj6));
16749 IkReal x5402=((r10)*(sj6));
16750 IkReal x5403=((IkReal(1.00000000000000))*(cj0));
16751 IkReal x5404=((cj0)*(sj4)*(sj6));
16752 IkReal x5405=((sj0)*(sj4)*(sj6));
16753 evalcond[0]=((((IkReal(-1.00000000000000))*(x5387)*(x5398)))+(((sj5)*(x5400)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5401))));
16754 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x5399)*(x5400)))+(((IkReal(-1.00000000000000))*(x5386)*(x5398)))+(((x5399)*(x5401)))+(((r20)*(x5397))));
16755 evalcond[2]=((((r12)*(x5392)))+(((IkReal(-1.00000000000000))*(r02)*(x5393)))+(((IkReal(-1.00000000000000))*(x5395)*(x5402)))+(((x5388)*(x5391)))+(((x5388)*(x5389)))+(x5386)+(((IkReal(-1.00000000000000))*(x5394)*(x5395))));
16756 evalcond[3]=((((IkReal(-1.00000000000000))*(x5388)*(x5402)))+(((IkReal(-1.00000000000000))*(x5391)*(x5395)))+(((IkReal(-1.00000000000000))*(x5388)*(x5394)))+(((IkReal(-1.00000000000000))*(x5389)*(x5395)))+(((IkReal(-1.00000000000000))*(x5387)*(x5396)))+(((r02)*(x5392)))+(((r12)*(x5393))));
16757 evalcond[4]=((((cj4)*(x5391)*(x5393)))+(((IkReal(-1.00000000000000))*(x5390)*(x5392)*(x5402)))+(((IkReal(-1.00000000000000))*(x5387)))+(((r11)*(x5404)))+(((IkReal(-1.00000000000000))*(r10)*(x5397)*(x5403)))+(((r00)*(sj0)*(x5397)))+(((IkReal(-1.00000000000000))*(r12)*(x5390)*(x5395)))+(((IkReal(-1.00000000000000))*(x5390)*(x5392)*(x5394)))+(((cj4)*(x5389)*(x5393)))+(((IkReal(-1.00000000000000))*(r01)*(x5405)))+(((cj4)*(r02)*(x5388))));
16758 evalcond[5]=((((IkReal(-1.00000000000000))*(x5386)*(x5396)))+(((IkReal(-1.00000000000000))*(r12)*(x5388)*(x5390)))+(((r11)*(x5405)))+(((IkReal(-1.00000000000000))*(x5390)*(x5393)*(x5402)))+(((IkReal(-1.00000000000000))*(x5390)*(x5393)*(x5394)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5397)))+(((IkReal(-1.00000000000000))*(r02)*(x5390)*(x5395)))+(((IkReal(-1.00000000000000))*(r00)*(x5397)*(x5403)))+(((r01)*(x5404)))+(((IkReal(-1.00000000000000))*(x5389)*(x5390)*(x5392)))+(((IkReal(-1.00000000000000))*(x5390)*(x5391)*(x5392))));
16759 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
16760 {
16761 continue;
16762 }
16763 }
16764 
16765 {
16766 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16767 vinfos[0].jointtype = 1;
16768 vinfos[0].foffset = j0;
16769 vinfos[0].indices[0] = _ij0[0];
16770 vinfos[0].indices[1] = _ij0[1];
16771 vinfos[0].maxsolutions = _nj0;
16772 vinfos[1].jointtype = 1;
16773 vinfos[1].foffset = j1;
16774 vinfos[1].indices[0] = _ij1[0];
16775 vinfos[1].indices[1] = _ij1[1];
16776 vinfos[1].maxsolutions = _nj1;
16777 vinfos[2].jointtype = 1;
16778 vinfos[2].foffset = j2;
16779 vinfos[2].indices[0] = _ij2[0];
16780 vinfos[2].indices[1] = _ij2[1];
16781 vinfos[2].maxsolutions = _nj2;
16782 vinfos[3].jointtype = 1;
16783 vinfos[3].foffset = j3;
16784 vinfos[3].indices[0] = _ij3[0];
16785 vinfos[3].indices[1] = _ij3[1];
16786 vinfos[3].maxsolutions = _nj3;
16787 vinfos[4].jointtype = 1;
16788 vinfos[4].foffset = j4;
16789 vinfos[4].indices[0] = _ij4[0];
16790 vinfos[4].indices[1] = _ij4[1];
16791 vinfos[4].maxsolutions = _nj4;
16792 vinfos[5].jointtype = 1;
16793 vinfos[5].foffset = j5;
16794 vinfos[5].indices[0] = _ij5[0];
16795 vinfos[5].indices[1] = _ij5[1];
16796 vinfos[5].maxsolutions = _nj5;
16797 vinfos[6].jointtype = 1;
16798 vinfos[6].foffset = j6;
16799 vinfos[6].indices[0] = _ij6[0];
16800 vinfos[6].indices[1] = _ij6[1];
16801 vinfos[6].maxsolutions = _nj6;
16802 std::vector<int> vfree(0);
16803 solutions.AddSolution(vinfos,vfree);
16804 }
16805 }
16806 }
16807 
16808 }
16809 
16810 }
16811 
16812 } else
16813 {
16814 {
16815 IkReal j3array[1], cj3array[1], sj3array[1];
16816 bool j3valid[1]={false};
16817 _nj3 = 1;
16818 IkReal x5406=((r20)*(sj6));
16819 IkReal x5407=((cj4)*(cj5));
16820 IkReal x5408=((cj6)*(r21));
16821 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5406)*(x5407)))+(((x5407)*(x5408))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((sj5)*(x5408)))+(((sj5)*(x5406)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH )
16822     continue;
16823 j3array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5406)*(x5407)))+(((x5407)*(x5408)))))), ((gconst30)*(((((sj5)*(x5408)))+(((sj5)*(x5406)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))));
16824 sj3array[0]=IKsin(j3array[0]);
16825 cj3array[0]=IKcos(j3array[0]);
16826 if( j3array[0] > IKPI )
16827 {
16828     j3array[0]-=IK2PI;
16829 }
16830 else if( j3array[0] < -IKPI )
16831 {    j3array[0]+=IK2PI;
16832 }
16833 j3valid[0] = true;
16834 for(int ij3 = 0; ij3 < 1; ++ij3)
16835 {
16836 if( !j3valid[ij3] )
16837 {
16838     continue;
16839 }
16840 _ij3[0] = ij3; _ij3[1] = -1;
16841 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
16842 {
16843 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
16844 {
16845     j3valid[iij3]=false; _ij3[1] = iij3; break; 
16846 }
16847 }
16848 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
16849 {
16850 IkReal evalcond[6];
16851 IkReal x5409=IKsin(j3);
16852 IkReal x5410=IKcos(j3);
16853 IkReal x5411=((sj0)*(sj5));
16854 IkReal x5412=((r00)*(sj6));
16855 IkReal x5413=((IkReal(1.00000000000000))*(cj4));
16856 IkReal x5414=((cj6)*(r01));
16857 IkReal x5415=((cj0)*(cj5));
16858 IkReal x5416=((cj5)*(sj0));
16859 IkReal x5417=((cj6)*(r11));
16860 IkReal x5418=((cj0)*(sj5));
16861 IkReal x5419=((IkReal(1.00000000000000))*(cj1));
16862 IkReal x5420=((cj6)*(sj4));
16863 IkReal x5421=((IkReal(1.00000000000000))*(sj1));
16864 IkReal x5422=((cj4)*(cj5));
16865 IkReal x5423=((cj6)*(r21));
16866 IkReal x5424=((r20)*(sj6));
16867 IkReal x5425=((r10)*(sj6));
16868 IkReal x5426=((IkReal(1.00000000000000))*(cj0));
16869 IkReal x5427=((cj0)*(sj4)*(sj6));
16870 IkReal x5428=((sj0)*(sj4)*(sj6));
16871 evalcond[0]=((((sj5)*(x5424)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x5410)*(x5421)))+(((sj5)*(x5423))));
16872 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5422)*(x5424)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x5420)))+(((x5422)*(x5423)))+(((IkReal(-1.00000000000000))*(x5409)*(x5421))));
16873 evalcond[2]=((((IkReal(-1.00000000000000))*(x5418)*(x5425)))+(((r12)*(x5415)))+(((x5411)*(x5412)))+(((x5411)*(x5414)))+(((IkReal(-1.00000000000000))*(r02)*(x5416)))+(((IkReal(-1.00000000000000))*(x5417)*(x5418)))+(x5409));
16874 evalcond[3]=((((IkReal(-1.00000000000000))*(x5411)*(x5417)))+(((r02)*(x5415)))+(((IkReal(-1.00000000000000))*(x5414)*(x5418)))+(((IkReal(-1.00000000000000))*(x5412)*(x5418)))+(((IkReal(-1.00000000000000))*(x5410)*(x5419)))+(((r12)*(x5416)))+(((IkReal(-1.00000000000000))*(x5411)*(x5425))));
16875 evalcond[4]=((((IkReal(-1.00000000000000))*(x5413)*(x5415)*(x5425)))+(((cj4)*(x5414)*(x5416)))+(((IkReal(-1.00000000000000))*(r01)*(x5428)))+(((cj4)*(x5412)*(x5416)))+(((IkReal(-1.00000000000000))*(r12)*(x5413)*(x5418)))+(((IkReal(-1.00000000000000))*(r10)*(x5420)*(x5426)))+(((cj4)*(r02)*(x5411)))+(((r11)*(x5427)))+(((IkReal(-1.00000000000000))*(x5413)*(x5415)*(x5417)))+(((IkReal(-1.00000000000000))*(x5410)))+(((r00)*(sj0)*(x5420))));
16876 evalcond[5]=((((IkReal(-1.00000000000000))*(x5409)*(x5419)))+(((r01)*(x5427)))+(((IkReal(-1.00000000000000))*(x5412)*(x5413)*(x5415)))+(((IkReal(-1.00000000000000))*(x5413)*(x5414)*(x5415)))+(((IkReal(-1.00000000000000))*(r00)*(x5420)*(x5426)))+(((r11)*(x5428)))+(((IkReal(-1.00000000000000))*(x5413)*(x5416)*(x5425)))+(((IkReal(-1.00000000000000))*(r12)*(x5411)*(x5413)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5420)))+(((IkReal(-1.00000000000000))*(r02)*(x5413)*(x5418)))+(((IkReal(-1.00000000000000))*(x5413)*(x5416)*(x5417))));
16877 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
16878 {
16879 continue;
16880 }
16881 }
16882 
16883 {
16884 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
16885 vinfos[0].jointtype = 1;
16886 vinfos[0].foffset = j0;
16887 vinfos[0].indices[0] = _ij0[0];
16888 vinfos[0].indices[1] = _ij0[1];
16889 vinfos[0].maxsolutions = _nj0;
16890 vinfos[1].jointtype = 1;
16891 vinfos[1].foffset = j1;
16892 vinfos[1].indices[0] = _ij1[0];
16893 vinfos[1].indices[1] = _ij1[1];
16894 vinfos[1].maxsolutions = _nj1;
16895 vinfos[2].jointtype = 1;
16896 vinfos[2].foffset = j2;
16897 vinfos[2].indices[0] = _ij2[0];
16898 vinfos[2].indices[1] = _ij2[1];
16899 vinfos[2].maxsolutions = _nj2;
16900 vinfos[3].jointtype = 1;
16901 vinfos[3].foffset = j3;
16902 vinfos[3].indices[0] = _ij3[0];
16903 vinfos[3].indices[1] = _ij3[1];
16904 vinfos[3].maxsolutions = _nj3;
16905 vinfos[4].jointtype = 1;
16906 vinfos[4].foffset = j4;
16907 vinfos[4].indices[0] = _ij4[0];
16908 vinfos[4].indices[1] = _ij4[1];
16909 vinfos[4].maxsolutions = _nj4;
16910 vinfos[5].jointtype = 1;
16911 vinfos[5].foffset = j5;
16912 vinfos[5].indices[0] = _ij5[0];
16913 vinfos[5].indices[1] = _ij5[1];
16914 vinfos[5].maxsolutions = _nj5;
16915 vinfos[6].jointtype = 1;
16916 vinfos[6].foffset = j6;
16917 vinfos[6].indices[0] = _ij6[0];
16918 vinfos[6].indices[1] = _ij6[1];
16919 vinfos[6].maxsolutions = _nj6;
16920 std::vector<int> vfree(0);
16921 solutions.AddSolution(vinfos,vfree);
16922 }
16923 }
16924 }
16925 
16926 }
16927 
16928 }
16929 }
16930 }
16931 
16932 }
16933 
16934 }
16935 
16936 } else
16937 {
16938 {
16939 IkReal j4array[1], cj4array[1], sj4array[1];
16940 bool j4valid[1]={false};
16941 _nj4 = 1;
16942 IkReal x5429=((cj1)*(sj6));
16943 IkReal x5430=((r01)*(sj0));
16944 IkReal x5431=((cj0)*(r11));
16945 IkReal x5432=((cj1)*(cj6));
16946 IkReal x5433=((cj0)*(r10));
16947 IkReal x5434=((IkReal(1.00000000000000))*(sj0));
16948 IkReal x5435=((cj1)*(sj5));
16949 if( IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(r00)*(x5432)*(x5434)))+(((IkReal(-1.00000000000000))*(x5429)*(x5431)))+(((x5432)*(x5433)))+(((x5429)*(x5430))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((cj5)*(x5431)*(x5432)))+(((IkReal(-1.00000000000000))*(r02)*(x5434)*(x5435)))+(((IkReal(-1.00000000000000))*(cj5)*(x5430)*(x5432)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5429)*(x5434)))+(((cj0)*(r12)*(x5435)))+(((cj5)*(x5429)*(x5433))))))) < IKFAST_ATAN2_MAGTHRESH )
16950     continue;
16951 j4array[0]=IKatan2(((gconst26)*(((((IkReal(-1.00000000000000))*(r00)*(x5432)*(x5434)))+(((IkReal(-1.00000000000000))*(x5429)*(x5431)))+(((x5432)*(x5433)))+(((x5429)*(x5430)))))), ((gconst26)*(((((cj5)*(x5431)*(x5432)))+(((IkReal(-1.00000000000000))*(r02)*(x5434)*(x5435)))+(((IkReal(-1.00000000000000))*(cj5)*(x5430)*(x5432)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5429)*(x5434)))+(((cj0)*(r12)*(x5435)))+(((cj5)*(x5429)*(x5433)))))));
16952 sj4array[0]=IKsin(j4array[0]);
16953 cj4array[0]=IKcos(j4array[0]);
16954 if( j4array[0] > IKPI )
16955 {
16956     j4array[0]-=IK2PI;
16957 }
16958 else if( j4array[0] < -IKPI )
16959 {    j4array[0]+=IK2PI;
16960 }
16961 j4valid[0] = true;
16962 for(int ij4 = 0; ij4 < 1; ++ij4)
16963 {
16964 if( !j4valid[ij4] )
16965 {
16966     continue;
16967 }
16968 _ij4[0] = ij4; _ij4[1] = -1;
16969 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
16970 {
16971 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
16972 {
16973     j4valid[iij4]=false; _ij4[1] = iij4; break; 
16974 }
16975 }
16976 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
16977 {
16978 IkReal evalcond[3];
16979 IkReal x5436=IKsin(j4);
16980 IkReal x5437=IKcos(j4);
16981 IkReal x5438=((r00)*(sj6));
16982 IkReal x5439=((cj6)*(r01));
16983 IkReal x5440=((IkReal(1.00000000000000))*(cj0));
16984 IkReal x5441=((IkReal(1.00000000000000))*(sj0));
16985 IkReal x5442=((r10)*(sj6));
16986 IkReal x5443=((sj5)*(x5436));
16987 IkReal x5444=((IkReal(1.00000000000000))*(cj6)*(r11));
16988 IkReal x5445=((cj5)*(x5436));
16989 IkReal x5446=((cj6)*(x5437));
16990 IkReal x5447=((sj0)*(x5445));
16991 IkReal x5448=((r01)*(sj6)*(x5437));
16992 IkReal x5449=((r11)*(sj6)*(x5437));
16993 evalcond[0]=((((r20)*(sj6)*(x5445)))+(((r22)*(x5443)))+(((r21)*(sj6)*(x5437)))+(cj1)+(((cj6)*(r21)*(x5445)))+(((IkReal(-1.00000000000000))*(r20)*(x5446))));
16994 evalcond[1]=((((IkReal(-1.00000000000000))*(x5440)*(x5442)*(x5445)))+(((x5439)*(x5447)))+(((r02)*(sj0)*(x5443)))+(((IkReal(-1.00000000000000))*(r12)*(x5440)*(x5443)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5440)*(x5445)))+(((cj0)*(r10)*(x5446)))+(((x5438)*(x5447)))+(((IkReal(-1.00000000000000))*(x5440)*(x5449)))+(((IkReal(-1.00000000000000))*(r00)*(x5441)*(x5446)))+(((sj0)*(x5448))));
16995 evalcond[2]=((((IkReal(-1.00000000000000))*(x5438)*(x5440)*(x5445)))+(((IkReal(-1.00000000000000))*(x5441)*(x5449)))+(((IkReal(-1.00000000000000))*(x5439)*(x5440)*(x5445)))+(((IkReal(-1.00000000000000))*(r12)*(x5441)*(x5443)))+(((IkReal(-1.00000000000000))*(r02)*(x5440)*(x5443)))+(((IkReal(-1.00000000000000))*(sj1)))+(((r10)*(sj0)*(x5446)))+(((IkReal(-1.00000000000000))*(x5441)*(x5442)*(x5445)))+(((IkReal(-1.00000000000000))*(x5440)*(x5448)))+(((cj0)*(r00)*(x5446)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5441)*(x5445))));
16996 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
16997 {
16998 continue;
16999 }
17000 }
17001 
17002 {
17003 IkReal dummyeval[1];
17004 IkReal gconst30;
17005 gconst30=IKsign(sj1);
17006 dummyeval[0]=sj1;
17007 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
17008 {
17009 {
17010 IkReal dummyeval[1];
17011 dummyeval[0]=sj1;
17012 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
17013 {
17014 {
17015 IkReal dummyeval[1];
17016 dummyeval[0]=cj1;
17017 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
17018 {
17019 {
17020 IkReal evalcond[9];
17021 IkReal x5450=((IkReal(1.00000000000000))*(cj0));
17022 IkReal x5451=((cj4)*(sj6));
17023 IkReal x5452=((sj0)*(sj6));
17024 IkReal x5453=((cj5)*(sj4));
17025 IkReal x5454=((IkReal(0.374290000000000))*(sj5));
17026 IkReal x5455=((sj4)*(sj5));
17027 IkReal x5456=((cj0)*(cj6));
17028 IkReal x5457=((IkReal(0.0100000000000000))*(cj5));
17029 IkReal x5458=((cj4)*(sj5));
17030 IkReal x5459=((cj5)*(sj0));
17031 IkReal x5460=((IkReal(0.374290000000000))*(r02));
17032 IkReal x5461=((r20)*(sj6));
17033 IkReal x5462=((cj6)*(r21));
17034 IkReal x5463=((IkReal(1.00000000000000))*(sj0));
17035 IkReal x5464=((cj0)*(sj6));
17036 IkReal x5465=((cj4)*(cj6));
17037 IkReal x5466=((IkReal(0.374290000000000))*(r12));
17038 IkReal x5467=((cj0)*(cj5));
17039 IkReal x5468=((cj6)*(sj5));
17040 IkReal x5469=((cj6)*(r01));
17041 IkReal x5470=((r00)*(sj6));
17042 IkReal x5471=((IkReal(0.0100000000000000))*(sj5));
17043 IkReal x5472=((cj6)*(r11));
17044 IkReal x5473=((IkReal(1.00000000000000))*(r10));
17045 IkReal x5474=((r02)*(sj0));
17046 IkReal x5475=((cj6)*(sj4));
17047 IkReal x5476=((r12)*(x5463));
17048 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
17049 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x5465)))+(((x5453)*(x5461)))+(((r22)*(x5455)))+(((x5453)*(x5462)))+(((r21)*(x5451))));
17050 evalcond[2]=((IkReal(0.364420000000000))+(((x5454)*(x5461)))+(((IkReal(-1.00000000000000))*(x5457)*(x5461)))+(((IkReal(-1.00000000000000))*(x5457)*(x5462)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x5471)))+(pz)+(((x5454)*(x5462))));
17051 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x5463)*(x5468)))+(((r02)*(x5467)))+(((IkReal(-1.00000000000000))*(r01)*(x5450)*(x5468)))+(((IkReal(-1.00000000000000))*(sj5)*(x5450)*(x5470)))+(((r12)*(x5459)))+(((IkReal(-1.00000000000000))*(sj5)*(x5452)*(x5473))));
17052 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x5450)*(x5455)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x5450)*(x5453)))+(((IkReal(-1.00000000000000))*(x5450)*(x5453)*(x5472)))+(((IkReal(-1.00000000000000))*(r11)*(x5450)*(x5451)))+(((sj0)*(x5453)*(x5469)))+(((x5455)*(x5474)))+(((r01)*(sj0)*(x5451)))+(((IkReal(-1.00000000000000))*(r00)*(x5463)*(x5465)))+(((cj4)*(r10)*(x5456)))+(((r00)*(x5452)*(x5453))));
17053 evalcond[5]=((IkReal(-1.00000000000000))+(((r10)*(sj0)*(x5465)))+(((IkReal(-1.00000000000000))*(r01)*(x5450)*(x5451)))+(((cj4)*(r00)*(x5456)))+(((IkReal(-1.00000000000000))*(x5452)*(x5453)*(x5473)))+(((IkReal(-1.00000000000000))*(x5450)*(x5453)*(x5470)))+(((IkReal(-1.00000000000000))*(r02)*(x5450)*(x5455)))+(((IkReal(-1.00000000000000))*(x5450)*(x5453)*(x5469)))+(((IkReal(-1.00000000000000))*(r11)*(x5451)*(x5463)))+(((IkReal(-1.00000000000000))*(x5453)*(x5463)*(x5472)))+(((IkReal(-1.00000000000000))*(x5455)*(x5476))));
17054 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x5454)*(x5456)))+(((cj0)*(r12)*(x5471)))+(((r10)*(x5457)*(x5464)))+(((IkReal(-1.00000000000000))*(x5459)*(x5460)))+(((IkReal(-1.00000000000000))*(py)*(x5450)))+(((IkReal(-1.00000000000000))*(sj0)*(x5457)*(x5469)))+(((IkReal(-1.00000000000000))*(x5471)*(x5474)))+(((IkReal(-1.00000000000000))*(r00)*(x5452)*(x5457)))+(((r11)*(x5456)*(x5457)))+(((r00)*(x5452)*(x5454)))+(((px)*(sj0)))+(((x5466)*(x5467)))+(((sj0)*(x5454)*(x5469)))+(((IkReal(-1.00000000000000))*(r10)*(x5454)*(x5464))));
17055 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x5450)*(x5475)))+(((IkReal(-1.00000000000000))*(x5451)*(x5459)*(x5473)))+(((IkReal(-1.00000000000000))*(x5458)*(x5476)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5450)*(x5451)))+(((IkReal(-1.00000000000000))*(r11)*(x5459)*(x5465)))+(((r11)*(sj4)*(x5452)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5450)*(x5465)))+(((IkReal(-1.00000000000000))*(r02)*(x5450)*(x5458)))+(((r01)*(sj4)*(x5464)))+(((IkReal(-1.00000000000000))*(r10)*(x5463)*(x5475))));
17056 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x5452)*(x5454)))+(((cj0)*(r02)*(x5471)))+(((r01)*(x5456)*(x5457)))+(((x5460)*(x5467)))+(((r12)*(sj0)*(x5471)))+(((IkReal(-1.00000000000000))*(px)*(x5450)))+(((IkReal(-1.00000000000000))*(r01)*(x5454)*(x5456)))+(((x5459)*(x5466)))+(((IkReal(-1.00000000000000))*(py)*(x5463)))+(((r00)*(x5457)*(x5464)))+(((r10)*(x5452)*(x5457)))+(((IkReal(-1.00000000000000))*(sj0)*(x5454)*(x5472)))+(((IkReal(-1.00000000000000))*(r00)*(x5454)*(x5464)))+(((sj0)*(x5457)*(x5472))));
17057 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
17058 {
17059 {
17060 IkReal j3array[1], cj3array[1], sj3array[1];
17061 bool j3valid[1]={false};
17062 _nj3 = 1;
17063 IkReal x5477=((r20)*(sj6));
17064 IkReal x5478=((cj4)*(cj5));
17065 IkReal x5479=((cj6)*(r21));
17066 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5477)*(x5478)))+(((x5478)*(x5479))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5477)))+(((sj5)*(x5479))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5477)*(x5478)))+(((x5478)*(x5479)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5477)))+(((sj5)*(x5479)))))-1) <= IKFAST_SINCOS_THRESH )
17067     continue;
17068 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5477)*(x5478)))+(((x5478)*(x5479)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5477)))+(((sj5)*(x5479)))));
17069 sj3array[0]=IKsin(j3array[0]);
17070 cj3array[0]=IKcos(j3array[0]);
17071 if( j3array[0] > IKPI )
17072 {
17073     j3array[0]-=IK2PI;
17074 }
17075 else if( j3array[0] < -IKPI )
17076 {    j3array[0]+=IK2PI;
17077 }
17078 j3valid[0] = true;
17079 for(int ij3 = 0; ij3 < 1; ++ij3)
17080 {
17081 if( !j3valid[ij3] )
17082 {
17083     continue;
17084 }
17085 _ij3[0] = ij3; _ij3[1] = -1;
17086 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17087 {
17088 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17089 {
17090     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17091 }
17092 }
17093 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17094 {
17095 IkReal evalcond[4];
17096 IkReal x5480=IKsin(j3);
17097 IkReal x5481=((sj0)*(sj5));
17098 IkReal x5482=((r00)*(sj6));
17099 IkReal x5483=((cj6)*(r01));
17100 IkReal x5484=((cj5)*(sj0));
17101 IkReal x5485=((cj0)*(cj5));
17102 IkReal x5486=((cj6)*(sj4));
17103 IkReal x5487=((sj4)*(sj6));
17104 IkReal x5488=((cj0)*(r11));
17105 IkReal x5489=((cj4)*(cj6));
17106 IkReal x5490=((cj4)*(sj6));
17107 IkReal x5491=((IkReal(1.00000000000000))*(cj0));
17108 IkReal x5492=((cj4)*(sj5));
17109 IkReal x5493=((sj5)*(sj6));
17110 IkReal x5494=((cj6)*(sj5));
17111 IkReal x5495=((IkReal(1.00000000000000))*(IKcos(j3)));
17112 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r21)*(x5494)))+(((r20)*(x5493)))+(((IkReal(-1.00000000000000))*(x5495))));
17113 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x5487)))+(((cj5)*(r20)*(x5490)))+(((IkReal(-1.00000000000000))*(x5480)))+(((r20)*(x5486)))+(((cj5)*(r21)*(x5489)))+(((r22)*(x5492))));
17114 evalcond[2]=((x5480)+(((IkReal(-1.00000000000000))*(r10)*(x5491)*(x5493)))+(((r12)*(x5485)))+(((IkReal(-1.00000000000000))*(r02)*(x5484)))+(((x5481)*(x5482)))+(((IkReal(-1.00000000000000))*(x5488)*(x5494)))+(((x5481)*(x5483))));
17115 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x5485)*(x5489)))+(((cj4)*(x5482)*(x5484)))+(((IkReal(-1.00000000000000))*(r12)*(x5491)*(x5492)))+(((IkReal(-1.00000000000000))*(r10)*(x5485)*(x5490)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x5487)))+(((cj4)*(x5483)*(x5484)))+(((r00)*(sj0)*(x5486)))+(((cj4)*(r02)*(x5481)))+(((x5487)*(x5488)))+(((IkReal(-1.00000000000000))*(r10)*(x5486)*(x5491)))+(((IkReal(-1.00000000000000))*(x5495))));
17116 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
17117 {
17118 continue;
17119 }
17120 }
17121 
17122 {
17123 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17124 vinfos[0].jointtype = 1;
17125 vinfos[0].foffset = j0;
17126 vinfos[0].indices[0] = _ij0[0];
17127 vinfos[0].indices[1] = _ij0[1];
17128 vinfos[0].maxsolutions = _nj0;
17129 vinfos[1].jointtype = 1;
17130 vinfos[1].foffset = j1;
17131 vinfos[1].indices[0] = _ij1[0];
17132 vinfos[1].indices[1] = _ij1[1];
17133 vinfos[1].maxsolutions = _nj1;
17134 vinfos[2].jointtype = 1;
17135 vinfos[2].foffset = j2;
17136 vinfos[2].indices[0] = _ij2[0];
17137 vinfos[2].indices[1] = _ij2[1];
17138 vinfos[2].maxsolutions = _nj2;
17139 vinfos[3].jointtype = 1;
17140 vinfos[3].foffset = j3;
17141 vinfos[3].indices[0] = _ij3[0];
17142 vinfos[3].indices[1] = _ij3[1];
17143 vinfos[3].maxsolutions = _nj3;
17144 vinfos[4].jointtype = 1;
17145 vinfos[4].foffset = j4;
17146 vinfos[4].indices[0] = _ij4[0];
17147 vinfos[4].indices[1] = _ij4[1];
17148 vinfos[4].maxsolutions = _nj4;
17149 vinfos[5].jointtype = 1;
17150 vinfos[5].foffset = j5;
17151 vinfos[5].indices[0] = _ij5[0];
17152 vinfos[5].indices[1] = _ij5[1];
17153 vinfos[5].maxsolutions = _nj5;
17154 vinfos[6].jointtype = 1;
17155 vinfos[6].foffset = j6;
17156 vinfos[6].indices[0] = _ij6[0];
17157 vinfos[6].indices[1] = _ij6[1];
17158 vinfos[6].maxsolutions = _nj6;
17159 std::vector<int> vfree(0);
17160 solutions.AddSolution(vinfos,vfree);
17161 }
17162 }
17163 }
17164 
17165 } else
17166 {
17167 IkReal x5496=((IkReal(1.00000000000000))*(cj0));
17168 IkReal x5497=((cj4)*(sj6));
17169 IkReal x5498=((sj0)*(sj6));
17170 IkReal x5499=((cj5)*(sj4));
17171 IkReal x5500=((IkReal(0.374290000000000))*(sj5));
17172 IkReal x5501=((sj4)*(sj5));
17173 IkReal x5502=((cj0)*(cj6));
17174 IkReal x5503=((IkReal(0.0100000000000000))*(cj5));
17175 IkReal x5504=((cj4)*(sj5));
17176 IkReal x5505=((cj5)*(sj0));
17177 IkReal x5506=((IkReal(0.374290000000000))*(r02));
17178 IkReal x5507=((r20)*(sj6));
17179 IkReal x5508=((cj6)*(r21));
17180 IkReal x5509=((IkReal(1.00000000000000))*(sj0));
17181 IkReal x5510=((cj0)*(sj6));
17182 IkReal x5511=((cj4)*(cj6));
17183 IkReal x5512=((IkReal(0.374290000000000))*(r12));
17184 IkReal x5513=((cj0)*(cj5));
17185 IkReal x5514=((cj6)*(sj5));
17186 IkReal x5515=((cj6)*(r01));
17187 IkReal x5516=((r00)*(sj6));
17188 IkReal x5517=((IkReal(0.0100000000000000))*(sj5));
17189 IkReal x5518=((cj6)*(r11));
17190 IkReal x5519=((IkReal(1.00000000000000))*(r10));
17191 IkReal x5520=((r02)*(sj0));
17192 IkReal x5521=((cj6)*(sj4));
17193 IkReal x5522=((r12)*(x5509));
17194 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
17195 evalcond[1]=((((r21)*(x5497)))+(((x5499)*(x5508)))+(((x5499)*(x5507)))+(((r22)*(x5501)))+(((IkReal(-1.00000000000000))*(r20)*(x5511))));
17196 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(r22)*(x5517)))+(((x5500)*(x5508)))+(((x5500)*(x5507)))+(((IkReal(-1.00000000000000))*(x5503)*(x5508)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x5503)*(x5507))));
17197 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x5509)*(x5514)))+(((r12)*(x5505)))+(((IkReal(-1.00000000000000))*(sj5)*(x5496)*(x5516)))+(((IkReal(-1.00000000000000))*(r01)*(x5496)*(x5514)))+(((IkReal(-1.00000000000000))*(sj5)*(x5498)*(x5519)))+(((r02)*(x5513))));
17198 evalcond[4]=((((r00)*(x5498)*(x5499)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x5496)*(x5499)))+(((cj4)*(r10)*(x5502)))+(((sj0)*(x5499)*(x5515)))+(((r01)*(sj0)*(x5497)))+(((IkReal(-1.00000000000000))*(r11)*(x5496)*(x5497)))+(((IkReal(-1.00000000000000))*(r12)*(x5496)*(x5501)))+(((IkReal(-1.00000000000000))*(x5496)*(x5499)*(x5518)))+(((IkReal(-1.00000000000000))*(r00)*(x5509)*(x5511)))+(((x5501)*(x5520))));
17199 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x5499)*(x5509)*(x5518)))+(((IkReal(-1.00000000000000))*(r02)*(x5496)*(x5501)))+(((IkReal(-1.00000000000000))*(x5496)*(x5499)*(x5516)))+(((IkReal(-1.00000000000000))*(r11)*(x5497)*(x5509)))+(((IkReal(-1.00000000000000))*(x5501)*(x5522)))+(((r10)*(sj0)*(x5511)))+(((cj4)*(r00)*(x5502)))+(((IkReal(-1.00000000000000))*(x5498)*(x5499)*(x5519)))+(((IkReal(-1.00000000000000))*(r01)*(x5496)*(x5497)))+(((IkReal(-1.00000000000000))*(x5496)*(x5499)*(x5515))));
17200 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x5500)*(x5510)))+(((IkReal(-1.00000000000000))*(x5505)*(x5506)))+(((IkReal(-1.00000000000000))*(sj0)*(x5503)*(x5515)))+(((cj0)*(r12)*(x5517)))+(((r10)*(x5503)*(x5510)))+(((r11)*(x5502)*(x5503)))+(((IkReal(-1.00000000000000))*(r00)*(x5498)*(x5503)))+(((IkReal(-1.00000000000000))*(py)*(x5496)))+(((r00)*(x5498)*(x5500)))+(((sj0)*(x5500)*(x5515)))+(((IkReal(-1.00000000000000))*(x5517)*(x5520)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x5500)*(x5502)))+(((x5512)*(x5513))));
17201 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x5496)*(x5497)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x5496)*(x5511)))+(((IkReal(-1.00000000000000))*(x5504)*(x5522)))+(((IkReal(-1.00000000000000))*(r02)*(x5496)*(x5504)))+(((r01)*(sj4)*(x5510)))+(((IkReal(-1.00000000000000))*(x5497)*(x5505)*(x5519)))+(((IkReal(-1.00000000000000))*(r10)*(x5509)*(x5521)))+(((r11)*(sj4)*(x5498)))+(((IkReal(-1.00000000000000))*(r11)*(x5505)*(x5511)))+(((IkReal(-1.00000000000000))*(r00)*(x5496)*(x5521))));
17202 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x5509)))+(((r00)*(x5503)*(x5510)))+(((IkReal(-1.00000000000000))*(sj0)*(x5500)*(x5518)))+(((IkReal(-1.00000000000000))*(px)*(x5496)))+(((IkReal(-1.00000000000000))*(r10)*(x5498)*(x5500)))+(((r01)*(x5502)*(x5503)))+(((r10)*(x5498)*(x5503)))+(((IkReal(-1.00000000000000))*(r01)*(x5500)*(x5502)))+(((sj0)*(x5503)*(x5518)))+(((x5505)*(x5512)))+(((r12)*(sj0)*(x5517)))+(((x5506)*(x5513)))+(((IkReal(-1.00000000000000))*(r00)*(x5500)*(x5510)))+(((cj0)*(r02)*(x5517))));
17203 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
17204 {
17205 {
17206 IkReal j3array[1], cj3array[1], sj3array[1];
17207 bool j3valid[1]={false};
17208 _nj3 = 1;
17209 IkReal x5523=((IkReal(1.00000000000000))*(sj5));
17210 IkReal x5524=((cj6)*(r21));
17211 IkReal x5525=((r20)*(sj6));
17212 IkReal x5526=((IkReal(1.00000000000000))*(cj4)*(cj5));
17213 if( IKabs(((((IkReal(-1.00000000000000))*(x5524)*(x5526)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5525)*(x5526)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5523)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x5523)*(x5525)))+(((IkReal(-1.00000000000000))*(x5523)*(x5524)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x5524)*(x5526)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5525)*(x5526)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5523)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x5523)*(x5525)))+(((IkReal(-1.00000000000000))*(x5523)*(x5524)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
17214     continue;
17215 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x5524)*(x5526)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x5525)*(x5526)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x5523)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x5523)*(x5525)))+(((IkReal(-1.00000000000000))*(x5523)*(x5524)))+(((cj5)*(r22)))));
17216 sj3array[0]=IKsin(j3array[0]);
17217 cj3array[0]=IKcos(j3array[0]);
17218 if( j3array[0] > IKPI )
17219 {
17220     j3array[0]-=IK2PI;
17221 }
17222 else if( j3array[0] < -IKPI )
17223 {    j3array[0]+=IK2PI;
17224 }
17225 j3valid[0] = true;
17226 for(int ij3 = 0; ij3 < 1; ++ij3)
17227 {
17228 if( !j3valid[ij3] )
17229 {
17230     continue;
17231 }
17232 _ij3[0] = ij3; _ij3[1] = -1;
17233 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17234 {
17235 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17236 {
17237     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17238 }
17239 }
17240 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17241 {
17242 IkReal evalcond[4];
17243 IkReal x5527=IKsin(j3);
17244 IkReal x5528=IKcos(j3);
17245 IkReal x5529=((sj0)*(sj5));
17246 IkReal x5530=((r00)*(sj6));
17247 IkReal x5531=((cj6)*(r01));
17248 IkReal x5532=((cj0)*(cj5));
17249 IkReal x5533=((IkReal(1.00000000000000))*(cj5));
17250 IkReal x5534=((cj4)*(cj5));
17251 IkReal x5535=((cj6)*(sj4));
17252 IkReal x5536=((sj4)*(sj6));
17253 IkReal x5537=((cj0)*(r11));
17254 IkReal x5538=((IkReal(1.00000000000000))*(cj4));
17255 IkReal x5539=((cj6)*(r21));
17256 IkReal x5540=((r20)*(sj6));
17257 IkReal x5541=((cj0)*(sj5));
17258 IkReal x5542=((r10)*(sj6));
17259 evalcond[0]=((((sj5)*(x5540)))+(((IkReal(-1.00000000000000))*(r22)*(x5533)))+(x5528)+(((sj5)*(x5539))));
17260 evalcond[1]=((((x5534)*(x5540)))+(((cj4)*(r22)*(sj5)))+(((x5534)*(x5539)))+(x5527)+(((r20)*(x5535)))+(((IkReal(-1.00000000000000))*(r21)*(x5536))));
17261 evalcond[2]=((((x5529)*(x5531)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x5537)))+(((r12)*(x5532)))+(x5527)+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x5533)))+(((x5529)*(x5530)))+(((IkReal(-1.00000000000000))*(x5541)*(x5542))));
17262 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x5538)*(x5541)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5532)*(x5538)))+(((r00)*(sj0)*(x5535)))+(((x5536)*(x5537)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x5535)))+(((IkReal(-1.00000000000000))*(x5528)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x5536)))+(((IkReal(-1.00000000000000))*(x5532)*(x5538)*(x5542)))+(((sj0)*(x5531)*(x5534)))+(((cj4)*(r02)*(x5529)))+(((sj0)*(x5530)*(x5534))));
17263 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
17264 {
17265 continue;
17266 }
17267 }
17268 
17269 {
17270 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17271 vinfos[0].jointtype = 1;
17272 vinfos[0].foffset = j0;
17273 vinfos[0].indices[0] = _ij0[0];
17274 vinfos[0].indices[1] = _ij0[1];
17275 vinfos[0].maxsolutions = _nj0;
17276 vinfos[1].jointtype = 1;
17277 vinfos[1].foffset = j1;
17278 vinfos[1].indices[0] = _ij1[0];
17279 vinfos[1].indices[1] = _ij1[1];
17280 vinfos[1].maxsolutions = _nj1;
17281 vinfos[2].jointtype = 1;
17282 vinfos[2].foffset = j2;
17283 vinfos[2].indices[0] = _ij2[0];
17284 vinfos[2].indices[1] = _ij2[1];
17285 vinfos[2].maxsolutions = _nj2;
17286 vinfos[3].jointtype = 1;
17287 vinfos[3].foffset = j3;
17288 vinfos[3].indices[0] = _ij3[0];
17289 vinfos[3].indices[1] = _ij3[1];
17290 vinfos[3].maxsolutions = _nj3;
17291 vinfos[4].jointtype = 1;
17292 vinfos[4].foffset = j4;
17293 vinfos[4].indices[0] = _ij4[0];
17294 vinfos[4].indices[1] = _ij4[1];
17295 vinfos[4].maxsolutions = _nj4;
17296 vinfos[5].jointtype = 1;
17297 vinfos[5].foffset = j5;
17298 vinfos[5].indices[0] = _ij5[0];
17299 vinfos[5].indices[1] = _ij5[1];
17300 vinfos[5].maxsolutions = _nj5;
17301 vinfos[6].jointtype = 1;
17302 vinfos[6].foffset = j6;
17303 vinfos[6].indices[0] = _ij6[0];
17304 vinfos[6].indices[1] = _ij6[1];
17305 vinfos[6].maxsolutions = _nj6;
17306 std::vector<int> vfree(0);
17307 solutions.AddSolution(vinfos,vfree);
17308 }
17309 }
17310 }
17311 
17312 } else
17313 {
17314 IkReal x5543=((IkReal(1.00000000000000))*(cj0));
17315 IkReal x5544=((cj4)*(sj6));
17316 IkReal x5545=((sj0)*(sj4));
17317 IkReal x5546=((cj5)*(sj6));
17318 IkReal x5547=((sj4)*(sj5));
17319 IkReal x5548=((r12)*(sj5));
17320 IkReal x5549=((IkReal(0.374290000000000))*(cj5));
17321 IkReal x5550=((r02)*(sj0));
17322 IkReal x5551=((r20)*(sj4));
17323 IkReal x5552=((IkReal(1.00000000000000))*(sj0));
17324 IkReal x5553=((IkReal(1.00000000000000))*(cj5));
17325 IkReal x5554=((cj0)*(r10));
17326 IkReal x5555=((cj4)*(cj6));
17327 IkReal x5556=((r00)*(sj0));
17328 IkReal x5557=((cj6)*(r21));
17329 IkReal x5558=((IkReal(0.374290000000000))*(sj5));
17330 IkReal x5559=((cj0)*(r00));
17331 IkReal x5560=((IkReal(0.0100000000000000))*(sj5));
17332 IkReal x5561=((cj0)*(r02));
17333 IkReal x5562=((cj5)*(sj4));
17334 IkReal x5563=((cj6)*(r01));
17335 IkReal x5564=((cj6)*(r11));
17336 IkReal x5565=((r01)*(sj0));
17337 IkReal x5566=((r10)*(sj0));
17338 IkReal x5567=((IkReal(0.0100000000000000))*(cj5)*(cj6));
17339 IkReal x5568=((sj6)*(x5558));
17340 IkReal x5569=((cj0)*(cj6)*(x5558));
17341 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
17342 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x5553)))+(((sj5)*(x5557)))+(((r20)*(sj5)*(sj6))));
17343 evalcond[2]=((IkReal(1.00000000000000))+(((x5546)*(x5551)))+(((x5557)*(x5562)))+(((r22)*(x5547)))+(((IkReal(-1.00000000000000))*(r20)*(x5555)))+(((r21)*(x5544))));
17344 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x5560)))+(((x5557)*(x5558)))+(((IkReal(-0.0100000000000000))*(cj5)*(x5557)))+(((r20)*(x5568)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x5549)))+(((IkReal(-0.0100000000000000))*(r20)*(x5546))));
17345 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x5551)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x5555)))+(((cj5)*(r20)*(x5544))));
17346 evalcond[5]=((((r02)*(sj5)*(x5545)))+(((cj5)*(x5545)*(x5563)))+(((r00)*(x5545)*(x5546)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x5543)*(x5546)))+(((IkReal(-1.00000000000000))*(x5543)*(x5562)*(x5564)))+(((IkReal(-1.00000000000000))*(r00)*(x5552)*(x5555)))+(((x5544)*(x5565)))+(((IkReal(-1.00000000000000))*(r11)*(x5543)*(x5544)))+(((IkReal(-1.00000000000000))*(r12)*(x5543)*(x5547)))+(((x5554)*(x5555))));
17347 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x5543)*(x5547)))+(((IkReal(-1.00000000000000))*(r10)*(x5545)*(x5546)))+(((IkReal(-1.00000000000000))*(x5545)*(x5548)))+(((x5555)*(x5566)))+(((IkReal(-1.00000000000000))*(x5545)*(x5553)*(x5564)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x5543)*(x5546)))+(((IkReal(-1.00000000000000))*(x5543)*(x5562)*(x5563)))+(((IkReal(-1.00000000000000))*(r11)*(x5544)*(x5552)))+(((IkReal(-1.00000000000000))*(r01)*(x5543)*(x5544)))+(((x5555)*(x5559))));
17348 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x5554)*(x5568)))+(((IkReal(-1.00000000000000))*(cj0)*(x5558)*(x5564)))+(((IkReal(0.0100000000000000))*(x5546)*(x5554)))+(((IkReal(-1.00000000000000))*(x5549)*(x5550)))+(((sj0)*(x5558)*(x5563)))+(((x5556)*(x5568)))+(((cj0)*(r12)*(x5549)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x5563)))+(((IkReal(0.0100000000000000))*(cj0)*(x5548)))+(((IkReal(-1.00000000000000))*(py)*(x5543)))+(((IkReal(-1.00000000000000))*(x5550)*(x5560)))+(((IkReal(-0.0100000000000000))*(x5546)*(x5556)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5564))));
17349 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(x5546)*(x5559)))+(((r12)*(sj0)*(x5549)))+(((x5549)*(x5561)))+(((IkReal(-1.00000000000000))*(x5566)*(x5568)))+(((IkReal(-1.00000000000000))*(py)*(x5552)))+(((IkReal(0.0100000000000000))*(x5546)*(x5566)))+(((IkReal(0.0100000000000000))*(sj0)*(x5548)))+(((x5560)*(x5561)))+(((IkReal(-1.00000000000000))*(sj0)*(x5558)*(x5564)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x5564)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5563)))+(((IkReal(-1.00000000000000))*(cj0)*(x5558)*(x5563)))+(((IkReal(-1.00000000000000))*(x5559)*(x5568)))+(((IkReal(-1.00000000000000))*(px)*(x5543))));
17350 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
17351 {
17352 {
17353 IkReal j3array[1], cj3array[1], sj3array[1];
17354 bool j3valid[1]={false};
17355 _nj3 = 1;
17356 IkReal x5570=((cj5)*(r02));
17357 IkReal x5571=((cj0)*(sj5));
17358 IkReal x5572=((r10)*(sj6));
17359 IkReal x5573=((IkReal(1.00000000000000))*(cj6));
17360 IkReal x5574=((sj0)*(sj5));
17361 IkReal x5575=((cj5)*(r12));
17362 IkReal x5576=((IkReal(1.00000000000000))*(r00)*(sj6));
17363 if( IKabs(((((cj6)*(r11)*(x5571)))+(((IkReal(-1.00000000000000))*(cj0)*(x5575)))+(((x5571)*(x5572)))+(((IkReal(-1.00000000000000))*(x5574)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5573)*(x5574)))+(((sj0)*(x5570))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r11)*(x5573)*(x5574)))+(((IkReal(-1.00000000000000))*(x5571)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5571)*(x5573)))+(((cj0)*(x5570)))+(((IkReal(-1.00000000000000))*(x5572)*(x5574)))+(((sj0)*(x5575))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj6)*(r11)*(x5571)))+(((IkReal(-1.00000000000000))*(cj0)*(x5575)))+(((x5571)*(x5572)))+(((IkReal(-1.00000000000000))*(x5574)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5573)*(x5574)))+(((sj0)*(x5570)))))+IKsqr(((((IkReal(-1.00000000000000))*(r11)*(x5573)*(x5574)))+(((IkReal(-1.00000000000000))*(x5571)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5571)*(x5573)))+(((cj0)*(x5570)))+(((IkReal(-1.00000000000000))*(x5572)*(x5574)))+(((sj0)*(x5575)))))-1) <= IKFAST_SINCOS_THRESH )
17364     continue;
17365 j3array[0]=IKatan2(((((cj6)*(r11)*(x5571)))+(((IkReal(-1.00000000000000))*(cj0)*(x5575)))+(((x5571)*(x5572)))+(((IkReal(-1.00000000000000))*(x5574)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5573)*(x5574)))+(((sj0)*(x5570)))), ((((IkReal(-1.00000000000000))*(r11)*(x5573)*(x5574)))+(((IkReal(-1.00000000000000))*(x5571)*(x5576)))+(((IkReal(-1.00000000000000))*(r01)*(x5571)*(x5573)))+(((cj0)*(x5570)))+(((IkReal(-1.00000000000000))*(x5572)*(x5574)))+(((sj0)*(x5575)))));
17366 sj3array[0]=IKsin(j3array[0]);
17367 cj3array[0]=IKcos(j3array[0]);
17368 if( j3array[0] > IKPI )
17369 {
17370     j3array[0]-=IK2PI;
17371 }
17372 else if( j3array[0] < -IKPI )
17373 {    j3array[0]+=IK2PI;
17374 }
17375 j3valid[0] = true;
17376 for(int ij3 = 0; ij3 < 1; ++ij3)
17377 {
17378 if( !j3valid[ij3] )
17379 {
17380     continue;
17381 }
17382 _ij3[0] = ij3; _ij3[1] = -1;
17383 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17384 {
17385 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17386 {
17387     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17388 }
17389 }
17390 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17391 {
17392 IkReal evalcond[4];
17393 IkReal x5577=IKsin(j3);
17394 IkReal x5578=((sj0)*(sj5));
17395 IkReal x5579=((r00)*(sj6));
17396 IkReal x5580=((IkReal(1.00000000000000))*(cj4));
17397 IkReal x5581=((cj6)*(sj0));
17398 IkReal x5582=((r00)*(sj4));
17399 IkReal x5583=((cj0)*(cj5));
17400 IkReal x5584=((cj6)*(r01));
17401 IkReal x5585=((cj5)*(sj0));
17402 IkReal x5586=((cj0)*(sj5));
17403 IkReal x5587=((cj6)*(r11));
17404 IkReal x5588=((r10)*(sj6));
17405 IkReal x5589=((r10)*(sj4));
17406 IkReal x5590=((IkReal(1.00000000000000))*(IKcos(j3)));
17407 IkReal x5591=((cj0)*(sj4)*(sj6));
17408 IkReal x5592=((sj0)*(sj4)*(sj6));
17409 IkReal x5593=((IkReal(1.00000000000000))*(cj0)*(cj6));
17410 evalcond[0]=((((x5578)*(x5584)))+(((r12)*(x5583)))+(((IkReal(-1.00000000000000))*(x5586)*(x5587)))+(((x5578)*(x5579)))+(((IkReal(-1.00000000000000))*(x5586)*(x5588)))+(((IkReal(-1.00000000000000))*(r02)*(x5585)))+(x5577));
17411 evalcond[1]=((((IkReal(-1.00000000000000))*(x5578)*(x5588)))+(((r02)*(x5583)))+(((r12)*(x5585)))+(((IkReal(-1.00000000000000))*(x5579)*(x5586)))+(((IkReal(-1.00000000000000))*(x5578)*(x5587)))+(((IkReal(-1.00000000000000))*(x5584)*(x5586)))+(((IkReal(-1.00000000000000))*(x5590))));
17412 evalcond[2]=((((cj4)*(cj5)*(r01)*(x5581)))+(((cj4)*(r02)*(x5578)))+(((IkReal(-1.00000000000000))*(x5589)*(x5593)))+(((IkReal(-1.00000000000000))*(x5580)*(x5583)*(x5587)))+(((IkReal(-1.00000000000000))*(r12)*(x5580)*(x5586)))+(((cj4)*(x5579)*(x5585)))+(((r11)*(x5591)))+(((IkReal(-1.00000000000000))*(x5590)))+(((x5581)*(x5582)))+(((IkReal(-1.00000000000000))*(x5580)*(x5583)*(x5588)))+(((IkReal(-1.00000000000000))*(r01)*(x5592))));
17413 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x5578)*(x5580)))+(((IkReal(-1.00000000000000))*(x5577)))+(((IkReal(-1.00000000000000))*(x5580)*(x5585)*(x5588)))+(((IkReal(-1.00000000000000))*(x5580)*(x5583)*(x5584)))+(((r01)*(x5591)))+(((IkReal(-1.00000000000000))*(x5579)*(x5580)*(x5583)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x5580)*(x5581)))+(((IkReal(-1.00000000000000))*(r02)*(x5580)*(x5586)))+(((IkReal(-1.00000000000000))*(x5582)*(x5593)))+(((IkReal(-1.00000000000000))*(x5581)*(x5589)))+(((r11)*(x5592))));
17414 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
17415 {
17416 continue;
17417 }
17418 }
17419 
17420 {
17421 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17422 vinfos[0].jointtype = 1;
17423 vinfos[0].foffset = j0;
17424 vinfos[0].indices[0] = _ij0[0];
17425 vinfos[0].indices[1] = _ij0[1];
17426 vinfos[0].maxsolutions = _nj0;
17427 vinfos[1].jointtype = 1;
17428 vinfos[1].foffset = j1;
17429 vinfos[1].indices[0] = _ij1[0];
17430 vinfos[1].indices[1] = _ij1[1];
17431 vinfos[1].maxsolutions = _nj1;
17432 vinfos[2].jointtype = 1;
17433 vinfos[2].foffset = j2;
17434 vinfos[2].indices[0] = _ij2[0];
17435 vinfos[2].indices[1] = _ij2[1];
17436 vinfos[2].maxsolutions = _nj2;
17437 vinfos[3].jointtype = 1;
17438 vinfos[3].foffset = j3;
17439 vinfos[3].indices[0] = _ij3[0];
17440 vinfos[3].indices[1] = _ij3[1];
17441 vinfos[3].maxsolutions = _nj3;
17442 vinfos[4].jointtype = 1;
17443 vinfos[4].foffset = j4;
17444 vinfos[4].indices[0] = _ij4[0];
17445 vinfos[4].indices[1] = _ij4[1];
17446 vinfos[4].maxsolutions = _nj4;
17447 vinfos[5].jointtype = 1;
17448 vinfos[5].foffset = j5;
17449 vinfos[5].indices[0] = _ij5[0];
17450 vinfos[5].indices[1] = _ij5[1];
17451 vinfos[5].maxsolutions = _nj5;
17452 vinfos[6].jointtype = 1;
17453 vinfos[6].foffset = j6;
17454 vinfos[6].indices[0] = _ij6[0];
17455 vinfos[6].indices[1] = _ij6[1];
17456 vinfos[6].maxsolutions = _nj6;
17457 std::vector<int> vfree(0);
17458 solutions.AddSolution(vinfos,vfree);
17459 }
17460 }
17461 }
17462 
17463 } else
17464 {
17465 IkReal x5594=((IkReal(1.00000000000000))*(cj0));
17466 IkReal x5595=((cj4)*(sj6));
17467 IkReal x5596=((sj0)*(sj4));
17468 IkReal x5597=((cj5)*(sj6));
17469 IkReal x5598=((sj4)*(sj5));
17470 IkReal x5599=((r12)*(sj5));
17471 IkReal x5600=((IkReal(0.374290000000000))*(cj5));
17472 IkReal x5601=((r02)*(sj0));
17473 IkReal x5602=((r20)*(sj4));
17474 IkReal x5603=((IkReal(1.00000000000000))*(sj0));
17475 IkReal x5604=((IkReal(1.00000000000000))*(cj5));
17476 IkReal x5605=((cj0)*(r10));
17477 IkReal x5606=((cj4)*(cj6));
17478 IkReal x5607=((r00)*(sj0));
17479 IkReal x5608=((cj6)*(r21));
17480 IkReal x5609=((IkReal(0.374290000000000))*(sj5));
17481 IkReal x5610=((cj0)*(r00));
17482 IkReal x5611=((IkReal(0.0100000000000000))*(sj5));
17483 IkReal x5612=((cj0)*(r02));
17484 IkReal x5613=((cj5)*(sj4));
17485 IkReal x5614=((cj6)*(r01));
17486 IkReal x5615=((cj6)*(r11));
17487 IkReal x5616=((r01)*(sj0));
17488 IkReal x5617=((r10)*(sj0));
17489 IkReal x5618=((IkReal(0.0100000000000000))*(cj5)*(cj6));
17490 IkReal x5619=((sj6)*(x5609));
17491 IkReal x5620=((cj0)*(cj6)*(x5609));
17492 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
17493 evalcond[1]=((((sj5)*(x5608)))+(((IkReal(-1.00000000000000))*(r22)*(x5604)))+(((r20)*(sj5)*(sj6))));
17494 evalcond[2]=((IkReal(-1.00000000000000))+(((x5597)*(x5602)))+(((x5608)*(x5613)))+(((r22)*(x5598)))+(((IkReal(-1.00000000000000))*(r20)*(x5606)))+(((r21)*(x5595))));
17495 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x5597)))+(((IkReal(-0.0100000000000000))*(cj5)*(x5608)))+(((IkReal(-1.00000000000000))*(r22)*(x5611)))+(((x5608)*(x5609)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x5600)))+(((r20)*(x5619))));
17496 evalcond[4]=((((cj5)*(r21)*(x5606)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x5595)))+(((cj6)*(x5602))));
17497 evalcond[5]=((((IkReal(-1.00000000000000))*(x5594)*(x5613)*(x5615)))+(((x5595)*(x5616)))+(((IkReal(-1.00000000000000))*(r00)*(x5603)*(x5606)))+(((IkReal(-1.00000000000000))*(r11)*(x5594)*(x5595)))+(((cj5)*(x5596)*(x5614)))+(((IkReal(-1.00000000000000))*(r12)*(x5594)*(x5598)))+(((r02)*(sj5)*(x5596)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x5594)*(x5597)))+(((r00)*(x5596)*(x5597)))+(((x5605)*(x5606))));
17498 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(sj4)*(x5594)*(x5597)))+(((x5606)*(x5617)))+(((IkReal(-1.00000000000000))*(r02)*(x5594)*(x5598)))+(((IkReal(-1.00000000000000))*(x5596)*(x5604)*(x5615)))+(((IkReal(-1.00000000000000))*(x5596)*(x5599)))+(((IkReal(-1.00000000000000))*(r01)*(x5594)*(x5595)))+(((IkReal(-1.00000000000000))*(x5594)*(x5613)*(x5614)))+(((IkReal(-1.00000000000000))*(r11)*(x5595)*(x5603)))+(((x5606)*(x5610)))+(((IkReal(-1.00000000000000))*(r10)*(x5596)*(x5597))));
17499 evalcond[7]=((IkReal(-0.0690000000000000))+(((cj0)*(r12)*(x5600)))+(((IkReal(-1.00000000000000))*(x5601)*(x5611)))+(((sj0)*(x5609)*(x5614)))+(((IkReal(-1.00000000000000))*(x5600)*(x5601)))+(((IkReal(0.0100000000000000))*(cj0)*(x5599)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x5614)))+(((IkReal(-0.0100000000000000))*(x5597)*(x5607)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5615)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x5594)))+(((IkReal(0.0100000000000000))*(x5597)*(x5605)))+(((x5607)*(x5619)))+(((IkReal(-1.00000000000000))*(x5605)*(x5619)))+(((IkReal(-1.00000000000000))*(cj0)*(x5609)*(x5615))));
17500 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x5614)))+(((IkReal(-1.00000000000000))*(cj0)*(x5609)*(x5614)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x5615)))+(((IkReal(0.0100000000000000))*(sj0)*(x5599)))+(((IkReal(-1.00000000000000))*(x5617)*(x5619)))+(((IkReal(-1.00000000000000))*(sj0)*(x5609)*(x5615)))+(((IkReal(0.0100000000000000))*(x5597)*(x5617)))+(((IkReal(-1.00000000000000))*(py)*(x5603)))+(((r12)*(sj0)*(x5600)))+(((IkReal(0.0100000000000000))*(x5597)*(x5610)))+(((x5611)*(x5612)))+(((x5600)*(x5612)))+(((IkReal(-1.00000000000000))*(x5610)*(x5619)))+(((IkReal(-1.00000000000000))*(px)*(x5594))));
17501 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
17502 {
17503 {
17504 IkReal j3array[1], cj3array[1], sj3array[1];
17505 bool j3valid[1]={false};
17506 _nj3 = 1;
17507 IkReal x5621=((IkReal(1.00000000000000))*(cj5));
17508 IkReal x5622=((r10)*(sj5)*(sj6));
17509 IkReal x5623=((cj6)*(sj0)*(sj5));
17510 IkReal x5624=((r00)*(sj5)*(sj6));
17511 IkReal x5625=((cj0)*(cj6)*(sj5));
17512 if( IKabs(((((r11)*(x5625)))+(((cj0)*(x5622)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x5624)))+(((IkReal(-1.00000000000000))*(r01)*(x5623)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5621))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5621)))+(((r11)*(x5623)))+(((sj0)*(x5622)))+(((cj0)*(x5624)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5621)))+(((r01)*(x5625))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r11)*(x5625)))+(((cj0)*(x5622)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x5624)))+(((IkReal(-1.00000000000000))*(r01)*(x5623)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5621)))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5621)))+(((r11)*(x5623)))+(((sj0)*(x5622)))+(((cj0)*(x5624)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5621)))+(((r01)*(x5625)))))-1) <= IKFAST_SINCOS_THRESH )
17513     continue;
17514 j3array[0]=IKatan2(((((r11)*(x5625)))+(((cj0)*(x5622)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x5624)))+(((IkReal(-1.00000000000000))*(r01)*(x5623)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5621)))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5621)))+(((r11)*(x5623)))+(((sj0)*(x5622)))+(((cj0)*(x5624)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5621)))+(((r01)*(x5625)))));
17515 sj3array[0]=IKsin(j3array[0]);
17516 cj3array[0]=IKcos(j3array[0]);
17517 if( j3array[0] > IKPI )
17518 {
17519     j3array[0]-=IK2PI;
17520 }
17521 else if( j3array[0] < -IKPI )
17522 {    j3array[0]+=IK2PI;
17523 }
17524 j3valid[0] = true;
17525 for(int ij3 = 0; ij3 < 1; ++ij3)
17526 {
17527 if( !j3valid[ij3] )
17528 {
17529     continue;
17530 }
17531 _ij3[0] = ij3; _ij3[1] = -1;
17532 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17533 {
17534 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17535 {
17536     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17537 }
17538 }
17539 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17540 {
17541 IkReal evalcond[4];
17542 IkReal x5626=IKcos(j3);
17543 IkReal x5627=IKsin(j3);
17544 IkReal x5628=((sj0)*(sj5));
17545 IkReal x5629=((r00)*(sj6));
17546 IkReal x5630=((IkReal(1.00000000000000))*(cj4));
17547 IkReal x5631=((cj6)*(sj0));
17548 IkReal x5632=((r00)*(sj4));
17549 IkReal x5633=((cj0)*(cj5));
17550 IkReal x5634=((cj6)*(r01));
17551 IkReal x5635=((cj5)*(sj0));
17552 IkReal x5636=((cj0)*(sj5));
17553 IkReal x5637=((cj6)*(r11));
17554 IkReal x5638=((r10)*(sj6));
17555 IkReal x5639=((r10)*(sj4));
17556 IkReal x5640=((cj0)*(sj4)*(sj6));
17557 IkReal x5641=((sj0)*(sj4)*(sj6));
17558 IkReal x5642=((IkReal(1.00000000000000))*(cj0)*(cj6));
17559 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x5635)))+(((x5628)*(x5629)))+(((IkReal(-1.00000000000000))*(x5636)*(x5638)))+(((r12)*(x5633)))+(((x5628)*(x5634)))+(x5627)+(((IkReal(-1.00000000000000))*(x5636)*(x5637))));
17560 evalcond[1]=((((IkReal(-1.00000000000000))*(x5628)*(x5637)))+(((IkReal(-1.00000000000000))*(x5629)*(x5636)))+(((IkReal(-1.00000000000000))*(x5634)*(x5636)))+(((IkReal(-1.00000000000000))*(x5628)*(x5638)))+(((r02)*(x5633)))+(((r12)*(x5635)))+(x5626));
17561 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x5641)))+(((IkReal(-1.00000000000000))*(r12)*(x5630)*(x5636)))+(((cj4)*(r02)*(x5628)))+(((IkReal(-1.00000000000000))*(x5630)*(x5633)*(x5638)))+(((cj4)*(cj5)*(r01)*(x5631)))+(((IkReal(-1.00000000000000))*(x5630)*(x5633)*(x5637)))+(((r11)*(x5640)))+(((cj4)*(x5629)*(x5635)))+(((x5631)*(x5632)))+(((IkReal(-1.00000000000000))*(x5639)*(x5642)))+(((IkReal(-1.00000000000000))*(x5626))));
17562 evalcond[3]=((((IkReal(-1.00000000000000))*(x5630)*(x5635)*(x5638)))+(((r11)*(x5641)))+(((IkReal(-1.00000000000000))*(x5629)*(x5630)*(x5633)))+(((IkReal(-1.00000000000000))*(x5631)*(x5639)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x5630)*(x5631)))+(((IkReal(-1.00000000000000))*(x5630)*(x5633)*(x5634)))+(((r01)*(x5640)))+(((IkReal(-1.00000000000000))*(r12)*(x5628)*(x5630)))+(((IkReal(-1.00000000000000))*(x5632)*(x5642)))+(x5627)+(((IkReal(-1.00000000000000))*(r02)*(x5630)*(x5636))));
17563 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
17564 {
17565 continue;
17566 }
17567 }
17568 
17569 {
17570 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17571 vinfos[0].jointtype = 1;
17572 vinfos[0].foffset = j0;
17573 vinfos[0].indices[0] = _ij0[0];
17574 vinfos[0].indices[1] = _ij0[1];
17575 vinfos[0].maxsolutions = _nj0;
17576 vinfos[1].jointtype = 1;
17577 vinfos[1].foffset = j1;
17578 vinfos[1].indices[0] = _ij1[0];
17579 vinfos[1].indices[1] = _ij1[1];
17580 vinfos[1].maxsolutions = _nj1;
17581 vinfos[2].jointtype = 1;
17582 vinfos[2].foffset = j2;
17583 vinfos[2].indices[0] = _ij2[0];
17584 vinfos[2].indices[1] = _ij2[1];
17585 vinfos[2].maxsolutions = _nj2;
17586 vinfos[3].jointtype = 1;
17587 vinfos[3].foffset = j3;
17588 vinfos[3].indices[0] = _ij3[0];
17589 vinfos[3].indices[1] = _ij3[1];
17590 vinfos[3].maxsolutions = _nj3;
17591 vinfos[4].jointtype = 1;
17592 vinfos[4].foffset = j4;
17593 vinfos[4].indices[0] = _ij4[0];
17594 vinfos[4].indices[1] = _ij4[1];
17595 vinfos[4].maxsolutions = _nj4;
17596 vinfos[5].jointtype = 1;
17597 vinfos[5].foffset = j5;
17598 vinfos[5].indices[0] = _ij5[0];
17599 vinfos[5].indices[1] = _ij5[1];
17600 vinfos[5].maxsolutions = _nj5;
17601 vinfos[6].jointtype = 1;
17602 vinfos[6].foffset = j6;
17603 vinfos[6].indices[0] = _ij6[0];
17604 vinfos[6].indices[1] = _ij6[1];
17605 vinfos[6].maxsolutions = _nj6;
17606 std::vector<int> vfree(0);
17607 solutions.AddSolution(vinfos,vfree);
17608 }
17609 }
17610 }
17611 
17612 } else
17613 {
17614 if( 1 )
17615 {
17616 continue;
17617 
17618 } else
17619 {
17620 }
17621 }
17622 }
17623 }
17624 }
17625 }
17626 
17627 } else
17628 {
17629 {
17630 IkReal j3array[1], cj3array[1], sj3array[1];
17631 bool j3valid[1]={false};
17632 _nj3 = 1;
17633 IkReal x5643=((cj5)*(r02));
17634 IkReal x5644=((cj0)*(sj5));
17635 IkReal x5645=((r10)*(sj6));
17636 IkReal x5646=((IkReal(1.00000000000000))*(cj6));
17637 IkReal x5647=((sj0)*(sj5));
17638 IkReal x5648=((cj5)*(r12));
17639 IkReal x5649=((IkReal(1.00000000000000))*(r00)*(sj6));
17640 if( IKabs(((((cj6)*(r11)*(x5644)))+(((x5644)*(x5645)))+(((IkReal(-1.00000000000000))*(cj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5647)*(x5649)))+(((IkReal(-1.00000000000000))*(r01)*(x5646)*(x5647)))+(((sj0)*(x5643))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5645)*(x5647)))+(((cj0)*(x5643)))+(((IkReal(-1.00000000000000))*(x5644)*(x5649)))+(((IkReal(-1.00000000000000))*(r11)*(x5646)*(x5647)))+(((IkReal(-1.00000000000000))*(r01)*(x5644)*(x5646))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj6)*(r11)*(x5644)))+(((x5644)*(x5645)))+(((IkReal(-1.00000000000000))*(cj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5647)*(x5649)))+(((IkReal(-1.00000000000000))*(r01)*(x5646)*(x5647)))+(((sj0)*(x5643)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5645)*(x5647)))+(((cj0)*(x5643)))+(((IkReal(-1.00000000000000))*(x5644)*(x5649)))+(((IkReal(-1.00000000000000))*(r11)*(x5646)*(x5647)))+(((IkReal(-1.00000000000000))*(r01)*(x5644)*(x5646)))))))-1) <= IKFAST_SINCOS_THRESH )
17641     continue;
17642 j3array[0]=IKatan2(((((cj6)*(r11)*(x5644)))+(((x5644)*(x5645)))+(((IkReal(-1.00000000000000))*(cj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5647)*(x5649)))+(((IkReal(-1.00000000000000))*(r01)*(x5646)*(x5647)))+(((sj0)*(x5643)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x5648)))+(((IkReal(-1.00000000000000))*(x5645)*(x5647)))+(((cj0)*(x5643)))+(((IkReal(-1.00000000000000))*(x5644)*(x5649)))+(((IkReal(-1.00000000000000))*(r11)*(x5646)*(x5647)))+(((IkReal(-1.00000000000000))*(r01)*(x5644)*(x5646)))))));
17643 sj3array[0]=IKsin(j3array[0]);
17644 cj3array[0]=IKcos(j3array[0]);
17645 if( j3array[0] > IKPI )
17646 {
17647     j3array[0]-=IK2PI;
17648 }
17649 else if( j3array[0] < -IKPI )
17650 {    j3array[0]+=IK2PI;
17651 }
17652 j3valid[0] = true;
17653 for(int ij3 = 0; ij3 < 1; ++ij3)
17654 {
17655 if( !j3valid[ij3] )
17656 {
17657     continue;
17658 }
17659 _ij3[0] = ij3; _ij3[1] = -1;
17660 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17661 {
17662 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17663 {
17664     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17665 }
17666 }
17667 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17668 {
17669 IkReal evalcond[6];
17670 IkReal x5650=IKsin(j3);
17671 IkReal x5651=IKcos(j3);
17672 IkReal x5652=((sj0)*(sj5));
17673 IkReal x5653=((r00)*(sj6));
17674 IkReal x5654=((IkReal(1.00000000000000))*(cj4));
17675 IkReal x5655=((cj6)*(r01));
17676 IkReal x5656=((cj0)*(cj5));
17677 IkReal x5657=((cj5)*(sj0));
17678 IkReal x5658=((cj6)*(r11));
17679 IkReal x5659=((cj0)*(sj5));
17680 IkReal x5660=((IkReal(1.00000000000000))*(cj1));
17681 IkReal x5661=((cj6)*(sj4));
17682 IkReal x5662=((IkReal(1.00000000000000))*(sj1));
17683 IkReal x5663=((cj4)*(cj5));
17684 IkReal x5664=((cj6)*(r21));
17685 IkReal x5665=((r20)*(sj6));
17686 IkReal x5666=((r10)*(sj6));
17687 IkReal x5667=((IkReal(1.00000000000000))*(cj0));
17688 IkReal x5668=((cj0)*(sj4)*(sj6));
17689 IkReal x5669=((sj0)*(sj4)*(sj6));
17690 evalcond[0]=((((sj5)*(x5664)))+(((IkReal(-1.00000000000000))*(x5651)*(x5662)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5665))));
17691 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x5661)))+(((x5663)*(x5665)))+(((IkReal(-1.00000000000000))*(x5650)*(x5662)))+(((x5663)*(x5664))));
17692 evalcond[2]=((((x5652)*(x5653)))+(((r12)*(x5656)))+(((x5652)*(x5655)))+(((IkReal(-1.00000000000000))*(x5659)*(x5666)))+(((IkReal(-1.00000000000000))*(x5658)*(x5659)))+(x5650)+(((IkReal(-1.00000000000000))*(r02)*(x5657))));
17693 evalcond[3]=((((r12)*(x5657)))+(((IkReal(-1.00000000000000))*(x5651)*(x5660)))+(((r02)*(x5656)))+(((IkReal(-1.00000000000000))*(x5655)*(x5659)))+(((IkReal(-1.00000000000000))*(x5652)*(x5666)))+(((IkReal(-1.00000000000000))*(x5652)*(x5658)))+(((IkReal(-1.00000000000000))*(x5653)*(x5659))));
17694 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x5669)))+(((cj4)*(x5655)*(x5657)))+(((IkReal(-1.00000000000000))*(x5654)*(x5656)*(x5658)))+(((r11)*(x5668)))+(((cj4)*(r02)*(x5652)))+(((IkReal(-1.00000000000000))*(x5654)*(x5656)*(x5666)))+(((IkReal(-1.00000000000000))*(r10)*(x5661)*(x5667)))+(((r00)*(sj0)*(x5661)))+(((cj4)*(x5653)*(x5657)))+(((IkReal(-1.00000000000000))*(r12)*(x5654)*(x5659)))+(((IkReal(-1.00000000000000))*(x5651))));
17695 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x5654)*(x5659)))+(((IkReal(-1.00000000000000))*(x5650)*(x5660)))+(((r11)*(x5669)))+(((IkReal(-1.00000000000000))*(x5653)*(x5654)*(x5656)))+(((IkReal(-1.00000000000000))*(r12)*(x5652)*(x5654)))+(((IkReal(-1.00000000000000))*(r00)*(x5661)*(x5667)))+(((IkReal(-1.00000000000000))*(x5654)*(x5657)*(x5658)))+(((IkReal(-1.00000000000000))*(x5654)*(x5655)*(x5656)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5661)))+(((IkReal(-1.00000000000000))*(x5654)*(x5657)*(x5666)))+(((r01)*(x5668))));
17696 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
17697 {
17698 continue;
17699 }
17700 }
17701 
17702 {
17703 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17704 vinfos[0].jointtype = 1;
17705 vinfos[0].foffset = j0;
17706 vinfos[0].indices[0] = _ij0[0];
17707 vinfos[0].indices[1] = _ij0[1];
17708 vinfos[0].maxsolutions = _nj0;
17709 vinfos[1].jointtype = 1;
17710 vinfos[1].foffset = j1;
17711 vinfos[1].indices[0] = _ij1[0];
17712 vinfos[1].indices[1] = _ij1[1];
17713 vinfos[1].maxsolutions = _nj1;
17714 vinfos[2].jointtype = 1;
17715 vinfos[2].foffset = j2;
17716 vinfos[2].indices[0] = _ij2[0];
17717 vinfos[2].indices[1] = _ij2[1];
17718 vinfos[2].maxsolutions = _nj2;
17719 vinfos[3].jointtype = 1;
17720 vinfos[3].foffset = j3;
17721 vinfos[3].indices[0] = _ij3[0];
17722 vinfos[3].indices[1] = _ij3[1];
17723 vinfos[3].maxsolutions = _nj3;
17724 vinfos[4].jointtype = 1;
17725 vinfos[4].foffset = j4;
17726 vinfos[4].indices[0] = _ij4[0];
17727 vinfos[4].indices[1] = _ij4[1];
17728 vinfos[4].maxsolutions = _nj4;
17729 vinfos[5].jointtype = 1;
17730 vinfos[5].foffset = j5;
17731 vinfos[5].indices[0] = _ij5[0];
17732 vinfos[5].indices[1] = _ij5[1];
17733 vinfos[5].maxsolutions = _nj5;
17734 vinfos[6].jointtype = 1;
17735 vinfos[6].foffset = j6;
17736 vinfos[6].indices[0] = _ij6[0];
17737 vinfos[6].indices[1] = _ij6[1];
17738 vinfos[6].maxsolutions = _nj6;
17739 std::vector<int> vfree(0);
17740 solutions.AddSolution(vinfos,vfree);
17741 }
17742 }
17743 }
17744 
17745 }
17746 
17747 }
17748 
17749 } else
17750 {
17751 {
17752 IkReal j3array[1], cj3array[1], sj3array[1];
17753 bool j3valid[1]={false};
17754 _nj3 = 1;
17755 IkReal x5670=((sj5)*(sj6));
17756 IkReal x5671=((IkReal(1.00000000000000))*(sj0));
17757 IkReal x5672=((cj6)*(sj5));
17758 IkReal x5673=((IkReal(1.00000000000000))*(cj5));
17759 if( IKabs(((((IkReal(-1.00000000000000))*(r00)*(x5670)*(x5671)))+(((cj0)*(r10)*(x5670)))+(((cj0)*(r11)*(x5672)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x5671)*(x5672)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5673))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5672)))+(((r20)*(x5670)))+(((IkReal(-1.00000000000000))*(r22)*(x5673))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r00)*(x5670)*(x5671)))+(((cj0)*(r10)*(x5670)))+(((cj0)*(r11)*(x5672)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x5671)*(x5672)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5673)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5672)))+(((r20)*(x5670)))+(((IkReal(-1.00000000000000))*(r22)*(x5673)))))))-1) <= IKFAST_SINCOS_THRESH )
17760     continue;
17761 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r00)*(x5670)*(x5671)))+(((cj0)*(r10)*(x5670)))+(((cj0)*(r11)*(x5672)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x5671)*(x5672)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x5673)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x5672)))+(((r20)*(x5670)))+(((IkReal(-1.00000000000000))*(r22)*(x5673)))))));
17762 sj3array[0]=IKsin(j3array[0]);
17763 cj3array[0]=IKcos(j3array[0]);
17764 if( j3array[0] > IKPI )
17765 {
17766     j3array[0]-=IK2PI;
17767 }
17768 else if( j3array[0] < -IKPI )
17769 {    j3array[0]+=IK2PI;
17770 }
17771 j3valid[0] = true;
17772 for(int ij3 = 0; ij3 < 1; ++ij3)
17773 {
17774 if( !j3valid[ij3] )
17775 {
17776     continue;
17777 }
17778 _ij3[0] = ij3; _ij3[1] = -1;
17779 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17780 {
17781 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17782 {
17783     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17784 }
17785 }
17786 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17787 {
17788 IkReal evalcond[6];
17789 IkReal x5674=IKsin(j3);
17790 IkReal x5675=IKcos(j3);
17791 IkReal x5676=((sj0)*(sj5));
17792 IkReal x5677=((r00)*(sj6));
17793 IkReal x5678=((IkReal(1.00000000000000))*(cj4));
17794 IkReal x5679=((cj6)*(r01));
17795 IkReal x5680=((cj0)*(cj5));
17796 IkReal x5681=((cj5)*(sj0));
17797 IkReal x5682=((cj6)*(r11));
17798 IkReal x5683=((cj0)*(sj5));
17799 IkReal x5684=((IkReal(1.00000000000000))*(cj1));
17800 IkReal x5685=((cj6)*(sj4));
17801 IkReal x5686=((IkReal(1.00000000000000))*(sj1));
17802 IkReal x5687=((cj4)*(cj5));
17803 IkReal x5688=((cj6)*(r21));
17804 IkReal x5689=((r20)*(sj6));
17805 IkReal x5690=((r10)*(sj6));
17806 IkReal x5691=((IkReal(1.00000000000000))*(cj0));
17807 IkReal x5692=((cj0)*(sj4)*(sj6));
17808 IkReal x5693=((sj0)*(sj4)*(sj6));
17809 evalcond[0]=((((IkReal(-1.00000000000000))*(x5675)*(x5686)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5689)))+(((sj5)*(x5688))));
17810 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5687)*(x5689)))+(((IkReal(-1.00000000000000))*(x5674)*(x5686)))+(((r20)*(x5685)))+(((cj4)*(r22)*(sj5)))+(((x5687)*(x5688))));
17811 evalcond[2]=((x5674)+(((IkReal(-1.00000000000000))*(x5682)*(x5683)))+(((IkReal(-1.00000000000000))*(r02)*(x5681)))+(((x5676)*(x5677)))+(((IkReal(-1.00000000000000))*(x5683)*(x5690)))+(((x5676)*(x5679)))+(((r12)*(x5680))));
17812 evalcond[3]=((((r02)*(x5680)))+(((IkReal(-1.00000000000000))*(x5675)*(x5684)))+(((IkReal(-1.00000000000000))*(x5679)*(x5683)))+(((IkReal(-1.00000000000000))*(x5676)*(x5690)))+(((r12)*(x5681)))+(((IkReal(-1.00000000000000))*(x5677)*(x5683)))+(((IkReal(-1.00000000000000))*(x5676)*(x5682))));
17813 evalcond[4]=((((IkReal(-1.00000000000000))*(x5675)))+(((cj4)*(x5677)*(x5681)))+(((IkReal(-1.00000000000000))*(r01)*(x5693)))+(((r00)*(sj0)*(x5685)))+(((cj4)*(x5679)*(x5681)))+(((IkReal(-1.00000000000000))*(x5678)*(x5680)*(x5682)))+(((cj4)*(r02)*(x5676)))+(((IkReal(-1.00000000000000))*(r12)*(x5678)*(x5683)))+(((IkReal(-1.00000000000000))*(r10)*(x5685)*(x5691)))+(((r11)*(x5692)))+(((IkReal(-1.00000000000000))*(x5678)*(x5680)*(x5690))));
17814 evalcond[5]=((((r01)*(x5692)))+(((IkReal(-1.00000000000000))*(x5674)*(x5684)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5685)))+(((r11)*(x5693)))+(((IkReal(-1.00000000000000))*(r02)*(x5678)*(x5683)))+(((IkReal(-1.00000000000000))*(x5678)*(x5681)*(x5690)))+(((IkReal(-1.00000000000000))*(r12)*(x5676)*(x5678)))+(((IkReal(-1.00000000000000))*(x5677)*(x5678)*(x5680)))+(((IkReal(-1.00000000000000))*(x5678)*(x5681)*(x5682)))+(((IkReal(-1.00000000000000))*(x5678)*(x5679)*(x5680)))+(((IkReal(-1.00000000000000))*(r00)*(x5685)*(x5691))));
17815 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
17816 {
17817 continue;
17818 }
17819 }
17820 
17821 {
17822 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17823 vinfos[0].jointtype = 1;
17824 vinfos[0].foffset = j0;
17825 vinfos[0].indices[0] = _ij0[0];
17826 vinfos[0].indices[1] = _ij0[1];
17827 vinfos[0].maxsolutions = _nj0;
17828 vinfos[1].jointtype = 1;
17829 vinfos[1].foffset = j1;
17830 vinfos[1].indices[0] = _ij1[0];
17831 vinfos[1].indices[1] = _ij1[1];
17832 vinfos[1].maxsolutions = _nj1;
17833 vinfos[2].jointtype = 1;
17834 vinfos[2].foffset = j2;
17835 vinfos[2].indices[0] = _ij2[0];
17836 vinfos[2].indices[1] = _ij2[1];
17837 vinfos[2].maxsolutions = _nj2;
17838 vinfos[3].jointtype = 1;
17839 vinfos[3].foffset = j3;
17840 vinfos[3].indices[0] = _ij3[0];
17841 vinfos[3].indices[1] = _ij3[1];
17842 vinfos[3].maxsolutions = _nj3;
17843 vinfos[4].jointtype = 1;
17844 vinfos[4].foffset = j4;
17845 vinfos[4].indices[0] = _ij4[0];
17846 vinfos[4].indices[1] = _ij4[1];
17847 vinfos[4].maxsolutions = _nj4;
17848 vinfos[5].jointtype = 1;
17849 vinfos[5].foffset = j5;
17850 vinfos[5].indices[0] = _ij5[0];
17851 vinfos[5].indices[1] = _ij5[1];
17852 vinfos[5].maxsolutions = _nj5;
17853 vinfos[6].jointtype = 1;
17854 vinfos[6].foffset = j6;
17855 vinfos[6].indices[0] = _ij6[0];
17856 vinfos[6].indices[1] = _ij6[1];
17857 vinfos[6].maxsolutions = _nj6;
17858 std::vector<int> vfree(0);
17859 solutions.AddSolution(vinfos,vfree);
17860 }
17861 }
17862 }
17863 
17864 }
17865 
17866 }
17867 
17868 } else
17869 {
17870 {
17871 IkReal j3array[1], cj3array[1], sj3array[1];
17872 bool j3valid[1]={false};
17873 _nj3 = 1;
17874 IkReal x5694=((r20)*(sj6));
17875 IkReal x5695=((cj4)*(cj5));
17876 IkReal x5696=((cj6)*(r21));
17877 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5695)*(x5696)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5694)*(x5695))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((sj5)*(x5694)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5696))))))) < IKFAST_ATAN2_MAGTHRESH )
17878     continue;
17879 j3array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x5695)*(x5696)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x5694)*(x5695)))))), ((gconst30)*(((((sj5)*(x5694)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5696)))))));
17880 sj3array[0]=IKsin(j3array[0]);
17881 cj3array[0]=IKcos(j3array[0]);
17882 if( j3array[0] > IKPI )
17883 {
17884     j3array[0]-=IK2PI;
17885 }
17886 else if( j3array[0] < -IKPI )
17887 {    j3array[0]+=IK2PI;
17888 }
17889 j3valid[0] = true;
17890 for(int ij3 = 0; ij3 < 1; ++ij3)
17891 {
17892 if( !j3valid[ij3] )
17893 {
17894     continue;
17895 }
17896 _ij3[0] = ij3; _ij3[1] = -1;
17897 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
17898 {
17899 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
17900 {
17901     j3valid[iij3]=false; _ij3[1] = iij3; break; 
17902 }
17903 }
17904 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
17905 {
17906 IkReal evalcond[6];
17907 IkReal x5697=IKsin(j3);
17908 IkReal x5698=IKcos(j3);
17909 IkReal x5699=((sj0)*(sj5));
17910 IkReal x5700=((r00)*(sj6));
17911 IkReal x5701=((IkReal(1.00000000000000))*(cj4));
17912 IkReal x5702=((cj6)*(r01));
17913 IkReal x5703=((cj0)*(cj5));
17914 IkReal x5704=((cj5)*(sj0));
17915 IkReal x5705=((cj6)*(r11));
17916 IkReal x5706=((cj0)*(sj5));
17917 IkReal x5707=((IkReal(1.00000000000000))*(cj1));
17918 IkReal x5708=((cj6)*(sj4));
17919 IkReal x5709=((IkReal(1.00000000000000))*(sj1));
17920 IkReal x5710=((cj4)*(cj5));
17921 IkReal x5711=((cj6)*(r21));
17922 IkReal x5712=((r20)*(sj6));
17923 IkReal x5713=((r10)*(sj6));
17924 IkReal x5714=((IkReal(1.00000000000000))*(cj0));
17925 IkReal x5715=((cj0)*(sj4)*(sj6));
17926 IkReal x5716=((sj0)*(sj4)*(sj6));
17927 evalcond[0]=((((sj5)*(x5711)))+(((IkReal(-1.00000000000000))*(x5698)*(x5709)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5712))));
17928 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x5710)*(x5711)))+(((r20)*(x5708)))+(((IkReal(-1.00000000000000))*(x5697)*(x5709)))+(((x5710)*(x5712))));
17929 evalcond[2]=((x5697)+(((x5699)*(x5702)))+(((x5699)*(x5700)))+(((IkReal(-1.00000000000000))*(r02)*(x5704)))+(((IkReal(-1.00000000000000))*(x5706)*(x5713)))+(((IkReal(-1.00000000000000))*(x5705)*(x5706)))+(((r12)*(x5703))));
17930 evalcond[3]=((((IkReal(-1.00000000000000))*(x5702)*(x5706)))+(((r02)*(x5703)))+(((IkReal(-1.00000000000000))*(x5700)*(x5706)))+(((IkReal(-1.00000000000000))*(x5699)*(x5705)))+(((IkReal(-1.00000000000000))*(x5698)*(x5707)))+(((r12)*(x5704)))+(((IkReal(-1.00000000000000))*(x5699)*(x5713))));
17931 evalcond[4]=((((IkReal(-1.00000000000000))*(x5701)*(x5703)*(x5713)))+(((IkReal(-1.00000000000000))*(r01)*(x5716)))+(((IkReal(-1.00000000000000))*(x5698)))+(((IkReal(-1.00000000000000))*(r12)*(x5701)*(x5706)))+(((IkReal(-1.00000000000000))*(r10)*(x5708)*(x5714)))+(((r00)*(sj0)*(x5708)))+(((r11)*(x5715)))+(((cj4)*(x5702)*(x5704)))+(((cj4)*(x5700)*(x5704)))+(((IkReal(-1.00000000000000))*(x5701)*(x5703)*(x5705)))+(((cj4)*(r02)*(x5699))));
17932 evalcond[5]=((((IkReal(-1.00000000000000))*(x5701)*(x5702)*(x5703)))+(((r01)*(x5715)))+(((IkReal(-1.00000000000000))*(x5700)*(x5701)*(x5703)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5708)))+(((IkReal(-1.00000000000000))*(r00)*(x5708)*(x5714)))+(((IkReal(-1.00000000000000))*(x5697)*(x5707)))+(((IkReal(-1.00000000000000))*(r12)*(x5699)*(x5701)))+(((r11)*(x5716)))+(((IkReal(-1.00000000000000))*(x5701)*(x5704)*(x5705)))+(((IkReal(-1.00000000000000))*(x5701)*(x5704)*(x5713)))+(((IkReal(-1.00000000000000))*(r02)*(x5701)*(x5706))));
17933 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
17934 {
17935 continue;
17936 }
17937 }
17938 
17939 {
17940 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
17941 vinfos[0].jointtype = 1;
17942 vinfos[0].foffset = j0;
17943 vinfos[0].indices[0] = _ij0[0];
17944 vinfos[0].indices[1] = _ij0[1];
17945 vinfos[0].maxsolutions = _nj0;
17946 vinfos[1].jointtype = 1;
17947 vinfos[1].foffset = j1;
17948 vinfos[1].indices[0] = _ij1[0];
17949 vinfos[1].indices[1] = _ij1[1];
17950 vinfos[1].maxsolutions = _nj1;
17951 vinfos[2].jointtype = 1;
17952 vinfos[2].foffset = j2;
17953 vinfos[2].indices[0] = _ij2[0];
17954 vinfos[2].indices[1] = _ij2[1];
17955 vinfos[2].maxsolutions = _nj2;
17956 vinfos[3].jointtype = 1;
17957 vinfos[3].foffset = j3;
17958 vinfos[3].indices[0] = _ij3[0];
17959 vinfos[3].indices[1] = _ij3[1];
17960 vinfos[3].maxsolutions = _nj3;
17961 vinfos[4].jointtype = 1;
17962 vinfos[4].foffset = j4;
17963 vinfos[4].indices[0] = _ij4[0];
17964 vinfos[4].indices[1] = _ij4[1];
17965 vinfos[4].maxsolutions = _nj4;
17966 vinfos[5].jointtype = 1;
17967 vinfos[5].foffset = j5;
17968 vinfos[5].indices[0] = _ij5[0];
17969 vinfos[5].indices[1] = _ij5[1];
17970 vinfos[5].maxsolutions = _nj5;
17971 vinfos[6].jointtype = 1;
17972 vinfos[6].foffset = j6;
17973 vinfos[6].indices[0] = _ij6[0];
17974 vinfos[6].indices[1] = _ij6[1];
17975 vinfos[6].maxsolutions = _nj6;
17976 std::vector<int> vfree(0);
17977 solutions.AddSolution(vinfos,vfree);
17978 }
17979 }
17980 }
17981 
17982 }
17983 
17984 }
17985 }
17986 }
17987 
17988 }
17989 
17990 }
17991 
17992 } else
17993 {
17994 if( 1 )
17995 {
17996 continue;
17997 
17998 } else
17999 {
18000 }
18001 }
18002 }
18003 }
18004 
18005 } else
18006 {
18007 {
18008 IkReal j3array[1], cj3array[1], sj3array[1];
18009 bool j3valid[1]={false};
18010 _nj3 = 1;
18011 IkReal x5717=(cj1)*(cj1);
18012 IkReal x5718=(sj1)*(sj1);
18013 IkReal x5719=((r00)*(sj6));
18014 IkReal x5720=((cj6)*(r01));
18015 IkReal x5721=((IkReal(1.00000000000000))*(cj1));
18016 IkReal x5722=((cj5)*(r22));
18017 IkReal x5723=((sj5)*(sj6));
18018 IkReal x5724=((r10)*(sj0));
18019 IkReal x5725=((cj1)*(cj5));
18020 IkReal x5726=((cj0)*(r02));
18021 IkReal x5727=((r12)*(sj0));
18022 IkReal x5728=((IkReal(1.00000000000000))*(sj1));
18023 IkReal x5729=((cj6)*(sj5));
18024 IkReal x5730=((cj0)*(sj5));
18025 IkReal x5731=((r11)*(sj0));
18026 IkReal x5732=((sj1)*(x5730));
18027 if( IKabs(((((IKabs(((((cj2)*(x5717)))+(((cj2)*(x5718))))) != 0)?((IkReal)1/(((((cj2)*(x5717)))+(((cj2)*(x5718)))))):(IkReal)1.0e30))*(((((x5720)*(x5732)))+(((sj1)*(x5729)*(x5731)))+(((IkReal(-1.00000000000000))*(cj5)*(x5726)*(x5728)))+(((IkReal(-1.00000000000000))*(cj5)*(x5727)*(x5728)))+(((cj1)*(r21)*(x5729)))+(((cj1)*(r20)*(x5723)))+(((x5719)*(x5732)))+(((sj1)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5721)*(x5722))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x5718)+(x5717))) != 0)?((IkReal)1/(((x5718)+(x5717)))):(IkReal)1.0e30))*(((((x5725)*(x5726)))+(((IkReal(-1.00000000000000))*(x5721)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5719)*(x5721)*(x5730)))+(((x5725)*(x5727)))+(((IkReal(-1.00000000000000))*(x5722)*(x5728)))+(((r20)*(sj1)*(x5723)))+(((r21)*(sj1)*(x5729)))+(((IkReal(-1.00000000000000))*(x5720)*(x5721)*(x5730)))+(((IkReal(-1.00000000000000))*(x5721)*(x5729)*(x5731))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x5717)))+(((cj2)*(x5718))))) != 0)?((IkReal)1/(((((cj2)*(x5717)))+(((cj2)*(x5718)))))):(IkReal)1.0e30))*(((((x5720)*(x5732)))+(((sj1)*(x5729)*(x5731)))+(((IkReal(-1.00000000000000))*(cj5)*(x5726)*(x5728)))+(((IkReal(-1.00000000000000))*(cj5)*(x5727)*(x5728)))+(((cj1)*(r21)*(x5729)))+(((cj1)*(r20)*(x5723)))+(((x5719)*(x5732)))+(((sj1)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5721)*(x5722)))))))+IKsqr(((((IKabs(((x5718)+(x5717))) != 0)?((IkReal)1/(((x5718)+(x5717)))):(IkReal)1.0e30))*(((((x5725)*(x5726)))+(((IkReal(-1.00000000000000))*(x5721)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5719)*(x5721)*(x5730)))+(((x5725)*(x5727)))+(((IkReal(-1.00000000000000))*(x5722)*(x5728)))+(((r20)*(sj1)*(x5723)))+(((r21)*(sj1)*(x5729)))+(((IkReal(-1.00000000000000))*(x5720)*(x5721)*(x5730)))+(((IkReal(-1.00000000000000))*(x5721)*(x5729)*(x5731)))))))-1) <= IKFAST_SINCOS_THRESH )
18028     continue;
18029 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x5717)))+(((cj2)*(x5718))))) != 0)?((IkReal)1/(((((cj2)*(x5717)))+(((cj2)*(x5718)))))):(IkReal)1.0e30))*(((((x5720)*(x5732)))+(((sj1)*(x5729)*(x5731)))+(((IkReal(-1.00000000000000))*(cj5)*(x5726)*(x5728)))+(((IkReal(-1.00000000000000))*(cj5)*(x5727)*(x5728)))+(((cj1)*(r21)*(x5729)))+(((cj1)*(r20)*(x5723)))+(((x5719)*(x5732)))+(((sj1)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5721)*(x5722)))))), ((((IKabs(((x5718)+(x5717))) != 0)?((IkReal)1/(((x5718)+(x5717)))):(IkReal)1.0e30))*(((((x5725)*(x5726)))+(((IkReal(-1.00000000000000))*(x5721)*(x5723)*(x5724)))+(((IkReal(-1.00000000000000))*(x5719)*(x5721)*(x5730)))+(((x5725)*(x5727)))+(((IkReal(-1.00000000000000))*(x5722)*(x5728)))+(((r20)*(sj1)*(x5723)))+(((r21)*(sj1)*(x5729)))+(((IkReal(-1.00000000000000))*(x5720)*(x5721)*(x5730)))+(((IkReal(-1.00000000000000))*(x5721)*(x5729)*(x5731)))))));
18030 sj3array[0]=IKsin(j3array[0]);
18031 cj3array[0]=IKcos(j3array[0]);
18032 if( j3array[0] > IKPI )
18033 {
18034     j3array[0]-=IK2PI;
18035 }
18036 else if( j3array[0] < -IKPI )
18037 {    j3array[0]+=IK2PI;
18038 }
18039 j3valid[0] = true;
18040 for(int ij3 = 0; ij3 < 1; ++ij3)
18041 {
18042 if( !j3valid[ij3] )
18043 {
18044     continue;
18045 }
18046 _ij3[0] = ij3; _ij3[1] = -1;
18047 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18048 {
18049 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18050 {
18051     j3valid[iij3]=false; _ij3[1] = iij3; break; 
18052 }
18053 }
18054 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18055 {
18056 IkReal evalcond[3];
18057 IkReal x5733=IKsin(j3);
18058 IkReal x5734=IKcos(j3);
18059 IkReal x5735=((sj5)*(sj6));
18060 IkReal x5736=((cj0)*(cj5));
18061 IkReal x5737=((IkReal(1.00000000000000))*(cj0));
18062 IkReal x5738=((IkReal(1.00000000000000))*(sj0));
18063 IkReal x5739=((IkReal(1.00000000000000))*(x5734));
18064 IkReal x5740=((IkReal(1.00000000000000))*(x5733));
18065 IkReal x5741=((cj6)*(r01)*(sj5));
18066 IkReal x5742=((cj6)*(r11)*(sj5));
18067 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x5739)))+(((IkReal(-1.00000000000000))*(cj1)*(cj2)*(x5740)))+(((r20)*(x5735))));
18068 evalcond[1]=((((IkReal(-1.00000000000000))*(x5737)*(x5742)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x5738)))+(((r12)*(x5736)))+(((IkReal(-1.00000000000000))*(r10)*(x5735)*(x5737)))+(((sj0)*(x5741)))+(((IkReal(-1.00000000000000))*(sj2)*(x5740)))+(((r00)*(sj0)*(x5735))));
18069 evalcond[2]=((((cj2)*(sj1)*(x5733)))+(((IkReal(-1.00000000000000))*(r00)*(x5735)*(x5737)))+(((IkReal(-1.00000000000000))*(x5738)*(x5742)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(x5737)*(x5741)))+(((r02)*(x5736)))+(((IkReal(-1.00000000000000))*(r10)*(x5735)*(x5738)))+(((IkReal(-1.00000000000000))*(cj1)*(x5739))));
18070 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
18071 {
18072 continue;
18073 }
18074 }
18075 
18076 {
18077 IkReal dummyeval[1];
18078 IkReal gconst2;
18079 IkReal x5743=(r21)*(r21);
18080 IkReal x5744=(cj5)*(cj5);
18081 IkReal x5745=(sj6)*(sj6);
18082 IkReal x5746=(cj6)*(cj6);
18083 IkReal x5747=(r20)*(r20);
18084 IkReal x5748=((cj6)*(r21));
18085 IkReal x5749=((IkReal(2.00000000000000))*(r20)*(sj6));
18086 IkReal x5750=((cj5)*(r22)*(sj5));
18087 IkReal x5751=((IkReal(1.00000000000000))*(x5745));
18088 IkReal x5752=((IkReal(1.00000000000000))*(x5746));
18089 gconst2=IKsign(((((x5748)*(x5749)))+(((IkReal(-1.00000000000000))*(x5749)*(x5750)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-2.00000000000000))*(x5748)*(x5750)))+(((IkReal(-1.00000000000000))*(x5744)*(x5747)*(x5751)))+(((IkReal(-1.00000000000000))*(x5743)*(x5744)*(x5752)))+(((IkReal(-1.00000000000000))*(x5743)*(x5751)))+(((IkReal(-1.00000000000000))*(x5747)*(x5752)))+(((IkReal(-1.00000000000000))*(x5744)*(x5748)*(x5749)))));
18090 IkReal x5753=(r21)*(r21);
18091 IkReal x5754=(cj5)*(cj5);
18092 IkReal x5755=(sj6)*(sj6);
18093 IkReal x5756=(cj6)*(cj6);
18094 IkReal x5757=(r20)*(r20);
18095 IkReal x5758=((cj6)*(r21));
18096 IkReal x5759=((IkReal(2.00000000000000))*(r20)*(sj6));
18097 IkReal x5760=((cj5)*(r22)*(sj5));
18098 IkReal x5761=((IkReal(1.00000000000000))*(x5755));
18099 IkReal x5762=((IkReal(1.00000000000000))*(x5756));
18100 dummyeval[0]=((((IkReal(-2.00000000000000))*(x5758)*(x5760)))+(((IkReal(-1.00000000000000))*(x5753)*(x5761)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x5754)*(x5758)*(x5759)))+(((IkReal(-1.00000000000000))*(x5754)*(x5757)*(x5761)))+(((IkReal(-1.00000000000000))*(x5759)*(x5760)))+(((x5758)*(x5759)))+(((IkReal(-1.00000000000000))*(x5753)*(x5754)*(x5762)))+(((IkReal(-1.00000000000000))*(x5757)*(x5762))));
18101 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18102 {
18103 {
18104 IkReal dummyeval[1];
18105 IkReal gconst3;
18106 IkReal x5763=(cj6)*(cj6);
18107 IkReal x5764=(sj6)*(sj6);
18108 IkReal x5765=((IkReal(1.00000000000000))*(r21));
18109 IkReal x5766=((cj6)*(r20));
18110 IkReal x5767=((r22)*(sj5));
18111 IkReal x5768=((r01)*(sj0));
18112 IkReal x5769=((r00)*(sj0));
18113 IkReal x5770=((cj0)*(r10));
18114 IkReal x5771=((r02)*(sj0)*(sj5));
18115 IkReal x5772=((cj5)*(x5763));
18116 IkReal x5773=((cj0)*(r12)*(sj5));
18117 IkReal x5774=((IkReal(1.00000000000000))*(cj0)*(r11));
18118 IkReal x5775=((cj5)*(x5764));
18119 IkReal x5776=((r20)*(x5775));
18120 gconst3=IKsign(((((IkReal(-1.00000000000000))*(x5765)*(x5769)*(x5775)))+(((sj6)*(x5767)*(x5768)))+(((IkReal(-1.00000000000000))*(x5774)*(x5776)))+(((x5768)*(x5776)))+(((r21)*(x5770)*(x5775)))+(((cj6)*(x5767)*(x5770)))+(((r21)*(x5770)*(x5772)))+(((IkReal(-1.00000000000000))*(r20)*(x5772)*(x5774)))+(((r21)*(sj6)*(x5773)))+(((IkReal(-1.00000000000000))*(x5766)*(x5773)))+(((IkReal(-1.00000000000000))*(sj6)*(x5767)*(x5774)))+(((IkReal(-1.00000000000000))*(cj6)*(x5767)*(x5769)))+(((IkReal(-1.00000000000000))*(x5765)*(x5769)*(x5772)))+(((r20)*(x5768)*(x5772)))+(((IkReal(-1.00000000000000))*(sj6)*(x5765)*(x5771)))+(((x5766)*(x5771)))));
18121 IkReal x5777=(cj6)*(cj6);
18122 IkReal x5778=(sj6)*(sj6);
18123 IkReal x5779=((IkReal(1.00000000000000))*(r21));
18124 IkReal x5780=((cj6)*(r20));
18125 IkReal x5781=((r22)*(sj5));
18126 IkReal x5782=((r01)*(sj0));
18127 IkReal x5783=((r00)*(sj0));
18128 IkReal x5784=((cj0)*(r10));
18129 IkReal x5785=((r02)*(sj0)*(sj5));
18130 IkReal x5786=((cj5)*(x5777));
18131 IkReal x5787=((cj0)*(r12)*(sj5));
18132 IkReal x5788=((IkReal(1.00000000000000))*(cj0)*(r11));
18133 IkReal x5789=((cj5)*(x5778));
18134 IkReal x5790=((r20)*(x5789));
18135 dummyeval[0]=((((x5780)*(x5785)))+(((r20)*(x5782)*(x5786)))+(((sj6)*(x5781)*(x5782)))+(((x5782)*(x5790)))+(((IkReal(-1.00000000000000))*(cj6)*(x5781)*(x5783)))+(((r21)*(x5784)*(x5789)))+(((r21)*(sj6)*(x5787)))+(((IkReal(-1.00000000000000))*(r20)*(x5786)*(x5788)))+(((IkReal(-1.00000000000000))*(sj6)*(x5779)*(x5785)))+(((IkReal(-1.00000000000000))*(x5788)*(x5790)))+(((r21)*(x5784)*(x5786)))+(((IkReal(-1.00000000000000))*(sj6)*(x5781)*(x5788)))+(((IkReal(-1.00000000000000))*(x5779)*(x5783)*(x5786)))+(((IkReal(-1.00000000000000))*(x5780)*(x5787)))+(((cj6)*(x5781)*(x5784)))+(((IkReal(-1.00000000000000))*(x5779)*(x5783)*(x5789))));
18136 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18137 {
18138 continue;
18139 
18140 } else
18141 {
18142 {
18143 IkReal j4array[1], cj4array[1], sj4array[1];
18144 bool j4valid[1]={false};
18145 _nj4 = 1;
18146 IkReal x5791=((cj5)*(sj6));
18147 IkReal x5792=((cj2)*(r21));
18148 IkReal x5793=((cj5)*(cj6));
18149 IkReal x5794=((IkReal(1.00000000000000))*(cj2)*(r20));
18150 IkReal x5795=((cj0)*(cj1)*(sj2));
18151 IkReal x5796=((IkReal(1.00000000000000))*(cj1)*(sj0)*(sj2));
18152 IkReal x5797=((r10)*(x5795));
18153 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(r11)*(sj6)*(x5795)))+(((sj6)*(x5792)))+(((IkReal(-1.00000000000000))*(cj6)*(x5794)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x5796)))+(((cj1)*(r01)*(sj0)*(sj2)*(sj6)))+(((cj6)*(x5797))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(x5792)*(x5793)))+(((r11)*(x5793)*(x5795)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x5796)))+(((x5791)*(x5797)))+(((IkReal(-1.00000000000000))*(r01)*(x5793)*(x5796)))+(((IkReal(-1.00000000000000))*(r00)*(x5791)*(x5796)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x5791)*(x5794)))+(((r12)*(sj5)*(x5795))))))) < IKFAST_ATAN2_MAGTHRESH )
18154     continue;
18155 j4array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(r11)*(sj6)*(x5795)))+(((sj6)*(x5792)))+(((IkReal(-1.00000000000000))*(cj6)*(x5794)))+(((IkReal(-1.00000000000000))*(cj6)*(r00)*(x5796)))+(((cj1)*(r01)*(sj0)*(sj2)*(sj6)))+(((cj6)*(x5797)))))), ((gconst3)*(((((IkReal(-1.00000000000000))*(x5792)*(x5793)))+(((r11)*(x5793)*(x5795)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x5796)))+(((x5791)*(x5797)))+(((IkReal(-1.00000000000000))*(r01)*(x5793)*(x5796)))+(((IkReal(-1.00000000000000))*(r00)*(x5791)*(x5796)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x5791)*(x5794)))+(((r12)*(sj5)*(x5795)))))));
18156 sj4array[0]=IKsin(j4array[0]);
18157 cj4array[0]=IKcos(j4array[0]);
18158 if( j4array[0] > IKPI )
18159 {
18160     j4array[0]-=IK2PI;
18161 }
18162 else if( j4array[0] < -IKPI )
18163 {    j4array[0]+=IK2PI;
18164 }
18165 j4valid[0] = true;
18166 for(int ij4 = 0; ij4 < 1; ++ij4)
18167 {
18168 if( !j4valid[ij4] )
18169 {
18170     continue;
18171 }
18172 _ij4[0] = ij4; _ij4[1] = -1;
18173 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
18174 {
18175 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
18176 {
18177     j4valid[iij4]=false; _ij4[1] = iij4; break; 
18178 }
18179 }
18180 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
18181 {
18182 IkReal evalcond[6];
18183 IkReal x5798=IKsin(j4);
18184 IkReal x5799=IKcos(j4);
18185 IkReal x5800=((r00)*(sj6));
18186 IkReal x5801=((IkReal(1.00000000000000))*(r12));
18187 IkReal x5802=((IkReal(1.00000000000000))*(cj6));
18188 IkReal x5803=((cj6)*(r01));
18189 IkReal x5804=((IkReal(1.00000000000000))*(cj1));
18190 IkReal x5805=((cj2)*(cj3));
18191 IkReal x5806=((IkReal(1.00000000000000))*(sj1));
18192 IkReal x5807=((r11)*(sj6));
18193 IkReal x5808=((r01)*(sj6));
18194 IkReal x5809=((IkReal(1.00000000000000))*(cj5));
18195 IkReal x5810=((r10)*(sj6));
18196 IkReal x5811=((cj5)*(r11));
18197 IkReal x5812=((cj6)*(r00));
18198 IkReal x5813=((r21)*(sj6));
18199 IkReal x5814=((r02)*(sj5));
18200 IkReal x5815=((cj6)*(r10));
18201 IkReal x5816=((cj5)*(sj6));
18202 IkReal x5817=((cj5)*(r01));
18203 IkReal x5818=((sj5)*(x5798));
18204 IkReal x5819=((cj0)*(x5799));
18205 IkReal x5820=((cj0)*(x5798));
18206 IkReal x5821=((sj0)*(x5799));
18207 IkReal x5822=((sj0)*(x5798));
18208 IkReal x5823=((r20)*(x5799));
18209 IkReal x5824=((cj5)*(cj6)*(r21));
18210 IkReal x5825=((r20)*(x5798));
18211 IkReal x5826=((cj5)*(x5822));
18212 evalcond[0]=((((IkReal(-1.00000000000000))*(sj2)*(x5804)))+(((x5816)*(x5825)))+(((r22)*(x5818)))+(((IkReal(-1.00000000000000))*(x5802)*(x5823)))+(((x5798)*(x5824)))+(((x5799)*(x5813))));
18213 evalcond[1]=((((x5799)*(x5824)))+(((IkReal(-1.00000000000000))*(sj3)*(x5806)))+(((cj1)*(x5805)))+(((r22)*(sj5)*(x5799)))+(((IkReal(-1.00000000000000))*(x5798)*(x5813)))+(((x5816)*(x5823)))+(((cj6)*(x5825))));
18214 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x5802)*(x5821)))+(((IkReal(-1.00000000000000))*(cj0)*(x5801)*(x5818)))+(((IkReal(-1.00000000000000))*(x5802)*(x5811)*(x5820)))+(((x5808)*(x5821)))+(cj2)+(((x5803)*(x5826)))+(((IkReal(-1.00000000000000))*(x5809)*(x5810)*(x5820)))+(((x5800)*(x5826)))+(((x5815)*(x5819)))+(((IkReal(-1.00000000000000))*(x5807)*(x5819)))+(((x5814)*(x5822))));
18215 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x5802)*(x5820)))+(((cj5)*(x5803)*(x5821)))+(((IkReal(-1.00000000000000))*(sj5)*(x5801)*(x5819)))+(((x5807)*(x5820)))+(((IkReal(-1.00000000000000))*(x5808)*(x5822)))+(((x5814)*(x5821)))+(((x5812)*(x5822)))+(((IkReal(-1.00000000000000))*(x5809)*(x5810)*(x5819)))+(((cj3)*(sj2)))+(((cj5)*(x5800)*(x5821)))+(((IkReal(-1.00000000000000))*(x5802)*(x5811)*(x5819))));
18216 evalcond[4]=((((IkReal(-1.00000000000000))*(x5809)*(x5810)*(x5822)))+(((x5815)*(x5821)))+(((IkReal(-1.00000000000000))*(x5814)*(x5820)))+(((IkReal(-1.00000000000000))*(x5808)*(x5819)))+(((x5812)*(x5819)))+(((IkReal(-1.00000000000000))*(sj0)*(x5801)*(x5818)))+(((IkReal(-1.00000000000000))*(x5807)*(x5821)))+(((IkReal(-1.00000000000000))*(x5800)*(x5809)*(x5820)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x5802)*(x5811)*(x5822)))+(((IkReal(-1.00000000000000))*(x5802)*(x5817)*(x5820))));
18217 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x5801)*(x5821)))+(((IkReal(-1.00000000000000))*(x5802)*(x5817)*(x5819)))+(((IkReal(-1.00000000000000))*(x5805)*(x5806)))+(((IkReal(-1.00000000000000))*(x5814)*(x5819)))+(((IkReal(-1.00000000000000))*(r10)*(x5802)*(x5822)))+(((IkReal(-1.00000000000000))*(x5809)*(x5810)*(x5821)))+(((IkReal(-1.00000000000000))*(x5802)*(x5811)*(x5821)))+(((x5808)*(x5820)))+(((IkReal(-1.00000000000000))*(r00)*(x5802)*(x5820)))+(((x5807)*(x5822)))+(((IkReal(-1.00000000000000))*(sj3)*(x5804)))+(((IkReal(-1.00000000000000))*(x5800)*(x5809)*(x5819))));
18218 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
18219 {
18220 continue;
18221 }
18222 }
18223 
18224 {
18225 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
18226 vinfos[0].jointtype = 1;
18227 vinfos[0].foffset = j0;
18228 vinfos[0].indices[0] = _ij0[0];
18229 vinfos[0].indices[1] = _ij0[1];
18230 vinfos[0].maxsolutions = _nj0;
18231 vinfos[1].jointtype = 1;
18232 vinfos[1].foffset = j1;
18233 vinfos[1].indices[0] = _ij1[0];
18234 vinfos[1].indices[1] = _ij1[1];
18235 vinfos[1].maxsolutions = _nj1;
18236 vinfos[2].jointtype = 1;
18237 vinfos[2].foffset = j2;
18238 vinfos[2].indices[0] = _ij2[0];
18239 vinfos[2].indices[1] = _ij2[1];
18240 vinfos[2].maxsolutions = _nj2;
18241 vinfos[3].jointtype = 1;
18242 vinfos[3].foffset = j3;
18243 vinfos[3].indices[0] = _ij3[0];
18244 vinfos[3].indices[1] = _ij3[1];
18245 vinfos[3].maxsolutions = _nj3;
18246 vinfos[4].jointtype = 1;
18247 vinfos[4].foffset = j4;
18248 vinfos[4].indices[0] = _ij4[0];
18249 vinfos[4].indices[1] = _ij4[1];
18250 vinfos[4].maxsolutions = _nj4;
18251 vinfos[5].jointtype = 1;
18252 vinfos[5].foffset = j5;
18253 vinfos[5].indices[0] = _ij5[0];
18254 vinfos[5].indices[1] = _ij5[1];
18255 vinfos[5].maxsolutions = _nj5;
18256 vinfos[6].jointtype = 1;
18257 vinfos[6].foffset = j6;
18258 vinfos[6].indices[0] = _ij6[0];
18259 vinfos[6].indices[1] = _ij6[1];
18260 vinfos[6].maxsolutions = _nj6;
18261 std::vector<int> vfree(0);
18262 solutions.AddSolution(vinfos,vfree);
18263 }
18264 }
18265 }
18266 
18267 }
18268 
18269 }
18270 
18271 } else
18272 {
18273 {
18274 IkReal j4array[1], cj4array[1], sj4array[1];
18275 bool j4valid[1]={false};
18276 _nj4 = 1;
18277 IkReal x5827=((cj1)*(sj2));
18278 IkReal x5828=((cj6)*(r20));
18279 IkReal x5829=((sj1)*(sj3));
18280 IkReal x5830=((r21)*(sj6));
18281 IkReal x5831=((IkReal(1.00000000000000))*(cj5));
18282 IkReal x5832=((cj6)*(r21));
18283 IkReal x5833=((r20)*(sj6));
18284 IkReal x5834=((IkReal(1.00000000000000))*(r22)*(sj5));
18285 IkReal x5835=((cj1)*(cj2)*(cj3));
18286 if( IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x5827)*(x5831)*(x5832)))+(((x5828)*(x5835)))+(((IkReal(-1.00000000000000))*(x5827)*(x5831)*(x5833)))+(((IkReal(-1.00000000000000))*(x5830)*(x5835)))+(((x5829)*(x5830)))+(((IkReal(-1.00000000000000))*(x5827)*(x5834)))+(((IkReal(-1.00000000000000))*(x5828)*(x5829))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x5829)*(x5831)*(x5832)))+(((IkReal(-1.00000000000000))*(x5829)*(x5834)))+(((cj5)*(x5833)*(x5835)))+(((IkReal(-1.00000000000000))*(x5827)*(x5830)))+(((x5827)*(x5828)))+(((r22)*(sj5)*(x5835)))+(((cj5)*(x5832)*(x5835)))+(((IkReal(-1.00000000000000))*(x5829)*(x5831)*(x5833))))))) < IKFAST_ATAN2_MAGTHRESH )
18287     continue;
18288 j4array[0]=IKatan2(((gconst2)*(((((IkReal(-1.00000000000000))*(x5827)*(x5831)*(x5832)))+(((x5828)*(x5835)))+(((IkReal(-1.00000000000000))*(x5827)*(x5831)*(x5833)))+(((IkReal(-1.00000000000000))*(x5830)*(x5835)))+(((x5829)*(x5830)))+(((IkReal(-1.00000000000000))*(x5827)*(x5834)))+(((IkReal(-1.00000000000000))*(x5828)*(x5829)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(x5829)*(x5831)*(x5832)))+(((IkReal(-1.00000000000000))*(x5829)*(x5834)))+(((cj5)*(x5833)*(x5835)))+(((IkReal(-1.00000000000000))*(x5827)*(x5830)))+(((x5827)*(x5828)))+(((r22)*(sj5)*(x5835)))+(((cj5)*(x5832)*(x5835)))+(((IkReal(-1.00000000000000))*(x5829)*(x5831)*(x5833)))))));
18289 sj4array[0]=IKsin(j4array[0]);
18290 cj4array[0]=IKcos(j4array[0]);
18291 if( j4array[0] > IKPI )
18292 {
18293     j4array[0]-=IK2PI;
18294 }
18295 else if( j4array[0] < -IKPI )
18296 {    j4array[0]+=IK2PI;
18297 }
18298 j4valid[0] = true;
18299 for(int ij4 = 0; ij4 < 1; ++ij4)
18300 {
18301 if( !j4valid[ij4] )
18302 {
18303     continue;
18304 }
18305 _ij4[0] = ij4; _ij4[1] = -1;
18306 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
18307 {
18308 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
18309 {
18310     j4valid[iij4]=false; _ij4[1] = iij4; break; 
18311 }
18312 }
18313 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
18314 {
18315 IkReal evalcond[6];
18316 IkReal x5836=IKsin(j4);
18317 IkReal x5837=IKcos(j4);
18318 IkReal x5838=((r00)*(sj6));
18319 IkReal x5839=((IkReal(1.00000000000000))*(r12));
18320 IkReal x5840=((IkReal(1.00000000000000))*(cj6));
18321 IkReal x5841=((cj6)*(r01));
18322 IkReal x5842=((IkReal(1.00000000000000))*(cj1));
18323 IkReal x5843=((cj2)*(cj3));
18324 IkReal x5844=((IkReal(1.00000000000000))*(sj1));
18325 IkReal x5845=((r11)*(sj6));
18326 IkReal x5846=((r01)*(sj6));
18327 IkReal x5847=((IkReal(1.00000000000000))*(cj5));
18328 IkReal x5848=((r10)*(sj6));
18329 IkReal x5849=((cj5)*(r11));
18330 IkReal x5850=((cj6)*(r00));
18331 IkReal x5851=((r21)*(sj6));
18332 IkReal x5852=((r02)*(sj5));
18333 IkReal x5853=((cj6)*(r10));
18334 IkReal x5854=((cj5)*(sj6));
18335 IkReal x5855=((cj5)*(r01));
18336 IkReal x5856=((sj5)*(x5836));
18337 IkReal x5857=((cj0)*(x5837));
18338 IkReal x5858=((cj0)*(x5836));
18339 IkReal x5859=((sj0)*(x5837));
18340 IkReal x5860=((sj0)*(x5836));
18341 IkReal x5861=((r20)*(x5837));
18342 IkReal x5862=((cj5)*(cj6)*(r21));
18343 IkReal x5863=((r20)*(x5836));
18344 IkReal x5864=((cj5)*(x5860));
18345 evalcond[0]=((((x5837)*(x5851)))+(((r22)*(x5856)))+(((x5836)*(x5862)))+(((IkReal(-1.00000000000000))*(x5840)*(x5861)))+(((x5854)*(x5863)))+(((IkReal(-1.00000000000000))*(sj2)*(x5842))));
18346 evalcond[1]=((((x5837)*(x5862)))+(((IkReal(-1.00000000000000))*(sj3)*(x5844)))+(((IkReal(-1.00000000000000))*(x5836)*(x5851)))+(((x5854)*(x5861)))+(((cj1)*(x5843)))+(((cj6)*(x5863)))+(((r22)*(sj5)*(x5837))));
18347 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(x5839)*(x5856)))+(((IkReal(-1.00000000000000))*(x5840)*(x5849)*(x5858)))+(((x5853)*(x5857)))+(((IkReal(-1.00000000000000))*(r00)*(x5840)*(x5859)))+(((IkReal(-1.00000000000000))*(x5845)*(x5857)))+(cj2)+(((IkReal(-1.00000000000000))*(x5847)*(x5848)*(x5858)))+(((x5846)*(x5859)))+(((x5841)*(x5864)))+(((x5838)*(x5864)))+(((x5852)*(x5860))));
18348 evalcond[3]=((((cj5)*(x5838)*(x5859)))+(((cj5)*(x5841)*(x5859)))+(((x5852)*(x5859)))+(((x5850)*(x5860)))+(((IkReal(-1.00000000000000))*(sj5)*(x5839)*(x5857)))+(((x5845)*(x5858)))+(((IkReal(-1.00000000000000))*(x5840)*(x5849)*(x5857)))+(((IkReal(-1.00000000000000))*(r10)*(x5840)*(x5858)))+(((IkReal(-1.00000000000000))*(x5847)*(x5848)*(x5857)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(x5846)*(x5860))));
18349 evalcond[4]=((((IkReal(-1.00000000000000))*(x5852)*(x5858)))+(((IkReal(-1.00000000000000))*(x5840)*(x5855)*(x5858)))+(((IkReal(-1.00000000000000))*(x5847)*(x5848)*(x5860)))+(((IkReal(-1.00000000000000))*(x5840)*(x5849)*(x5860)))+(((IkReal(-1.00000000000000))*(sj0)*(x5839)*(x5856)))+(((x5853)*(x5859)))+(((IkReal(-1.00000000000000))*(x5838)*(x5847)*(x5858)))+(((x5850)*(x5857)))+(((IkReal(-1.00000000000000))*(x5845)*(x5859)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x5846)*(x5857))));
18350 evalcond[5]=((((IkReal(-1.00000000000000))*(x5840)*(x5855)*(x5857)))+(((IkReal(-1.00000000000000))*(x5852)*(x5857)))+(((IkReal(-1.00000000000000))*(x5838)*(x5847)*(x5857)))+(((IkReal(-1.00000000000000))*(r10)*(x5840)*(x5860)))+(((IkReal(-1.00000000000000))*(x5847)*(x5848)*(x5859)))+(((x5845)*(x5860)))+(((IkReal(-1.00000000000000))*(x5840)*(x5849)*(x5859)))+(((IkReal(-1.00000000000000))*(r00)*(x5840)*(x5858)))+(((x5846)*(x5858)))+(((IkReal(-1.00000000000000))*(x5843)*(x5844)))+(((IkReal(-1.00000000000000))*(sj3)*(x5842)))+(((IkReal(-1.00000000000000))*(sj5)*(x5839)*(x5859))));
18351 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
18352 {
18353 continue;
18354 }
18355 }
18356 
18357 {
18358 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
18359 vinfos[0].jointtype = 1;
18360 vinfos[0].foffset = j0;
18361 vinfos[0].indices[0] = _ij0[0];
18362 vinfos[0].indices[1] = _ij0[1];
18363 vinfos[0].maxsolutions = _nj0;
18364 vinfos[1].jointtype = 1;
18365 vinfos[1].foffset = j1;
18366 vinfos[1].indices[0] = _ij1[0];
18367 vinfos[1].indices[1] = _ij1[1];
18368 vinfos[1].maxsolutions = _nj1;
18369 vinfos[2].jointtype = 1;
18370 vinfos[2].foffset = j2;
18371 vinfos[2].indices[0] = _ij2[0];
18372 vinfos[2].indices[1] = _ij2[1];
18373 vinfos[2].maxsolutions = _nj2;
18374 vinfos[3].jointtype = 1;
18375 vinfos[3].foffset = j3;
18376 vinfos[3].indices[0] = _ij3[0];
18377 vinfos[3].indices[1] = _ij3[1];
18378 vinfos[3].maxsolutions = _nj3;
18379 vinfos[4].jointtype = 1;
18380 vinfos[4].foffset = j4;
18381 vinfos[4].indices[0] = _ij4[0];
18382 vinfos[4].indices[1] = _ij4[1];
18383 vinfos[4].maxsolutions = _nj4;
18384 vinfos[5].jointtype = 1;
18385 vinfos[5].foffset = j5;
18386 vinfos[5].indices[0] = _ij5[0];
18387 vinfos[5].indices[1] = _ij5[1];
18388 vinfos[5].maxsolutions = _nj5;
18389 vinfos[6].jointtype = 1;
18390 vinfos[6].foffset = j6;
18391 vinfos[6].indices[0] = _ij6[0];
18392 vinfos[6].indices[1] = _ij6[1];
18393 vinfos[6].maxsolutions = _nj6;
18394 std::vector<int> vfree(0);
18395 solutions.AddSolution(vinfos,vfree);
18396 }
18397 }
18398 }
18399 
18400 }
18401 
18402 }
18403 }
18404 }
18405 
18406 }
18407 
18408 }
18409 
18410 } else
18411 {
18412 {
18413 IkReal j4array[1], cj4array[1], sj4array[1];
18414 bool j4valid[1]={false};
18415 _nj4 = 1;
18416 IkReal x5865=((cj0)*(r00));
18417 IkReal x5866=((r10)*(sj0));
18418 IkReal x5867=((cj0)*(r01));
18419 IkReal x5868=((IkReal(1.00000000000000))*(cj5));
18420 IkReal x5869=((r11)*(sj0));
18421 IkReal x5870=((sj2)*(sj5));
18422 IkReal x5871=((IkReal(1.00000000000000))*(cj1));
18423 IkReal x5872=((r20)*(sj1)*(sj2));
18424 IkReal x5873=((cj1)*(sj2)*(sj6));
18425 IkReal x5874=((r21)*(sj1)*(sj2));
18426 IkReal x5875=((cj6)*(sj2)*(x5871));
18427 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(sj6)*(x5874)))+(((IkReal(-1.00000000000000))*(x5865)*(x5875)))+(((x5867)*(x5873)))+(((x5869)*(x5873)))+(((cj6)*(x5872)))+(((IkReal(-1.00000000000000))*(x5866)*(x5875))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5870)*(x5871)))+(((cj5)*(sj6)*(x5872)))+(((IkReal(-1.00000000000000))*(x5866)*(x5868)*(x5873)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5870)*(x5871)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x5868)*(x5869)))+(((r22)*(sj1)*(x5870)))+(((cj5)*(cj6)*(x5874)))+(((IkReal(-1.00000000000000))*(x5865)*(x5868)*(x5873)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x5867)*(x5868))))))) < IKFAST_ATAN2_MAGTHRESH )
18428     continue;
18429 j4array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(sj6)*(x5874)))+(((IkReal(-1.00000000000000))*(x5865)*(x5875)))+(((x5867)*(x5873)))+(((x5869)*(x5873)))+(((cj6)*(x5872)))+(((IkReal(-1.00000000000000))*(x5866)*(x5875)))))), ((gconst1)*(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x5870)*(x5871)))+(((cj5)*(sj6)*(x5872)))+(((IkReal(-1.00000000000000))*(x5866)*(x5868)*(x5873)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x5870)*(x5871)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x5868)*(x5869)))+(((r22)*(sj1)*(x5870)))+(((cj5)*(cj6)*(x5874)))+(((IkReal(-1.00000000000000))*(x5865)*(x5868)*(x5873)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x5867)*(x5868)))))));
18430 sj4array[0]=IKsin(j4array[0]);
18431 cj4array[0]=IKcos(j4array[0]);
18432 if( j4array[0] > IKPI )
18433 {
18434     j4array[0]-=IK2PI;
18435 }
18436 else if( j4array[0] < -IKPI )
18437 {    j4array[0]+=IK2PI;
18438 }
18439 j4valid[0] = true;
18440 for(int ij4 = 0; ij4 < 1; ++ij4)
18441 {
18442 if( !j4valid[ij4] )
18443 {
18444     continue;
18445 }
18446 _ij4[0] = ij4; _ij4[1] = -1;
18447 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
18448 {
18449 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
18450 {
18451     j4valid[iij4]=false; _ij4[1] = iij4; break; 
18452 }
18453 }
18454 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
18455 {
18456 IkReal evalcond[3];
18457 IkReal x5876=IKsin(j4);
18458 IkReal x5877=IKcos(j4);
18459 IkReal x5878=((r00)*(sj6));
18460 IkReal x5879=((cj6)*(r01));
18461 IkReal x5880=((IkReal(1.00000000000000))*(cj0));
18462 IkReal x5881=((IkReal(1.00000000000000))*(sj0));
18463 IkReal x5882=((r10)*(sj6));
18464 IkReal x5883=((sj5)*(x5876));
18465 IkReal x5884=((IkReal(1.00000000000000))*(cj6)*(r11));
18466 IkReal x5885=((cj5)*(x5876));
18467 IkReal x5886=((cj6)*(x5877));
18468 IkReal x5887=((sj0)*(x5885));
18469 IkReal x5888=((r01)*(sj6)*(x5877));
18470 IkReal x5889=((r11)*(sj6)*(x5877));
18471 evalcond[0]=((((cj6)*(r21)*(x5885)))+(((r22)*(x5883)))+(((IkReal(-1.00000000000000))*(cj1)*(sj2)))+(((r20)*(sj6)*(x5885)))+(((r21)*(sj6)*(x5877)))+(((IkReal(-1.00000000000000))*(r20)*(x5886))));
18472 evalcond[1]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5880)*(x5885)))+(((IkReal(-1.00000000000000))*(x5880)*(x5889)))+(((r02)*(sj0)*(x5883)))+(((IkReal(-1.00000000000000))*(r00)*(x5881)*(x5886)))+(((IkReal(-1.00000000000000))*(r12)*(x5880)*(x5883)))+(((IkReal(-1.00000000000000))*(x5880)*(x5882)*(x5885)))+(cj2)+(((x5878)*(x5887)))+(((x5879)*(x5887)))+(((sj0)*(x5888)))+(((cj0)*(r10)*(x5886))));
18473 evalcond[2]=((((IkReal(-1.00000000000000))*(x5878)*(x5880)*(x5885)))+(((IkReal(-1.00000000000000))*(x5880)*(x5888)))+(((IkReal(-1.00000000000000))*(x5879)*(x5880)*(x5885)))+(((IkReal(-1.00000000000000))*(x5881)*(x5882)*(x5885)))+(((r10)*(sj0)*(x5886)))+(((cj0)*(r00)*(x5886)))+(((IkReal(-1.00000000000000))*(x5881)*(x5889)))+(((IkReal(-1.00000000000000))*(r02)*(x5880)*(x5883)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r12)*(x5881)*(x5883)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x5881)*(x5885))));
18474 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
18475 {
18476 continue;
18477 }
18478 }
18479 
18480 {
18481 IkReal dummyeval[1];
18482 IkReal gconst4;
18483 gconst4=IKsign((((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2))))));
18484 dummyeval[0]=(((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2)))));
18485 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18486 {
18487 {
18488 IkReal dummyeval[2];
18489 IkReal x5890=(cj1)*(cj1);
18490 IkReal x5891=(sj1)*(sj1);
18491 dummyeval[0]=((((cj2)*(x5890)))+(((cj2)*(x5891))));
18492 dummyeval[1]=((x5890)+(x5891));
18493 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
18494 {
18495 {
18496 IkReal dummyeval[2];
18497 dummyeval[0]=sj2;
18498 dummyeval[1]=sj1;
18499 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
18500 {
18501 {
18502 IkReal evalcond[9];
18503 IkReal x5892=((cj5)*(sj4));
18504 IkReal x5893=((IkReal(1.00000000000000))*(sj6));
18505 IkReal x5894=((r10)*(sj0));
18506 IkReal x5895=((sj4)*(sj5));
18507 IkReal x5896=((cj4)*(cj5));
18508 IkReal x5897=((IkReal(1.00000000000000))*(r02));
18509 IkReal x5898=((IkReal(0.374290000000000))*(cj0));
18510 IkReal x5899=((cj5)*(r12));
18511 IkReal x5900=((cj6)*(sj5));
18512 IkReal x5901=((cj0)*(r11));
18513 IkReal x5902=((cj5)*(sj0));
18514 IkReal x5903=((r20)*(sj6));
18515 IkReal x5904=((IkReal(1.00000000000000))*(sj0));
18516 IkReal x5905=((IkReal(1.00000000000000))*(cj6));
18517 IkReal x5906=((IkReal(0.0100000000000000))*(cj5));
18518 IkReal x5907=((IkReal(0.0100000000000000))*(sj5));
18519 IkReal x5908=((sj5)*(sj6));
18520 IkReal x5909=((cj0)*(r10));
18521 IkReal x5910=((cj4)*(cj6));
18522 IkReal x5911=((cj0)*(r01));
18523 IkReal x5912=((cj0)*(r00));
18524 IkReal x5913=((cj6)*(r21));
18525 IkReal x5914=((IkReal(0.374290000000000))*(sj0));
18526 IkReal x5915=((IkReal(0.374290000000000))*(sj5));
18527 IkReal x5916=((cj6)*(r11));
18528 IkReal x5917=((sj0)*(sj4));
18529 IkReal x5918=((cj4)*(sj5));
18530 IkReal x5919=((cj4)*(sj6));
18531 IkReal x5920=((IkReal(1.00000000000000))*(cj0));
18532 IkReal x5921=((r02)*(sj0));
18533 IkReal x5922=((r00)*(sj0)*(sj6));
18534 IkReal x5923=((cj6)*(r01)*(sj0));
18535 IkReal x5924=((r00)*(x5910));
18536 IkReal x5925=((r12)*(x5920));
18537 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
18538 evalcond[1]=((((x5892)*(x5913)))+(((x5892)*(x5903)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x5905)))+(((r21)*(x5919)))+(((r22)*(x5895))));
18539 evalcond[2]=((((IkReal(-1.00000000000000))*(x5906)*(x5913)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(0.374290000000000))*(r21)*(x5900)))+(((IkReal(-1.00000000000000))*(r22)*(x5907)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x5903)*(x5915)))+(((IkReal(-1.00000000000000))*(x5903)*(x5906)))+(((IkReal(0.0690000000000000))*(cj1))));
18540 evalcond[3]=((((r01)*(sj0)*(x5900)))+(((IkReal(-1.00000000000000))*(x5900)*(x5901)))+(((r00)*(sj0)*(x5908)))+(((IkReal(-1.00000000000000))*(sj5)*(x5893)*(x5909)))+(((cj0)*(x5899)))+(((IkReal(-1.00000000000000))*(x5897)*(x5902))));
18541 evalcond[4]=((IkReal(1.00000000000000))+(((x5892)*(x5922)))+(((IkReal(-1.00000000000000))*(x5892)*(x5901)*(x5905)))+(((IkReal(-1.00000000000000))*(x5904)*(x5924)))+(((x5895)*(x5921)))+(((x5909)*(x5910)))+(((IkReal(-1.00000000000000))*(cj4)*(x5893)*(x5901)))+(((r01)*(sj0)*(x5919)))+(((x5892)*(x5923)))+(((IkReal(-1.00000000000000))*(x5895)*(x5925)))+(((IkReal(-1.00000000000000))*(x5892)*(x5893)*(x5909))));
18542 evalcond[5]=((((sj4)*(sj6)*(x5901)))+(((IkReal(-1.00000000000000))*(sj4)*(x5905)*(x5909)))+(((IkReal(-1.00000000000000))*(x5918)*(x5925)))+(((x5896)*(x5922)))+(((IkReal(-1.00000000000000))*(x5896)*(x5901)*(x5905)))+(((x5918)*(x5921)))+(((IkReal(-1.00000000000000))*(r01)*(x5893)*(x5917)))+(((cj6)*(r00)*(x5917)))+(((x5896)*(x5923)))+(((IkReal(-1.00000000000000))*(x5893)*(x5896)*(x5909))));
18543 evalcond[6]=((((x5894)*(x5910)))+(((IkReal(-1.00000000000000))*(r12)*(x5895)*(x5904)))+(((IkReal(-1.00000000000000))*(x5892)*(x5893)*(x5894)))+(((IkReal(-1.00000000000000))*(x5892)*(x5905)*(x5911)))+(((IkReal(-1.00000000000000))*(x5892)*(x5893)*(x5912)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x5893)))+(((IkReal(-1.00000000000000))*(x5892)*(x5904)*(x5916)))+(((x5910)*(x5912)))+(((IkReal(-1.00000000000000))*(cj0)*(x5895)*(x5897)))+(((IkReal(-1.00000000000000))*(cj4)*(x5893)*(x5911))));
18544 evalcond[7]=((((cj6)*(x5901)*(x5906)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x5902)))+(((IkReal(-1.00000000000000))*(r10)*(x5898)*(x5908)))+(((IkReal(-1.00000000000000))*(x5907)*(x5921)))+(((sj6)*(x5906)*(x5909)))+(((IkReal(-1.00000000000000))*(r11)*(x5898)*(x5900)))+(((IkReal(-0.374290000000000))*(r02)*(x5902)))+(((r01)*(x5900)*(x5914)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x5902)))+(((x5898)*(x5899)))+(((px)*(sj0)))+(((cj0)*(r12)*(x5907)))+(((IkReal(-1.00000000000000))*(py)*(x5920)))+(((r00)*(x5908)*(x5914))));
18545 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-0.0690000000000000))*(sj1)))+(((sj6)*(x5906)*(x5912)))+(((r12)*(sj0)*(x5907)))+(((IkReal(-1.00000000000000))*(r01)*(x5898)*(x5900)))+(((IkReal(0.0100000000000000))*(x5902)*(x5916)))+(((cj5)*(r02)*(x5898)))+(((IkReal(-1.00000000000000))*(r00)*(x5898)*(x5908)))+(((x5899)*(x5914)))+(((cj6)*(x5906)*(x5911)))+(((IkReal(-1.00000000000000))*(px)*(x5920)))+(((IkReal(-1.00000000000000))*(py)*(x5904)))+(((IkReal(-0.374290000000000))*(x5894)*(x5908)))+(((IkReal(-1.00000000000000))*(r11)*(x5900)*(x5914)))+(((sj6)*(x5894)*(x5906)))+(((IkReal(0.364420000000000))*(cj1)))+(((cj0)*(r02)*(x5907))));
18546 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
18547 {
18548 {
18549 IkReal dummyeval[1];
18550 IkReal gconst5;
18551 gconst5=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
18552 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
18553 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18554 {
18555 {
18556 IkReal dummyeval[1];
18557 IkReal gconst6;
18558 gconst6=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
18559 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
18560 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18561 {
18562 continue;
18563 
18564 } else
18565 {
18566 {
18567 IkReal j3array[1], cj3array[1], sj3array[1];
18568 bool j3valid[1]={false};
18569 _nj3 = 1;
18570 IkReal x5926=((sj5)*(sj6));
18571 IkReal x5927=((IkReal(1.00000000000000))*(sj0));
18572 IkReal x5928=((cj5)*(r12));
18573 IkReal x5929=((cj0)*(r00));
18574 IkReal x5930=((cj0)*(cj1));
18575 IkReal x5931=((cj6)*(sj5));
18576 IkReal x5932=((cj5)*(r02));
18577 IkReal x5933=((IkReal(1.00000000000000))*(cj1));
18578 IkReal x5934=((sj0)*(sj1));
18579 IkReal x5935=((cj0)*(sj1));
18580 IkReal x5936=((cj5)*(r22));
18581 if( IKabs(((gconst6)*(((((r10)*(x5926)*(x5934)))+(((IkReal(-1.00000000000000))*(x5932)*(x5935)))+(((IkReal(-1.00000000000000))*(sj1)*(x5927)*(x5928)))+(((r11)*(x5931)*(x5934)))+(((IkReal(-1.00000000000000))*(x5933)*(x5936)))+(((cj1)*(r20)*(x5926)))+(((r01)*(x5931)*(x5935)))+(((cj1)*(r21)*(x5931)))+(((sj1)*(x5926)*(x5929))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((IkReal(-1.00000000000000))*(sj1)*(x5936)))+(((x5930)*(x5932)))+(((r20)*(sj1)*(x5926)))+(((IkReal(-1.00000000000000))*(r01)*(x5930)*(x5931)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x5926)*(x5927)))+(((r21)*(sj1)*(x5931)))+(((cj1)*(sj0)*(x5928)))+(((IkReal(-1.00000000000000))*(x5926)*(x5929)*(x5933)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x5927)*(x5931))))))) < IKFAST_ATAN2_MAGTHRESH )
18582     continue;
18583 j3array[0]=IKatan2(((gconst6)*(((((r10)*(x5926)*(x5934)))+(((IkReal(-1.00000000000000))*(x5932)*(x5935)))+(((IkReal(-1.00000000000000))*(sj1)*(x5927)*(x5928)))+(((r11)*(x5931)*(x5934)))+(((IkReal(-1.00000000000000))*(x5933)*(x5936)))+(((cj1)*(r20)*(x5926)))+(((r01)*(x5931)*(x5935)))+(((cj1)*(r21)*(x5931)))+(((sj1)*(x5926)*(x5929)))))), ((gconst6)*(((((IkReal(-1.00000000000000))*(sj1)*(x5936)))+(((x5930)*(x5932)))+(((r20)*(sj1)*(x5926)))+(((IkReal(-1.00000000000000))*(r01)*(x5930)*(x5931)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x5926)*(x5927)))+(((r21)*(sj1)*(x5931)))+(((cj1)*(sj0)*(x5928)))+(((IkReal(-1.00000000000000))*(x5926)*(x5929)*(x5933)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x5927)*(x5931)))))));
18584 sj3array[0]=IKsin(j3array[0]);
18585 cj3array[0]=IKcos(j3array[0]);
18586 if( j3array[0] > IKPI )
18587 {
18588     j3array[0]-=IK2PI;
18589 }
18590 else if( j3array[0] < -IKPI )
18591 {    j3array[0]+=IK2PI;
18592 }
18593 j3valid[0] = true;
18594 for(int ij3 = 0; ij3 < 1; ++ij3)
18595 {
18596 if( !j3valid[ij3] )
18597 {
18598     continue;
18599 }
18600 _ij3[0] = ij3; _ij3[1] = -1;
18601 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18602 {
18603 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18604 {
18605     j3valid[iij3]=false; _ij3[1] = iij3; break; 
18606 }
18607 }
18608 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18609 {
18610 IkReal evalcond[4];
18611 IkReal x5937=IKcos(j3);
18612 IkReal x5938=IKsin(j3);
18613 IkReal x5939=((IkReal(1.00000000000000))*(cj4));
18614 IkReal x5940=((sj0)*(sj5));
18615 IkReal x5941=((cj0)*(cj5));
18616 IkReal x5942=((cj6)*(r01));
18617 IkReal x5943=((r00)*(sj6));
18618 IkReal x5944=((cj6)*(r11));
18619 IkReal x5945=((cj5)*(sj0));
18620 IkReal x5946=((cj6)*(sj4));
18621 IkReal x5947=((sj4)*(sj6));
18622 IkReal x5948=((cj4)*(cj5));
18623 IkReal x5949=((cj6)*(r21));
18624 IkReal x5950=((r20)*(sj6));
18625 IkReal x5951=((r10)*(sj6));
18626 IkReal x5952=((cj1)*(x5937));
18627 IkReal x5953=((IkReal(1.00000000000000))*(cj0)*(sj5));
18628 IkReal x5954=((IkReal(1.00000000000000))*(x5938));
18629 IkReal x5955=((IkReal(1.00000000000000))*(sj1)*(x5937));
18630 IkReal x5956=((cj1)*(x5954));
18631 IkReal x5957=((x5955)+(x5956));
18632 evalcond[0]=((((sj5)*(x5950)))+(((IkReal(-1.00000000000000))*(x5957)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5949))));
18633 evalcond[1]=((((r20)*(x5946)))+(((IkReal(-1.00000000000000))*(sj1)*(x5954)))+(((cj4)*(r22)*(sj5)))+(x5952)+(((x5948)*(x5950)))+(((x5948)*(x5949)))+(((IkReal(-1.00000000000000))*(r21)*(x5947))));
18634 evalcond[2]=((((sj1)*(x5938)))+(((r12)*(x5945)))+(((IkReal(-1.00000000000000))*(x5940)*(x5944)))+(((IkReal(-1.00000000000000))*(x5942)*(x5953)))+(((r02)*(x5941)))+(((IkReal(-1.00000000000000))*(x5943)*(x5953)))+(((IkReal(-1.00000000000000))*(x5952)))+(((IkReal(-1.00000000000000))*(x5940)*(x5951))));
18635 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x5939)*(x5940)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x5939)))+(((r11)*(sj0)*(x5947)))+(((cj0)*(r01)*(x5947)))+(((IkReal(-1.00000000000000))*(x5957)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x5946)))+(((IkReal(-1.00000000000000))*(x5939)*(x5945)*(x5951)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5946)))+(((IkReal(-1.00000000000000))*(x5939)*(x5941)*(x5943)))+(((IkReal(-1.00000000000000))*(x5939)*(x5941)*(x5942)))+(((IkReal(-1.00000000000000))*(x5939)*(x5944)*(x5945))));
18636 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
18637 {
18638 continue;
18639 }
18640 }
18641 
18642 {
18643 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
18644 vinfos[0].jointtype = 1;
18645 vinfos[0].foffset = j0;
18646 vinfos[0].indices[0] = _ij0[0];
18647 vinfos[0].indices[1] = _ij0[1];
18648 vinfos[0].maxsolutions = _nj0;
18649 vinfos[1].jointtype = 1;
18650 vinfos[1].foffset = j1;
18651 vinfos[1].indices[0] = _ij1[0];
18652 vinfos[1].indices[1] = _ij1[1];
18653 vinfos[1].maxsolutions = _nj1;
18654 vinfos[2].jointtype = 1;
18655 vinfos[2].foffset = j2;
18656 vinfos[2].indices[0] = _ij2[0];
18657 vinfos[2].indices[1] = _ij2[1];
18658 vinfos[2].maxsolutions = _nj2;
18659 vinfos[3].jointtype = 1;
18660 vinfos[3].foffset = j3;
18661 vinfos[3].indices[0] = _ij3[0];
18662 vinfos[3].indices[1] = _ij3[1];
18663 vinfos[3].maxsolutions = _nj3;
18664 vinfos[4].jointtype = 1;
18665 vinfos[4].foffset = j4;
18666 vinfos[4].indices[0] = _ij4[0];
18667 vinfos[4].indices[1] = _ij4[1];
18668 vinfos[4].maxsolutions = _nj4;
18669 vinfos[5].jointtype = 1;
18670 vinfos[5].foffset = j5;
18671 vinfos[5].indices[0] = _ij5[0];
18672 vinfos[5].indices[1] = _ij5[1];
18673 vinfos[5].maxsolutions = _nj5;
18674 vinfos[6].jointtype = 1;
18675 vinfos[6].foffset = j6;
18676 vinfos[6].indices[0] = _ij6[0];
18677 vinfos[6].indices[1] = _ij6[1];
18678 vinfos[6].maxsolutions = _nj6;
18679 std::vector<int> vfree(0);
18680 solutions.AddSolution(vinfos,vfree);
18681 }
18682 }
18683 }
18684 
18685 }
18686 
18687 }
18688 
18689 } else
18690 {
18691 {
18692 IkReal j3array[1], cj3array[1], sj3array[1];
18693 bool j3valid[1]={false};
18694 _nj3 = 1;
18695 IkReal x5958=((sj1)*(sj5));
18696 IkReal x5959=((r20)*(sj6));
18697 IkReal x5960=((cj4)*(r22));
18698 IkReal x5961=((IkReal(1.00000000000000))*(cj1));
18699 IkReal x5962=((cj5)*(sj1));
18700 IkReal x5963=((cj6)*(r21));
18701 IkReal x5964=((cj1)*(sj5));
18702 IkReal x5965=((cj4)*(cj5));
18703 IkReal x5966=((cj6)*(r20)*(sj4));
18704 IkReal x5967=((r21)*(sj4)*(sj6));
18705 if( IKabs(((gconst5)*(((((x5963)*(x5964)))+(((IkReal(-1.00000000000000))*(sj1)*(x5967)))+(((cj4)*(x5962)*(x5963)))+(((cj4)*(x5959)*(x5962)))+(((x5959)*(x5964)))+(((x5958)*(x5960)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x5961)))+(((sj1)*(x5966))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((x5958)*(x5963)))+(((IkReal(-1.00000000000000))*(x5961)*(x5963)*(x5965)))+(((cj1)*(x5967)))+(((IkReal(-1.00000000000000))*(x5961)*(x5966)))+(((x5958)*(x5959)))+(((IkReal(-1.00000000000000))*(r22)*(x5962)))+(((IkReal(-1.00000000000000))*(sj5)*(x5960)*(x5961)))+(((IkReal(-1.00000000000000))*(x5959)*(x5961)*(x5965))))))) < IKFAST_ATAN2_MAGTHRESH )
18706     continue;
18707 j3array[0]=IKatan2(((gconst5)*(((((x5963)*(x5964)))+(((IkReal(-1.00000000000000))*(sj1)*(x5967)))+(((cj4)*(x5962)*(x5963)))+(((cj4)*(x5959)*(x5962)))+(((x5959)*(x5964)))+(((x5958)*(x5960)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x5961)))+(((sj1)*(x5966)))))), ((gconst5)*(((((x5958)*(x5963)))+(((IkReal(-1.00000000000000))*(x5961)*(x5963)*(x5965)))+(((cj1)*(x5967)))+(((IkReal(-1.00000000000000))*(x5961)*(x5966)))+(((x5958)*(x5959)))+(((IkReal(-1.00000000000000))*(r22)*(x5962)))+(((IkReal(-1.00000000000000))*(sj5)*(x5960)*(x5961)))+(((IkReal(-1.00000000000000))*(x5959)*(x5961)*(x5965)))))));
18708 sj3array[0]=IKsin(j3array[0]);
18709 cj3array[0]=IKcos(j3array[0]);
18710 if( j3array[0] > IKPI )
18711 {
18712     j3array[0]-=IK2PI;
18713 }
18714 else if( j3array[0] < -IKPI )
18715 {    j3array[0]+=IK2PI;
18716 }
18717 j3valid[0] = true;
18718 for(int ij3 = 0; ij3 < 1; ++ij3)
18719 {
18720 if( !j3valid[ij3] )
18721 {
18722     continue;
18723 }
18724 _ij3[0] = ij3; _ij3[1] = -1;
18725 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18726 {
18727 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18728 {
18729     j3valid[iij3]=false; _ij3[1] = iij3; break; 
18730 }
18731 }
18732 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18733 {
18734 IkReal evalcond[4];
18735 IkReal x5968=IKcos(j3);
18736 IkReal x5969=IKsin(j3);
18737 IkReal x5970=((IkReal(1.00000000000000))*(cj4));
18738 IkReal x5971=((sj0)*(sj5));
18739 IkReal x5972=((cj0)*(cj5));
18740 IkReal x5973=((cj6)*(r01));
18741 IkReal x5974=((r00)*(sj6));
18742 IkReal x5975=((cj6)*(r11));
18743 IkReal x5976=((cj5)*(sj0));
18744 IkReal x5977=((cj6)*(sj4));
18745 IkReal x5978=((sj4)*(sj6));
18746 IkReal x5979=((cj4)*(cj5));
18747 IkReal x5980=((cj6)*(r21));
18748 IkReal x5981=((r20)*(sj6));
18749 IkReal x5982=((r10)*(sj6));
18750 IkReal x5983=((cj1)*(x5968));
18751 IkReal x5984=((IkReal(1.00000000000000))*(cj0)*(sj5));
18752 IkReal x5985=((IkReal(1.00000000000000))*(x5969));
18753 IkReal x5986=((IkReal(1.00000000000000))*(sj1)*(x5968));
18754 IkReal x5987=((cj1)*(x5985));
18755 IkReal x5988=((x5986)+(x5987));
18756 evalcond[0]=((((sj5)*(x5980)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x5981)))+(((IkReal(-1.00000000000000))*(x5988))));
18757 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x5978)))+(((IkReal(-1.00000000000000))*(sj1)*(x5985)))+(x5983)+(((x5979)*(x5980)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x5977)))+(((x5979)*(x5981))));
18758 evalcond[2]=((((IkReal(-1.00000000000000))*(x5983)))+(((IkReal(-1.00000000000000))*(x5973)*(x5984)))+(((IkReal(-1.00000000000000))*(x5971)*(x5975)))+(((IkReal(-1.00000000000000))*(x5971)*(x5982)))+(((r12)*(x5976)))+(((IkReal(-1.00000000000000))*(x5974)*(x5984)))+(((sj1)*(x5969)))+(((r02)*(x5972))));
18759 evalcond[3]=((((IkReal(-1.00000000000000))*(x5970)*(x5972)*(x5974)))+(((r11)*(sj0)*(x5978)))+(((IkReal(-1.00000000000000))*(r12)*(x5970)*(x5971)))+(((cj0)*(r01)*(x5978)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x5977)))+(((IkReal(-1.00000000000000))*(x5970)*(x5976)*(x5982)))+(((IkReal(-1.00000000000000))*(x5970)*(x5972)*(x5973)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x5970)))+(((IkReal(-1.00000000000000))*(x5988)))+(((IkReal(-1.00000000000000))*(x5970)*(x5975)*(x5976)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x5977))));
18760 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
18761 {
18762 continue;
18763 }
18764 }
18765 
18766 {
18767 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
18768 vinfos[0].jointtype = 1;
18769 vinfos[0].foffset = j0;
18770 vinfos[0].indices[0] = _ij0[0];
18771 vinfos[0].indices[1] = _ij0[1];
18772 vinfos[0].maxsolutions = _nj0;
18773 vinfos[1].jointtype = 1;
18774 vinfos[1].foffset = j1;
18775 vinfos[1].indices[0] = _ij1[0];
18776 vinfos[1].indices[1] = _ij1[1];
18777 vinfos[1].maxsolutions = _nj1;
18778 vinfos[2].jointtype = 1;
18779 vinfos[2].foffset = j2;
18780 vinfos[2].indices[0] = _ij2[0];
18781 vinfos[2].indices[1] = _ij2[1];
18782 vinfos[2].maxsolutions = _nj2;
18783 vinfos[3].jointtype = 1;
18784 vinfos[3].foffset = j3;
18785 vinfos[3].indices[0] = _ij3[0];
18786 vinfos[3].indices[1] = _ij3[1];
18787 vinfos[3].maxsolutions = _nj3;
18788 vinfos[4].jointtype = 1;
18789 vinfos[4].foffset = j4;
18790 vinfos[4].indices[0] = _ij4[0];
18791 vinfos[4].indices[1] = _ij4[1];
18792 vinfos[4].maxsolutions = _nj4;
18793 vinfos[5].jointtype = 1;
18794 vinfos[5].foffset = j5;
18795 vinfos[5].indices[0] = _ij5[0];
18796 vinfos[5].indices[1] = _ij5[1];
18797 vinfos[5].maxsolutions = _nj5;
18798 vinfos[6].jointtype = 1;
18799 vinfos[6].foffset = j6;
18800 vinfos[6].indices[0] = _ij6[0];
18801 vinfos[6].indices[1] = _ij6[1];
18802 vinfos[6].maxsolutions = _nj6;
18803 std::vector<int> vfree(0);
18804 solutions.AddSolution(vinfos,vfree);
18805 }
18806 }
18807 }
18808 
18809 }
18810 
18811 }
18812 
18813 } else
18814 {
18815 IkReal x5989=((cj5)*(sj4));
18816 IkReal x5990=((IkReal(1.00000000000000))*(sj6));
18817 IkReal x5991=((r10)*(sj0));
18818 IkReal x5992=((sj4)*(sj5));
18819 IkReal x5993=((cj4)*(cj5));
18820 IkReal x5994=((IkReal(1.00000000000000))*(r02));
18821 IkReal x5995=((IkReal(0.374290000000000))*(cj0));
18822 IkReal x5996=((cj5)*(r12));
18823 IkReal x5997=((cj6)*(sj5));
18824 IkReal x5998=((cj0)*(r11));
18825 IkReal x5999=((cj5)*(sj0));
18826 IkReal x6000=((r20)*(sj6));
18827 IkReal x6001=((IkReal(1.00000000000000))*(sj0));
18828 IkReal x6002=((IkReal(1.00000000000000))*(cj6));
18829 IkReal x6003=((IkReal(0.0100000000000000))*(cj5));
18830 IkReal x6004=((IkReal(0.0100000000000000))*(sj5));
18831 IkReal x6005=((sj5)*(sj6));
18832 IkReal x6006=((cj0)*(r10));
18833 IkReal x6007=((cj4)*(cj6));
18834 IkReal x6008=((cj0)*(r01));
18835 IkReal x6009=((cj0)*(r00));
18836 IkReal x6010=((cj6)*(r21));
18837 IkReal x6011=((IkReal(0.374290000000000))*(sj0));
18838 IkReal x6012=((IkReal(0.374290000000000))*(sj5));
18839 IkReal x6013=((cj6)*(r11));
18840 IkReal x6014=((sj0)*(sj4));
18841 IkReal x6015=((cj4)*(sj5));
18842 IkReal x6016=((cj4)*(sj6));
18843 IkReal x6017=((IkReal(1.00000000000000))*(cj0));
18844 IkReal x6018=((r02)*(sj0));
18845 IkReal x6019=((r00)*(sj0)*(sj6));
18846 IkReal x6020=((cj6)*(r01)*(sj0));
18847 IkReal x6021=((r00)*(x6007));
18848 IkReal x6022=((r12)*(x6017));
18849 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
18850 evalcond[1]=((((r22)*(x5992)))+(((x5989)*(x6000)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x6002)))+(((x5989)*(x6010)))+(((r21)*(x6016))));
18851 evalcond[2]=((((IkReal(-1.00000000000000))*(x6000)*(x6003)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.0690000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x6003)*(x6010)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x6000)*(x6012)))+(((IkReal(0.374290000000000))*(r21)*(x5997)))+(((IkReal(-1.00000000000000))*(r22)*(x6004))));
18852 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x5990)*(x6006)))+(((cj0)*(x5996)))+(((IkReal(-1.00000000000000))*(x5994)*(x5999)))+(((r01)*(sj0)*(x5997)))+(((r00)*(sj0)*(x6005)))+(((IkReal(-1.00000000000000))*(x5997)*(x5998))));
18853 evalcond[4]=((IkReal(-1.00000000000000))+(((x5989)*(x6020)))+(((x5992)*(x6018)))+(((r01)*(sj0)*(x6016)))+(((IkReal(-1.00000000000000))*(cj4)*(x5990)*(x5998)))+(((x6006)*(x6007)))+(((IkReal(-1.00000000000000))*(x5992)*(x6022)))+(((x5989)*(x6019)))+(((IkReal(-1.00000000000000))*(x6001)*(x6021)))+(((IkReal(-1.00000000000000))*(x5989)*(x5990)*(x6006)))+(((IkReal(-1.00000000000000))*(x5989)*(x5998)*(x6002))));
18854 evalcond[5]=((((sj4)*(sj6)*(x5998)))+(((x5993)*(x6020)))+(((x5993)*(x6019)))+(((IkReal(-1.00000000000000))*(x5990)*(x5993)*(x6006)))+(((IkReal(-1.00000000000000))*(x5993)*(x5998)*(x6002)))+(((x6015)*(x6018)))+(((cj6)*(r00)*(x6014)))+(((IkReal(-1.00000000000000))*(x6015)*(x6022)))+(((IkReal(-1.00000000000000))*(r01)*(x5990)*(x6014)))+(((IkReal(-1.00000000000000))*(sj4)*(x6002)*(x6006))));
18855 evalcond[6]=((((IkReal(-1.00000000000000))*(x5989)*(x6002)*(x6008)))+(((x5991)*(x6007)))+(((IkReal(-1.00000000000000))*(r12)*(x5992)*(x6001)))+(((IkReal(-1.00000000000000))*(x5989)*(x6001)*(x6013)))+(((IkReal(-1.00000000000000))*(cj4)*(x5990)*(x6008)))+(((x6007)*(x6009)))+(((IkReal(-1.00000000000000))*(x5989)*(x5990)*(x6009)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x5990)))+(((IkReal(-1.00000000000000))*(x5989)*(x5990)*(x5991)))+(((IkReal(-1.00000000000000))*(cj0)*(x5992)*(x5994))));
18856 evalcond[7]=((((IkReal(-1.00000000000000))*(py)*(x6017)))+(((r01)*(x5997)*(x6011)))+(((IkReal(-1.00000000000000))*(x6004)*(x6018)))+(((IkReal(-1.00000000000000))*(r11)*(x5995)*(x5997)))+(((x5995)*(x5996)))+(((sj6)*(x6003)*(x6006)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x5999)))+(((cj0)*(r12)*(x6004)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x5999)))+(((IkReal(-0.374290000000000))*(r02)*(x5999)))+(((IkReal(-1.00000000000000))*(r10)*(x5995)*(x6005)))+(((r00)*(x6005)*(x6011)))+(((cj6)*(x5998)*(x6003)))+(((px)*(sj0))));
18857 evalcond[8]=((IkReal(0.0690000000000000))+(((x5996)*(x6011)))+(((IkReal(-1.00000000000000))*(r01)*(x5995)*(x5997)))+(((IkReal(-1.00000000000000))*(r11)*(x5997)*(x6011)))+(((cj0)*(r02)*(x6004)))+(((cj6)*(x6003)*(x6008)))+(((IkReal(0.0690000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r00)*(x5995)*(x6005)))+(((sj6)*(x6003)*(x6009)))+(((cj5)*(r02)*(x5995)))+(((IkReal(-0.374290000000000))*(x5991)*(x6005)))+(((IkReal(-1.00000000000000))*(px)*(x6017)))+(((IkReal(-1.00000000000000))*(py)*(x6001)))+(((IkReal(0.0100000000000000))*(x5999)*(x6013)))+(((r12)*(sj0)*(x6004)))+(((IkReal(0.364420000000000))*(cj1)))+(((sj6)*(x5991)*(x6003))));
18858 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
18859 {
18860 {
18861 IkReal dummyeval[1];
18862 IkReal gconst7;
18863 gconst7=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
18864 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
18865 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18866 {
18867 {
18868 IkReal dummyeval[1];
18869 IkReal gconst8;
18870 gconst8=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
18871 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
18872 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
18873 {
18874 continue;
18875 
18876 } else
18877 {
18878 {
18879 IkReal j3array[1], cj3array[1], sj3array[1];
18880 bool j3valid[1]={false};
18881 _nj3 = 1;
18882 IkReal x6023=((IkReal(1.00000000000000))*(sj0));
18883 IkReal x6024=((cj6)*(r21));
18884 IkReal x6025=((cj0)*(r00));
18885 IkReal x6026=((cj5)*(sj1));
18886 IkReal x6027=((r12)*(sj0));
18887 IkReal x6028=((cj1)*(cj5));
18888 IkReal x6029=((cj0)*(r02));
18889 IkReal x6030=((sj1)*(sj5));
18890 IkReal x6031=((cj6)*(r11));
18891 IkReal x6032=((cj1)*(sj5));
18892 IkReal x6033=((sj6)*(x6030));
18893 IkReal x6034=((IkReal(1.00000000000000))*(x6032));
18894 IkReal x6035=((cj0)*(cj6)*(r01));
18895 if( IKabs(((gconst8)*(((((x6026)*(x6029)))+(((IkReal(-1.00000000000000))*(x6023)*(x6030)*(x6031)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x6034)))+(((IkReal(-1.00000000000000))*(x6025)*(x6033)))+(((IkReal(-1.00000000000000))*(x6024)*(x6034)))+(((x6026)*(x6027)))+(((IkReal(-1.00000000000000))*(x6030)*(x6035)))+(((r22)*(x6028)))+(((IkReal(-1.00000000000000))*(r10)*(x6023)*(x6033))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6023)*(x6032)))+(((x6028)*(x6029)))+(((IkReal(-1.00000000000000))*(x6023)*(x6031)*(x6032)))+(((IkReal(-1.00000000000000))*(x6034)*(x6035)))+(((x6027)*(x6028)))+(((IkReal(-1.00000000000000))*(sj6)*(x6025)*(x6034)))+(((IkReal(-1.00000000000000))*(r22)*(x6026)))+(((r20)*(x6033)))+(((x6024)*(x6030))))))) < IKFAST_ATAN2_MAGTHRESH )
18896     continue;
18897 j3array[0]=IKatan2(((gconst8)*(((((x6026)*(x6029)))+(((IkReal(-1.00000000000000))*(x6023)*(x6030)*(x6031)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x6034)))+(((IkReal(-1.00000000000000))*(x6025)*(x6033)))+(((IkReal(-1.00000000000000))*(x6024)*(x6034)))+(((x6026)*(x6027)))+(((IkReal(-1.00000000000000))*(x6030)*(x6035)))+(((r22)*(x6028)))+(((IkReal(-1.00000000000000))*(r10)*(x6023)*(x6033)))))), ((gconst8)*(((((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6023)*(x6032)))+(((x6028)*(x6029)))+(((IkReal(-1.00000000000000))*(x6023)*(x6031)*(x6032)))+(((IkReal(-1.00000000000000))*(x6034)*(x6035)))+(((x6027)*(x6028)))+(((IkReal(-1.00000000000000))*(sj6)*(x6025)*(x6034)))+(((IkReal(-1.00000000000000))*(r22)*(x6026)))+(((r20)*(x6033)))+(((x6024)*(x6030)))))));
18898 sj3array[0]=IKsin(j3array[0]);
18899 cj3array[0]=IKcos(j3array[0]);
18900 if( j3array[0] > IKPI )
18901 {
18902     j3array[0]-=IK2PI;
18903 }
18904 else if( j3array[0] < -IKPI )
18905 {    j3array[0]+=IK2PI;
18906 }
18907 j3valid[0] = true;
18908 for(int ij3 = 0; ij3 < 1; ++ij3)
18909 {
18910 if( !j3valid[ij3] )
18911 {
18912     continue;
18913 }
18914 _ij3[0] = ij3; _ij3[1] = -1;
18915 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
18916 {
18917 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
18918 {
18919     j3valid[iij3]=false; _ij3[1] = iij3; break; 
18920 }
18921 }
18922 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
18923 {
18924 IkReal evalcond[4];
18925 IkReal x6036=IKsin(j3);
18926 IkReal x6037=IKcos(j3);
18927 IkReal x6038=((IkReal(1.00000000000000))*(cj4));
18928 IkReal x6039=((sj0)*(sj5));
18929 IkReal x6040=((cj0)*(cj5));
18930 IkReal x6041=((cj6)*(r01));
18931 IkReal x6042=((r00)*(sj6));
18932 IkReal x6043=((cj6)*(r11));
18933 IkReal x6044=((cj5)*(sj0));
18934 IkReal x6045=((cj6)*(sj4));
18935 IkReal x6046=((sj4)*(sj6));
18936 IkReal x6047=((cj4)*(cj5));
18937 IkReal x6048=((cj6)*(r21));
18938 IkReal x6049=((r20)*(sj6));
18939 IkReal x6050=((r10)*(sj6));
18940 IkReal x6051=((cj1)*(x6036));
18941 IkReal x6052=((IkReal(1.00000000000000))*(cj0)*(sj5));
18942 IkReal x6053=((IkReal(1.00000000000000))*(x6037));
18943 IkReal x6054=((IkReal(1.00000000000000))*(sj1)*(x6036));
18944 IkReal x6055=((cj1)*(x6053));
18945 IkReal x6056=((x6055)+(x6054));
18946 evalcond[0]=((((sj5)*(x6049)))+(((IkReal(-1.00000000000000))*(sj1)*(x6053)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x6051)+(((sj5)*(x6048))));
18947 evalcond[1]=((((x6047)*(x6048)))+(((IkReal(-1.00000000000000))*(r21)*(x6046)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x6045)))+(((x6047)*(x6049)))+(((IkReal(-1.00000000000000))*(x6056))));
18948 evalcond[2]=((((IkReal(-1.00000000000000))*(x6039)*(x6043)))+(((IkReal(-1.00000000000000))*(x6042)*(x6052)))+(((r02)*(x6040)))+(((IkReal(-1.00000000000000))*(x6041)*(x6052)))+(((IkReal(-1.00000000000000))*(x6039)*(x6050)))+(((IkReal(-1.00000000000000))*(x6056)))+(((r12)*(x6044))));
18949 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x6038)*(x6039)))+(((IkReal(-1.00000000000000))*(x6038)*(x6040)*(x6042)))+(((IkReal(-1.00000000000000))*(x6051)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6045)))+(((sj1)*(x6037)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6045)))+(((IkReal(-1.00000000000000))*(x6038)*(x6043)*(x6044)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6038)))+(((IkReal(-1.00000000000000))*(x6038)*(x6040)*(x6041)))+(((IkReal(-1.00000000000000))*(x6038)*(x6044)*(x6050)))+(((r11)*(sj0)*(x6046)))+(((cj0)*(r01)*(x6046))));
18950 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
18951 {
18952 continue;
18953 }
18954 }
18955 
18956 {
18957 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
18958 vinfos[0].jointtype = 1;
18959 vinfos[0].foffset = j0;
18960 vinfos[0].indices[0] = _ij0[0];
18961 vinfos[0].indices[1] = _ij0[1];
18962 vinfos[0].maxsolutions = _nj0;
18963 vinfos[1].jointtype = 1;
18964 vinfos[1].foffset = j1;
18965 vinfos[1].indices[0] = _ij1[0];
18966 vinfos[1].indices[1] = _ij1[1];
18967 vinfos[1].maxsolutions = _nj1;
18968 vinfos[2].jointtype = 1;
18969 vinfos[2].foffset = j2;
18970 vinfos[2].indices[0] = _ij2[0];
18971 vinfos[2].indices[1] = _ij2[1];
18972 vinfos[2].maxsolutions = _nj2;
18973 vinfos[3].jointtype = 1;
18974 vinfos[3].foffset = j3;
18975 vinfos[3].indices[0] = _ij3[0];
18976 vinfos[3].indices[1] = _ij3[1];
18977 vinfos[3].maxsolutions = _nj3;
18978 vinfos[4].jointtype = 1;
18979 vinfos[4].foffset = j4;
18980 vinfos[4].indices[0] = _ij4[0];
18981 vinfos[4].indices[1] = _ij4[1];
18982 vinfos[4].maxsolutions = _nj4;
18983 vinfos[5].jointtype = 1;
18984 vinfos[5].foffset = j5;
18985 vinfos[5].indices[0] = _ij5[0];
18986 vinfos[5].indices[1] = _ij5[1];
18987 vinfos[5].maxsolutions = _nj5;
18988 vinfos[6].jointtype = 1;
18989 vinfos[6].foffset = j6;
18990 vinfos[6].indices[0] = _ij6[0];
18991 vinfos[6].indices[1] = _ij6[1];
18992 vinfos[6].maxsolutions = _nj6;
18993 std::vector<int> vfree(0);
18994 solutions.AddSolution(vinfos,vfree);
18995 }
18996 }
18997 }
18998 
18999 }
19000 
19001 }
19002 
19003 } else
19004 {
19005 {
19006 IkReal j3array[1], cj3array[1], sj3array[1];
19007 bool j3valid[1]={false};
19008 _nj3 = 1;
19009 IkReal x6057=((sj1)*(sj6));
19010 IkReal x6058=((r20)*(sj5));
19011 IkReal x6059=((IkReal(1.00000000000000))*(r21));
19012 IkReal x6060=((cj1)*(cj6));
19013 IkReal x6061=((r20)*(sj4));
19014 IkReal x6062=((cj6)*(sj1));
19015 IkReal x6063=((cj4)*(cj5));
19016 IkReal x6064=((cj1)*(sj6));
19017 IkReal x6065=((cj5)*(r22));
19018 IkReal x6066=((cj4)*(r22)*(sj5));
19019 if( IKabs(((gconst7)*(((((IkReal(-1.00000000000000))*(sj5)*(x6059)*(x6060)))+(((r21)*(x6062)*(x6063)))+(((cj1)*(x6065)))+(((x6061)*(x6062)))+(((IkReal(-1.00000000000000))*(sj4)*(x6057)*(x6059)))+(((sj1)*(x6066)))+(((r20)*(x6057)*(x6063)))+(((IkReal(-1.00000000000000))*(x6058)*(x6064))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((IkReal(-1.00000000000000))*(sj1)*(x6065)))+(((r20)*(x6063)*(x6064)))+(((cj1)*(x6066)))+(((IkReal(-1.00000000000000))*(sj4)*(x6059)*(x6064)))+(((x6057)*(x6058)))+(((r21)*(sj5)*(x6062)))+(((x6060)*(x6061)))+(((r21)*(x6060)*(x6063))))))) < IKFAST_ATAN2_MAGTHRESH )
19020     continue;
19021 j3array[0]=IKatan2(((gconst7)*(((((IkReal(-1.00000000000000))*(sj5)*(x6059)*(x6060)))+(((r21)*(x6062)*(x6063)))+(((cj1)*(x6065)))+(((x6061)*(x6062)))+(((IkReal(-1.00000000000000))*(sj4)*(x6057)*(x6059)))+(((sj1)*(x6066)))+(((r20)*(x6057)*(x6063)))+(((IkReal(-1.00000000000000))*(x6058)*(x6064)))))), ((gconst7)*(((((IkReal(-1.00000000000000))*(sj1)*(x6065)))+(((r20)*(x6063)*(x6064)))+(((cj1)*(x6066)))+(((IkReal(-1.00000000000000))*(sj4)*(x6059)*(x6064)))+(((x6057)*(x6058)))+(((r21)*(sj5)*(x6062)))+(((x6060)*(x6061)))+(((r21)*(x6060)*(x6063)))))));
19022 sj3array[0]=IKsin(j3array[0]);
19023 cj3array[0]=IKcos(j3array[0]);
19024 if( j3array[0] > IKPI )
19025 {
19026     j3array[0]-=IK2PI;
19027 }
19028 else if( j3array[0] < -IKPI )
19029 {    j3array[0]+=IK2PI;
19030 }
19031 j3valid[0] = true;
19032 for(int ij3 = 0; ij3 < 1; ++ij3)
19033 {
19034 if( !j3valid[ij3] )
19035 {
19036     continue;
19037 }
19038 _ij3[0] = ij3; _ij3[1] = -1;
19039 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19040 {
19041 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19042 {
19043     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19044 }
19045 }
19046 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19047 {
19048 IkReal evalcond[4];
19049 IkReal x6067=IKsin(j3);
19050 IkReal x6068=IKcos(j3);
19051 IkReal x6069=((IkReal(1.00000000000000))*(cj4));
19052 IkReal x6070=((sj0)*(sj5));
19053 IkReal x6071=((cj0)*(cj5));
19054 IkReal x6072=((cj6)*(r01));
19055 IkReal x6073=((r00)*(sj6));
19056 IkReal x6074=((cj6)*(r11));
19057 IkReal x6075=((cj5)*(sj0));
19058 IkReal x6076=((cj6)*(sj4));
19059 IkReal x6077=((sj4)*(sj6));
19060 IkReal x6078=((cj4)*(cj5));
19061 IkReal x6079=((cj6)*(r21));
19062 IkReal x6080=((r20)*(sj6));
19063 IkReal x6081=((r10)*(sj6));
19064 IkReal x6082=((cj1)*(x6067));
19065 IkReal x6083=((IkReal(1.00000000000000))*(cj0)*(sj5));
19066 IkReal x6084=((IkReal(1.00000000000000))*(x6068));
19067 IkReal x6085=((IkReal(1.00000000000000))*(sj1)*(x6067));
19068 IkReal x6086=((cj1)*(x6084));
19069 IkReal x6087=((x6086)+(x6085));
19070 evalcond[0]=((((sj5)*(x6080)))+(((IkReal(-1.00000000000000))*(sj1)*(x6084)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x6082)+(((sj5)*(x6079))));
19071 evalcond[1]=((((x6078)*(x6080)))+(((IkReal(-1.00000000000000))*(r21)*(x6077)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x6087)))+(((x6078)*(x6079)))+(((r20)*(x6076))));
19072 evalcond[2]=((((IkReal(-1.00000000000000))*(x6070)*(x6074)))+(((IkReal(-1.00000000000000))*(x6072)*(x6083)))+(((IkReal(-1.00000000000000))*(x6073)*(x6083)))+(((r12)*(x6075)))+(((r02)*(x6071)))+(((IkReal(-1.00000000000000))*(x6087)))+(((IkReal(-1.00000000000000))*(x6070)*(x6081))));
19073 evalcond[3]=((((IkReal(-1.00000000000000))*(x6069)*(x6071)*(x6073)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6076)))+(((sj1)*(x6068)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6069)))+(((IkReal(-1.00000000000000))*(r12)*(x6069)*(x6070)))+(((IkReal(-1.00000000000000))*(x6069)*(x6075)*(x6081)))+(((IkReal(-1.00000000000000))*(x6069)*(x6074)*(x6075)))+(((r11)*(sj0)*(x6077)))+(((IkReal(-1.00000000000000))*(x6069)*(x6071)*(x6072)))+(((cj0)*(r01)*(x6077)))+(((IkReal(-1.00000000000000))*(x6082)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6076))));
19074 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
19075 {
19076 continue;
19077 }
19078 }
19079 
19080 {
19081 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19082 vinfos[0].jointtype = 1;
19083 vinfos[0].foffset = j0;
19084 vinfos[0].indices[0] = _ij0[0];
19085 vinfos[0].indices[1] = _ij0[1];
19086 vinfos[0].maxsolutions = _nj0;
19087 vinfos[1].jointtype = 1;
19088 vinfos[1].foffset = j1;
19089 vinfos[1].indices[0] = _ij1[0];
19090 vinfos[1].indices[1] = _ij1[1];
19091 vinfos[1].maxsolutions = _nj1;
19092 vinfos[2].jointtype = 1;
19093 vinfos[2].foffset = j2;
19094 vinfos[2].indices[0] = _ij2[0];
19095 vinfos[2].indices[1] = _ij2[1];
19096 vinfos[2].maxsolutions = _nj2;
19097 vinfos[3].jointtype = 1;
19098 vinfos[3].foffset = j3;
19099 vinfos[3].indices[0] = _ij3[0];
19100 vinfos[3].indices[1] = _ij3[1];
19101 vinfos[3].maxsolutions = _nj3;
19102 vinfos[4].jointtype = 1;
19103 vinfos[4].foffset = j4;
19104 vinfos[4].indices[0] = _ij4[0];
19105 vinfos[4].indices[1] = _ij4[1];
19106 vinfos[4].maxsolutions = _nj4;
19107 vinfos[5].jointtype = 1;
19108 vinfos[5].foffset = j5;
19109 vinfos[5].indices[0] = _ij5[0];
19110 vinfos[5].indices[1] = _ij5[1];
19111 vinfos[5].maxsolutions = _nj5;
19112 vinfos[6].jointtype = 1;
19113 vinfos[6].foffset = j6;
19114 vinfos[6].indices[0] = _ij6[0];
19115 vinfos[6].indices[1] = _ij6[1];
19116 vinfos[6].maxsolutions = _nj6;
19117 std::vector<int> vfree(0);
19118 solutions.AddSolution(vinfos,vfree);
19119 }
19120 }
19121 }
19122 
19123 }
19124 
19125 }
19126 
19127 } else
19128 {
19129 IkReal x6088=((IkReal(1.00000000000000))*(cj0));
19130 IkReal x6089=((cj4)*(sj6));
19131 IkReal x6090=((sj0)*(sj4));
19132 IkReal x6091=((cj5)*(sj6));
19133 IkReal x6092=((sj4)*(sj5));
19134 IkReal x6093=((r12)*(sj5));
19135 IkReal x6094=((IkReal(0.374290000000000))*(cj5));
19136 IkReal x6095=((r02)*(sj0));
19137 IkReal x6096=((cj6)*(r21));
19138 IkReal x6097=((IkReal(0.0100000000000000))*(cj5));
19139 IkReal x6098=((IkReal(1.00000000000000))*(sj0));
19140 IkReal x6099=((cj0)*(r10));
19141 IkReal x6100=((cj4)*(cj6));
19142 IkReal x6101=((r00)*(sj0));
19143 IkReal x6102=((IkReal(0.374290000000000))*(sj5));
19144 IkReal x6103=((cj0)*(r00));
19145 IkReal x6104=((IkReal(0.0100000000000000))*(sj5));
19146 IkReal x6105=((cj0)*(r02));
19147 IkReal x6106=((cj5)*(sj4));
19148 IkReal x6107=((cj6)*(r01));
19149 IkReal x6108=((cj6)*(r11));
19150 IkReal x6109=((r10)*(sj0));
19151 IkReal x6110=((sj6)*(x6102));
19152 IkReal x6111=((cj0)*(cj6)*(x6102));
19153 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
19154 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(r20)*(x6100)))+(((r22)*(x6092)))+(((r20)*(sj4)*(x6091)))+(((x6096)*(x6106)))+(((r21)*(x6089))));
19155 evalcond[2]=((((IkReal(-0.0100000000000000))*(r20)*(x6091)))+(((IkReal(-1.00000000000000))*(r22)*(x6094)))+(((IkReal(-1.00000000000000))*(r22)*(x6104)))+(pz)+(((r20)*(x6110)))+(((IkReal(-1.00000000000000))*(x6096)*(x6097)))+(((x6096)*(x6102)))+(((IkReal(0.0690000000000000))*(cj2))));
19156 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x6088)*(x6089)))+(((x6099)*(x6100)))+(((IkReal(-1.00000000000000))*(x6088)*(x6106)*(x6108)))+(((r01)*(sj0)*(x6089)))+(((cj5)*(x6090)*(x6107)))+(((r00)*(x6090)*(x6091)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x6098)*(x6100)))+(((r02)*(sj5)*(x6090)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6088)*(x6091)))+(((IkReal(-1.00000000000000))*(r12)*(x6088)*(x6092))));
19157 evalcond[4]=((((IkReal(-1.00000000000000))*(x6090)*(x6093)))+(((IkReal(-1.00000000000000))*(r11)*(x6089)*(x6098)))+(((IkReal(-1.00000000000000))*(r01)*(x6088)*(x6089)))+(((IkReal(-1.00000000000000))*(r10)*(x6090)*(x6091)))+(((x6100)*(x6109)))+(((x6100)*(x6103)))+(((IkReal(-1.00000000000000))*(x6088)*(x6106)*(x6107)))+(((IkReal(-1.00000000000000))*(cj5)*(x6090)*(x6108)))+(((IkReal(-1.00000000000000))*(r02)*(x6088)*(x6092)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6088)*(x6091))));
19158 evalcond[5]=((((IkReal(-1.00000000000000))*(x6099)*(x6110)))+(((x6101)*(x6110)))+(((IkReal(-1.00000000000000))*(sj0)*(x6097)*(x6107)))+(((IkReal(-1.00000000000000))*(py)*(x6088)))+(((IkReal(-0.0100000000000000))*(x6091)*(x6101)))+(((IkReal(-1.00000000000000))*(cj0)*(x6102)*(x6108)))+(((IkReal(0.0690000000000000))*(sj2)))+(((cj0)*(x6097)*(x6108)))+(((IkReal(0.0100000000000000))*(cj0)*(x6093)))+(((IkReal(0.0100000000000000))*(x6091)*(x6099)))+(((px)*(sj0)))+(((cj0)*(r12)*(x6094)))+(((sj0)*(x6102)*(x6107)))+(((IkReal(-1.00000000000000))*(x6095)*(x6104)))+(((IkReal(-1.00000000000000))*(x6094)*(x6095))));
19159 evalcond[6]=((IkReal(0.433420000000000))+(((x6094)*(x6105)))+(((IkReal(-1.00000000000000))*(px)*(x6088)))+(((IkReal(-1.00000000000000))*(py)*(x6098)))+(((sj0)*(x6097)*(x6108)))+(((IkReal(-1.00000000000000))*(x6103)*(x6110)))+(((IkReal(0.0100000000000000))*(x6091)*(x6109)))+(((r12)*(sj0)*(x6094)))+(((IkReal(-1.00000000000000))*(sj0)*(x6102)*(x6108)))+(((IkReal(-1.00000000000000))*(cj0)*(x6102)*(x6107)))+(((x6104)*(x6105)))+(((cj0)*(x6097)*(x6107)))+(((IkReal(-1.00000000000000))*(x6109)*(x6110)))+(((IkReal(0.0100000000000000))*(x6091)*(x6103)))+(((IkReal(0.0100000000000000))*(sj0)*(x6093))));
19160 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
19161 {
19162 {
19163 IkReal dummyeval[1];
19164 IkReal gconst9;
19165 gconst9=IKsign(cj2);
19166 dummyeval[0]=cj2;
19167 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
19168 {
19169 {
19170 IkReal dummyeval[1];
19171 dummyeval[0]=cj2;
19172 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
19173 {
19174 {
19175 IkReal dummyeval[1];
19176 dummyeval[0]=sj2;
19177 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
19178 {
19179 {
19180 IkReal evalcond[9];
19181 IkReal x6112=((cj5)*(sj4));
19182 IkReal x6113=((IkReal(1.00000000000000))*(sj6));
19183 IkReal x6114=((r10)*(sj0));
19184 IkReal x6115=((sj4)*(sj5));
19185 IkReal x6116=((cj5)*(cj6));
19186 IkReal x6117=((r01)*(sj0));
19187 IkReal x6118=((IkReal(1.00000000000000))*(r02));
19188 IkReal x6119=((IkReal(0.374290000000000))*(cj0));
19189 IkReal x6120=((cj5)*(r12));
19190 IkReal x6121=((cj6)*(sj5));
19191 IkReal x6122=((cj0)*(r11));
19192 IkReal x6123=((cj5)*(sj0));
19193 IkReal x6124=((r20)*(sj6));
19194 IkReal x6125=((IkReal(1.00000000000000))*(sj0));
19195 IkReal x6126=((cj4)*(cj5));
19196 IkReal x6127=((IkReal(1.00000000000000))*(cj6));
19197 IkReal x6128=((IkReal(0.0100000000000000))*(sj5));
19198 IkReal x6129=((sj5)*(sj6));
19199 IkReal x6130=((cj0)*(r10));
19200 IkReal x6131=((cj4)*(cj6));
19201 IkReal x6132=((cj0)*(r01));
19202 IkReal x6133=((IkReal(1.00000000000000))*(cj4));
19203 IkReal x6134=((cj0)*(r00));
19204 IkReal x6135=((IkReal(0.374290000000000))*(sj0));
19205 IkReal x6136=((cj0)*(r12));
19206 IkReal x6137=((IkReal(0.374290000000000))*(sj5));
19207 IkReal x6138=((cj4)*(sj6));
19208 IkReal x6139=((IkReal(1.00000000000000))*(cj0));
19209 IkReal x6140=((r02)*(sj0));
19210 IkReal x6141=((IkReal(0.0100000000000000))*(cj5));
19211 IkReal x6142=((r11)*(sj0));
19212 IkReal x6143=((r00)*(sj0)*(sj6));
19213 IkReal x6144=((r00)*(x6131));
19214 IkReal x6145=((sj6)*(x6141));
19215 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
19216 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(r20)*(x6127)))+(((cj6)*(r21)*(x6112)))+(((x6112)*(x6124)))+(((r21)*(x6138)))+(((r22)*(x6115))));
19217 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x6128)))+(((IkReal(-1.00000000000000))*(x6124)*(x6141)))+(((IkReal(0.374290000000000))*(r21)*(x6121)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x6124)*(x6137)))+(pz)+(((IkReal(-0.0100000000000000))*(r21)*(x6116))));
19218 evalcond[3]=((((IkReal(-1.00000000000000))*(x6121)*(x6122)))+(((x6117)*(x6121)))+(((r00)*(sj0)*(x6129)))+(((cj0)*(x6120)))+(((IkReal(-1.00000000000000))*(sj5)*(x6113)*(x6130)))+(((IkReal(-1.00000000000000))*(x6118)*(x6123))));
19219 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x6115)*(x6136)))+(((IkReal(-1.00000000000000))*(x6125)*(x6144)))+(((cj6)*(x6112)*(x6117)))+(((x6112)*(x6143)))+(((x6115)*(x6140)))+(((IkReal(-1.00000000000000))*(x6112)*(x6122)*(x6127)))+(((x6130)*(x6131)))+(((IkReal(-1.00000000000000))*(cj4)*(x6113)*(x6122)))+(((x6117)*(x6138)))+(((IkReal(-1.00000000000000))*(x6112)*(x6113)*(x6130))));
19220 evalcond[5]=((((sj4)*(sj6)*(x6122)))+(((cj4)*(sj5)*(x6140)))+(((r00)*(x6123)*(x6138)))+(((IkReal(-1.00000000000000))*(x6116)*(x6122)*(x6133)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x6127)*(x6130)))+(((cj4)*(x6116)*(x6117)))+(((IkReal(-1.00000000000000))*(sj4)*(x6113)*(x6117)))+(((IkReal(-1.00000000000000))*(sj5)*(x6133)*(x6136)))+(((IkReal(-1.00000000000000))*(x6113)*(x6126)*(x6130))));
19221 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x6113)*(x6132)))+(((IkReal(-1.00000000000000))*(x6112)*(x6113)*(x6114)))+(((IkReal(-1.00000000000000))*(cj4)*(x6113)*(x6142)))+(((IkReal(-1.00000000000000))*(r12)*(x6115)*(x6125)))+(((IkReal(-1.00000000000000))*(cj0)*(x6115)*(x6118)))+(((x6114)*(x6131)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x6112)*(x6125)))+(((x6131)*(x6134)))+(((IkReal(-1.00000000000000))*(x6112)*(x6113)*(x6134)))+(((IkReal(-1.00000000000000))*(x6112)*(x6127)*(x6132))));
19222 evalcond[7]=((((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x6123)))+(((x6128)*(x6136)))+(((IkReal(-0.0100000000000000))*(x6116)*(x6117)))+(((x6119)*(x6120)))+(((IkReal(0.0100000000000000))*(x6116)*(x6122)))+(((IkReal(-0.374290000000000))*(r02)*(x6123)))+(((IkReal(-1.00000000000000))*(py)*(x6139)))+(((IkReal(-1.00000000000000))*(r10)*(x6119)*(x6129)))+(((IkReal(-1.00000000000000))*(r11)*(x6119)*(x6121)))+(((px)*(sj0)))+(((x6130)*(x6145)))+(((IkReal(0.374290000000000))*(x6117)*(x6121)))+(((r00)*(x6129)*(x6135)))+(((IkReal(-1.00000000000000))*(x6128)*(x6140))));
19223 evalcond[8]=((IkReal(0.433420000000000))+(((cj5)*(r02)*(x6119)))+(((r12)*(sj0)*(x6128)))+(((IkReal(0.0100000000000000))*(x6116)*(x6142)))+(((IkReal(-1.00000000000000))*(px)*(x6139)))+(((IkReal(-1.00000000000000))*(r00)*(x6119)*(x6129)))+(((cj0)*(r02)*(x6128)))+(((IkReal(-1.00000000000000))*(py)*(x6125)))+(((x6134)*(x6145)))+(((IkReal(-1.00000000000000))*(r11)*(x6121)*(x6135)))+(((IkReal(-0.374290000000000))*(x6114)*(x6129)))+(((IkReal(0.0100000000000000))*(x6116)*(x6132)))+(((x6114)*(x6145)))+(((x6120)*(x6135)))+(((IkReal(-1.00000000000000))*(r01)*(x6119)*(x6121))));
19224 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
19225 {
19226 {
19227 IkReal j3array[1], cj3array[1], sj3array[1];
19228 bool j3valid[1]={false};
19229 _nj3 = 1;
19230 IkReal x6146=((IkReal(1.00000000000000))*(cj4));
19231 IkReal x6147=((cj6)*(r21));
19232 IkReal x6148=((r20)*(sj6));
19233 if( IKabs(((((sj5)*(x6147)))+(((sj5)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6147)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6146)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x6147)))+(((sj5)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6147)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6146)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
19234     continue;
19235 j3array[0]=IKatan2(((((sj5)*(x6147)))+(((sj5)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6148)))+(((IkReal(-1.00000000000000))*(cj5)*(x6146)*(x6147)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6146)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
19236 sj3array[0]=IKsin(j3array[0]);
19237 cj3array[0]=IKcos(j3array[0]);
19238 if( j3array[0] > IKPI )
19239 {
19240     j3array[0]-=IK2PI;
19241 }
19242 else if( j3array[0] < -IKPI )
19243 {    j3array[0]+=IK2PI;
19244 }
19245 j3valid[0] = true;
19246 for(int ij3 = 0; ij3 < 1; ++ij3)
19247 {
19248 if( !j3valid[ij3] )
19249 {
19250     continue;
19251 }
19252 _ij3[0] = ij3; _ij3[1] = -1;
19253 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19254 {
19255 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19256 {
19257     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19258 }
19259 }
19260 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19261 {
19262 IkReal evalcond[4];
19263 IkReal x6149=IKcos(j3);
19264 IkReal x6150=((IkReal(1.00000000000000))*(cj4));
19265 IkReal x6151=((sj0)*(sj5));
19266 IkReal x6152=((cj0)*(cj5));
19267 IkReal x6153=((cj6)*(r01));
19268 IkReal x6154=((r00)*(sj6));
19269 IkReal x6155=((cj6)*(r11));
19270 IkReal x6156=((cj5)*(sj0));
19271 IkReal x6157=((cj6)*(sj4));
19272 IkReal x6158=((sj4)*(sj6));
19273 IkReal x6159=((cj4)*(cj5));
19274 IkReal x6160=((cj6)*(r21));
19275 IkReal x6161=((r20)*(sj6));
19276 IkReal x6162=((r10)*(sj6));
19277 IkReal x6163=((IkReal(1.00000000000000))*(IKsin(j3)));
19278 IkReal x6164=((IkReal(1.00000000000000))*(cj0)*(sj5));
19279 evalcond[0]=((((IkReal(-1.00000000000000))*(x6163)))+(((sj5)*(x6160)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6161))));
19280 evalcond[1]=((((x6159)*(x6160)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x6157)))+(((IkReal(-1.00000000000000))*(r21)*(x6158)))+(x6149)+(((x6159)*(x6161))));
19281 evalcond[2]=((((r02)*(x6152)))+(((r12)*(x6156)))+(((IkReal(-1.00000000000000))*(x6151)*(x6155)))+(((IkReal(-1.00000000000000))*(x6154)*(x6164)))+(((IkReal(-1.00000000000000))*(x6153)*(x6164)))+(((IkReal(-1.00000000000000))*(x6149)))+(((IkReal(-1.00000000000000))*(x6151)*(x6162))));
19282 evalcond[3]=((((IkReal(-1.00000000000000))*(x6150)*(x6155)*(x6156)))+(((IkReal(-1.00000000000000))*(x6163)))+(((cj0)*(r01)*(x6158)))+(((r11)*(sj0)*(x6158)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6157)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6150)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6157)))+(((IkReal(-1.00000000000000))*(x6150)*(x6156)*(x6162)))+(((IkReal(-1.00000000000000))*(x6150)*(x6152)*(x6154)))+(((IkReal(-1.00000000000000))*(r12)*(x6150)*(x6151)))+(((IkReal(-1.00000000000000))*(x6150)*(x6152)*(x6153))));
19283 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
19284 {
19285 continue;
19286 }
19287 }
19288 
19289 {
19290 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19291 vinfos[0].jointtype = 1;
19292 vinfos[0].foffset = j0;
19293 vinfos[0].indices[0] = _ij0[0];
19294 vinfos[0].indices[1] = _ij0[1];
19295 vinfos[0].maxsolutions = _nj0;
19296 vinfos[1].jointtype = 1;
19297 vinfos[1].foffset = j1;
19298 vinfos[1].indices[0] = _ij1[0];
19299 vinfos[1].indices[1] = _ij1[1];
19300 vinfos[1].maxsolutions = _nj1;
19301 vinfos[2].jointtype = 1;
19302 vinfos[2].foffset = j2;
19303 vinfos[2].indices[0] = _ij2[0];
19304 vinfos[2].indices[1] = _ij2[1];
19305 vinfos[2].maxsolutions = _nj2;
19306 vinfos[3].jointtype = 1;
19307 vinfos[3].foffset = j3;
19308 vinfos[3].indices[0] = _ij3[0];
19309 vinfos[3].indices[1] = _ij3[1];
19310 vinfos[3].maxsolutions = _nj3;
19311 vinfos[4].jointtype = 1;
19312 vinfos[4].foffset = j4;
19313 vinfos[4].indices[0] = _ij4[0];
19314 vinfos[4].indices[1] = _ij4[1];
19315 vinfos[4].maxsolutions = _nj4;
19316 vinfos[5].jointtype = 1;
19317 vinfos[5].foffset = j5;
19318 vinfos[5].indices[0] = _ij5[0];
19319 vinfos[5].indices[1] = _ij5[1];
19320 vinfos[5].maxsolutions = _nj5;
19321 vinfos[6].jointtype = 1;
19322 vinfos[6].foffset = j6;
19323 vinfos[6].indices[0] = _ij6[0];
19324 vinfos[6].indices[1] = _ij6[1];
19325 vinfos[6].maxsolutions = _nj6;
19326 std::vector<int> vfree(0);
19327 solutions.AddSolution(vinfos,vfree);
19328 }
19329 }
19330 }
19331 
19332 } else
19333 {
19334 IkReal x6165=((cj5)*(sj4));
19335 IkReal x6166=((IkReal(1.00000000000000))*(sj6));
19336 IkReal x6167=((r10)*(sj0));
19337 IkReal x6168=((sj4)*(sj5));
19338 IkReal x6169=((cj5)*(cj6));
19339 IkReal x6170=((r01)*(sj0));
19340 IkReal x6171=((IkReal(1.00000000000000))*(r02));
19341 IkReal x6172=((IkReal(0.374290000000000))*(cj0));
19342 IkReal x6173=((cj5)*(r12));
19343 IkReal x6174=((cj6)*(sj5));
19344 IkReal x6175=((cj0)*(r11));
19345 IkReal x6176=((cj5)*(sj0));
19346 IkReal x6177=((r20)*(sj6));
19347 IkReal x6178=((IkReal(1.00000000000000))*(sj0));
19348 IkReal x6179=((cj4)*(cj5));
19349 IkReal x6180=((IkReal(1.00000000000000))*(cj6));
19350 IkReal x6181=((IkReal(0.0100000000000000))*(sj5));
19351 IkReal x6182=((sj5)*(sj6));
19352 IkReal x6183=((cj0)*(r10));
19353 IkReal x6184=((cj4)*(cj6));
19354 IkReal x6185=((cj0)*(r01));
19355 IkReal x6186=((IkReal(1.00000000000000))*(cj4));
19356 IkReal x6187=((cj0)*(r00));
19357 IkReal x6188=((IkReal(0.374290000000000))*(sj0));
19358 IkReal x6189=((cj0)*(r12));
19359 IkReal x6190=((IkReal(0.374290000000000))*(sj5));
19360 IkReal x6191=((cj4)*(sj6));
19361 IkReal x6192=((IkReal(1.00000000000000))*(cj0));
19362 IkReal x6193=((r02)*(sj0));
19363 IkReal x6194=((IkReal(0.0100000000000000))*(cj5));
19364 IkReal x6195=((r11)*(sj0));
19365 IkReal x6196=((r00)*(sj0)*(sj6));
19366 IkReal x6197=((r00)*(x6184));
19367 IkReal x6198=((sj6)*(x6194));
19368 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
19369 evalcond[1]=((((cj6)*(r21)*(x6165)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x6180)))+(((x6165)*(x6177)))+(((r21)*(x6191)))+(((r22)*(x6168))));
19370 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x6181)))+(((IkReal(-1.00000000000000))*(x6177)*(x6194)))+(((IkReal(0.374290000000000))*(r21)*(x6174)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x6169)))+(pz)+(((x6177)*(x6190))));
19371 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x6166)*(x6183)))+(((IkReal(-1.00000000000000))*(x6174)*(x6175)))+(((r00)*(sj0)*(x6182)))+(((IkReal(-1.00000000000000))*(x6171)*(x6176)))+(((x6170)*(x6174)))+(((cj0)*(x6173))));
19372 evalcond[4]=((IkReal(-1.00000000000000))+(((x6183)*(x6184)))+(((IkReal(-1.00000000000000))*(x6168)*(x6189)))+(((x6168)*(x6193)))+(((x6170)*(x6191)))+(((IkReal(-1.00000000000000))*(x6165)*(x6166)*(x6183)))+(((cj6)*(x6165)*(x6170)))+(((x6165)*(x6196)))+(((IkReal(-1.00000000000000))*(x6178)*(x6197)))+(((IkReal(-1.00000000000000))*(cj4)*(x6166)*(x6175)))+(((IkReal(-1.00000000000000))*(x6165)*(x6175)*(x6180))));
19373 evalcond[5]=((((sj4)*(sj6)*(x6175)))+(((IkReal(-1.00000000000000))*(x6169)*(x6175)*(x6186)))+(((IkReal(-1.00000000000000))*(x6166)*(x6179)*(x6183)))+(((IkReal(-1.00000000000000))*(sj5)*(x6186)*(x6189)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(x6169)*(x6170)))+(((IkReal(-1.00000000000000))*(sj4)*(x6166)*(x6170)))+(((IkReal(-1.00000000000000))*(sj4)*(x6180)*(x6183)))+(((r00)*(x6176)*(x6191)))+(((cj4)*(sj5)*(x6193))));
19374 evalcond[6]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x6165)*(x6178)))+(((x6167)*(x6184)))+(((x6184)*(x6187)))+(((IkReal(-1.00000000000000))*(x6165)*(x6180)*(x6185)))+(((IkReal(-1.00000000000000))*(cj4)*(x6166)*(x6185)))+(((IkReal(-1.00000000000000))*(x6165)*(x6166)*(x6167)))+(((IkReal(-1.00000000000000))*(r12)*(x6168)*(x6178)))+(((IkReal(-1.00000000000000))*(cj4)*(x6166)*(x6195)))+(((IkReal(-1.00000000000000))*(cj0)*(x6168)*(x6171)))+(((IkReal(-1.00000000000000))*(x6165)*(x6166)*(x6187))));
19375 evalcond[7]=((((x6181)*(x6189)))+(((x6172)*(x6173)))+(((IkReal(0.374290000000000))*(x6170)*(x6174)))+(((IkReal(-1.00000000000000))*(r11)*(x6172)*(x6174)))+(((IkReal(-0.0100000000000000))*(x6169)*(x6170)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x6176)))+(((r00)*(x6182)*(x6188)))+(((IkReal(-1.00000000000000))*(x6181)*(x6193)))+(((IkReal(0.0100000000000000))*(x6169)*(x6175)))+(((IkReal(-1.00000000000000))*(py)*(x6192)))+(((IkReal(-1.00000000000000))*(r10)*(x6172)*(x6182)))+(((IkReal(-0.374290000000000))*(r02)*(x6176)))+(((px)*(sj0)))+(((x6183)*(x6198))));
19376 evalcond[8]=((IkReal(0.433420000000000))+(((x6173)*(x6188)))+(((IkReal(-1.00000000000000))*(py)*(x6178)))+(((cj0)*(r02)*(x6181)))+(((cj5)*(r02)*(x6172)))+(((IkReal(0.0100000000000000))*(x6169)*(x6185)))+(((IkReal(-1.00000000000000))*(px)*(x6192)))+(((IkReal(-1.00000000000000))*(r01)*(x6172)*(x6174)))+(((IkReal(-1.00000000000000))*(r11)*(x6174)*(x6188)))+(((r12)*(sj0)*(x6181)))+(((IkReal(-0.374290000000000))*(x6167)*(x6182)))+(((x6187)*(x6198)))+(((x6167)*(x6198)))+(((IkReal(-1.00000000000000))*(r00)*(x6172)*(x6182)))+(((IkReal(0.0100000000000000))*(x6169)*(x6195))));
19377 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
19378 {
19379 {
19380 IkReal j3array[1], cj3array[1], sj3array[1];
19381 bool j3valid[1]={false};
19382 _nj3 = 1;
19383 IkReal x6199=((IkReal(1.00000000000000))*(r21));
19384 IkReal x6200=((cj4)*(cj5));
19385 IkReal x6201=((r20)*(sj6));
19386 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x6201)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6199)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r21)*(x6200)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6199)))+(((x6200)*(x6201))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x6201)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6199)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r21)*(x6200)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6199)))+(((x6200)*(x6201)))))-1) <= IKFAST_SINCOS_THRESH )
19387     continue;
19388 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x6201)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6199)))+(((cj5)*(r22)))), ((((cj6)*(r21)*(x6200)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6199)))+(((x6200)*(x6201)))));
19389 sj3array[0]=IKsin(j3array[0]);
19390 cj3array[0]=IKcos(j3array[0]);
19391 if( j3array[0] > IKPI )
19392 {
19393     j3array[0]-=IK2PI;
19394 }
19395 else if( j3array[0] < -IKPI )
19396 {    j3array[0]+=IK2PI;
19397 }
19398 j3valid[0] = true;
19399 for(int ij3 = 0; ij3 < 1; ++ij3)
19400 {
19401 if( !j3valid[ij3] )
19402 {
19403     continue;
19404 }
19405 _ij3[0] = ij3; _ij3[1] = -1;
19406 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19407 {
19408 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19409 {
19410     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19411 }
19412 }
19413 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19414 {
19415 IkReal evalcond[4];
19416 IkReal x6202=IKsin(j3);
19417 IkReal x6203=((IkReal(1.00000000000000))*(cj4));
19418 IkReal x6204=((sj0)*(sj5));
19419 IkReal x6205=((cj0)*(cj5));
19420 IkReal x6206=((cj6)*(r01));
19421 IkReal x6207=((r00)*(sj6));
19422 IkReal x6208=((cj6)*(r11));
19423 IkReal x6209=((cj5)*(sj0));
19424 IkReal x6210=((cj6)*(sj4));
19425 IkReal x6211=((sj4)*(sj6));
19426 IkReal x6212=((cj4)*(cj5));
19427 IkReal x6213=((cj6)*(r21));
19428 IkReal x6214=((r20)*(sj6));
19429 IkReal x6215=((r10)*(sj6));
19430 IkReal x6216=((IkReal(1.00000000000000))*(IKcos(j3)));
19431 IkReal x6217=((IkReal(1.00000000000000))*(cj0)*(sj5));
19432 evalcond[0]=((((sj5)*(x6213)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x6202)+(((sj5)*(x6214))));
19433 evalcond[1]=((((x6212)*(x6214)))+(((cj4)*(r22)*(sj5)))+(((x6212)*(x6213)))+(((IkReal(-1.00000000000000))*(r21)*(x6211)))+(((IkReal(-1.00000000000000))*(x6216)))+(((r20)*(x6210))));
19434 evalcond[2]=((((r02)*(x6205)))+(((IkReal(-1.00000000000000))*(x6204)*(x6208)))+(((IkReal(-1.00000000000000))*(x6207)*(x6217)))+(((IkReal(-1.00000000000000))*(x6206)*(x6217)))+(((r12)*(x6209)))+(((IkReal(-1.00000000000000))*(x6216)))+(((IkReal(-1.00000000000000))*(x6204)*(x6215))));
19435 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6210)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6203)))+(((r11)*(sj0)*(x6211)))+(((IkReal(-1.00000000000000))*(x6203)*(x6205)*(x6207)))+(((IkReal(-1.00000000000000))*(x6203)*(x6205)*(x6206)))+(((IkReal(-1.00000000000000))*(x6203)*(x6208)*(x6209)))+(((IkReal(-1.00000000000000))*(x6203)*(x6209)*(x6215)))+(((IkReal(-1.00000000000000))*(x6202)))+(((IkReal(-1.00000000000000))*(r12)*(x6203)*(x6204)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6210)))+(((cj0)*(r01)*(x6211))));
19436 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
19437 {
19438 continue;
19439 }
19440 }
19441 
19442 {
19443 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19444 vinfos[0].jointtype = 1;
19445 vinfos[0].foffset = j0;
19446 vinfos[0].indices[0] = _ij0[0];
19447 vinfos[0].indices[1] = _ij0[1];
19448 vinfos[0].maxsolutions = _nj0;
19449 vinfos[1].jointtype = 1;
19450 vinfos[1].foffset = j1;
19451 vinfos[1].indices[0] = _ij1[0];
19452 vinfos[1].indices[1] = _ij1[1];
19453 vinfos[1].maxsolutions = _nj1;
19454 vinfos[2].jointtype = 1;
19455 vinfos[2].foffset = j2;
19456 vinfos[2].indices[0] = _ij2[0];
19457 vinfos[2].indices[1] = _ij2[1];
19458 vinfos[2].maxsolutions = _nj2;
19459 vinfos[3].jointtype = 1;
19460 vinfos[3].foffset = j3;
19461 vinfos[3].indices[0] = _ij3[0];
19462 vinfos[3].indices[1] = _ij3[1];
19463 vinfos[3].maxsolutions = _nj3;
19464 vinfos[4].jointtype = 1;
19465 vinfos[4].foffset = j4;
19466 vinfos[4].indices[0] = _ij4[0];
19467 vinfos[4].indices[1] = _ij4[1];
19468 vinfos[4].maxsolutions = _nj4;
19469 vinfos[5].jointtype = 1;
19470 vinfos[5].foffset = j5;
19471 vinfos[5].indices[0] = _ij5[0];
19472 vinfos[5].indices[1] = _ij5[1];
19473 vinfos[5].maxsolutions = _nj5;
19474 vinfos[6].jointtype = 1;
19475 vinfos[6].foffset = j6;
19476 vinfos[6].indices[0] = _ij6[0];
19477 vinfos[6].indices[1] = _ij6[1];
19478 vinfos[6].maxsolutions = _nj6;
19479 std::vector<int> vfree(0);
19480 solutions.AddSolution(vinfos,vfree);
19481 }
19482 }
19483 }
19484 
19485 } else
19486 {
19487 IkReal x6218=((IkReal(1.00000000000000))*(cj0));
19488 IkReal x6219=((cj4)*(sj6));
19489 IkReal x6220=((sj0)*(sj4));
19490 IkReal x6221=((cj5)*(sj6));
19491 IkReal x6222=((sj4)*(sj5));
19492 IkReal x6223=((r12)*(sj5));
19493 IkReal x6224=((IkReal(0.374290000000000))*(cj5));
19494 IkReal x6225=((r02)*(sj0));
19495 IkReal x6226=((r20)*(sj4));
19496 IkReal x6227=((IkReal(1.00000000000000))*(sj0));
19497 IkReal x6228=((IkReal(1.00000000000000))*(cj5));
19498 IkReal x6229=((cj0)*(r10));
19499 IkReal x6230=((cj4)*(cj6));
19500 IkReal x6231=((r00)*(sj0));
19501 IkReal x6232=((cj6)*(r21));
19502 IkReal x6233=((IkReal(0.374290000000000))*(sj5));
19503 IkReal x6234=((cj0)*(r00));
19504 IkReal x6235=((IkReal(0.0100000000000000))*(sj5));
19505 IkReal x6236=((cj0)*(r02));
19506 IkReal x6237=((cj5)*(sj4));
19507 IkReal x6238=((cj6)*(r01));
19508 IkReal x6239=((cj6)*(r11));
19509 IkReal x6240=((r01)*(sj0));
19510 IkReal x6241=((r10)*(sj0));
19511 IkReal x6242=((IkReal(0.0100000000000000))*(cj5)*(cj6));
19512 IkReal x6243=((sj6)*(x6233));
19513 IkReal x6244=((cj0)*(cj6)*(x6233));
19514 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
19515 evalcond[1]=((((sj5)*(x6232)))+(((IkReal(-1.00000000000000))*(r22)*(x6228)))+(((r20)*(sj5)*(sj6))));
19516 evalcond[2]=((IkReal(-1.00000000000000))+(((r21)*(x6219)))+(((IkReal(-1.00000000000000))*(r20)*(x6230)))+(((x6232)*(x6237)))+(((r22)*(x6222)))+(((x6221)*(x6226))));
19517 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x6221)))+(((x6232)*(x6233)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x6224)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6232)))+(((r20)*(x6243)))+(((IkReal(-1.00000000000000))*(r22)*(x6235))));
19518 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x6219)))+(((cj6)*(x6226)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x6230))));
19519 evalcond[5]=((((r00)*(x6220)*(x6221)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6218)*(x6221)))+(((cj5)*(x6220)*(x6238)))+(((IkReal(-1.00000000000000))*(x6218)*(x6237)*(x6239)))+(((IkReal(-1.00000000000000))*(r12)*(x6218)*(x6222)))+(((x6219)*(x6240)))+(((IkReal(-1.00000000000000))*(r00)*(x6227)*(x6230)))+(((IkReal(-1.00000000000000))*(r11)*(x6218)*(x6219)))+(((x6229)*(x6230)))+(((r02)*(sj5)*(x6220))));
19520 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(x6220)*(x6221)))+(((x6230)*(x6241)))+(((IkReal(-1.00000000000000))*(x6220)*(x6223)))+(((x6230)*(x6234)))+(((IkReal(-1.00000000000000))*(r02)*(x6218)*(x6222)))+(((IkReal(-1.00000000000000))*(r01)*(x6218)*(x6219)))+(((IkReal(-1.00000000000000))*(r11)*(x6219)*(x6227)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6218)*(x6221)))+(((IkReal(-1.00000000000000))*(x6218)*(x6237)*(x6238)))+(((IkReal(-1.00000000000000))*(x6220)*(x6228)*(x6239))));
19521 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(x6223)))+(((IkReal(-1.00000000000000))*(py)*(x6218)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6238)))+(((IkReal(-1.00000000000000))*(x6225)*(x6235)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6239)))+(((cj0)*(r12)*(x6224)))+(((x6231)*(x6243)))+(((IkReal(-1.00000000000000))*(cj0)*(x6233)*(x6239)))+(((IkReal(0.0100000000000000))*(x6221)*(x6229)))+(((sj0)*(x6233)*(x6238)))+(((IkReal(-0.0100000000000000))*(x6221)*(x6231)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x6229)*(x6243)))+(((IkReal(-1.00000000000000))*(x6224)*(x6225))));
19522 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(x6221)*(x6234)))+(((IkReal(0.0100000000000000))*(sj0)*(x6223)))+(((IkReal(0.0100000000000000))*(x6221)*(x6241)))+(((IkReal(-1.00000000000000))*(x6241)*(x6243)))+(((r12)*(sj0)*(x6224)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6239)))+(((IkReal(-1.00000000000000))*(x6234)*(x6243)))+(((IkReal(-1.00000000000000))*(sj0)*(x6233)*(x6239)))+(((IkReal(-1.00000000000000))*(px)*(x6218)))+(((x6224)*(x6236)))+(((IkReal(-1.00000000000000))*(py)*(x6227)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6238)))+(((IkReal(-1.00000000000000))*(cj0)*(x6233)*(x6238)))+(((x6235)*(x6236))));
19523 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
19524 {
19525 {
19526 IkReal j3array[1], cj3array[1], sj3array[1];
19527 bool j3valid[1]={false};
19528 _nj3 = 1;
19529 IkReal x6245=((cj0)*(cj5));
19530 IkReal x6246=((IkReal(1.00000000000000))*(cj0));
19531 IkReal x6247=((cj6)*(r11));
19532 IkReal x6248=((r10)*(sj6));
19533 IkReal x6249=((cj5)*(sj0));
19534 IkReal x6250=((r00)*(sj5)*(sj6));
19535 IkReal x6251=((cj6)*(r01)*(sj5));
19536 IkReal x6252=((IkReal(1.00000000000000))*(sj0)*(sj5));
19537 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6247)))+(((IkReal(-1.00000000000000))*(r02)*(x6249)))+(((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6248)))+(((sj0)*(x6251)))+(((sj0)*(x6250)))+(((r12)*(x6245))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x6247)*(x6252)))+(((r02)*(x6245)))+(((IkReal(-1.00000000000000))*(x6246)*(x6251)))+(((r12)*(x6249)))+(((IkReal(-1.00000000000000))*(x6246)*(x6250)))+(((IkReal(-1.00000000000000))*(x6248)*(x6252))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6247)))+(((IkReal(-1.00000000000000))*(r02)*(x6249)))+(((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6248)))+(((sj0)*(x6251)))+(((sj0)*(x6250)))+(((r12)*(x6245)))))+IKsqr(((((IkReal(-1.00000000000000))*(x6247)*(x6252)))+(((r02)*(x6245)))+(((IkReal(-1.00000000000000))*(x6246)*(x6251)))+(((r12)*(x6249)))+(((IkReal(-1.00000000000000))*(x6246)*(x6250)))+(((IkReal(-1.00000000000000))*(x6248)*(x6252)))))-1) <= IKFAST_SINCOS_THRESH )
19538     continue;
19539 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6247)))+(((IkReal(-1.00000000000000))*(r02)*(x6249)))+(((IkReal(-1.00000000000000))*(sj5)*(x6246)*(x6248)))+(((sj0)*(x6251)))+(((sj0)*(x6250)))+(((r12)*(x6245)))), ((((IkReal(-1.00000000000000))*(x6247)*(x6252)))+(((r02)*(x6245)))+(((IkReal(-1.00000000000000))*(x6246)*(x6251)))+(((r12)*(x6249)))+(((IkReal(-1.00000000000000))*(x6246)*(x6250)))+(((IkReal(-1.00000000000000))*(x6248)*(x6252)))));
19540 sj3array[0]=IKsin(j3array[0]);
19541 cj3array[0]=IKcos(j3array[0]);
19542 if( j3array[0] > IKPI )
19543 {
19544     j3array[0]-=IK2PI;
19545 }
19546 else if( j3array[0] < -IKPI )
19547 {    j3array[0]+=IK2PI;
19548 }
19549 j3valid[0] = true;
19550 for(int ij3 = 0; ij3 < 1; ++ij3)
19551 {
19552 if( !j3valid[ij3] )
19553 {
19554     continue;
19555 }
19556 _ij3[0] = ij3; _ij3[1] = -1;
19557 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19558 {
19559 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19560 {
19561     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19562 }
19563 }
19564 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19565 {
19566 IkReal evalcond[4];
19567 IkReal x6253=IKcos(j3);
19568 IkReal x6254=((sj0)*(sj5));
19569 IkReal x6255=((r00)*(sj6));
19570 IkReal x6256=((cj6)*(sj0));
19571 IkReal x6257=((IkReal(1.00000000000000))*(cj4));
19572 IkReal x6258=((r00)*(sj4));
19573 IkReal x6259=((cj0)*(cj5));
19574 IkReal x6260=((cj5)*(sj0));
19575 IkReal x6261=((cj6)*(r11));
19576 IkReal x6262=((r10)*(sj6));
19577 IkReal x6263=((cj0)*(sj5));
19578 IkReal x6264=((r10)*(sj4));
19579 IkReal x6265=((IkReal(1.00000000000000))*(IKsin(j3)));
19580 IkReal x6266=((cj4)*(cj5)*(r01));
19581 IkReal x6267=((IkReal(1.00000000000000))*(cj0)*(cj6));
19582 IkReal x6268=((cj0)*(sj4)*(sj6));
19583 IkReal x6269=((sj0)*(sj4)*(sj6));
19584 evalcond[0]=((((IkReal(-1.00000000000000))*(x6261)*(x6263)))+(((IkReal(-1.00000000000000))*(r02)*(x6260)))+(((cj6)*(r01)*(x6254)))+(((IkReal(-1.00000000000000))*(x6262)*(x6263)))+(((r12)*(x6259)))+(((IkReal(-1.00000000000000))*(x6265)))+(((x6254)*(x6255))));
19585 evalcond[1]=((((r12)*(x6260)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x6263)))+(((r02)*(x6259)))+(((IkReal(-1.00000000000000))*(x6253)))+(((IkReal(-1.00000000000000))*(x6254)*(x6262)))+(((IkReal(-1.00000000000000))*(x6255)*(x6263)))+(((IkReal(-1.00000000000000))*(x6254)*(x6261))));
19586 evalcond[2]=((((r11)*(x6268)))+(x6253)+(((IkReal(-1.00000000000000))*(r01)*(x6269)))+(((cj4)*(r02)*(x6254)))+(((IkReal(-1.00000000000000))*(r12)*(x6257)*(x6263)))+(((x6256)*(x6266)))+(((cj4)*(x6255)*(x6260)))+(((IkReal(-1.00000000000000))*(x6264)*(x6267)))+(((x6256)*(x6258)))+(((IkReal(-1.00000000000000))*(x6257)*(x6259)*(x6261)))+(((IkReal(-1.00000000000000))*(x6257)*(x6259)*(x6262))));
19587 evalcond[3]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x6257)*(x6259)))+(((IkReal(-1.00000000000000))*(x6257)*(x6260)*(x6262)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x6256)*(x6257)))+(((IkReal(-1.00000000000000))*(x6256)*(x6264)))+(((IkReal(-1.00000000000000))*(x6258)*(x6267)))+(((r01)*(x6268)))+(((IkReal(-1.00000000000000))*(x6265)))+(((IkReal(-1.00000000000000))*(r02)*(x6257)*(x6263)))+(((IkReal(-1.00000000000000))*(r12)*(x6254)*(x6257)))+(((r11)*(x6269)))+(((IkReal(-1.00000000000000))*(x6255)*(x6257)*(x6259))));
19588 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
19589 {
19590 continue;
19591 }
19592 }
19593 
19594 {
19595 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19596 vinfos[0].jointtype = 1;
19597 vinfos[0].foffset = j0;
19598 vinfos[0].indices[0] = _ij0[0];
19599 vinfos[0].indices[1] = _ij0[1];
19600 vinfos[0].maxsolutions = _nj0;
19601 vinfos[1].jointtype = 1;
19602 vinfos[1].foffset = j1;
19603 vinfos[1].indices[0] = _ij1[0];
19604 vinfos[1].indices[1] = _ij1[1];
19605 vinfos[1].maxsolutions = _nj1;
19606 vinfos[2].jointtype = 1;
19607 vinfos[2].foffset = j2;
19608 vinfos[2].indices[0] = _ij2[0];
19609 vinfos[2].indices[1] = _ij2[1];
19610 vinfos[2].maxsolutions = _nj2;
19611 vinfos[3].jointtype = 1;
19612 vinfos[3].foffset = j3;
19613 vinfos[3].indices[0] = _ij3[0];
19614 vinfos[3].indices[1] = _ij3[1];
19615 vinfos[3].maxsolutions = _nj3;
19616 vinfos[4].jointtype = 1;
19617 vinfos[4].foffset = j4;
19618 vinfos[4].indices[0] = _ij4[0];
19619 vinfos[4].indices[1] = _ij4[1];
19620 vinfos[4].maxsolutions = _nj4;
19621 vinfos[5].jointtype = 1;
19622 vinfos[5].foffset = j5;
19623 vinfos[5].indices[0] = _ij5[0];
19624 vinfos[5].indices[1] = _ij5[1];
19625 vinfos[5].maxsolutions = _nj5;
19626 vinfos[6].jointtype = 1;
19627 vinfos[6].foffset = j6;
19628 vinfos[6].indices[0] = _ij6[0];
19629 vinfos[6].indices[1] = _ij6[1];
19630 vinfos[6].maxsolutions = _nj6;
19631 std::vector<int> vfree(0);
19632 solutions.AddSolution(vinfos,vfree);
19633 }
19634 }
19635 }
19636 
19637 } else
19638 {
19639 IkReal x6270=((IkReal(1.00000000000000))*(cj0));
19640 IkReal x6271=((cj4)*(sj6));
19641 IkReal x6272=((sj0)*(sj4));
19642 IkReal x6273=((cj5)*(sj6));
19643 IkReal x6274=((sj4)*(sj5));
19644 IkReal x6275=((r12)*(sj5));
19645 IkReal x6276=((IkReal(0.374290000000000))*(cj5));
19646 IkReal x6277=((r02)*(sj0));
19647 IkReal x6278=((r20)*(sj4));
19648 IkReal x6279=((IkReal(1.00000000000000))*(sj0));
19649 IkReal x6280=((IkReal(1.00000000000000))*(cj5));
19650 IkReal x6281=((cj0)*(r10));
19651 IkReal x6282=((cj4)*(cj6));
19652 IkReal x6283=((r00)*(sj0));
19653 IkReal x6284=((cj6)*(r21));
19654 IkReal x6285=((IkReal(0.374290000000000))*(sj5));
19655 IkReal x6286=((cj0)*(r00));
19656 IkReal x6287=((IkReal(0.0100000000000000))*(sj5));
19657 IkReal x6288=((cj0)*(r02));
19658 IkReal x6289=((cj5)*(sj4));
19659 IkReal x6290=((cj6)*(r01));
19660 IkReal x6291=((cj6)*(r11));
19661 IkReal x6292=((r01)*(sj0));
19662 IkReal x6293=((r10)*(sj0));
19663 IkReal x6294=((IkReal(0.0100000000000000))*(cj5)*(cj6));
19664 IkReal x6295=((sj6)*(x6285));
19665 IkReal x6296=((cj0)*(cj6)*(x6285));
19666 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
19667 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x6280)))+(((sj5)*(x6284)))+(((r20)*(sj5)*(sj6))));
19668 evalcond[2]=((IkReal(1.00000000000000))+(((x6273)*(x6278)))+(((x6284)*(x6289)))+(((r21)*(x6271)))+(((r22)*(x6274)))+(((IkReal(-1.00000000000000))*(r20)*(x6282))));
19669 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x6273)))+(((r20)*(x6295)))+(((IkReal(-1.00000000000000))*(r22)*(x6276)))+(((x6284)*(x6285)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x6287)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6284))));
19670 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x6282)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x6271)))+(((cj6)*(x6278))));
19671 evalcond[5]=((((r00)*(x6272)*(x6273)))+(((IkReal(-1.00000000000000))*(r11)*(x6270)*(x6271)))+(((r02)*(sj5)*(x6272)))+(((IkReal(-1.00000000000000))*(r12)*(x6270)*(x6274)))+(((x6281)*(x6282)))+(((IkReal(-1.00000000000000))*(x6270)*(x6289)*(x6291)))+(((x6271)*(x6292)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6270)*(x6273)))+(((cj5)*(x6272)*(x6290)))+(((IkReal(-1.00000000000000))*(r00)*(x6279)*(x6282))));
19672 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x6271)*(x6279)))+(((IkReal(-1.00000000000000))*(x6272)*(x6275)))+(((x6282)*(x6293)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6270)*(x6273)))+(((x6282)*(x6286)))+(((IkReal(-1.00000000000000))*(x6270)*(x6289)*(x6290)))+(((IkReal(-1.00000000000000))*(r10)*(x6272)*(x6273)))+(((IkReal(-1.00000000000000))*(x6272)*(x6280)*(x6291)))+(((IkReal(-1.00000000000000))*(r02)*(x6270)*(x6274)))+(((IkReal(-1.00000000000000))*(r01)*(x6270)*(x6271))));
19673 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x6276)*(x6277)))+(((IkReal(0.0100000000000000))*(x6273)*(x6281)))+(((sj0)*(x6285)*(x6290)))+(((cj0)*(r12)*(x6276)))+(((IkReal(-1.00000000000000))*(py)*(x6270)))+(((x6283)*(x6295)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6291)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6290)))+(((IkReal(-1.00000000000000))*(cj0)*(x6285)*(x6291)))+(((IkReal(-1.00000000000000))*(x6281)*(x6295)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x6277)*(x6287)))+(((IkReal(-0.0100000000000000))*(x6273)*(x6283)))+(((IkReal(0.0100000000000000))*(cj0)*(x6275))));
19674 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(x6273)*(x6293)))+(((IkReal(0.0100000000000000))*(x6273)*(x6286)))+(((IkReal(-1.00000000000000))*(py)*(x6279)))+(((IkReal(-1.00000000000000))*(x6286)*(x6295)))+(((x6276)*(x6288)))+(((IkReal(-1.00000000000000))*(px)*(x6270)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6291)))+(((x6287)*(x6288)))+(((r12)*(sj0)*(x6276)))+(((IkReal(-1.00000000000000))*(sj0)*(x6285)*(x6291)))+(((IkReal(-1.00000000000000))*(x6293)*(x6295)))+(((IkReal(0.0100000000000000))*(sj0)*(x6275)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6290)))+(((IkReal(-1.00000000000000))*(cj0)*(x6285)*(x6290))));
19675 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
19676 {
19677 {
19678 IkReal j3array[1], cj3array[1], sj3array[1];
19679 bool j3valid[1]={false};
19680 _nj3 = 1;
19681 IkReal x6297=((cj5)*(r02));
19682 IkReal x6298=((cj0)*(sj5));
19683 IkReal x6299=((r10)*(sj6));
19684 IkReal x6300=((IkReal(1.00000000000000))*(cj6));
19685 IkReal x6301=((sj0)*(sj5));
19686 IkReal x6302=((cj5)*(r12));
19687 IkReal x6303=((IkReal(1.00000000000000))*(r00)*(sj6));
19688 if( IKabs(((((sj0)*(x6297)))+(((IkReal(-1.00000000000000))*(x6301)*(x6303)))+(((cj6)*(r11)*(x6298)))+(((x6298)*(x6299)))+(((IkReal(-1.00000000000000))*(r01)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(cj0)*(x6302))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x6299)*(x6301)))+(((cj0)*(x6297)))+(((IkReal(-1.00000000000000))*(r11)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(x6298)*(x6303)))+(((sj0)*(x6302)))+(((IkReal(-1.00000000000000))*(r01)*(x6298)*(x6300))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x6297)))+(((IkReal(-1.00000000000000))*(x6301)*(x6303)))+(((cj6)*(r11)*(x6298)))+(((x6298)*(x6299)))+(((IkReal(-1.00000000000000))*(r01)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(cj0)*(x6302)))))+IKsqr(((((IkReal(-1.00000000000000))*(x6299)*(x6301)))+(((cj0)*(x6297)))+(((IkReal(-1.00000000000000))*(r11)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(x6298)*(x6303)))+(((sj0)*(x6302)))+(((IkReal(-1.00000000000000))*(r01)*(x6298)*(x6300)))))-1) <= IKFAST_SINCOS_THRESH )
19689     continue;
19690 j3array[0]=IKatan2(((((sj0)*(x6297)))+(((IkReal(-1.00000000000000))*(x6301)*(x6303)))+(((cj6)*(r11)*(x6298)))+(((x6298)*(x6299)))+(((IkReal(-1.00000000000000))*(r01)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(cj0)*(x6302)))), ((((IkReal(-1.00000000000000))*(x6299)*(x6301)))+(((cj0)*(x6297)))+(((IkReal(-1.00000000000000))*(r11)*(x6300)*(x6301)))+(((IkReal(-1.00000000000000))*(x6298)*(x6303)))+(((sj0)*(x6302)))+(((IkReal(-1.00000000000000))*(r01)*(x6298)*(x6300)))));
19691 sj3array[0]=IKsin(j3array[0]);
19692 cj3array[0]=IKcos(j3array[0]);
19693 if( j3array[0] > IKPI )
19694 {
19695     j3array[0]-=IK2PI;
19696 }
19697 else if( j3array[0] < -IKPI )
19698 {    j3array[0]+=IK2PI;
19699 }
19700 j3valid[0] = true;
19701 for(int ij3 = 0; ij3 < 1; ++ij3)
19702 {
19703 if( !j3valid[ij3] )
19704 {
19705     continue;
19706 }
19707 _ij3[0] = ij3; _ij3[1] = -1;
19708 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19709 {
19710 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19711 {
19712     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19713 }
19714 }
19715 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19716 {
19717 IkReal evalcond[4];
19718 IkReal x6304=IKsin(j3);
19719 IkReal x6305=((sj0)*(sj5));
19720 IkReal x6306=((r00)*(sj6));
19721 IkReal x6307=((IkReal(1.00000000000000))*(cj4));
19722 IkReal x6308=((cj6)*(sj0));
19723 IkReal x6309=((r00)*(sj4));
19724 IkReal x6310=((cj0)*(cj5));
19725 IkReal x6311=((cj6)*(r01));
19726 IkReal x6312=((cj5)*(sj0));
19727 IkReal x6313=((cj0)*(sj5));
19728 IkReal x6314=((cj6)*(r11));
19729 IkReal x6315=((r10)*(sj6));
19730 IkReal x6316=((r10)*(sj4));
19731 IkReal x6317=((IkReal(1.00000000000000))*(IKcos(j3)));
19732 IkReal x6318=((cj0)*(sj4)*(sj6));
19733 IkReal x6319=((sj0)*(sj4)*(sj6));
19734 IkReal x6320=((IkReal(1.00000000000000))*(cj0)*(cj6));
19735 evalcond[0]=((((x6305)*(x6311)))+(x6304)+(((IkReal(-1.00000000000000))*(x6313)*(x6314)))+(((x6305)*(x6306)))+(((IkReal(-1.00000000000000))*(x6313)*(x6315)))+(((r12)*(x6310)))+(((IkReal(-1.00000000000000))*(r02)*(x6312))));
19736 evalcond[1]=((((IkReal(-1.00000000000000))*(x6311)*(x6313)))+(((IkReal(-1.00000000000000))*(x6317)))+(((IkReal(-1.00000000000000))*(x6305)*(x6315)))+(((IkReal(-1.00000000000000))*(x6306)*(x6313)))+(((IkReal(-1.00000000000000))*(x6305)*(x6314)))+(((r02)*(x6310)))+(((r12)*(x6312))));
19737 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x6319)))+(((cj4)*(cj5)*(r01)*(x6308)))+(((cj4)*(r02)*(x6305)))+(((IkReal(-1.00000000000000))*(x6317)))+(((IkReal(-1.00000000000000))*(x6307)*(x6310)*(x6315)))+(((IkReal(-1.00000000000000))*(x6316)*(x6320)))+(((IkReal(-1.00000000000000))*(x6307)*(x6310)*(x6314)))+(((IkReal(-1.00000000000000))*(r12)*(x6307)*(x6313)))+(((x6308)*(x6309)))+(((cj4)*(x6306)*(x6312)))+(((r11)*(x6318))));
19738 evalcond[3]=((((IkReal(-1.00000000000000))*(x6309)*(x6320)))+(((r11)*(x6319)))+(((IkReal(-1.00000000000000))*(x6307)*(x6310)*(x6311)))+(((IkReal(-1.00000000000000))*(x6304)))+(((IkReal(-1.00000000000000))*(x6307)*(x6312)*(x6315)))+(((IkReal(-1.00000000000000))*(r12)*(x6305)*(x6307)))+(((IkReal(-1.00000000000000))*(x6308)*(x6316)))+(((IkReal(-1.00000000000000))*(r02)*(x6307)*(x6313)))+(((r01)*(x6318)))+(((IkReal(-1.00000000000000))*(x6306)*(x6307)*(x6310)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x6307)*(x6308))));
19739 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
19740 {
19741 continue;
19742 }
19743 }
19744 
19745 {
19746 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19747 vinfos[0].jointtype = 1;
19748 vinfos[0].foffset = j0;
19749 vinfos[0].indices[0] = _ij0[0];
19750 vinfos[0].indices[1] = _ij0[1];
19751 vinfos[0].maxsolutions = _nj0;
19752 vinfos[1].jointtype = 1;
19753 vinfos[1].foffset = j1;
19754 vinfos[1].indices[0] = _ij1[0];
19755 vinfos[1].indices[1] = _ij1[1];
19756 vinfos[1].maxsolutions = _nj1;
19757 vinfos[2].jointtype = 1;
19758 vinfos[2].foffset = j2;
19759 vinfos[2].indices[0] = _ij2[0];
19760 vinfos[2].indices[1] = _ij2[1];
19761 vinfos[2].maxsolutions = _nj2;
19762 vinfos[3].jointtype = 1;
19763 vinfos[3].foffset = j3;
19764 vinfos[3].indices[0] = _ij3[0];
19765 vinfos[3].indices[1] = _ij3[1];
19766 vinfos[3].maxsolutions = _nj3;
19767 vinfos[4].jointtype = 1;
19768 vinfos[4].foffset = j4;
19769 vinfos[4].indices[0] = _ij4[0];
19770 vinfos[4].indices[1] = _ij4[1];
19771 vinfos[4].maxsolutions = _nj4;
19772 vinfos[5].jointtype = 1;
19773 vinfos[5].foffset = j5;
19774 vinfos[5].indices[0] = _ij5[0];
19775 vinfos[5].indices[1] = _ij5[1];
19776 vinfos[5].maxsolutions = _nj5;
19777 vinfos[6].jointtype = 1;
19778 vinfos[6].foffset = j6;
19779 vinfos[6].indices[0] = _ij6[0];
19780 vinfos[6].indices[1] = _ij6[1];
19781 vinfos[6].maxsolutions = _nj6;
19782 std::vector<int> vfree(0);
19783 solutions.AddSolution(vinfos,vfree);
19784 }
19785 }
19786 }
19787 
19788 } else
19789 {
19790 if( 1 )
19791 {
19792 continue;
19793 
19794 } else
19795 {
19796 }
19797 }
19798 }
19799 }
19800 }
19801 }
19802 
19803 } else
19804 {
19805 {
19806 IkReal j3array[1], cj3array[1], sj3array[1];
19807 bool j3valid[1]={false};
19808 _nj3 = 1;
19809 IkReal x6321=((cj0)*(cj5));
19810 IkReal x6322=((IkReal(1.00000000000000))*(cj0));
19811 IkReal x6323=((cj6)*(r11));
19812 IkReal x6324=((r10)*(sj6));
19813 IkReal x6325=((cj5)*(sj0));
19814 IkReal x6326=((r00)*(sj5)*(sj6));
19815 IkReal x6327=((cj6)*(r01)*(sj5));
19816 IkReal x6328=((IkReal(1.00000000000000))*(sj0)*(sj5));
19817 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6324)))+(((sj0)*(x6327)))+(((r12)*(x6321)))+(((sj0)*(x6326)))+(((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6323)))+(((IkReal(-1.00000000000000))*(r02)*(x6325))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x6323)*(x6328)))+(((IkReal(-1.00000000000000))*(x6324)*(x6328)))+(((r02)*(x6321)))+(((IkReal(-1.00000000000000))*(x6322)*(x6327)))+(((IkReal(-1.00000000000000))*(x6322)*(x6326)))+(((r12)*(x6325))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6324)))+(((sj0)*(x6327)))+(((r12)*(x6321)))+(((sj0)*(x6326)))+(((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6323)))+(((IkReal(-1.00000000000000))*(r02)*(x6325)))))))+IKsqr(((((IkReal(-1.00000000000000))*(x6323)*(x6328)))+(((IkReal(-1.00000000000000))*(x6324)*(x6328)))+(((r02)*(x6321)))+(((IkReal(-1.00000000000000))*(x6322)*(x6327)))+(((IkReal(-1.00000000000000))*(x6322)*(x6326)))+(((r12)*(x6325)))))-1) <= IKFAST_SINCOS_THRESH )
19818     continue;
19819 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6324)))+(((sj0)*(x6327)))+(((r12)*(x6321)))+(((sj0)*(x6326)))+(((IkReal(-1.00000000000000))*(sj5)*(x6322)*(x6323)))+(((IkReal(-1.00000000000000))*(r02)*(x6325)))))), ((((IkReal(-1.00000000000000))*(x6323)*(x6328)))+(((IkReal(-1.00000000000000))*(x6324)*(x6328)))+(((r02)*(x6321)))+(((IkReal(-1.00000000000000))*(x6322)*(x6327)))+(((IkReal(-1.00000000000000))*(x6322)*(x6326)))+(((r12)*(x6325)))));
19820 sj3array[0]=IKsin(j3array[0]);
19821 cj3array[0]=IKcos(j3array[0]);
19822 if( j3array[0] > IKPI )
19823 {
19824     j3array[0]-=IK2PI;
19825 }
19826 else if( j3array[0] < -IKPI )
19827 {    j3array[0]+=IK2PI;
19828 }
19829 j3valid[0] = true;
19830 for(int ij3 = 0; ij3 < 1; ++ij3)
19831 {
19832 if( !j3valid[ij3] )
19833 {
19834     continue;
19835 }
19836 _ij3[0] = ij3; _ij3[1] = -1;
19837 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19838 {
19839 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19840 {
19841     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19842 }
19843 }
19844 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19845 {
19846 IkReal evalcond[6];
19847 IkReal x6329=IKsin(j3);
19848 IkReal x6330=IKcos(j3);
19849 IkReal x6331=((sj0)*(sj5));
19850 IkReal x6332=((r00)*(sj6));
19851 IkReal x6333=((IkReal(1.00000000000000))*(cj4));
19852 IkReal x6334=((cj6)*(r01));
19853 IkReal x6335=((cj0)*(cj5));
19854 IkReal x6336=((cj5)*(sj0));
19855 IkReal x6337=((cj6)*(r11));
19856 IkReal x6338=((cj0)*(sj5));
19857 IkReal x6339=((cj6)*(sj4));
19858 IkReal x6340=((cj4)*(cj5));
19859 IkReal x6341=((cj6)*(r21));
19860 IkReal x6342=((r20)*(sj6));
19861 IkReal x6343=((r10)*(sj6));
19862 IkReal x6344=((IkReal(1.00000000000000))*(cj0));
19863 IkReal x6345=((IkReal(1.00000000000000))*(x6329));
19864 IkReal x6346=((cj0)*(sj4)*(sj6));
19865 IkReal x6347=((sj0)*(sj4)*(sj6));
19866 evalcond[0]=((((sj5)*(x6341)))+(((sj5)*(x6342)))+(((IkReal(-1.00000000000000))*(cj2)*(x6345)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
19867 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x6339)))+(((x6340)*(x6342)))+(((x6340)*(x6341)))+(((cj2)*(x6330)))+(((cj4)*(r22)*(sj5))));
19868 evalcond[2]=((((IkReal(-1.00000000000000))*(x6338)*(x6343)))+(((r12)*(x6335)))+(((IkReal(-1.00000000000000))*(sj2)*(x6345)))+(((x6331)*(x6332)))+(((IkReal(-1.00000000000000))*(r02)*(x6336)))+(((IkReal(-1.00000000000000))*(x6337)*(x6338)))+(((x6331)*(x6334))));
19869 evalcond[3]=((((r02)*(x6335)))+(((IkReal(-1.00000000000000))*(x6331)*(x6343)))+(((IkReal(-1.00000000000000))*(x6332)*(x6338)))+(((IkReal(-1.00000000000000))*(x6334)*(x6338)))+(((r12)*(x6336)))+(((IkReal(-1.00000000000000))*(x6330)))+(((IkReal(-1.00000000000000))*(x6331)*(x6337))));
19870 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x6339)*(x6344)))+(((cj4)*(x6334)*(x6336)))+(((cj4)*(r02)*(x6331)))+(((IkReal(-1.00000000000000))*(x6333)*(x6335)*(x6337)))+(((IkReal(-1.00000000000000))*(r01)*(x6347)))+(((r11)*(x6346)))+(((IkReal(-1.00000000000000))*(x6333)*(x6335)*(x6343)))+(((IkReal(-1.00000000000000))*(r12)*(x6333)*(x6338)))+(((cj4)*(x6332)*(x6336)))+(((r00)*(sj0)*(x6339)))+(((sj2)*(x6330))));
19871 evalcond[5]=((((IkReal(-1.00000000000000))*(x6333)*(x6336)*(x6337)))+(((IkReal(-1.00000000000000))*(x6332)*(x6333)*(x6335)))+(((IkReal(-1.00000000000000))*(r02)*(x6333)*(x6338)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6339)))+(((IkReal(-1.00000000000000))*(r12)*(x6331)*(x6333)))+(((IkReal(-1.00000000000000))*(x6333)*(x6336)*(x6343)))+(((IkReal(-1.00000000000000))*(x6333)*(x6334)*(x6335)))+(((r11)*(x6347)))+(((r01)*(x6346)))+(((IkReal(-1.00000000000000))*(r00)*(x6339)*(x6344)))+(((IkReal(-1.00000000000000))*(x6345))));
19872 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
19873 {
19874 continue;
19875 }
19876 }
19877 
19878 {
19879 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19880 vinfos[0].jointtype = 1;
19881 vinfos[0].foffset = j0;
19882 vinfos[0].indices[0] = _ij0[0];
19883 vinfos[0].indices[1] = _ij0[1];
19884 vinfos[0].maxsolutions = _nj0;
19885 vinfos[1].jointtype = 1;
19886 vinfos[1].foffset = j1;
19887 vinfos[1].indices[0] = _ij1[0];
19888 vinfos[1].indices[1] = _ij1[1];
19889 vinfos[1].maxsolutions = _nj1;
19890 vinfos[2].jointtype = 1;
19891 vinfos[2].foffset = j2;
19892 vinfos[2].indices[0] = _ij2[0];
19893 vinfos[2].indices[1] = _ij2[1];
19894 vinfos[2].maxsolutions = _nj2;
19895 vinfos[3].jointtype = 1;
19896 vinfos[3].foffset = j3;
19897 vinfos[3].indices[0] = _ij3[0];
19898 vinfos[3].indices[1] = _ij3[1];
19899 vinfos[3].maxsolutions = _nj3;
19900 vinfos[4].jointtype = 1;
19901 vinfos[4].foffset = j4;
19902 vinfos[4].indices[0] = _ij4[0];
19903 vinfos[4].indices[1] = _ij4[1];
19904 vinfos[4].maxsolutions = _nj4;
19905 vinfos[5].jointtype = 1;
19906 vinfos[5].foffset = j5;
19907 vinfos[5].indices[0] = _ij5[0];
19908 vinfos[5].indices[1] = _ij5[1];
19909 vinfos[5].maxsolutions = _nj5;
19910 vinfos[6].jointtype = 1;
19911 vinfos[6].foffset = j6;
19912 vinfos[6].indices[0] = _ij6[0];
19913 vinfos[6].indices[1] = _ij6[1];
19914 vinfos[6].maxsolutions = _nj6;
19915 std::vector<int> vfree(0);
19916 solutions.AddSolution(vinfos,vfree);
19917 }
19918 }
19919 }
19920 
19921 }
19922 
19923 }
19924 
19925 } else
19926 {
19927 {
19928 IkReal j3array[1], cj3array[1], sj3array[1];
19929 bool j3valid[1]={false};
19930 _nj3 = 1;
19931 IkReal x6348=((sj5)*(sj6));
19932 IkReal x6349=((IkReal(1.00000000000000))*(cj6)*(sj5));
19933 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x6348)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x6349)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6348)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6348)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x6349))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x6348)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x6349)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6348)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6348)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x6349)))))-1) <= IKFAST_SINCOS_THRESH )
19934     continue;
19935 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((r20)*(x6348)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x6349)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6348)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6348)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x6349)))));
19936 sj3array[0]=IKsin(j3array[0]);
19937 cj3array[0]=IKcos(j3array[0]);
19938 if( j3array[0] > IKPI )
19939 {
19940     j3array[0]-=IK2PI;
19941 }
19942 else if( j3array[0] < -IKPI )
19943 {    j3array[0]+=IK2PI;
19944 }
19945 j3valid[0] = true;
19946 for(int ij3 = 0; ij3 < 1; ++ij3)
19947 {
19948 if( !j3valid[ij3] )
19949 {
19950     continue;
19951 }
19952 _ij3[0] = ij3; _ij3[1] = -1;
19953 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
19954 {
19955 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
19956 {
19957     j3valid[iij3]=false; _ij3[1] = iij3; break; 
19958 }
19959 }
19960 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
19961 {
19962 IkReal evalcond[6];
19963 IkReal x6350=IKsin(j3);
19964 IkReal x6351=IKcos(j3);
19965 IkReal x6352=((sj0)*(sj5));
19966 IkReal x6353=((r00)*(sj6));
19967 IkReal x6354=((IkReal(1.00000000000000))*(cj4));
19968 IkReal x6355=((cj6)*(r01));
19969 IkReal x6356=((cj0)*(cj5));
19970 IkReal x6357=((cj5)*(sj0));
19971 IkReal x6358=((cj6)*(r11));
19972 IkReal x6359=((cj0)*(sj5));
19973 IkReal x6360=((cj6)*(sj4));
19974 IkReal x6361=((cj4)*(cj5));
19975 IkReal x6362=((cj6)*(r21));
19976 IkReal x6363=((r20)*(sj6));
19977 IkReal x6364=((r10)*(sj6));
19978 IkReal x6365=((IkReal(1.00000000000000))*(cj0));
19979 IkReal x6366=((IkReal(1.00000000000000))*(x6350));
19980 IkReal x6367=((cj0)*(sj4)*(sj6));
19981 IkReal x6368=((sj0)*(sj4)*(sj6));
19982 evalcond[0]=((((sj5)*(x6363)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6362)))+(((IkReal(-1.00000000000000))*(cj2)*(x6366))));
19983 evalcond[1]=((((x6361)*(x6363)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x6360)))+(((x6361)*(x6362)))+(((cj2)*(x6351)))+(((cj4)*(r22)*(sj5))));
19984 evalcond[2]=((((x6352)*(x6353)))+(((IkReal(-1.00000000000000))*(sj2)*(x6366)))+(((r12)*(x6356)))+(((x6352)*(x6355)))+(((IkReal(-1.00000000000000))*(x6358)*(x6359)))+(((IkReal(-1.00000000000000))*(r02)*(x6357)))+(((IkReal(-1.00000000000000))*(x6359)*(x6364))));
19985 evalcond[3]=((((IkReal(-1.00000000000000))*(x6353)*(x6359)))+(((IkReal(-1.00000000000000))*(x6351)))+(((IkReal(-1.00000000000000))*(x6352)*(x6364)))+(((IkReal(-1.00000000000000))*(x6352)*(x6358)))+(((r02)*(x6356)))+(((r12)*(x6357)))+(((IkReal(-1.00000000000000))*(x6355)*(x6359))));
19986 evalcond[4]=((((cj4)*(r02)*(x6352)))+(((r11)*(x6367)))+(((sj2)*(x6351)))+(((cj4)*(x6353)*(x6357)))+(((IkReal(-1.00000000000000))*(r10)*(x6360)*(x6365)))+(((IkReal(-1.00000000000000))*(x6354)*(x6356)*(x6358)))+(((IkReal(-1.00000000000000))*(x6354)*(x6356)*(x6364)))+(((cj4)*(x6355)*(x6357)))+(((IkReal(-1.00000000000000))*(r12)*(x6354)*(x6359)))+(((IkReal(-1.00000000000000))*(r01)*(x6368)))+(((r00)*(sj0)*(x6360))));
19987 evalcond[5]=((((IkReal(-1.00000000000000))*(x6354)*(x6357)*(x6364)))+(((IkReal(-1.00000000000000))*(r12)*(x6352)*(x6354)))+(((r01)*(x6367)))+(((r11)*(x6368)))+(((IkReal(-1.00000000000000))*(x6366)))+(((IkReal(-1.00000000000000))*(x6354)*(x6355)*(x6356)))+(((IkReal(-1.00000000000000))*(r00)*(x6360)*(x6365)))+(((IkReal(-1.00000000000000))*(r02)*(x6354)*(x6359)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6360)))+(((IkReal(-1.00000000000000))*(x6354)*(x6357)*(x6358)))+(((IkReal(-1.00000000000000))*(x6353)*(x6354)*(x6356))));
19988 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
19989 {
19990 continue;
19991 }
19992 }
19993 
19994 {
19995 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
19996 vinfos[0].jointtype = 1;
19997 vinfos[0].foffset = j0;
19998 vinfos[0].indices[0] = _ij0[0];
19999 vinfos[0].indices[1] = _ij0[1];
20000 vinfos[0].maxsolutions = _nj0;
20001 vinfos[1].jointtype = 1;
20002 vinfos[1].foffset = j1;
20003 vinfos[1].indices[0] = _ij1[0];
20004 vinfos[1].indices[1] = _ij1[1];
20005 vinfos[1].maxsolutions = _nj1;
20006 vinfos[2].jointtype = 1;
20007 vinfos[2].foffset = j2;
20008 vinfos[2].indices[0] = _ij2[0];
20009 vinfos[2].indices[1] = _ij2[1];
20010 vinfos[2].maxsolutions = _nj2;
20011 vinfos[3].jointtype = 1;
20012 vinfos[3].foffset = j3;
20013 vinfos[3].indices[0] = _ij3[0];
20014 vinfos[3].indices[1] = _ij3[1];
20015 vinfos[3].maxsolutions = _nj3;
20016 vinfos[4].jointtype = 1;
20017 vinfos[4].foffset = j4;
20018 vinfos[4].indices[0] = _ij4[0];
20019 vinfos[4].indices[1] = _ij4[1];
20020 vinfos[4].maxsolutions = _nj4;
20021 vinfos[5].jointtype = 1;
20022 vinfos[5].foffset = j5;
20023 vinfos[5].indices[0] = _ij5[0];
20024 vinfos[5].indices[1] = _ij5[1];
20025 vinfos[5].maxsolutions = _nj5;
20026 vinfos[6].jointtype = 1;
20027 vinfos[6].foffset = j6;
20028 vinfos[6].indices[0] = _ij6[0];
20029 vinfos[6].indices[1] = _ij6[1];
20030 vinfos[6].maxsolutions = _nj6;
20031 std::vector<int> vfree(0);
20032 solutions.AddSolution(vinfos,vfree);
20033 }
20034 }
20035 }
20036 
20037 }
20038 
20039 }
20040 
20041 } else
20042 {
20043 {
20044 IkReal j3array[1], cj3array[1], sj3array[1];
20045 bool j3valid[1]={false};
20046 _nj3 = 1;
20047 IkReal x6369=((IkReal(1.00000000000000))*(cj4));
20048 IkReal x6370=((cj6)*(r21));
20049 IkReal x6371=((r20)*(sj6));
20050 if( IKabs(((gconst9)*(((((sj5)*(x6371)))+(((sj5)*(x6370)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x6369)*(x6370)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6369)))+(((IkReal(-1.00000000000000))*(cj5)*(x6369)*(x6371)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
20051     continue;
20052 j3array[0]=IKatan2(((gconst9)*(((((sj5)*(x6371)))+(((sj5)*(x6370)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x6369)*(x6370)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6369)))+(((IkReal(-1.00000000000000))*(cj5)*(x6369)*(x6371)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
20053 sj3array[0]=IKsin(j3array[0]);
20054 cj3array[0]=IKcos(j3array[0]);
20055 if( j3array[0] > IKPI )
20056 {
20057     j3array[0]-=IK2PI;
20058 }
20059 else if( j3array[0] < -IKPI )
20060 {    j3array[0]+=IK2PI;
20061 }
20062 j3valid[0] = true;
20063 for(int ij3 = 0; ij3 < 1; ++ij3)
20064 {
20065 if( !j3valid[ij3] )
20066 {
20067     continue;
20068 }
20069 _ij3[0] = ij3; _ij3[1] = -1;
20070 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20071 {
20072 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20073 {
20074     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20075 }
20076 }
20077 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20078 {
20079 IkReal evalcond[6];
20080 IkReal x6372=IKsin(j3);
20081 IkReal x6373=IKcos(j3);
20082 IkReal x6374=((sj0)*(sj5));
20083 IkReal x6375=((r00)*(sj6));
20084 IkReal x6376=((IkReal(1.00000000000000))*(cj4));
20085 IkReal x6377=((cj6)*(r01));
20086 IkReal x6378=((cj0)*(cj5));
20087 IkReal x6379=((cj5)*(sj0));
20088 IkReal x6380=((cj6)*(r11));
20089 IkReal x6381=((cj0)*(sj5));
20090 IkReal x6382=((cj6)*(sj4));
20091 IkReal x6383=((cj4)*(cj5));
20092 IkReal x6384=((cj6)*(r21));
20093 IkReal x6385=((r20)*(sj6));
20094 IkReal x6386=((r10)*(sj6));
20095 IkReal x6387=((IkReal(1.00000000000000))*(cj0));
20096 IkReal x6388=((IkReal(1.00000000000000))*(x6372));
20097 IkReal x6389=((cj0)*(sj4)*(sj6));
20098 IkReal x6390=((sj0)*(sj4)*(sj6));
20099 evalcond[0]=((((sj5)*(x6384)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6385)))+(((IkReal(-1.00000000000000))*(cj2)*(x6388))));
20100 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x6373)))+(((r20)*(x6382)))+(((cj4)*(r22)*(sj5)))+(((x6383)*(x6384)))+(((x6383)*(x6385))));
20101 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x6388)))+(((x6374)*(x6377)))+(((IkReal(-1.00000000000000))*(x6380)*(x6381)))+(((x6374)*(x6375)))+(((IkReal(-1.00000000000000))*(x6381)*(x6386)))+(((IkReal(-1.00000000000000))*(r02)*(x6379)))+(((r12)*(x6378))));
20102 evalcond[3]=((((IkReal(-1.00000000000000))*(x6377)*(x6381)))+(((IkReal(-1.00000000000000))*(x6373)))+(((IkReal(-1.00000000000000))*(x6374)*(x6380)))+(((IkReal(-1.00000000000000))*(x6375)*(x6381)))+(((r12)*(x6379)))+(((IkReal(-1.00000000000000))*(x6374)*(x6386)))+(((r02)*(x6378))));
20103 evalcond[4]=((((sj2)*(x6373)))+(((IkReal(-1.00000000000000))*(r12)*(x6376)*(x6381)))+(((IkReal(-1.00000000000000))*(r10)*(x6382)*(x6387)))+(((r11)*(x6389)))+(((r00)*(sj0)*(x6382)))+(((IkReal(-1.00000000000000))*(r01)*(x6390)))+(((cj4)*(x6375)*(x6379)))+(((cj4)*(r02)*(x6374)))+(((IkReal(-1.00000000000000))*(x6376)*(x6378)*(x6386)))+(((cj4)*(x6377)*(x6379)))+(((IkReal(-1.00000000000000))*(x6376)*(x6378)*(x6380))));
20104 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x6376)*(x6381)))+(((IkReal(-1.00000000000000))*(r00)*(x6382)*(x6387)))+(((r11)*(x6390)))+(((IkReal(-1.00000000000000))*(x6376)*(x6377)*(x6378)))+(((r01)*(x6389)))+(((IkReal(-1.00000000000000))*(x6376)*(x6379)*(x6380)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6382)))+(((IkReal(-1.00000000000000))*(x6375)*(x6376)*(x6378)))+(((IkReal(-1.00000000000000))*(r12)*(x6374)*(x6376)))+(((IkReal(-1.00000000000000))*(x6388)))+(((IkReal(-1.00000000000000))*(x6376)*(x6379)*(x6386))));
20105 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
20106 {
20107 continue;
20108 }
20109 }
20110 
20111 {
20112 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20113 vinfos[0].jointtype = 1;
20114 vinfos[0].foffset = j0;
20115 vinfos[0].indices[0] = _ij0[0];
20116 vinfos[0].indices[1] = _ij0[1];
20117 vinfos[0].maxsolutions = _nj0;
20118 vinfos[1].jointtype = 1;
20119 vinfos[1].foffset = j1;
20120 vinfos[1].indices[0] = _ij1[0];
20121 vinfos[1].indices[1] = _ij1[1];
20122 vinfos[1].maxsolutions = _nj1;
20123 vinfos[2].jointtype = 1;
20124 vinfos[2].foffset = j2;
20125 vinfos[2].indices[0] = _ij2[0];
20126 vinfos[2].indices[1] = _ij2[1];
20127 vinfos[2].maxsolutions = _nj2;
20128 vinfos[3].jointtype = 1;
20129 vinfos[3].foffset = j3;
20130 vinfos[3].indices[0] = _ij3[0];
20131 vinfos[3].indices[1] = _ij3[1];
20132 vinfos[3].maxsolutions = _nj3;
20133 vinfos[4].jointtype = 1;
20134 vinfos[4].foffset = j4;
20135 vinfos[4].indices[0] = _ij4[0];
20136 vinfos[4].indices[1] = _ij4[1];
20137 vinfos[4].maxsolutions = _nj4;
20138 vinfos[5].jointtype = 1;
20139 vinfos[5].foffset = j5;
20140 vinfos[5].indices[0] = _ij5[0];
20141 vinfos[5].indices[1] = _ij5[1];
20142 vinfos[5].maxsolutions = _nj5;
20143 vinfos[6].jointtype = 1;
20144 vinfos[6].foffset = j6;
20145 vinfos[6].indices[0] = _ij6[0];
20146 vinfos[6].indices[1] = _ij6[1];
20147 vinfos[6].maxsolutions = _nj6;
20148 std::vector<int> vfree(0);
20149 solutions.AddSolution(vinfos,vfree);
20150 }
20151 }
20152 }
20153 
20154 }
20155 
20156 }
20157 
20158 } else
20159 {
20160 IkReal x6391=((IkReal(1.00000000000000))*(cj0));
20161 IkReal x6392=((cj4)*(sj6));
20162 IkReal x6393=((sj0)*(sj4));
20163 IkReal x6394=((cj5)*(sj6));
20164 IkReal x6395=((sj4)*(sj5));
20165 IkReal x6396=((r12)*(sj5));
20166 IkReal x6397=((IkReal(0.374290000000000))*(cj5));
20167 IkReal x6398=((r02)*(sj0));
20168 IkReal x6399=((IkReal(1.00000000000000))*(sj0));
20169 IkReal x6400=((cj0)*(r10));
20170 IkReal x6401=((cj4)*(cj6));
20171 IkReal x6402=((r00)*(sj0));
20172 IkReal x6403=((cj6)*(r21));
20173 IkReal x6404=((IkReal(0.374290000000000))*(sj5));
20174 IkReal x6405=((cj0)*(r00));
20175 IkReal x6406=((IkReal(0.0100000000000000))*(sj5));
20176 IkReal x6407=((cj0)*(r02));
20177 IkReal x6408=((cj5)*(sj4));
20178 IkReal x6409=((cj6)*(r01));
20179 IkReal x6410=((cj6)*(r11));
20180 IkReal x6411=((r01)*(sj0));
20181 IkReal x6412=((r10)*(sj0));
20182 IkReal x6413=((IkReal(0.0100000000000000))*(cj5)*(cj6));
20183 IkReal x6414=((sj6)*(x6404));
20184 IkReal x6415=((cj0)*(cj6)*(x6404));
20185 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
20186 evalcond[1]=((((r20)*(sj4)*(x6394)))+(((x6403)*(x6408)))+(sj2)+(((r22)*(x6395)))+(((r21)*(x6392)))+(((IkReal(-1.00000000000000))*(r20)*(x6401))));
20187 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x6397)))+(((r20)*(x6414)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6403)))+(((IkReal(-0.0690000000000000))*(cj2)))+(pz)+(((x6403)*(x6404)))+(((IkReal(-1.00000000000000))*(r22)*(x6406)))+(((IkReal(-0.0100000000000000))*(r20)*(x6394))));
20188 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x6391)*(x6395)))+(((x6392)*(x6411)))+(((IkReal(-1.00000000000000))*(r11)*(x6391)*(x6392)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6391)*(x6394)))+(((r00)*(x6393)*(x6394)))+(((x6400)*(x6401)))+(cj2)+(((cj5)*(x6393)*(x6409)))+(((r02)*(sj5)*(x6393)))+(((IkReal(-1.00000000000000))*(r00)*(x6399)*(x6401)))+(((IkReal(-1.00000000000000))*(x6391)*(x6408)*(x6410))));
20189 evalcond[4]=((((IkReal(-1.00000000000000))*(cj5)*(x6393)*(x6410)))+(((IkReal(-1.00000000000000))*(r02)*(x6391)*(x6395)))+(((IkReal(-1.00000000000000))*(x6393)*(x6396)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6391)*(x6394)))+(((IkReal(-1.00000000000000))*(x6391)*(x6408)*(x6409)))+(((x6401)*(x6405)))+(((IkReal(-1.00000000000000))*(r11)*(x6392)*(x6399)))+(((IkReal(-1.00000000000000))*(r01)*(x6391)*(x6392)))+(((IkReal(-1.00000000000000))*(r10)*(x6393)*(x6394)))+(((x6401)*(x6412))));
20190 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(x6404)*(x6410)))+(((IkReal(-0.0100000000000000))*(x6394)*(x6402)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(0.0100000000000000))*(cj0)*(x6396)))+(((IkReal(-1.00000000000000))*(x6397)*(x6398)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6409)))+(((IkReal(0.0100000000000000))*(x6394)*(x6400)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6410)))+(((x6402)*(x6414)))+(((cj0)*(r12)*(x6397)))+(((IkReal(-1.00000000000000))*(x6400)*(x6414)))+(((sj0)*(x6404)*(x6409)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x6398)*(x6406)))+(((IkReal(-1.00000000000000))*(py)*(x6391))));
20191 evalcond[6]=((IkReal(-0.295420000000000))+(((x6406)*(x6407)))+(((IkReal(-1.00000000000000))*(px)*(x6391)))+(((IkReal(-1.00000000000000))*(x6405)*(x6414)))+(((IkReal(0.0100000000000000))*(x6394)*(x6405)))+(((IkReal(-1.00000000000000))*(x6412)*(x6414)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6410)))+(((IkReal(0.0100000000000000))*(x6394)*(x6412)))+(((r12)*(sj0)*(x6397)))+(((IkReal(-1.00000000000000))*(sj0)*(x6404)*(x6410)))+(((IkReal(-1.00000000000000))*(py)*(x6399)))+(((x6397)*(x6407)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6409)))+(((IkReal(0.0100000000000000))*(sj0)*(x6396)))+(((IkReal(-1.00000000000000))*(cj0)*(x6404)*(x6409))));
20192 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
20193 {
20194 {
20195 IkReal dummyeval[1];
20196 IkReal gconst10;
20197 gconst10=IKsign(cj2);
20198 dummyeval[0]=cj2;
20199 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
20200 {
20201 {
20202 IkReal dummyeval[1];
20203 dummyeval[0]=cj2;
20204 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
20205 {
20206 {
20207 IkReal dummyeval[1];
20208 dummyeval[0]=sj2;
20209 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
20210 {
20211 {
20212 IkReal evalcond[9];
20213 IkReal x6416=((cj5)*(sj4));
20214 IkReal x6417=((IkReal(1.00000000000000))*(sj6));
20215 IkReal x6418=((r10)*(sj0));
20216 IkReal x6419=((sj4)*(sj5));
20217 IkReal x6420=((cj5)*(cj6));
20218 IkReal x6421=((r01)*(sj0));
20219 IkReal x6422=((IkReal(1.00000000000000))*(r02));
20220 IkReal x6423=((IkReal(0.374290000000000))*(cj0));
20221 IkReal x6424=((cj5)*(r12));
20222 IkReal x6425=((cj6)*(sj5));
20223 IkReal x6426=((cj0)*(r11));
20224 IkReal x6427=((cj5)*(sj0));
20225 IkReal x6428=((r20)*(sj6));
20226 IkReal x6429=((IkReal(1.00000000000000))*(sj0));
20227 IkReal x6430=((cj4)*(cj5));
20228 IkReal x6431=((IkReal(1.00000000000000))*(cj6));
20229 IkReal x6432=((IkReal(0.0100000000000000))*(sj5));
20230 IkReal x6433=((sj5)*(sj6));
20231 IkReal x6434=((cj0)*(r10));
20232 IkReal x6435=((cj4)*(cj6));
20233 IkReal x6436=((cj0)*(r01));
20234 IkReal x6437=((IkReal(1.00000000000000))*(cj4));
20235 IkReal x6438=((cj0)*(r00));
20236 IkReal x6439=((IkReal(0.374290000000000))*(sj0));
20237 IkReal x6440=((cj0)*(r12));
20238 IkReal x6441=((IkReal(0.374290000000000))*(sj5));
20239 IkReal x6442=((cj4)*(sj6));
20240 IkReal x6443=((IkReal(1.00000000000000))*(cj0));
20241 IkReal x6444=((r02)*(sj0));
20242 IkReal x6445=((IkReal(0.0100000000000000))*(cj5));
20243 IkReal x6446=((r11)*(sj0));
20244 IkReal x6447=((r00)*(sj0)*(sj6));
20245 IkReal x6448=((r00)*(x6435));
20246 IkReal x6449=((sj6)*(x6445));
20247 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
20248 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(r20)*(x6431)))+(((r22)*(x6419)))+(((cj6)*(r21)*(x6416)))+(((x6416)*(x6428)))+(((r21)*(x6442))));
20249 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x6425)))+(((x6428)*(x6441)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x6432)))+(((IkReal(-1.00000000000000))*(x6428)*(x6445)))+(((IkReal(-0.0100000000000000))*(r21)*(x6420))));
20250 evalcond[3]=((((r00)*(sj0)*(x6433)))+(((IkReal(-1.00000000000000))*(sj5)*(x6417)*(x6434)))+(((IkReal(-1.00000000000000))*(x6422)*(x6427)))+(((x6421)*(x6425)))+(((cj0)*(x6424)))+(((IkReal(-1.00000000000000))*(x6425)*(x6426))));
20251 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x6416)*(x6426)*(x6431)))+(((x6416)*(x6447)))+(((cj6)*(x6416)*(x6421)))+(((IkReal(-1.00000000000000))*(x6419)*(x6440)))+(((x6434)*(x6435)))+(((IkReal(-1.00000000000000))*(cj4)*(x6417)*(x6426)))+(((IkReal(-1.00000000000000))*(x6416)*(x6417)*(x6434)))+(((x6419)*(x6444)))+(((x6421)*(x6442)))+(((IkReal(-1.00000000000000))*(x6429)*(x6448))));
20252 evalcond[5]=((((cj4)*(x6420)*(x6421)))+(((IkReal(-1.00000000000000))*(x6417)*(x6430)*(x6434)))+(((r00)*(x6427)*(x6442)))+(((sj4)*(sj6)*(x6426)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(sj5)*(x6444)))+(((IkReal(-1.00000000000000))*(sj4)*(x6417)*(x6421)))+(((IkReal(-1.00000000000000))*(sj4)*(x6431)*(x6434)))+(((IkReal(-1.00000000000000))*(x6420)*(x6426)*(x6437)))+(((IkReal(-1.00000000000000))*(sj5)*(x6437)*(x6440))));
20253 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x6417)*(x6436)))+(((IkReal(-1.00000000000000))*(r12)*(x6419)*(x6429)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x6416)*(x6429)))+(((IkReal(-1.00000000000000))*(cj0)*(x6419)*(x6422)))+(((x6435)*(x6438)))+(((x6418)*(x6435)))+(((IkReal(-1.00000000000000))*(x6416)*(x6431)*(x6436)))+(((IkReal(-1.00000000000000))*(cj4)*(x6417)*(x6446)))+(((IkReal(-1.00000000000000))*(x6416)*(x6417)*(x6438)))+(((IkReal(-1.00000000000000))*(x6416)*(x6417)*(x6418))));
20254 evalcond[7]=((((IkReal(-0.0100000000000000))*(x6420)*(x6421)))+(((IkReal(-1.00000000000000))*(py)*(x6443)))+(((IkReal(-1.00000000000000))*(r11)*(x6423)*(x6425)))+(((IkReal(0.374290000000000))*(x6421)*(x6425)))+(((x6434)*(x6449)))+(((x6432)*(x6440)))+(((x6423)*(x6424)))+(((IkReal(-1.00000000000000))*(r10)*(x6423)*(x6433)))+(((IkReal(-0.374290000000000))*(r02)*(x6427)))+(((IkReal(-1.00000000000000))*(x6432)*(x6444)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x6427)))+(((IkReal(0.0100000000000000))*(x6420)*(x6426)))+(((px)*(sj0)))+(((r00)*(x6433)*(x6439))));
20255 evalcond[8]=((IkReal(-0.295420000000000))+(((cj0)*(r02)*(x6432)))+(((IkReal(0.0100000000000000))*(x6420)*(x6436)))+(((x6424)*(x6439)))+(((r12)*(sj0)*(x6432)))+(((IkReal(-1.00000000000000))*(r00)*(x6423)*(x6433)))+(((IkReal(-1.00000000000000))*(r11)*(x6425)*(x6439)))+(((IkReal(-0.374290000000000))*(x6418)*(x6433)))+(((IkReal(-1.00000000000000))*(py)*(x6429)))+(((IkReal(-1.00000000000000))*(r01)*(x6423)*(x6425)))+(((IkReal(-1.00000000000000))*(px)*(x6443)))+(((x6438)*(x6449)))+(((x6418)*(x6449)))+(((IkReal(0.0100000000000000))*(x6420)*(x6446)))+(((cj5)*(r02)*(x6423))));
20256 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
20257 {
20258 {
20259 IkReal j3array[1], cj3array[1], sj3array[1];
20260 bool j3valid[1]={false};
20261 _nj3 = 1;
20262 IkReal x6450=((IkReal(1.00000000000000))*(r21));
20263 IkReal x6451=((cj4)*(cj5));
20264 IkReal x6452=((r20)*(sj6));
20265 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x6452)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6450)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6450)))+(((x6451)*(x6452)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x6451))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x6452)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6450)))+(((cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6450)))+(((x6451)*(x6452)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x6451)))))-1) <= IKFAST_SINCOS_THRESH )
20266     continue;
20267 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x6452)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6450)))+(((cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6450)))+(((x6451)*(x6452)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x6451)))));
20268 sj3array[0]=IKsin(j3array[0]);
20269 cj3array[0]=IKcos(j3array[0]);
20270 if( j3array[0] > IKPI )
20271 {
20272     j3array[0]-=IK2PI;
20273 }
20274 else if( j3array[0] < -IKPI )
20275 {    j3array[0]+=IK2PI;
20276 }
20277 j3valid[0] = true;
20278 for(int ij3 = 0; ij3 < 1; ++ij3)
20279 {
20280 if( !j3valid[ij3] )
20281 {
20282     continue;
20283 }
20284 _ij3[0] = ij3; _ij3[1] = -1;
20285 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20286 {
20287 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20288 {
20289     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20290 }
20291 }
20292 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20293 {
20294 IkReal evalcond[4];
20295 IkReal x6453=IKcos(j3);
20296 IkReal x6454=IKsin(j3);
20297 IkReal x6455=((IkReal(1.00000000000000))*(cj4));
20298 IkReal x6456=((sj0)*(sj5));
20299 IkReal x6457=((cj0)*(cj5));
20300 IkReal x6458=((cj6)*(r01));
20301 IkReal x6459=((r00)*(sj6));
20302 IkReal x6460=((cj6)*(r11));
20303 IkReal x6461=((cj5)*(sj0));
20304 IkReal x6462=((cj6)*(sj4));
20305 IkReal x6463=((sj4)*(sj6));
20306 IkReal x6464=((cj4)*(cj5));
20307 IkReal x6465=((cj6)*(r21));
20308 IkReal x6466=((r20)*(sj6));
20309 IkReal x6467=((r10)*(sj6));
20310 IkReal x6468=((IkReal(1.00000000000000))*(cj0)*(sj5));
20311 evalcond[0]=((((sj5)*(x6465)))+(((sj5)*(x6466)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x6454));
20312 evalcond[1]=((((x6464)*(x6466)))+(((IkReal(-1.00000000000000))*(x6453)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x6462)))+(((x6464)*(x6465)))+(((IkReal(-1.00000000000000))*(r21)*(x6463))));
20313 evalcond[2]=((((IkReal(-1.00000000000000))*(x6456)*(x6460)))+(((IkReal(-1.00000000000000))*(x6458)*(x6468)))+(((IkReal(-1.00000000000000))*(x6459)*(x6468)))+(((r12)*(x6461)))+(((r02)*(x6457)))+(((IkReal(-1.00000000000000))*(x6456)*(x6467)))+(x6453));
20314 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6455)))+(((IkReal(-1.00000000000000))*(x6455)*(x6460)*(x6461)))+(((IkReal(-1.00000000000000))*(x6455)*(x6461)*(x6467)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6462)))+(((IkReal(-1.00000000000000))*(x6455)*(x6457)*(x6458)))+(((r11)*(sj0)*(x6463)))+(((IkReal(-1.00000000000000))*(x6455)*(x6457)*(x6459)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6462)))+(((cj0)*(r01)*(x6463)))+(x6454)+(((IkReal(-1.00000000000000))*(r12)*(x6455)*(x6456))));
20315 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
20316 {
20317 continue;
20318 }
20319 }
20320 
20321 {
20322 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20323 vinfos[0].jointtype = 1;
20324 vinfos[0].foffset = j0;
20325 vinfos[0].indices[0] = _ij0[0];
20326 vinfos[0].indices[1] = _ij0[1];
20327 vinfos[0].maxsolutions = _nj0;
20328 vinfos[1].jointtype = 1;
20329 vinfos[1].foffset = j1;
20330 vinfos[1].indices[0] = _ij1[0];
20331 vinfos[1].indices[1] = _ij1[1];
20332 vinfos[1].maxsolutions = _nj1;
20333 vinfos[2].jointtype = 1;
20334 vinfos[2].foffset = j2;
20335 vinfos[2].indices[0] = _ij2[0];
20336 vinfos[2].indices[1] = _ij2[1];
20337 vinfos[2].maxsolutions = _nj2;
20338 vinfos[3].jointtype = 1;
20339 vinfos[3].foffset = j3;
20340 vinfos[3].indices[0] = _ij3[0];
20341 vinfos[3].indices[1] = _ij3[1];
20342 vinfos[3].maxsolutions = _nj3;
20343 vinfos[4].jointtype = 1;
20344 vinfos[4].foffset = j4;
20345 vinfos[4].indices[0] = _ij4[0];
20346 vinfos[4].indices[1] = _ij4[1];
20347 vinfos[4].maxsolutions = _nj4;
20348 vinfos[5].jointtype = 1;
20349 vinfos[5].foffset = j5;
20350 vinfos[5].indices[0] = _ij5[0];
20351 vinfos[5].indices[1] = _ij5[1];
20352 vinfos[5].maxsolutions = _nj5;
20353 vinfos[6].jointtype = 1;
20354 vinfos[6].foffset = j6;
20355 vinfos[6].indices[0] = _ij6[0];
20356 vinfos[6].indices[1] = _ij6[1];
20357 vinfos[6].maxsolutions = _nj6;
20358 std::vector<int> vfree(0);
20359 solutions.AddSolution(vinfos,vfree);
20360 }
20361 }
20362 }
20363 
20364 } else
20365 {
20366 IkReal x6469=((cj5)*(sj4));
20367 IkReal x6470=((IkReal(1.00000000000000))*(sj6));
20368 IkReal x6471=((r10)*(sj0));
20369 IkReal x6472=((sj4)*(sj5));
20370 IkReal x6473=((cj5)*(cj6));
20371 IkReal x6474=((r01)*(sj0));
20372 IkReal x6475=((IkReal(1.00000000000000))*(r02));
20373 IkReal x6476=((IkReal(0.374290000000000))*(cj0));
20374 IkReal x6477=((cj5)*(r12));
20375 IkReal x6478=((cj6)*(sj5));
20376 IkReal x6479=((cj0)*(r11));
20377 IkReal x6480=((cj5)*(sj0));
20378 IkReal x6481=((r20)*(sj6));
20379 IkReal x6482=((IkReal(1.00000000000000))*(sj0));
20380 IkReal x6483=((cj4)*(cj5));
20381 IkReal x6484=((IkReal(1.00000000000000))*(cj6));
20382 IkReal x6485=((IkReal(0.0100000000000000))*(sj5));
20383 IkReal x6486=((sj5)*(sj6));
20384 IkReal x6487=((cj0)*(r10));
20385 IkReal x6488=((cj4)*(cj6));
20386 IkReal x6489=((cj0)*(r01));
20387 IkReal x6490=((IkReal(1.00000000000000))*(cj4));
20388 IkReal x6491=((cj0)*(r00));
20389 IkReal x6492=((IkReal(0.374290000000000))*(sj0));
20390 IkReal x6493=((cj0)*(r12));
20391 IkReal x6494=((IkReal(0.374290000000000))*(sj5));
20392 IkReal x6495=((cj4)*(sj6));
20393 IkReal x6496=((IkReal(1.00000000000000))*(cj0));
20394 IkReal x6497=((r02)*(sj0));
20395 IkReal x6498=((IkReal(0.0100000000000000))*(cj5));
20396 IkReal x6499=((r11)*(sj0));
20397 IkReal x6500=((r00)*(sj0)*(sj6));
20398 IkReal x6501=((r00)*(x6488));
20399 IkReal x6502=((sj6)*(x6498));
20400 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
20401 evalcond[1]=((((r22)*(x6472)))+(((x6469)*(x6481)))+(((cj6)*(r21)*(x6469)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x6484)))+(((r21)*(x6495))));
20402 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x6473)))+(((IkReal(-1.00000000000000))*(r22)*(x6485)))+(((x6481)*(x6494)))+(pz)+(((IkReal(0.374290000000000))*(r21)*(x6478)))+(((IkReal(-1.00000000000000))*(x6481)*(x6498))));
20403 evalcond[3]=((((r00)*(sj0)*(x6486)))+(((IkReal(-1.00000000000000))*(x6478)*(x6479)))+(((x6474)*(x6478)))+(((IkReal(-1.00000000000000))*(x6475)*(x6480)))+(((cj0)*(x6477)))+(((IkReal(-1.00000000000000))*(sj5)*(x6470)*(x6487))));
20404 evalcond[4]=((IkReal(-1.00000000000000))+(((x6487)*(x6488)))+(((IkReal(-1.00000000000000))*(x6482)*(x6501)))+(((IkReal(-1.00000000000000))*(x6469)*(x6470)*(x6487)))+(((x6469)*(x6500)))+(((x6474)*(x6495)))+(((cj6)*(x6469)*(x6474)))+(((x6472)*(x6497)))+(((IkReal(-1.00000000000000))*(cj4)*(x6470)*(x6479)))+(((IkReal(-1.00000000000000))*(x6472)*(x6493)))+(((IkReal(-1.00000000000000))*(x6469)*(x6479)*(x6484))));
20405 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x6490)*(x6493)))+(((IkReal(-1.00000000000000))*(x6470)*(x6483)*(x6487)))+(((IkReal(-1.00000000000000))*(sj4)*(x6470)*(x6474)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x6473)*(x6479)*(x6490)))+(((IkReal(-1.00000000000000))*(sj4)*(x6484)*(x6487)))+(((sj4)*(sj6)*(x6479)))+(((cj4)*(sj5)*(x6497)))+(((cj4)*(x6473)*(x6474)))+(((r00)*(x6480)*(x6495))));
20406 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x6470)*(x6499)))+(((x6488)*(x6491)))+(((x6471)*(x6488)))+(((IkReal(-1.00000000000000))*(x6469)*(x6470)*(x6491)))+(((IkReal(-1.00000000000000))*(r12)*(x6472)*(x6482)))+(((IkReal(-1.00000000000000))*(x6469)*(x6484)*(x6489)))+(((IkReal(-1.00000000000000))*(x6469)*(x6470)*(x6471)))+(((IkReal(-1.00000000000000))*(cj0)*(x6472)*(x6475)))+(((IkReal(-1.00000000000000))*(cj4)*(x6470)*(x6489)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x6469)*(x6482))));
20407 evalcond[7]=((((x6487)*(x6502)))+(((IkReal(0.374290000000000))*(x6474)*(x6478)))+(((IkReal(-0.0100000000000000))*(x6473)*(x6474)))+(((x6476)*(x6477)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x6480)))+(((IkReal(-1.00000000000000))*(x6485)*(x6497)))+(((px)*(sj0)))+(((IkReal(-0.374290000000000))*(r02)*(x6480)))+(((IkReal(-1.00000000000000))*(r10)*(x6476)*(x6486)))+(((IkReal(-1.00000000000000))*(py)*(x6496)))+(((IkReal(-1.00000000000000))*(r11)*(x6476)*(x6478)))+(((x6485)*(x6493)))+(((r00)*(x6486)*(x6492)))+(((IkReal(0.0100000000000000))*(x6473)*(x6479))));
20408 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(r00)*(x6476)*(x6486)))+(((IkReal(-1.00000000000000))*(px)*(x6496)))+(((cj0)*(r02)*(x6485)))+(((r12)*(sj0)*(x6485)))+(((IkReal(-0.374290000000000))*(x6471)*(x6486)))+(((cj5)*(r02)*(x6476)))+(((x6477)*(x6492)))+(((IkReal(-1.00000000000000))*(r01)*(x6476)*(x6478)))+(((x6471)*(x6502)))+(((IkReal(0.0100000000000000))*(x6473)*(x6499)))+(((IkReal(-1.00000000000000))*(py)*(x6482)))+(((IkReal(0.0100000000000000))*(x6473)*(x6489)))+(((IkReal(-1.00000000000000))*(r11)*(x6478)*(x6492)))+(((x6491)*(x6502))));
20409 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
20410 {
20411 {
20412 IkReal j3array[1], cj3array[1], sj3array[1];
20413 bool j3valid[1]={false};
20414 _nj3 = 1;
20415 IkReal x6503=((IkReal(1.00000000000000))*(cj4));
20416 IkReal x6504=((cj6)*(r21));
20417 IkReal x6505=((r20)*(sj6));
20418 if( IKabs(((((sj5)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6504))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6504)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6503)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6504)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6504)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6503)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
20419     continue;
20420 j3array[0]=IKatan2(((((sj5)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6504)))), ((((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6505)))+(((IkReal(-1.00000000000000))*(cj5)*(x6503)*(x6504)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x6503)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
20421 sj3array[0]=IKsin(j3array[0]);
20422 cj3array[0]=IKcos(j3array[0]);
20423 if( j3array[0] > IKPI )
20424 {
20425     j3array[0]-=IK2PI;
20426 }
20427 else if( j3array[0] < -IKPI )
20428 {    j3array[0]+=IK2PI;
20429 }
20430 j3valid[0] = true;
20431 for(int ij3 = 0; ij3 < 1; ++ij3)
20432 {
20433 if( !j3valid[ij3] )
20434 {
20435     continue;
20436 }
20437 _ij3[0] = ij3; _ij3[1] = -1;
20438 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20439 {
20440 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20441 {
20442     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20443 }
20444 }
20445 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20446 {
20447 IkReal evalcond[4];
20448 IkReal x6506=IKcos(j3);
20449 IkReal x6507=IKsin(j3);
20450 IkReal x6508=((IkReal(1.00000000000000))*(cj4));
20451 IkReal x6509=((sj0)*(sj5));
20452 IkReal x6510=((cj0)*(cj5));
20453 IkReal x6511=((cj6)*(r01));
20454 IkReal x6512=((r00)*(sj6));
20455 IkReal x6513=((cj6)*(r11));
20456 IkReal x6514=((cj5)*(sj0));
20457 IkReal x6515=((cj6)*(sj4));
20458 IkReal x6516=((sj4)*(sj6));
20459 IkReal x6517=((cj4)*(cj5));
20460 IkReal x6518=((cj6)*(r21));
20461 IkReal x6519=((r20)*(sj6));
20462 IkReal x6520=((r10)*(sj6));
20463 IkReal x6521=((IkReal(1.00000000000000))*(cj0)*(sj5));
20464 evalcond[0]=((((sj5)*(x6518)))+(((IkReal(-1.00000000000000))*(x6507)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6519))));
20465 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x6516)))+(((x6517)*(x6518)))+(((x6517)*(x6519)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x6515)))+(x6506));
20466 evalcond[2]=((((IkReal(-1.00000000000000))*(x6509)*(x6513)))+(((IkReal(-1.00000000000000))*(x6511)*(x6521)))+(((r02)*(x6510)))+(((IkReal(-1.00000000000000))*(x6509)*(x6520)))+(x6506)+(((r12)*(x6514)))+(((IkReal(-1.00000000000000))*(x6512)*(x6521))));
20467 evalcond[3]=((((IkReal(-1.00000000000000))*(x6508)*(x6510)*(x6511)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6515)))+(((IkReal(-1.00000000000000))*(x6508)*(x6514)*(x6520)))+(((IkReal(-1.00000000000000))*(x6508)*(x6510)*(x6512)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x6515)))+(((cj0)*(r01)*(x6516)))+(((IkReal(-1.00000000000000))*(x6508)*(x6513)*(x6514)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x6508)))+(((r11)*(sj0)*(x6516)))+(((IkReal(-1.00000000000000))*(r12)*(x6508)*(x6509)))+(x6507));
20468 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
20469 {
20470 continue;
20471 }
20472 }
20473 
20474 {
20475 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20476 vinfos[0].jointtype = 1;
20477 vinfos[0].foffset = j0;
20478 vinfos[0].indices[0] = _ij0[0];
20479 vinfos[0].indices[1] = _ij0[1];
20480 vinfos[0].maxsolutions = _nj0;
20481 vinfos[1].jointtype = 1;
20482 vinfos[1].foffset = j1;
20483 vinfos[1].indices[0] = _ij1[0];
20484 vinfos[1].indices[1] = _ij1[1];
20485 vinfos[1].maxsolutions = _nj1;
20486 vinfos[2].jointtype = 1;
20487 vinfos[2].foffset = j2;
20488 vinfos[2].indices[0] = _ij2[0];
20489 vinfos[2].indices[1] = _ij2[1];
20490 vinfos[2].maxsolutions = _nj2;
20491 vinfos[3].jointtype = 1;
20492 vinfos[3].foffset = j3;
20493 vinfos[3].indices[0] = _ij3[0];
20494 vinfos[3].indices[1] = _ij3[1];
20495 vinfos[3].maxsolutions = _nj3;
20496 vinfos[4].jointtype = 1;
20497 vinfos[4].foffset = j4;
20498 vinfos[4].indices[0] = _ij4[0];
20499 vinfos[4].indices[1] = _ij4[1];
20500 vinfos[4].maxsolutions = _nj4;
20501 vinfos[5].jointtype = 1;
20502 vinfos[5].foffset = j5;
20503 vinfos[5].indices[0] = _ij5[0];
20504 vinfos[5].indices[1] = _ij5[1];
20505 vinfos[5].maxsolutions = _nj5;
20506 vinfos[6].jointtype = 1;
20507 vinfos[6].foffset = j6;
20508 vinfos[6].indices[0] = _ij6[0];
20509 vinfos[6].indices[1] = _ij6[1];
20510 vinfos[6].maxsolutions = _nj6;
20511 std::vector<int> vfree(0);
20512 solutions.AddSolution(vinfos,vfree);
20513 }
20514 }
20515 }
20516 
20517 } else
20518 {
20519 IkReal x6522=((IkReal(1.00000000000000))*(cj0));
20520 IkReal x6523=((cj4)*(sj6));
20521 IkReal x6524=((sj0)*(sj4));
20522 IkReal x6525=((cj5)*(sj6));
20523 IkReal x6526=((sj4)*(sj5));
20524 IkReal x6527=((r12)*(sj5));
20525 IkReal x6528=((IkReal(0.374290000000000))*(cj5));
20526 IkReal x6529=((r02)*(sj0));
20527 IkReal x6530=((r20)*(sj4));
20528 IkReal x6531=((IkReal(1.00000000000000))*(sj0));
20529 IkReal x6532=((IkReal(1.00000000000000))*(cj5));
20530 IkReal x6533=((cj0)*(r10));
20531 IkReal x6534=((cj4)*(cj6));
20532 IkReal x6535=((r00)*(sj0));
20533 IkReal x6536=((cj6)*(r21));
20534 IkReal x6537=((IkReal(0.374290000000000))*(sj5));
20535 IkReal x6538=((cj0)*(r00));
20536 IkReal x6539=((IkReal(0.0100000000000000))*(sj5));
20537 IkReal x6540=((cj0)*(r02));
20538 IkReal x6541=((cj5)*(sj4));
20539 IkReal x6542=((cj6)*(r01));
20540 IkReal x6543=((cj6)*(r11));
20541 IkReal x6544=((r01)*(sj0));
20542 IkReal x6545=((r10)*(sj0));
20543 IkReal x6546=((IkReal(0.0100000000000000))*(cj5)*(cj6));
20544 IkReal x6547=((sj6)*(x6537));
20545 IkReal x6548=((cj0)*(cj6)*(x6537));
20546 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
20547 evalcond[1]=((((sj5)*(x6536)))+(((IkReal(-1.00000000000000))*(r22)*(x6532)))+(((r20)*(sj5)*(sj6))));
20548 evalcond[2]=((IkReal(1.00000000000000))+(((x6536)*(x6541)))+(((r21)*(x6523)))+(((r22)*(x6526)))+(((IkReal(-1.00000000000000))*(r20)*(x6534)))+(((x6525)*(x6530))));
20549 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x6536)))+(((x6536)*(x6537)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x6539)))+(((IkReal(-0.0100000000000000))*(r20)*(x6525)))+(((r20)*(x6547)))+(((IkReal(-1.00000000000000))*(r22)*(x6528))));
20550 evalcond[4]=((((cj6)*(x6530)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x6534)))+(((cj5)*(r20)*(x6523))));
20551 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x6522)*(x6526)))+(((r02)*(sj5)*(x6524)))+(((IkReal(-1.00000000000000))*(x6522)*(x6541)*(x6543)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6522)*(x6525)))+(((x6523)*(x6544)))+(((x6533)*(x6534)))+(((IkReal(-1.00000000000000))*(r11)*(x6522)*(x6523)))+(((r00)*(x6524)*(x6525)))+(((cj5)*(x6524)*(x6542)))+(((IkReal(-1.00000000000000))*(r00)*(x6531)*(x6534))));
20552 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x6522)*(x6523)))+(((IkReal(-1.00000000000000))*(x6524)*(x6532)*(x6543)))+(((IkReal(-1.00000000000000))*(r02)*(x6522)*(x6526)))+(((x6534)*(x6538)))+(((IkReal(-1.00000000000000))*(x6524)*(x6527)))+(((IkReal(-1.00000000000000))*(r11)*(x6523)*(x6531)))+(((IkReal(-1.00000000000000))*(x6522)*(x6541)*(x6542)))+(((IkReal(-1.00000000000000))*(r10)*(x6524)*(x6525)))+(((x6534)*(x6545)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6522)*(x6525))));
20553 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x6537)*(x6543)))+(((IkReal(0.0100000000000000))*(x6525)*(x6533)))+(((IkReal(-1.00000000000000))*(x6533)*(x6547)))+(((cj0)*(r12)*(x6528)))+(((IkReal(-1.00000000000000))*(py)*(x6522)))+(((IkReal(-1.00000000000000))*(x6529)*(x6539)))+(((IkReal(-0.0100000000000000))*(x6525)*(x6535)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6543)))+(((IkReal(0.0100000000000000))*(cj0)*(x6527)))+(((IkReal(-1.00000000000000))*(x6528)*(x6529)))+(((sj0)*(x6537)*(x6542)))+(((x6535)*(x6547)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6542)))+(((px)*(sj0))));
20554 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(x6525)*(x6538)))+(((IkReal(-1.00000000000000))*(sj0)*(x6537)*(x6543)))+(((IkReal(-1.00000000000000))*(py)*(x6531)))+(((IkReal(-1.00000000000000))*(x6538)*(x6547)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6543)))+(((IkReal(-1.00000000000000))*(x6545)*(x6547)))+(((x6528)*(x6540)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6542)))+(((x6539)*(x6540)))+(((IkReal(-1.00000000000000))*(px)*(x6522)))+(((IkReal(0.0100000000000000))*(x6525)*(x6545)))+(((r12)*(sj0)*(x6528)))+(((IkReal(0.0100000000000000))*(sj0)*(x6527)))+(((IkReal(-1.00000000000000))*(cj0)*(x6537)*(x6542))));
20555 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
20556 {
20557 {
20558 IkReal j3array[1], cj3array[1], sj3array[1];
20559 bool j3valid[1]={false};
20560 _nj3 = 1;
20561 IkReal x6549=((sj0)*(sj5));
20562 IkReal x6550=((r00)*(sj6));
20563 IkReal x6551=((IkReal(1.00000000000000))*(cj5));
20564 IkReal x6552=((cj6)*(r11));
20565 IkReal x6553=((cj6)*(r01));
20566 IkReal x6554=((r10)*(sj6));
20567 IkReal x6555=((cj0)*(sj5));
20568 if( IKabs(((((IkReal(-1.00000000000000))*(x6552)*(x6555)))+(((IkReal(-1.00000000000000))*(x6554)*(x6555)))+(((x6549)*(x6550)))+(((x6549)*(x6553)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6551))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x6553)*(x6555)))+(((x6549)*(x6554)))+(((x6549)*(x6552)))+(((x6550)*(x6555)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6551)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6551))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x6552)*(x6555)))+(((IkReal(-1.00000000000000))*(x6554)*(x6555)))+(((x6549)*(x6550)))+(((x6549)*(x6553)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6551)))))+IKsqr(((((x6553)*(x6555)))+(((x6549)*(x6554)))+(((x6549)*(x6552)))+(((x6550)*(x6555)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6551)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6551)))))-1) <= IKFAST_SINCOS_THRESH )
20569     continue;
20570 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x6552)*(x6555)))+(((IkReal(-1.00000000000000))*(x6554)*(x6555)))+(((x6549)*(x6550)))+(((x6549)*(x6553)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6551)))), ((((x6553)*(x6555)))+(((x6549)*(x6554)))+(((x6549)*(x6552)))+(((x6550)*(x6555)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6551)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6551)))));
20571 sj3array[0]=IKsin(j3array[0]);
20572 cj3array[0]=IKcos(j3array[0]);
20573 if( j3array[0] > IKPI )
20574 {
20575     j3array[0]-=IK2PI;
20576 }
20577 else if( j3array[0] < -IKPI )
20578 {    j3array[0]+=IK2PI;
20579 }
20580 j3valid[0] = true;
20581 for(int ij3 = 0; ij3 < 1; ++ij3)
20582 {
20583 if( !j3valid[ij3] )
20584 {
20585     continue;
20586 }
20587 _ij3[0] = ij3; _ij3[1] = -1;
20588 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20589 {
20590 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20591 {
20592     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20593 }
20594 }
20595 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20596 {
20597 IkReal evalcond[4];
20598 IkReal x6556=IKcos(j3);
20599 IkReal x6557=IKsin(j3);
20600 IkReal x6558=((sj0)*(sj5));
20601 IkReal x6559=((r00)*(sj6));
20602 IkReal x6560=((cj6)*(sj0));
20603 IkReal x6561=((IkReal(1.00000000000000))*(cj4));
20604 IkReal x6562=((r00)*(sj4));
20605 IkReal x6563=((cj0)*(cj5));
20606 IkReal x6564=((cj5)*(sj0));
20607 IkReal x6565=((cj6)*(r11));
20608 IkReal x6566=((r10)*(sj6));
20609 IkReal x6567=((cj0)*(sj5));
20610 IkReal x6568=((r10)*(sj4));
20611 IkReal x6569=((cj4)*(cj5)*(r01));
20612 IkReal x6570=((IkReal(1.00000000000000))*(cj0)*(cj6));
20613 IkReal x6571=((cj0)*(sj4)*(sj6));
20614 IkReal x6572=((sj0)*(sj4)*(sj6));
20615 evalcond[0]=((((r12)*(x6563)))+(((IkReal(-1.00000000000000))*(r02)*(x6564)))+(((IkReal(-1.00000000000000))*(x6566)*(x6567)))+(((cj6)*(r01)*(x6558)))+(((x6558)*(x6559)))+(((IkReal(-1.00000000000000))*(x6557)))+(((IkReal(-1.00000000000000))*(x6565)*(x6567))));
20616 evalcond[1]=((((r12)*(x6564)))+(((IkReal(-1.00000000000000))*(x6559)*(x6567)))+(((r02)*(x6563)))+(((IkReal(-1.00000000000000))*(x6558)*(x6565)))+(((IkReal(-1.00000000000000))*(x6558)*(x6566)))+(x6556)+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x6567))));
20617 evalcond[2]=((((IkReal(-1.00000000000000))*(x6568)*(x6570)))+(((cj4)*(x6559)*(x6564)))+(((IkReal(-1.00000000000000))*(x6561)*(x6563)*(x6566)))+(((r11)*(x6571)))+(((x6560)*(x6562)))+(((IkReal(-1.00000000000000))*(r01)*(x6572)))+(((cj4)*(r02)*(x6558)))+(x6556)+(((IkReal(-1.00000000000000))*(r12)*(x6561)*(x6567)))+(((x6560)*(x6569)))+(((IkReal(-1.00000000000000))*(x6561)*(x6563)*(x6565))));
20618 evalcond[3]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x6561)*(x6563)))+(((IkReal(-1.00000000000000))*(x6560)*(x6568)))+(((r01)*(x6571)))+(((r11)*(x6572)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x6560)*(x6561)))+(x6557)+(((IkReal(-1.00000000000000))*(r02)*(x6561)*(x6567)))+(((IkReal(-1.00000000000000))*(x6562)*(x6570)))+(((IkReal(-1.00000000000000))*(x6559)*(x6561)*(x6563)))+(((IkReal(-1.00000000000000))*(r12)*(x6558)*(x6561)))+(((IkReal(-1.00000000000000))*(x6561)*(x6564)*(x6566))));
20619 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
20620 {
20621 continue;
20622 }
20623 }
20624 
20625 {
20626 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20627 vinfos[0].jointtype = 1;
20628 vinfos[0].foffset = j0;
20629 vinfos[0].indices[0] = _ij0[0];
20630 vinfos[0].indices[1] = _ij0[1];
20631 vinfos[0].maxsolutions = _nj0;
20632 vinfos[1].jointtype = 1;
20633 vinfos[1].foffset = j1;
20634 vinfos[1].indices[0] = _ij1[0];
20635 vinfos[1].indices[1] = _ij1[1];
20636 vinfos[1].maxsolutions = _nj1;
20637 vinfos[2].jointtype = 1;
20638 vinfos[2].foffset = j2;
20639 vinfos[2].indices[0] = _ij2[0];
20640 vinfos[2].indices[1] = _ij2[1];
20641 vinfos[2].maxsolutions = _nj2;
20642 vinfos[3].jointtype = 1;
20643 vinfos[3].foffset = j3;
20644 vinfos[3].indices[0] = _ij3[0];
20645 vinfos[3].indices[1] = _ij3[1];
20646 vinfos[3].maxsolutions = _nj3;
20647 vinfos[4].jointtype = 1;
20648 vinfos[4].foffset = j4;
20649 vinfos[4].indices[0] = _ij4[0];
20650 vinfos[4].indices[1] = _ij4[1];
20651 vinfos[4].maxsolutions = _nj4;
20652 vinfos[5].jointtype = 1;
20653 vinfos[5].foffset = j5;
20654 vinfos[5].indices[0] = _ij5[0];
20655 vinfos[5].indices[1] = _ij5[1];
20656 vinfos[5].maxsolutions = _nj5;
20657 vinfos[6].jointtype = 1;
20658 vinfos[6].foffset = j6;
20659 vinfos[6].indices[0] = _ij6[0];
20660 vinfos[6].indices[1] = _ij6[1];
20661 vinfos[6].maxsolutions = _nj6;
20662 std::vector<int> vfree(0);
20663 solutions.AddSolution(vinfos,vfree);
20664 }
20665 }
20666 }
20667 
20668 } else
20669 {
20670 IkReal x6573=((IkReal(1.00000000000000))*(cj0));
20671 IkReal x6574=((cj4)*(sj6));
20672 IkReal x6575=((sj0)*(sj4));
20673 IkReal x6576=((cj5)*(sj6));
20674 IkReal x6577=((sj4)*(sj5));
20675 IkReal x6578=((r12)*(sj5));
20676 IkReal x6579=((IkReal(0.374290000000000))*(cj5));
20677 IkReal x6580=((r02)*(sj0));
20678 IkReal x6581=((r20)*(sj4));
20679 IkReal x6582=((IkReal(1.00000000000000))*(sj0));
20680 IkReal x6583=((IkReal(1.00000000000000))*(cj5));
20681 IkReal x6584=((cj0)*(r10));
20682 IkReal x6585=((cj4)*(cj6));
20683 IkReal x6586=((r00)*(sj0));
20684 IkReal x6587=((cj6)*(r21));
20685 IkReal x6588=((IkReal(0.374290000000000))*(sj5));
20686 IkReal x6589=((cj0)*(r00));
20687 IkReal x6590=((IkReal(0.0100000000000000))*(sj5));
20688 IkReal x6591=((cj0)*(r02));
20689 IkReal x6592=((cj5)*(sj4));
20690 IkReal x6593=((cj6)*(r01));
20691 IkReal x6594=((cj6)*(r11));
20692 IkReal x6595=((r01)*(sj0));
20693 IkReal x6596=((r10)*(sj0));
20694 IkReal x6597=((IkReal(0.0100000000000000))*(cj5)*(cj6));
20695 IkReal x6598=((sj6)*(x6588));
20696 IkReal x6599=((cj0)*(cj6)*(x6588));
20697 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
20698 evalcond[1]=((((sj5)*(x6587)))+(((IkReal(-1.00000000000000))*(r22)*(x6583)))+(((r20)*(sj5)*(sj6))));
20699 evalcond[2]=((IkReal(-1.00000000000000))+(((x6587)*(x6592)))+(((r22)*(x6577)))+(((x6576)*(x6581)))+(((r21)*(x6574)))+(((IkReal(-1.00000000000000))*(r20)*(x6585))));
20700 evalcond[3]=((((r20)*(x6598)))+(((IkReal(-1.00000000000000))*(r22)*(x6579)))+(((x6587)*(x6588)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6587)))+(((IkReal(-1.00000000000000))*(r22)*(x6590)))+(((IkReal(-0.0100000000000000))*(r20)*(x6576)))+(pz));
20701 evalcond[4]=((((cj6)*(x6581)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x6585)))+(((cj5)*(r20)*(x6574))));
20702 evalcond[5]=((((r00)*(x6575)*(x6576)))+(((IkReal(-1.00000000000000))*(r00)*(x6582)*(x6585)))+(((IkReal(-1.00000000000000))*(r11)*(x6573)*(x6574)))+(((x6584)*(x6585)))+(((IkReal(-1.00000000000000))*(x6573)*(x6592)*(x6594)))+(((cj5)*(x6575)*(x6593)))+(((IkReal(-1.00000000000000))*(r12)*(x6573)*(x6577)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6573)*(x6576)))+(((r02)*(sj5)*(x6575)))+(((x6574)*(x6595))));
20703 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x6573)*(x6574)))+(((IkReal(-1.00000000000000))*(x6575)*(x6583)*(x6594)))+(((IkReal(-1.00000000000000))*(r10)*(x6575)*(x6576)))+(((x6585)*(x6589)))+(((IkReal(-1.00000000000000))*(r02)*(x6573)*(x6577)))+(((IkReal(-1.00000000000000))*(r11)*(x6574)*(x6582)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6573)*(x6576)))+(((IkReal(-1.00000000000000))*(x6575)*(x6578)))+(((x6585)*(x6596)))+(((IkReal(-1.00000000000000))*(x6573)*(x6592)*(x6593))));
20704 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(0.0100000000000000))*(x6576)*(x6584)))+(((IkReal(-0.0100000000000000))*(x6576)*(x6586)))+(((IkReal(0.0100000000000000))*(cj0)*(x6578)))+(((sj0)*(x6588)*(x6593)))+(((IkReal(-1.00000000000000))*(x6579)*(x6580)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6593)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6594)))+(((x6586)*(x6598)))+(((cj0)*(r12)*(x6579)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x6588)*(x6594)))+(((IkReal(-1.00000000000000))*(py)*(x6573)))+(((IkReal(-1.00000000000000))*(x6584)*(x6598)))+(((IkReal(-1.00000000000000))*(x6580)*(x6590))));
20705 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(sj0)*(x6578)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6593)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6594)))+(((IkReal(-1.00000000000000))*(cj0)*(x6588)*(x6593)))+(((r12)*(sj0)*(x6579)))+(((IkReal(-1.00000000000000))*(x6596)*(x6598)))+(((IkReal(0.0100000000000000))*(x6576)*(x6596)))+(((x6590)*(x6591)))+(((x6579)*(x6591)))+(((IkReal(-1.00000000000000))*(py)*(x6582)))+(((IkReal(-1.00000000000000))*(x6589)*(x6598)))+(((IkReal(0.0100000000000000))*(x6576)*(x6589)))+(((IkReal(-1.00000000000000))*(px)*(x6573)))+(((IkReal(-1.00000000000000))*(sj0)*(x6588)*(x6594))));
20706 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
20707 {
20708 {
20709 IkReal j3array[1], cj3array[1], sj3array[1];
20710 bool j3valid[1]={false};
20711 _nj3 = 1;
20712 IkReal x6600=((IkReal(1.00000000000000))*(cj5));
20713 IkReal x6601=((r10)*(sj5)*(sj6));
20714 IkReal x6602=((cj6)*(sj0)*(sj5));
20715 IkReal x6603=((r00)*(sj5)*(sj6));
20716 IkReal x6604=((cj0)*(cj6)*(sj5));
20717 if( IKabs(((((IkReal(-1.00000000000000))*(sj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r01)*(x6602)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x6600)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x6601)))+(((r11)*(x6604))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj0)*(x6601)))+(((cj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6600)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6600)))+(((r01)*(x6604)))+(((r11)*(x6602))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r01)*(x6602)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x6600)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x6601)))+(((r11)*(x6604)))))+IKsqr(((((sj0)*(x6601)))+(((cj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6600)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6600)))+(((r01)*(x6604)))+(((r11)*(x6602)))))-1) <= IKFAST_SINCOS_THRESH )
20718     continue;
20719 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r01)*(x6602)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x6600)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(x6601)))+(((r11)*(x6604)))), ((((sj0)*(x6601)))+(((cj0)*(x6603)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6600)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6600)))+(((r01)*(x6604)))+(((r11)*(x6602)))));
20720 sj3array[0]=IKsin(j3array[0]);
20721 cj3array[0]=IKcos(j3array[0]);
20722 if( j3array[0] > IKPI )
20723 {
20724     j3array[0]-=IK2PI;
20725 }
20726 else if( j3array[0] < -IKPI )
20727 {    j3array[0]+=IK2PI;
20728 }
20729 j3valid[0] = true;
20730 for(int ij3 = 0; ij3 < 1; ++ij3)
20731 {
20732 if( !j3valid[ij3] )
20733 {
20734     continue;
20735 }
20736 _ij3[0] = ij3; _ij3[1] = -1;
20737 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20738 {
20739 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20740 {
20741     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20742 }
20743 }
20744 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20745 {
20746 IkReal evalcond[4];
20747 IkReal x6605=IKcos(j3);
20748 IkReal x6606=IKsin(j3);
20749 IkReal x6607=((sj0)*(sj5));
20750 IkReal x6608=((r00)*(sj6));
20751 IkReal x6609=((IkReal(1.00000000000000))*(cj4));
20752 IkReal x6610=((cj6)*(sj0));
20753 IkReal x6611=((r00)*(sj4));
20754 IkReal x6612=((cj0)*(cj5));
20755 IkReal x6613=((cj6)*(r01));
20756 IkReal x6614=((cj5)*(sj0));
20757 IkReal x6615=((cj0)*(sj5));
20758 IkReal x6616=((cj6)*(r11));
20759 IkReal x6617=((r10)*(sj6));
20760 IkReal x6618=((r10)*(sj4));
20761 IkReal x6619=((cj0)*(sj4)*(sj6));
20762 IkReal x6620=((sj0)*(sj4)*(sj6));
20763 IkReal x6621=((IkReal(1.00000000000000))*(cj0)*(cj6));
20764 evalcond[0]=((((IkReal(-1.00000000000000))*(x6615)*(x6617)))+(x6606)+(((r12)*(x6612)))+(((x6607)*(x6608)))+(((IkReal(-1.00000000000000))*(x6615)*(x6616)))+(((x6607)*(x6613)))+(((IkReal(-1.00000000000000))*(r02)*(x6614))));
20765 evalcond[1]=((x6605)+(((IkReal(-1.00000000000000))*(x6613)*(x6615)))+(((r12)*(x6614)))+(((IkReal(-1.00000000000000))*(x6608)*(x6615)))+(((IkReal(-1.00000000000000))*(x6607)*(x6616)))+(((r02)*(x6612)))+(((IkReal(-1.00000000000000))*(x6607)*(x6617))));
20766 evalcond[2]=((((IkReal(-1.00000000000000))*(x6605)))+(((r11)*(x6619)))+(((cj4)*(r02)*(x6607)))+(((IkReal(-1.00000000000000))*(r12)*(x6609)*(x6615)))+(((IkReal(-1.00000000000000))*(r01)*(x6620)))+(((IkReal(-1.00000000000000))*(x6609)*(x6612)*(x6617)))+(((IkReal(-1.00000000000000))*(x6609)*(x6612)*(x6616)))+(((IkReal(-1.00000000000000))*(x6618)*(x6621)))+(((cj4)*(x6608)*(x6614)))+(((cj4)*(cj5)*(r01)*(x6610)))+(((x6610)*(x6611))));
20767 evalcond[3]=((x6606)+(((IkReal(-1.00000000000000))*(r02)*(x6609)*(x6615)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x6609)*(x6610)))+(((IkReal(-1.00000000000000))*(x6609)*(x6614)*(x6617)))+(((IkReal(-1.00000000000000))*(x6608)*(x6609)*(x6612)))+(((IkReal(-1.00000000000000))*(x6610)*(x6618)))+(((r01)*(x6619)))+(((IkReal(-1.00000000000000))*(x6609)*(x6612)*(x6613)))+(((IkReal(-1.00000000000000))*(x6611)*(x6621)))+(((r11)*(x6620)))+(((IkReal(-1.00000000000000))*(r12)*(x6607)*(x6609))));
20768 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
20769 {
20770 continue;
20771 }
20772 }
20773 
20774 {
20775 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20776 vinfos[0].jointtype = 1;
20777 vinfos[0].foffset = j0;
20778 vinfos[0].indices[0] = _ij0[0];
20779 vinfos[0].indices[1] = _ij0[1];
20780 vinfos[0].maxsolutions = _nj0;
20781 vinfos[1].jointtype = 1;
20782 vinfos[1].foffset = j1;
20783 vinfos[1].indices[0] = _ij1[0];
20784 vinfos[1].indices[1] = _ij1[1];
20785 vinfos[1].maxsolutions = _nj1;
20786 vinfos[2].jointtype = 1;
20787 vinfos[2].foffset = j2;
20788 vinfos[2].indices[0] = _ij2[0];
20789 vinfos[2].indices[1] = _ij2[1];
20790 vinfos[2].maxsolutions = _nj2;
20791 vinfos[3].jointtype = 1;
20792 vinfos[3].foffset = j3;
20793 vinfos[3].indices[0] = _ij3[0];
20794 vinfos[3].indices[1] = _ij3[1];
20795 vinfos[3].maxsolutions = _nj3;
20796 vinfos[4].jointtype = 1;
20797 vinfos[4].foffset = j4;
20798 vinfos[4].indices[0] = _ij4[0];
20799 vinfos[4].indices[1] = _ij4[1];
20800 vinfos[4].maxsolutions = _nj4;
20801 vinfos[5].jointtype = 1;
20802 vinfos[5].foffset = j5;
20803 vinfos[5].indices[0] = _ij5[0];
20804 vinfos[5].indices[1] = _ij5[1];
20805 vinfos[5].maxsolutions = _nj5;
20806 vinfos[6].jointtype = 1;
20807 vinfos[6].foffset = j6;
20808 vinfos[6].indices[0] = _ij6[0];
20809 vinfos[6].indices[1] = _ij6[1];
20810 vinfos[6].maxsolutions = _nj6;
20811 std::vector<int> vfree(0);
20812 solutions.AddSolution(vinfos,vfree);
20813 }
20814 }
20815 }
20816 
20817 } else
20818 {
20819 if( 1 )
20820 {
20821 continue;
20822 
20823 } else
20824 {
20825 }
20826 }
20827 }
20828 }
20829 }
20830 }
20831 
20832 } else
20833 {
20834 {
20835 IkReal j3array[1], cj3array[1], sj3array[1];
20836 bool j3valid[1]={false};
20837 _nj3 = 1;
20838 IkReal x6622=((sj0)*(sj5));
20839 IkReal x6623=((r00)*(sj6));
20840 IkReal x6624=((IkReal(1.00000000000000))*(cj5));
20841 IkReal x6625=((cj6)*(r11));
20842 IkReal x6626=((cj6)*(r01));
20843 IkReal x6627=((cj0)*(sj5));
20844 IkReal x6628=((r10)*(sj6));
20845 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x6622)*(x6623)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6624)))+(((IkReal(-1.00000000000000))*(x6625)*(x6627)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x6627)*(x6628)))+(((x6622)*(x6626))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6624)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6624)))+(((x6623)*(x6627)))+(((x6622)*(x6625)))+(((x6622)*(x6628)))+(((x6626)*(x6627))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x6622)*(x6623)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6624)))+(((IkReal(-1.00000000000000))*(x6625)*(x6627)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x6627)*(x6628)))+(((x6622)*(x6626)))))))+IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6624)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6624)))+(((x6623)*(x6627)))+(((x6622)*(x6625)))+(((x6622)*(x6628)))+(((x6626)*(x6627)))))-1) <= IKFAST_SINCOS_THRESH )
20846     continue;
20847 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((x6622)*(x6623)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6624)))+(((IkReal(-1.00000000000000))*(x6625)*(x6627)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x6627)*(x6628)))+(((x6622)*(x6626)))))), ((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6624)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6624)))+(((x6623)*(x6627)))+(((x6622)*(x6625)))+(((x6622)*(x6628)))+(((x6626)*(x6627)))));
20848 sj3array[0]=IKsin(j3array[0]);
20849 cj3array[0]=IKcos(j3array[0]);
20850 if( j3array[0] > IKPI )
20851 {
20852     j3array[0]-=IK2PI;
20853 }
20854 else if( j3array[0] < -IKPI )
20855 {    j3array[0]+=IK2PI;
20856 }
20857 j3valid[0] = true;
20858 for(int ij3 = 0; ij3 < 1; ++ij3)
20859 {
20860 if( !j3valid[ij3] )
20861 {
20862     continue;
20863 }
20864 _ij3[0] = ij3; _ij3[1] = -1;
20865 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20866 {
20867 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20868 {
20869     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20870 }
20871 }
20872 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20873 {
20874 IkReal evalcond[6];
20875 IkReal x6629=IKsin(j3);
20876 IkReal x6630=IKcos(j3);
20877 IkReal x6631=((sj0)*(sj5));
20878 IkReal x6632=((r00)*(sj6));
20879 IkReal x6633=((IkReal(1.00000000000000))*(cj4));
20880 IkReal x6634=((cj6)*(r01));
20881 IkReal x6635=((cj0)*(cj5));
20882 IkReal x6636=((cj5)*(sj0));
20883 IkReal x6637=((cj6)*(r11));
20884 IkReal x6638=((cj6)*(sj4));
20885 IkReal x6639=((cj0)*(sj5));
20886 IkReal x6640=((cj4)*(cj5));
20887 IkReal x6641=((cj6)*(r21));
20888 IkReal x6642=((r20)*(sj6));
20889 IkReal x6643=((r10)*(sj6));
20890 IkReal x6644=((IkReal(1.00000000000000))*(cj0));
20891 IkReal x6645=((cj0)*(sj4)*(sj6));
20892 IkReal x6646=((sj0)*(sj4)*(sj6));
20893 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6641)))+(((sj5)*(x6642)))+(((cj2)*(x6629))));
20894 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x6640)*(x6642)))+(((IkReal(-1.00000000000000))*(cj2)*(x6630)))+(((r20)*(x6638)))+(((cj4)*(r22)*(sj5)))+(((x6640)*(x6641))));
20895 evalcond[2]=((((x6631)*(x6632)))+(((r12)*(x6635)))+(((x6631)*(x6634)))+(((IkReal(-1.00000000000000))*(r02)*(x6636)))+(((IkReal(-1.00000000000000))*(x6639)*(x6643)))+(((IkReal(-1.00000000000000))*(sj2)*(x6629)))+(((IkReal(-1.00000000000000))*(x6637)*(x6639))));
20896 evalcond[3]=((((IkReal(-1.00000000000000))*(x6631)*(x6643)))+(x6630)+(((r02)*(x6635)))+(((r12)*(x6636)))+(((IkReal(-1.00000000000000))*(x6634)*(x6639)))+(((IkReal(-1.00000000000000))*(x6631)*(x6637)))+(((IkReal(-1.00000000000000))*(x6632)*(x6639))));
20897 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x6638)*(x6644)))+(((cj4)*(r02)*(x6631)))+(((sj2)*(x6630)))+(((cj4)*(x6632)*(x6636)))+(((IkReal(-1.00000000000000))*(x6633)*(x6635)*(x6643)))+(((IkReal(-1.00000000000000))*(r12)*(x6633)*(x6639)))+(((r11)*(x6645)))+(((IkReal(-1.00000000000000))*(r01)*(x6646)))+(((cj4)*(x6634)*(x6636)))+(((r00)*(sj0)*(x6638)))+(((IkReal(-1.00000000000000))*(x6633)*(x6635)*(x6637))));
20898 evalcond[5]=((((IkReal(-1.00000000000000))*(x6632)*(x6633)*(x6635)))+(((IkReal(-1.00000000000000))*(r12)*(x6631)*(x6633)))+(((r11)*(x6646)))+(x6629)+(((IkReal(-1.00000000000000))*(x6633)*(x6636)*(x6643)))+(((IkReal(-1.00000000000000))*(r00)*(x6638)*(x6644)))+(((IkReal(-1.00000000000000))*(x6633)*(x6634)*(x6635)))+(((IkReal(-1.00000000000000))*(x6633)*(x6636)*(x6637)))+(((IkReal(-1.00000000000000))*(r02)*(x6633)*(x6639)))+(((r01)*(x6645)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6638))));
20899 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
20900 {
20901 continue;
20902 }
20903 }
20904 
20905 {
20906 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
20907 vinfos[0].jointtype = 1;
20908 vinfos[0].foffset = j0;
20909 vinfos[0].indices[0] = _ij0[0];
20910 vinfos[0].indices[1] = _ij0[1];
20911 vinfos[0].maxsolutions = _nj0;
20912 vinfos[1].jointtype = 1;
20913 vinfos[1].foffset = j1;
20914 vinfos[1].indices[0] = _ij1[0];
20915 vinfos[1].indices[1] = _ij1[1];
20916 vinfos[1].maxsolutions = _nj1;
20917 vinfos[2].jointtype = 1;
20918 vinfos[2].foffset = j2;
20919 vinfos[2].indices[0] = _ij2[0];
20920 vinfos[2].indices[1] = _ij2[1];
20921 vinfos[2].maxsolutions = _nj2;
20922 vinfos[3].jointtype = 1;
20923 vinfos[3].foffset = j3;
20924 vinfos[3].indices[0] = _ij3[0];
20925 vinfos[3].indices[1] = _ij3[1];
20926 vinfos[3].maxsolutions = _nj3;
20927 vinfos[4].jointtype = 1;
20928 vinfos[4].foffset = j4;
20929 vinfos[4].indices[0] = _ij4[0];
20930 vinfos[4].indices[1] = _ij4[1];
20931 vinfos[4].maxsolutions = _nj4;
20932 vinfos[5].jointtype = 1;
20933 vinfos[5].foffset = j5;
20934 vinfos[5].indices[0] = _ij5[0];
20935 vinfos[5].indices[1] = _ij5[1];
20936 vinfos[5].maxsolutions = _nj5;
20937 vinfos[6].jointtype = 1;
20938 vinfos[6].foffset = j6;
20939 vinfos[6].indices[0] = _ij6[0];
20940 vinfos[6].indices[1] = _ij6[1];
20941 vinfos[6].maxsolutions = _nj6;
20942 std::vector<int> vfree(0);
20943 solutions.AddSolution(vinfos,vfree);
20944 }
20945 }
20946 }
20947 
20948 }
20949 
20950 }
20951 
20952 } else
20953 {
20954 {
20955 IkReal j3array[1], cj3array[1], sj3array[1];
20956 bool j3valid[1]={false};
20957 _nj3 = 1;
20958 IkReal x6647=((cj6)*(sj5));
20959 IkReal x6648=((IkReal(1.00000000000000))*(cj5));
20960 IkReal x6649=((sj5)*(sj6));
20961 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x6649)))+(((IkReal(-1.00000000000000))*(r21)*(x6647)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(r00)*(x6649)))+(((r10)*(sj0)*(x6649)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6648)))+(((cj0)*(r01)*(x6647)))+(((r11)*(sj0)*(x6647)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6648))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x6649)))+(((IkReal(-1.00000000000000))*(r21)*(x6647)))+(((cj5)*(r22)))))))+IKsqr(((((cj0)*(r00)*(x6649)))+(((r10)*(sj0)*(x6649)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6648)))+(((cj0)*(r01)*(x6647)))+(((r11)*(sj0)*(x6647)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6648)))))-1) <= IKFAST_SINCOS_THRESH )
20962     continue;
20963 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x6649)))+(((IkReal(-1.00000000000000))*(r21)*(x6647)))+(((cj5)*(r22)))))), ((((cj0)*(r00)*(x6649)))+(((r10)*(sj0)*(x6649)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x6648)))+(((cj0)*(r01)*(x6647)))+(((r11)*(sj0)*(x6647)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x6648)))));
20964 sj3array[0]=IKsin(j3array[0]);
20965 cj3array[0]=IKcos(j3array[0]);
20966 if( j3array[0] > IKPI )
20967 {
20968     j3array[0]-=IK2PI;
20969 }
20970 else if( j3array[0] < -IKPI )
20971 {    j3array[0]+=IK2PI;
20972 }
20973 j3valid[0] = true;
20974 for(int ij3 = 0; ij3 < 1; ++ij3)
20975 {
20976 if( !j3valid[ij3] )
20977 {
20978     continue;
20979 }
20980 _ij3[0] = ij3; _ij3[1] = -1;
20981 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
20982 {
20983 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
20984 {
20985     j3valid[iij3]=false; _ij3[1] = iij3; break; 
20986 }
20987 }
20988 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
20989 {
20990 IkReal evalcond[6];
20991 IkReal x6650=IKsin(j3);
20992 IkReal x6651=IKcos(j3);
20993 IkReal x6652=((sj0)*(sj5));
20994 IkReal x6653=((r00)*(sj6));
20995 IkReal x6654=((IkReal(1.00000000000000))*(cj4));
20996 IkReal x6655=((cj6)*(r01));
20997 IkReal x6656=((cj0)*(cj5));
20998 IkReal x6657=((cj5)*(sj0));
20999 IkReal x6658=((cj6)*(r11));
21000 IkReal x6659=((cj6)*(sj4));
21001 IkReal x6660=((cj0)*(sj5));
21002 IkReal x6661=((cj4)*(cj5));
21003 IkReal x6662=((cj6)*(r21));
21004 IkReal x6663=((r20)*(sj6));
21005 IkReal x6664=((r10)*(sj6));
21006 IkReal x6665=((IkReal(1.00000000000000))*(cj0));
21007 IkReal x6666=((cj0)*(sj4)*(sj6));
21008 IkReal x6667=((sj0)*(sj4)*(sj6));
21009 evalcond[0]=((((sj5)*(x6663)))+(((sj5)*(x6662)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x6650))));
21010 evalcond[1]=((((r20)*(x6659)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj2)*(x6651)))+(((cj4)*(r22)*(sj5)))+(((x6661)*(x6662)))+(((x6661)*(x6663))));
21011 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x6657)))+(((IkReal(-1.00000000000000))*(x6658)*(x6660)))+(((IkReal(-1.00000000000000))*(x6660)*(x6664)))+(((x6652)*(x6655)))+(((r12)*(x6656)))+(((IkReal(-1.00000000000000))*(sj2)*(x6650)))+(((x6652)*(x6653))));
21012 evalcond[3]=((((r12)*(x6657)))+(((IkReal(-1.00000000000000))*(x6653)*(x6660)))+(((IkReal(-1.00000000000000))*(x6655)*(x6660)))+(((r02)*(x6656)))+(x6651)+(((IkReal(-1.00000000000000))*(x6652)*(x6664)))+(((IkReal(-1.00000000000000))*(x6652)*(x6658))));
21013 evalcond[4]=((((r11)*(x6666)))+(((IkReal(-1.00000000000000))*(r10)*(x6659)*(x6665)))+(((r00)*(sj0)*(x6659)))+(((cj4)*(x6653)*(x6657)))+(((IkReal(-1.00000000000000))*(x6654)*(x6656)*(x6658)))+(((cj4)*(r02)*(x6652)))+(((IkReal(-1.00000000000000))*(r12)*(x6654)*(x6660)))+(((sj2)*(x6651)))+(((IkReal(-1.00000000000000))*(r01)*(x6667)))+(((cj4)*(x6655)*(x6657)))+(((IkReal(-1.00000000000000))*(x6654)*(x6656)*(x6664))));
21014 evalcond[5]=((((IkReal(-1.00000000000000))*(x6654)*(x6657)*(x6664)))+(((IkReal(-1.00000000000000))*(x6653)*(x6654)*(x6656)))+(((IkReal(-1.00000000000000))*(r02)*(x6654)*(x6660)))+(((IkReal(-1.00000000000000))*(x6654)*(x6655)*(x6656)))+(((IkReal(-1.00000000000000))*(r12)*(x6652)*(x6654)))+(((IkReal(-1.00000000000000))*(r00)*(x6659)*(x6665)))+(x6650)+(((r11)*(x6667)))+(((r01)*(x6666)))+(((IkReal(-1.00000000000000))*(x6654)*(x6657)*(x6658)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6659))));
21015 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
21016 {
21017 continue;
21018 }
21019 }
21020 
21021 {
21022 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21023 vinfos[0].jointtype = 1;
21024 vinfos[0].foffset = j0;
21025 vinfos[0].indices[0] = _ij0[0];
21026 vinfos[0].indices[1] = _ij0[1];
21027 vinfos[0].maxsolutions = _nj0;
21028 vinfos[1].jointtype = 1;
21029 vinfos[1].foffset = j1;
21030 vinfos[1].indices[0] = _ij1[0];
21031 vinfos[1].indices[1] = _ij1[1];
21032 vinfos[1].maxsolutions = _nj1;
21033 vinfos[2].jointtype = 1;
21034 vinfos[2].foffset = j2;
21035 vinfos[2].indices[0] = _ij2[0];
21036 vinfos[2].indices[1] = _ij2[1];
21037 vinfos[2].maxsolutions = _nj2;
21038 vinfos[3].jointtype = 1;
21039 vinfos[3].foffset = j3;
21040 vinfos[3].indices[0] = _ij3[0];
21041 vinfos[3].indices[1] = _ij3[1];
21042 vinfos[3].maxsolutions = _nj3;
21043 vinfos[4].jointtype = 1;
21044 vinfos[4].foffset = j4;
21045 vinfos[4].indices[0] = _ij4[0];
21046 vinfos[4].indices[1] = _ij4[1];
21047 vinfos[4].maxsolutions = _nj4;
21048 vinfos[5].jointtype = 1;
21049 vinfos[5].foffset = j5;
21050 vinfos[5].indices[0] = _ij5[0];
21051 vinfos[5].indices[1] = _ij5[1];
21052 vinfos[5].maxsolutions = _nj5;
21053 vinfos[6].jointtype = 1;
21054 vinfos[6].foffset = j6;
21055 vinfos[6].indices[0] = _ij6[0];
21056 vinfos[6].indices[1] = _ij6[1];
21057 vinfos[6].maxsolutions = _nj6;
21058 std::vector<int> vfree(0);
21059 solutions.AddSolution(vinfos,vfree);
21060 }
21061 }
21062 }
21063 
21064 }
21065 
21066 }
21067 
21068 } else
21069 {
21070 {
21071 IkReal j3array[1], cj3array[1], sj3array[1];
21072 bool j3valid[1]={false};
21073 _nj3 = 1;
21074 IkReal x6668=((IkReal(1.00000000000000))*(r21));
21075 IkReal x6669=((cj4)*(cj5));
21076 IkReal x6670=((r20)*(sj6));
21077 if( IKabs(((gconst10)*(((((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6668)))+(((IkReal(-1.00000000000000))*(sj5)*(x6670))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6668)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x6669)))+(((x6669)*(x6670))))))) < IKFAST_ATAN2_MAGTHRESH )
21078     continue;
21079 j3array[0]=IKatan2(((gconst10)*(((((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6668)))+(((IkReal(-1.00000000000000))*(sj5)*(x6670)))))), ((gconst10)*(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x6668)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x6669)))+(((x6669)*(x6670)))))));
21080 sj3array[0]=IKsin(j3array[0]);
21081 cj3array[0]=IKcos(j3array[0]);
21082 if( j3array[0] > IKPI )
21083 {
21084     j3array[0]-=IK2PI;
21085 }
21086 else if( j3array[0] < -IKPI )
21087 {    j3array[0]+=IK2PI;
21088 }
21089 j3valid[0] = true;
21090 for(int ij3 = 0; ij3 < 1; ++ij3)
21091 {
21092 if( !j3valid[ij3] )
21093 {
21094     continue;
21095 }
21096 _ij3[0] = ij3; _ij3[1] = -1;
21097 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21098 {
21099 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21100 {
21101     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21102 }
21103 }
21104 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21105 {
21106 IkReal evalcond[6];
21107 IkReal x6671=IKsin(j3);
21108 IkReal x6672=IKcos(j3);
21109 IkReal x6673=((sj0)*(sj5));
21110 IkReal x6674=((r00)*(sj6));
21111 IkReal x6675=((IkReal(1.00000000000000))*(cj4));
21112 IkReal x6676=((cj6)*(r01));
21113 IkReal x6677=((cj0)*(cj5));
21114 IkReal x6678=((cj5)*(sj0));
21115 IkReal x6679=((cj6)*(r11));
21116 IkReal x6680=((cj6)*(sj4));
21117 IkReal x6681=((cj0)*(sj5));
21118 IkReal x6682=((cj4)*(cj5));
21119 IkReal x6683=((cj6)*(r21));
21120 IkReal x6684=((r20)*(sj6));
21121 IkReal x6685=((r10)*(sj6));
21122 IkReal x6686=((IkReal(1.00000000000000))*(cj0));
21123 IkReal x6687=((cj0)*(sj4)*(sj6));
21124 IkReal x6688=((sj0)*(sj4)*(sj6));
21125 evalcond[0]=((((sj5)*(x6684)))+(((sj5)*(x6683)))+(((cj2)*(x6671)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
21126 evalcond[1]=((((x6682)*(x6683)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x6682)*(x6684)))+(((r20)*(x6680)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x6672))));
21127 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x6671)))+(((IkReal(-1.00000000000000))*(x6681)*(x6685)))+(((r12)*(x6677)))+(((x6673)*(x6676)))+(((IkReal(-1.00000000000000))*(r02)*(x6678)))+(((x6673)*(x6674)))+(((IkReal(-1.00000000000000))*(x6679)*(x6681))));
21128 evalcond[3]=((((IkReal(-1.00000000000000))*(x6673)*(x6679)))+(((IkReal(-1.00000000000000))*(x6673)*(x6685)))+(((r12)*(x6678)))+(((IkReal(-1.00000000000000))*(x6674)*(x6681)))+(((IkReal(-1.00000000000000))*(x6676)*(x6681)))+(x6672)+(((r02)*(x6677))));
21129 evalcond[4]=((((r00)*(sj0)*(x6680)))+(((IkReal(-1.00000000000000))*(r01)*(x6688)))+(((sj2)*(x6672)))+(((IkReal(-1.00000000000000))*(r10)*(x6680)*(x6686)))+(((cj4)*(x6674)*(x6678)))+(((IkReal(-1.00000000000000))*(r12)*(x6675)*(x6681)))+(((IkReal(-1.00000000000000))*(x6675)*(x6677)*(x6679)))+(((cj4)*(x6676)*(x6678)))+(((cj4)*(r02)*(x6673)))+(((IkReal(-1.00000000000000))*(x6675)*(x6677)*(x6685)))+(((r11)*(x6687))));
21130 evalcond[5]=((((IkReal(-1.00000000000000))*(x6675)*(x6678)*(x6679)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x6680)))+(((IkReal(-1.00000000000000))*(x6675)*(x6676)*(x6677)))+(((r11)*(x6688)))+(((IkReal(-1.00000000000000))*(r00)*(x6680)*(x6686)))+(((IkReal(-1.00000000000000))*(x6674)*(x6675)*(x6677)))+(((IkReal(-1.00000000000000))*(r02)*(x6675)*(x6681)))+(x6671)+(((IkReal(-1.00000000000000))*(x6675)*(x6678)*(x6685)))+(((IkReal(-1.00000000000000))*(r12)*(x6673)*(x6675)))+(((r01)*(x6687))));
21131 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
21132 {
21133 continue;
21134 }
21135 }
21136 
21137 {
21138 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21139 vinfos[0].jointtype = 1;
21140 vinfos[0].foffset = j0;
21141 vinfos[0].indices[0] = _ij0[0];
21142 vinfos[0].indices[1] = _ij0[1];
21143 vinfos[0].maxsolutions = _nj0;
21144 vinfos[1].jointtype = 1;
21145 vinfos[1].foffset = j1;
21146 vinfos[1].indices[0] = _ij1[0];
21147 vinfos[1].indices[1] = _ij1[1];
21148 vinfos[1].maxsolutions = _nj1;
21149 vinfos[2].jointtype = 1;
21150 vinfos[2].foffset = j2;
21151 vinfos[2].indices[0] = _ij2[0];
21152 vinfos[2].indices[1] = _ij2[1];
21153 vinfos[2].maxsolutions = _nj2;
21154 vinfos[3].jointtype = 1;
21155 vinfos[3].foffset = j3;
21156 vinfos[3].indices[0] = _ij3[0];
21157 vinfos[3].indices[1] = _ij3[1];
21158 vinfos[3].maxsolutions = _nj3;
21159 vinfos[4].jointtype = 1;
21160 vinfos[4].foffset = j4;
21161 vinfos[4].indices[0] = _ij4[0];
21162 vinfos[4].indices[1] = _ij4[1];
21163 vinfos[4].maxsolutions = _nj4;
21164 vinfos[5].jointtype = 1;
21165 vinfos[5].foffset = j5;
21166 vinfos[5].indices[0] = _ij5[0];
21167 vinfos[5].indices[1] = _ij5[1];
21168 vinfos[5].maxsolutions = _nj5;
21169 vinfos[6].jointtype = 1;
21170 vinfos[6].foffset = j6;
21171 vinfos[6].indices[0] = _ij6[0];
21172 vinfos[6].indices[1] = _ij6[1];
21173 vinfos[6].maxsolutions = _nj6;
21174 std::vector<int> vfree(0);
21175 solutions.AddSolution(vinfos,vfree);
21176 }
21177 }
21178 }
21179 
21180 }
21181 
21182 }
21183 
21184 } else
21185 {
21186 IkReal x6689=((IkReal(1.00000000000000))*(cj0));
21187 IkReal x6690=((cj4)*(sj6));
21188 IkReal x6691=((sj0)*(sj4));
21189 IkReal x6692=((cj5)*(sj6));
21190 IkReal x6693=((sj4)*(sj5));
21191 IkReal x6694=((r12)*(sj5));
21192 IkReal x6695=((IkReal(0.374290000000000))*(cj5));
21193 IkReal x6696=((r02)*(sj0));
21194 IkReal x6697=((IkReal(1.00000000000000))*(sj0));
21195 IkReal x6698=((cj0)*(r10));
21196 IkReal x6699=((cj4)*(cj6));
21197 IkReal x6700=((r00)*(sj0));
21198 IkReal x6701=((cj6)*(r21));
21199 IkReal x6702=((IkReal(0.374290000000000))*(sj5));
21200 IkReal x6703=((IkReal(0.0100000000000000))*(sj5));
21201 IkReal x6704=((cj0)*(r02));
21202 IkReal x6705=((cj5)*(sj4));
21203 IkReal x6706=((cj6)*(r01));
21204 IkReal x6707=((cj0)*(r00));
21205 IkReal x6708=((cj6)*(r11));
21206 IkReal x6709=((r01)*(sj0));
21207 IkReal x6710=((r10)*(sj0));
21208 IkReal x6711=((IkReal(0.0100000000000000))*(cj5)*(cj6));
21209 IkReal x6712=((sj6)*(x6702));
21210 IkReal x6713=((cj0)*(cj6)*(x6702));
21211 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
21212 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x6699)))+(((r21)*(x6690)))+(((r20)*(sj4)*(x6692)))+(((IkReal(-1.00000000000000))*(cj1)))+(((x6701)*(x6705)))+(((r22)*(x6693))));
21213 evalcond[2]=((((IkReal(-0.0100000000000000))*(r20)*(x6692)))+(((IkReal(0.364420000000000))*(sj1)))+(((r20)*(x6712)))+(((IkReal(-1.00000000000000))*(r22)*(x6703)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6701)))+(pz)+(((x6701)*(x6702)))+(((IkReal(-1.00000000000000))*(r22)*(x6695))));
21214 evalcond[3]=((((cj5)*(x6691)*(x6706)))+(((IkReal(-1.00000000000000))*(x6689)*(x6705)*(x6708)))+(((IkReal(-1.00000000000000))*(r11)*(x6689)*(x6690)))+(((r02)*(sj5)*(x6691)))+(((r00)*(x6691)*(x6692)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6689)*(x6692)))+(((IkReal(-1.00000000000000))*(r12)*(x6689)*(x6693)))+(((IkReal(-1.00000000000000))*(r00)*(x6697)*(x6699)))+(((x6690)*(x6709)))+(((x6698)*(x6699))));
21215 evalcond[4]=((((x6699)*(x6707)))+(((IkReal(-1.00000000000000))*(r01)*(x6689)*(x6690)))+(((IkReal(-1.00000000000000))*(cj5)*(x6691)*(x6708)))+(sj1)+(((IkReal(-1.00000000000000))*(x6691)*(x6694)))+(((IkReal(-1.00000000000000))*(x6689)*(x6705)*(x6706)))+(((x6699)*(x6710)))+(((IkReal(-1.00000000000000))*(r02)*(x6689)*(x6693)))+(((IkReal(-1.00000000000000))*(r11)*(x6690)*(x6697)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6689)*(x6692)))+(((IkReal(-1.00000000000000))*(r10)*(x6691)*(x6692))));
21216 evalcond[5]=((IkReal(0.0690000000000000))+(((x6700)*(x6712)))+(((IkReal(-1.00000000000000))*(x6698)*(x6712)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6708)))+(((IkReal(-1.00000000000000))*(py)*(x6689)))+(((IkReal(0.0100000000000000))*(cj0)*(x6694)))+(((cj0)*(r12)*(x6695)))+(((IkReal(0.0100000000000000))*(x6692)*(x6698)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6706)))+(((sj0)*(x6702)*(x6706)))+(((IkReal(-1.00000000000000))*(cj0)*(x6702)*(x6708)))+(((IkReal(-1.00000000000000))*(x6696)*(x6703)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x6695)*(x6696)))+(((IkReal(-0.0100000000000000))*(x6692)*(x6700))));
21217 evalcond[6]=((IkReal(0.0690000000000000))+(((r12)*(sj0)*(x6695)))+(((x6703)*(x6704)))+(((IkReal(-1.00000000000000))*(cj0)*(x6702)*(x6706)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6706)))+(((IkReal(-1.00000000000000))*(x6707)*(x6712)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6708)))+(((IkReal(0.0100000000000000))*(x6692)*(x6707)))+(((x6695)*(x6704)))+(((IkReal(0.0100000000000000))*(x6692)*(x6710)))+(((IkReal(-1.00000000000000))*(py)*(x6697)))+(((IkReal(-1.00000000000000))*(px)*(x6689)))+(((IkReal(0.0100000000000000))*(sj0)*(x6694)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x6710)*(x6712)))+(((IkReal(-1.00000000000000))*(sj0)*(x6702)*(x6708))));
21218 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
21219 {
21220 {
21221 IkReal dummyeval[1];
21222 IkReal gconst11;
21223 gconst11=IKsign(sj1);
21224 dummyeval[0]=sj1;
21225 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21226 {
21227 {
21228 IkReal dummyeval[1];
21229 dummyeval[0]=sj1;
21230 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21231 {
21232 {
21233 IkReal dummyeval[1];
21234 dummyeval[0]=cj1;
21235 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21236 {
21237 {
21238 IkReal evalcond[9];
21239 IkReal x6714=((IkReal(1.00000000000000))*(cj0));
21240 IkReal x6715=((cj4)*(sj6));
21241 IkReal x6716=((sj0)*(sj6));
21242 IkReal x6717=((cj5)*(sj4));
21243 IkReal x6718=((IkReal(0.374290000000000))*(sj5));
21244 IkReal x6719=((sj4)*(sj5));
21245 IkReal x6720=((cj0)*(cj6));
21246 IkReal x6721=((IkReal(0.0100000000000000))*(cj5));
21247 IkReal x6722=((cj4)*(sj5));
21248 IkReal x6723=((cj5)*(sj0));
21249 IkReal x6724=((IkReal(0.374290000000000))*(r02));
21250 IkReal x6725=((r20)*(sj6));
21251 IkReal x6726=((cj6)*(r21));
21252 IkReal x6727=((IkReal(1.00000000000000))*(sj0));
21253 IkReal x6728=((cj0)*(sj6));
21254 IkReal x6729=((cj4)*(cj6));
21255 IkReal x6730=((IkReal(0.374290000000000))*(r12));
21256 IkReal x6731=((cj0)*(cj5));
21257 IkReal x6732=((cj6)*(sj5));
21258 IkReal x6733=((cj6)*(r01));
21259 IkReal x6734=((r00)*(sj6));
21260 IkReal x6735=((IkReal(0.0100000000000000))*(sj5));
21261 IkReal x6736=((cj6)*(r11));
21262 IkReal x6737=((IkReal(1.00000000000000))*(r10));
21263 IkReal x6738=((r02)*(sj0));
21264 IkReal x6739=((cj6)*(sj4));
21265 IkReal x6740=((r12)*(x6727));
21266 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
21267 evalcond[1]=((((x6717)*(x6726)))+(((r22)*(x6719)))+(((r21)*(x6715)))+(((x6717)*(x6725)))+(((IkReal(-1.00000000000000))*(r20)*(x6729))));
21268 evalcond[2]=((IkReal(0.364420000000000))+(((x6718)*(x6725)))+(((x6718)*(x6726)))+(((IkReal(-1.00000000000000))*(x6721)*(x6726)))+(((IkReal(-1.00000000000000))*(r22)*(x6735)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x6721)*(x6725))));
21269 evalcond[3]=((((r02)*(x6731)))+(((IkReal(-1.00000000000000))*(r01)*(x6714)*(x6732)))+(((IkReal(-1.00000000000000))*(sj5)*(x6714)*(x6734)))+(((IkReal(-1.00000000000000))*(r11)*(x6727)*(x6732)))+(((IkReal(-1.00000000000000))*(sj5)*(x6716)*(x6737)))+(((r12)*(x6723))));
21270 evalcond[4]=((((IkReal(-1.00000000000000))*(x6714)*(x6717)*(x6736)))+(((IkReal(-1.00000000000000))*(r11)*(x6714)*(x6715)))+(((sj0)*(x6717)*(x6733)))+(((r00)*(x6716)*(x6717)))+(((cj4)*(r10)*(x6720)))+(((r01)*(sj0)*(x6715)))+(((x6719)*(x6738)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6714)*(x6717)))+(((IkReal(-1.00000000000000))*(r12)*(x6714)*(x6719)))+(((IkReal(-1.00000000000000))*(r00)*(x6727)*(x6729))));
21271 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x6717)*(x6727)*(x6736)))+(((IkReal(-1.00000000000000))*(r11)*(x6715)*(x6727)))+(((IkReal(-1.00000000000000))*(r02)*(x6714)*(x6719)))+(((IkReal(-1.00000000000000))*(r01)*(x6714)*(x6715)))+(((IkReal(-1.00000000000000))*(x6716)*(x6717)*(x6737)))+(((IkReal(-1.00000000000000))*(x6714)*(x6717)*(x6734)))+(((IkReal(-1.00000000000000))*(x6714)*(x6717)*(x6733)))+(((r10)*(sj0)*(x6729)))+(((cj4)*(r00)*(x6720)))+(((IkReal(-1.00000000000000))*(x6719)*(x6740))));
21272 evalcond[6]=((IkReal(0.0690000000000000))+(((sj0)*(x6718)*(x6733)))+(((x6730)*(x6731)))+(((IkReal(-1.00000000000000))*(r11)*(x6718)*(x6720)))+(((IkReal(-1.00000000000000))*(py)*(x6714)))+(((r10)*(x6721)*(x6728)))+(((r11)*(x6720)*(x6721)))+(((IkReal(-1.00000000000000))*(x6723)*(x6724)))+(((IkReal(-1.00000000000000))*(sj0)*(x6721)*(x6733)))+(((IkReal(-1.00000000000000))*(r00)*(x6716)*(x6721)))+(((r00)*(x6716)*(x6718)))+(((cj0)*(r12)*(x6735)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x6735)*(x6738)))+(((IkReal(-1.00000000000000))*(r10)*(x6718)*(x6728))));
21273 evalcond[7]=((((IkReal(-1.00000000000000))*(x6715)*(x6723)*(x6737)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x6714)*(x6715)))+(((IkReal(-1.00000000000000))*(r02)*(x6714)*(x6722)))+(((IkReal(-1.00000000000000))*(x6722)*(x6740)))+(((r01)*(sj4)*(x6728)))+(((IkReal(-1.00000000000000))*(r10)*(x6727)*(x6739)))+(((r11)*(sj4)*(x6716)))+(((IkReal(-1.00000000000000))*(r11)*(x6723)*(x6729)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x6714)*(x6729)))+(((IkReal(-1.00000000000000))*(r00)*(x6714)*(x6739))));
21274 evalcond[8]=((IkReal(0.0690000000000000))+(((r00)*(x6721)*(x6728)))+(((IkReal(-1.00000000000000))*(r00)*(x6718)*(x6728)))+(((cj0)*(r02)*(x6735)))+(((IkReal(-1.00000000000000))*(py)*(x6727)))+(((x6723)*(x6730)))+(((IkReal(-1.00000000000000))*(px)*(x6714)))+(((r12)*(sj0)*(x6735)))+(((IkReal(-1.00000000000000))*(r10)*(x6716)*(x6718)))+(((r01)*(x6720)*(x6721)))+(((IkReal(-1.00000000000000))*(sj0)*(x6718)*(x6736)))+(((sj0)*(x6721)*(x6736)))+(((r10)*(x6716)*(x6721)))+(((IkReal(-1.00000000000000))*(r01)*(x6718)*(x6720)))+(((x6724)*(x6731))));
21275 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
21276 {
21277 {
21278 IkReal j3array[1], cj3array[1], sj3array[1];
21279 bool j3valid[1]={false};
21280 _nj3 = 1;
21281 IkReal x6741=((r20)*(sj6));
21282 IkReal x6742=((cj4)*(cj5));
21283 IkReal x6743=((cj6)*(r21));
21284 if( IKabs(((((x6742)*(x6743)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6741)*(x6742))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6741)))+(((sj5)*(x6743))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x6742)*(x6743)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6741)*(x6742)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6741)))+(((sj5)*(x6743)))))-1) <= IKFAST_SINCOS_THRESH )
21285     continue;
21286 j3array[0]=IKatan2(((((x6742)*(x6743)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6741)*(x6742)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6741)))+(((sj5)*(x6743)))));
21287 sj3array[0]=IKsin(j3array[0]);
21288 cj3array[0]=IKcos(j3array[0]);
21289 if( j3array[0] > IKPI )
21290 {
21291     j3array[0]-=IK2PI;
21292 }
21293 else if( j3array[0] < -IKPI )
21294 {    j3array[0]+=IK2PI;
21295 }
21296 j3valid[0] = true;
21297 for(int ij3 = 0; ij3 < 1; ++ij3)
21298 {
21299 if( !j3valid[ij3] )
21300 {
21301     continue;
21302 }
21303 _ij3[0] = ij3; _ij3[1] = -1;
21304 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21305 {
21306 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21307 {
21308     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21309 }
21310 }
21311 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21312 {
21313 IkReal evalcond[4];
21314 IkReal x6744=IKcos(j3);
21315 IkReal x6745=((sj0)*(sj5));
21316 IkReal x6746=((r00)*(sj6));
21317 IkReal x6747=((cj6)*(r01));
21318 IkReal x6748=((cj5)*(sj0));
21319 IkReal x6749=((cj0)*(cj5));
21320 IkReal x6750=((cj6)*(sj4));
21321 IkReal x6751=((sj4)*(sj6));
21322 IkReal x6752=((cj0)*(r11));
21323 IkReal x6753=((cj4)*(cj6));
21324 IkReal x6754=((cj4)*(sj6));
21325 IkReal x6755=((IkReal(1.00000000000000))*(cj0));
21326 IkReal x6756=((cj4)*(sj5));
21327 IkReal x6757=((sj5)*(sj6));
21328 IkReal x6758=((cj6)*(sj5));
21329 IkReal x6759=((IkReal(1.00000000000000))*(IKsin(j3)));
21330 evalcond[0]=((((r21)*(x6758)))+(((IkReal(-1.00000000000000))*(x6744)))+(((r20)*(x6757)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
21331 evalcond[1]=((((cj5)*(r20)*(x6754)))+(((r22)*(x6756)))+(((cj5)*(r21)*(x6753)))+(((IkReal(-1.00000000000000))*(r21)*(x6751)))+(((r20)*(x6750)))+(((IkReal(-1.00000000000000))*(x6759))));
21332 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x6755)*(x6757)))+(((IkReal(-1.00000000000000))*(r02)*(x6748)))+(((r12)*(x6749)))+(((x6745)*(x6747)))+(((IkReal(-1.00000000000000))*(x6759)))+(((x6745)*(x6746)))+(((IkReal(-1.00000000000000))*(x6752)*(x6758))));
21333 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x6755)*(x6756)))+(((IkReal(-1.00000000000000))*(r10)*(x6750)*(x6755)))+(((cj4)*(x6747)*(x6748)))+(((IkReal(-1.00000000000000))*(r10)*(x6749)*(x6754)))+(((cj4)*(r02)*(x6745)))+(((r00)*(sj0)*(x6750)))+(((IkReal(-1.00000000000000))*(r11)*(x6749)*(x6753)))+(((cj4)*(x6746)*(x6748)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x6751)))+(x6744)+(((x6751)*(x6752))));
21334 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
21335 {
21336 continue;
21337 }
21338 }
21339 
21340 {
21341 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21342 vinfos[0].jointtype = 1;
21343 vinfos[0].foffset = j0;
21344 vinfos[0].indices[0] = _ij0[0];
21345 vinfos[0].indices[1] = _ij0[1];
21346 vinfos[0].maxsolutions = _nj0;
21347 vinfos[1].jointtype = 1;
21348 vinfos[1].foffset = j1;
21349 vinfos[1].indices[0] = _ij1[0];
21350 vinfos[1].indices[1] = _ij1[1];
21351 vinfos[1].maxsolutions = _nj1;
21352 vinfos[2].jointtype = 1;
21353 vinfos[2].foffset = j2;
21354 vinfos[2].indices[0] = _ij2[0];
21355 vinfos[2].indices[1] = _ij2[1];
21356 vinfos[2].maxsolutions = _nj2;
21357 vinfos[3].jointtype = 1;
21358 vinfos[3].foffset = j3;
21359 vinfos[3].indices[0] = _ij3[0];
21360 vinfos[3].indices[1] = _ij3[1];
21361 vinfos[3].maxsolutions = _nj3;
21362 vinfos[4].jointtype = 1;
21363 vinfos[4].foffset = j4;
21364 vinfos[4].indices[0] = _ij4[0];
21365 vinfos[4].indices[1] = _ij4[1];
21366 vinfos[4].maxsolutions = _nj4;
21367 vinfos[5].jointtype = 1;
21368 vinfos[5].foffset = j5;
21369 vinfos[5].indices[0] = _ij5[0];
21370 vinfos[5].indices[1] = _ij5[1];
21371 vinfos[5].maxsolutions = _nj5;
21372 vinfos[6].jointtype = 1;
21373 vinfos[6].foffset = j6;
21374 vinfos[6].indices[0] = _ij6[0];
21375 vinfos[6].indices[1] = _ij6[1];
21376 vinfos[6].maxsolutions = _nj6;
21377 std::vector<int> vfree(0);
21378 solutions.AddSolution(vinfos,vfree);
21379 }
21380 }
21381 }
21382 
21383 } else
21384 {
21385 IkReal x6760=((IkReal(1.00000000000000))*(cj0));
21386 IkReal x6761=((cj4)*(sj6));
21387 IkReal x6762=((sj0)*(sj6));
21388 IkReal x6763=((cj5)*(sj4));
21389 IkReal x6764=((IkReal(0.374290000000000))*(sj5));
21390 IkReal x6765=((sj4)*(sj5));
21391 IkReal x6766=((cj0)*(cj6));
21392 IkReal x6767=((IkReal(0.0100000000000000))*(cj5));
21393 IkReal x6768=((cj4)*(sj5));
21394 IkReal x6769=((cj5)*(sj0));
21395 IkReal x6770=((IkReal(0.374290000000000))*(r02));
21396 IkReal x6771=((r20)*(sj6));
21397 IkReal x6772=((cj6)*(r21));
21398 IkReal x6773=((IkReal(1.00000000000000))*(sj0));
21399 IkReal x6774=((cj0)*(sj6));
21400 IkReal x6775=((cj4)*(cj6));
21401 IkReal x6776=((IkReal(0.374290000000000))*(r12));
21402 IkReal x6777=((cj0)*(cj5));
21403 IkReal x6778=((cj6)*(sj5));
21404 IkReal x6779=((cj6)*(r01));
21405 IkReal x6780=((r00)*(sj6));
21406 IkReal x6781=((IkReal(0.0100000000000000))*(sj5));
21407 IkReal x6782=((cj6)*(r11));
21408 IkReal x6783=((IkReal(1.00000000000000))*(r10));
21409 IkReal x6784=((r02)*(sj0));
21410 IkReal x6785=((cj6)*(sj4));
21411 IkReal x6786=((r12)*(x6773));
21412 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
21413 evalcond[1]=((((r22)*(x6765)))+(((x6763)*(x6772)))+(((r21)*(x6761)))+(((x6763)*(x6771)))+(((IkReal(-1.00000000000000))*(r20)*(x6775))));
21414 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x6767)*(x6772)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x6781)))+(((x6764)*(x6771)))+(((x6764)*(x6772)))+(pz)+(((IkReal(-1.00000000000000))*(x6767)*(x6771))));
21415 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x6773)*(x6778)))+(((r02)*(x6777)))+(((IkReal(-1.00000000000000))*(sj5)*(x6762)*(x6783)))+(((IkReal(-1.00000000000000))*(r01)*(x6760)*(x6778)))+(((r12)*(x6769)))+(((IkReal(-1.00000000000000))*(sj5)*(x6760)*(x6780))));
21416 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x6773)*(x6775)))+(((IkReal(-1.00000000000000))*(r12)*(x6760)*(x6765)))+(((cj4)*(r10)*(x6766)))+(((r00)*(x6762)*(x6763)))+(((sj0)*(x6763)*(x6779)))+(((r01)*(sj0)*(x6761)))+(((x6765)*(x6784)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6760)*(x6763)))+(((IkReal(-1.00000000000000))*(x6760)*(x6763)*(x6782)))+(((IkReal(-1.00000000000000))*(r11)*(x6760)*(x6761))));
21417 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x6760)*(x6763)*(x6780)))+(((IkReal(-1.00000000000000))*(r02)*(x6760)*(x6765)))+(((r10)*(sj0)*(x6775)))+(((IkReal(-1.00000000000000))*(x6760)*(x6763)*(x6779)))+(((IkReal(-1.00000000000000))*(x6762)*(x6763)*(x6783)))+(((IkReal(-1.00000000000000))*(r11)*(x6761)*(x6773)))+(((IkReal(-1.00000000000000))*(x6763)*(x6773)*(x6782)))+(((IkReal(-1.00000000000000))*(x6765)*(x6786)))+(((cj4)*(r00)*(x6766)))+(((IkReal(-1.00000000000000))*(r01)*(x6760)*(x6761))));
21418 evalcond[6]=((IkReal(0.0690000000000000))+(((r10)*(x6767)*(x6774)))+(((IkReal(-1.00000000000000))*(r11)*(x6764)*(x6766)))+(((IkReal(-1.00000000000000))*(x6769)*(x6770)))+(((r11)*(x6766)*(x6767)))+(((cj0)*(r12)*(x6781)))+(((IkReal(-1.00000000000000))*(r00)*(x6762)*(x6767)))+(((r00)*(x6762)*(x6764)))+(((IkReal(-1.00000000000000))*(r10)*(x6764)*(x6774)))+(((IkReal(-1.00000000000000))*(x6781)*(x6784)))+(((sj0)*(x6764)*(x6779)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x6767)*(x6779)))+(((IkReal(-1.00000000000000))*(py)*(x6760)))+(((x6776)*(x6777))));
21419 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x6760)*(x6785)))+(((IkReal(-1.00000000000000))*(r10)*(x6773)*(x6785)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x6760)*(x6761)))+(((IkReal(-1.00000000000000))*(r02)*(x6760)*(x6768)))+(((IkReal(-1.00000000000000))*(r11)*(x6769)*(x6775)))+(((IkReal(-1.00000000000000))*(x6761)*(x6769)*(x6783)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x6760)*(x6775)))+(((IkReal(-1.00000000000000))*(x6768)*(x6786)))+(((r01)*(sj4)*(x6774)))+(((r11)*(sj4)*(x6762))));
21420 evalcond[8]=((IkReal(0.0690000000000000))+(((r00)*(x6767)*(x6774)))+(((x6770)*(x6777)))+(((IkReal(-1.00000000000000))*(py)*(x6773)))+(((IkReal(-1.00000000000000))*(r10)*(x6762)*(x6764)))+(((r01)*(x6766)*(x6767)))+(((cj0)*(r02)*(x6781)))+(((IkReal(-1.00000000000000))*(r01)*(x6764)*(x6766)))+(((x6769)*(x6776)))+(((IkReal(-1.00000000000000))*(px)*(x6760)))+(((sj0)*(x6767)*(x6782)))+(((r10)*(x6762)*(x6767)))+(((IkReal(-1.00000000000000))*(r00)*(x6764)*(x6774)))+(((IkReal(-1.00000000000000))*(sj0)*(x6764)*(x6782)))+(((r12)*(sj0)*(x6781))));
21421 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
21422 {
21423 {
21424 IkReal j3array[1], cj3array[1], sj3array[1];
21425 bool j3valid[1]={false};
21426 _nj3 = 1;
21427 IkReal x6787=((IkReal(1.00000000000000))*(sj5));
21428 IkReal x6788=((cj6)*(r21));
21429 IkReal x6789=((r20)*(sj6));
21430 IkReal x6790=((IkReal(1.00000000000000))*(cj4)*(cj5));
21431 if( IKabs(((((IkReal(-1.00000000000000))*(x6788)*(x6790)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6787)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x6789)*(x6790)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x6787)*(x6788)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x6787)*(x6789))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x6788)*(x6790)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6787)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x6789)*(x6790)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x6787)*(x6788)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x6787)*(x6789)))))-1) <= IKFAST_SINCOS_THRESH )
21432     continue;
21433 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x6788)*(x6790)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6787)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x6789)*(x6790)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x6787)*(x6788)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x6787)*(x6789)))));
21434 sj3array[0]=IKsin(j3array[0]);
21435 cj3array[0]=IKcos(j3array[0]);
21436 if( j3array[0] > IKPI )
21437 {
21438     j3array[0]-=IK2PI;
21439 }
21440 else if( j3array[0] < -IKPI )
21441 {    j3array[0]+=IK2PI;
21442 }
21443 j3valid[0] = true;
21444 for(int ij3 = 0; ij3 < 1; ++ij3)
21445 {
21446 if( !j3valid[ij3] )
21447 {
21448     continue;
21449 }
21450 _ij3[0] = ij3; _ij3[1] = -1;
21451 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21452 {
21453 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21454 {
21455     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21456 }
21457 }
21458 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21459 {
21460 IkReal evalcond[4];
21461 IkReal x6791=IKsin(j3);
21462 IkReal x6792=IKcos(j3);
21463 IkReal x6793=((sj0)*(sj5));
21464 IkReal x6794=((r00)*(sj6));
21465 IkReal x6795=((cj6)*(r01));
21466 IkReal x6796=((cj5)*(sj0));
21467 IkReal x6797=((cj0)*(cj5));
21468 IkReal x6798=((cj6)*(sj4));
21469 IkReal x6799=((sj4)*(sj6));
21470 IkReal x6800=((cj0)*(r11));
21471 IkReal x6801=((cj4)*(cj6));
21472 IkReal x6802=((cj4)*(sj6));
21473 IkReal x6803=((IkReal(1.00000000000000))*(cj0));
21474 IkReal x6804=((cj4)*(sj5));
21475 IkReal x6805=((sj5)*(sj6));
21476 IkReal x6806=((cj6)*(sj5));
21477 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x6792)+(((r21)*(x6806)))+(((r20)*(x6805))));
21478 evalcond[1]=((((cj5)*(r21)*(x6801)))+(((IkReal(-1.00000000000000))*(r21)*(x6799)))+(((r20)*(x6798)))+(((cj5)*(r20)*(x6802)))+(((r22)*(x6804)))+(x6791));
21479 evalcond[2]=((((IkReal(-1.00000000000000))*(x6791)))+(((r12)*(x6797)))+(((x6793)*(x6794)))+(((IkReal(-1.00000000000000))*(x6800)*(x6806)))+(((IkReal(-1.00000000000000))*(r02)*(x6796)))+(((x6793)*(x6795)))+(((IkReal(-1.00000000000000))*(r10)*(x6803)*(x6805))));
21480 evalcond[3]=((((cj4)*(x6794)*(x6796)))+(((IkReal(-1.00000000000000))*(r10)*(x6797)*(x6802)))+(((cj4)*(x6795)*(x6796)))+(((x6799)*(x6800)))+(((IkReal(-1.00000000000000))*(r12)*(x6803)*(x6804)))+(((r00)*(sj0)*(x6798)))+(((cj4)*(r02)*(x6793)))+(x6792)+(((IkReal(-1.00000000000000))*(r11)*(x6797)*(x6801)))+(((IkReal(-1.00000000000000))*(r10)*(x6798)*(x6803)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x6799))));
21481 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
21482 {
21483 continue;
21484 }
21485 }
21486 
21487 {
21488 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21489 vinfos[0].jointtype = 1;
21490 vinfos[0].foffset = j0;
21491 vinfos[0].indices[0] = _ij0[0];
21492 vinfos[0].indices[1] = _ij0[1];
21493 vinfos[0].maxsolutions = _nj0;
21494 vinfos[1].jointtype = 1;
21495 vinfos[1].foffset = j1;
21496 vinfos[1].indices[0] = _ij1[0];
21497 vinfos[1].indices[1] = _ij1[1];
21498 vinfos[1].maxsolutions = _nj1;
21499 vinfos[2].jointtype = 1;
21500 vinfos[2].foffset = j2;
21501 vinfos[2].indices[0] = _ij2[0];
21502 vinfos[2].indices[1] = _ij2[1];
21503 vinfos[2].maxsolutions = _nj2;
21504 vinfos[3].jointtype = 1;
21505 vinfos[3].foffset = j3;
21506 vinfos[3].indices[0] = _ij3[0];
21507 vinfos[3].indices[1] = _ij3[1];
21508 vinfos[3].maxsolutions = _nj3;
21509 vinfos[4].jointtype = 1;
21510 vinfos[4].foffset = j4;
21511 vinfos[4].indices[0] = _ij4[0];
21512 vinfos[4].indices[1] = _ij4[1];
21513 vinfos[4].maxsolutions = _nj4;
21514 vinfos[5].jointtype = 1;
21515 vinfos[5].foffset = j5;
21516 vinfos[5].indices[0] = _ij5[0];
21517 vinfos[5].indices[1] = _ij5[1];
21518 vinfos[5].maxsolutions = _nj5;
21519 vinfos[6].jointtype = 1;
21520 vinfos[6].foffset = j6;
21521 vinfos[6].indices[0] = _ij6[0];
21522 vinfos[6].indices[1] = _ij6[1];
21523 vinfos[6].maxsolutions = _nj6;
21524 std::vector<int> vfree(0);
21525 solutions.AddSolution(vinfos,vfree);
21526 }
21527 }
21528 }
21529 
21530 } else
21531 {
21532 if( 1 )
21533 {
21534 continue;
21535 
21536 } else
21537 {
21538 }
21539 }
21540 }
21541 }
21542 
21543 } else
21544 {
21545 {
21546 IkReal j3array[1], cj3array[1], sj3array[1];
21547 bool j3valid[1]={false};
21548 _nj3 = 1;
21549 IkReal x6807=((cj0)*(cj5));
21550 IkReal x6808=((IkReal(1.00000000000000))*(cj0));
21551 IkReal x6809=((cj6)*(r11));
21552 IkReal x6810=((r10)*(sj6));
21553 IkReal x6811=((cj5)*(sj0));
21554 IkReal x6812=((r00)*(sj5)*(sj6));
21555 IkReal x6813=((cj6)*(r01)*(sj5));
21556 IkReal x6814=((IkReal(1.00000000000000))*(sj0)*(sj5));
21557 if( IKabs(((((sj0)*(x6813)))+(((sj0)*(x6812)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6810)))+(((r12)*(x6807)))+(((IkReal(-1.00000000000000))*(r02)*(x6811)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6809))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x6810)*(x6814)))+(((IkReal(-1.00000000000000))*(x6808)*(x6813)))+(((IkReal(-1.00000000000000))*(x6809)*(x6814)))+(((r12)*(x6811)))+(((IkReal(-1.00000000000000))*(x6808)*(x6812)))+(((r02)*(x6807))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x6813)))+(((sj0)*(x6812)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6810)))+(((r12)*(x6807)))+(((IkReal(-1.00000000000000))*(r02)*(x6811)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6809)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x6810)*(x6814)))+(((IkReal(-1.00000000000000))*(x6808)*(x6813)))+(((IkReal(-1.00000000000000))*(x6809)*(x6814)))+(((r12)*(x6811)))+(((IkReal(-1.00000000000000))*(x6808)*(x6812)))+(((r02)*(x6807)))))))-1) <= IKFAST_SINCOS_THRESH )
21558     continue;
21559 j3array[0]=IKatan2(((((sj0)*(x6813)))+(((sj0)*(x6812)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6810)))+(((r12)*(x6807)))+(((IkReal(-1.00000000000000))*(r02)*(x6811)))+(((IkReal(-1.00000000000000))*(sj5)*(x6808)*(x6809)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x6810)*(x6814)))+(((IkReal(-1.00000000000000))*(x6808)*(x6813)))+(((IkReal(-1.00000000000000))*(x6809)*(x6814)))+(((r12)*(x6811)))+(((IkReal(-1.00000000000000))*(x6808)*(x6812)))+(((r02)*(x6807)))))));
21560 sj3array[0]=IKsin(j3array[0]);
21561 cj3array[0]=IKcos(j3array[0]);
21562 if( j3array[0] > IKPI )
21563 {
21564     j3array[0]-=IK2PI;
21565 }
21566 else if( j3array[0] < -IKPI )
21567 {    j3array[0]+=IK2PI;
21568 }
21569 j3valid[0] = true;
21570 for(int ij3 = 0; ij3 < 1; ++ij3)
21571 {
21572 if( !j3valid[ij3] )
21573 {
21574     continue;
21575 }
21576 _ij3[0] = ij3; _ij3[1] = -1;
21577 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21578 {
21579 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21580 {
21581     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21582 }
21583 }
21584 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21585 {
21586 IkReal evalcond[6];
21587 IkReal x6815=IKsin(j3);
21588 IkReal x6816=IKcos(j3);
21589 IkReal x6817=((sj0)*(sj5));
21590 IkReal x6818=((r00)*(sj6));
21591 IkReal x6819=((cj6)*(r01));
21592 IkReal x6820=((cj4)*(cj5));
21593 IkReal x6821=((IkReal(1.00000000000000))*(cj0));
21594 IkReal x6822=((cj5)*(r12));
21595 IkReal x6823=((IkReal(1.00000000000000))*(sj0));
21596 IkReal x6824=((cj6)*(r11));
21597 IkReal x6825=((cj5)*(r02));
21598 IkReal x6826=((IkReal(1.00000000000000))*(cj1));
21599 IkReal x6827=((cj6)*(sj4));
21600 IkReal x6828=((cj6)*(r21));
21601 IkReal x6829=((r20)*(sj6));
21602 IkReal x6830=((r10)*(sj6));
21603 IkReal x6831=((sj4)*(sj6));
21604 IkReal x6832=((cj4)*(r02));
21605 IkReal x6833=((IkReal(1.00000000000000))*(cj4)*(r12));
21606 IkReal x6834=((IkReal(1.00000000000000))*(x6815));
21607 IkReal x6835=((cj0)*(x6831));
21608 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x6816)))+(((sj5)*(x6829)))+(((sj5)*(x6828)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
21609 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x6834)))+(((r20)*(x6827)))+(((x6820)*(x6829)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x6831)))+(((x6820)*(x6828))));
21610 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x6821)*(x6824)))+(((cj0)*(x6822)))+(((IkReal(-1.00000000000000))*(sj5)*(x6821)*(x6830)))+(((x6817)*(x6819)))+(((IkReal(-1.00000000000000))*(x6834)))+(((x6817)*(x6818)))+(((IkReal(-1.00000000000000))*(x6823)*(x6825))));
21611 evalcond[3]=((((sj0)*(x6822)))+(((IkReal(-1.00000000000000))*(x6817)*(x6830)))+(((IkReal(-1.00000000000000))*(sj5)*(x6818)*(x6821)))+(((cj0)*(x6825)))+(((IkReal(-1.00000000000000))*(x6817)*(x6824)))+(((IkReal(-1.00000000000000))*(sj5)*(x6819)*(x6821)))+(((IkReal(-1.00000000000000))*(x6816)*(x6826))));
21612 evalcond[4]=((((x6817)*(x6832)))+(((IkReal(-1.00000000000000))*(x6820)*(x6821)*(x6830)))+(((sj0)*(x6819)*(x6820)))+(((IkReal(-1.00000000000000))*(r01)*(x6823)*(x6831)))+(((IkReal(-1.00000000000000))*(x6820)*(x6821)*(x6824)))+(((r00)*(sj0)*(x6827)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x6821)))+(((r11)*(x6835)))+(((sj0)*(x6818)*(x6820)))+(((IkReal(-1.00000000000000))*(r10)*(x6821)*(x6827)))+(x6816));
21613 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x6823)*(x6827)))+(((IkReal(-1.00000000000000))*(x6819)*(x6820)*(x6821)))+(((IkReal(-1.00000000000000))*(sj5)*(x6821)*(x6832)))+(((IkReal(-1.00000000000000))*(x6817)*(x6833)))+(((IkReal(-1.00000000000000))*(x6820)*(x6823)*(x6824)))+(((IkReal(-1.00000000000000))*(x6818)*(x6820)*(x6821)))+(((IkReal(-1.00000000000000))*(x6815)*(x6826)))+(((r11)*(sj0)*(x6831)))+(((IkReal(-1.00000000000000))*(r00)*(x6821)*(x6827)))+(((r01)*(x6835)))+(((IkReal(-1.00000000000000))*(x6820)*(x6823)*(x6830))));
21614 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
21615 {
21616 continue;
21617 }
21618 }
21619 
21620 {
21621 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21622 vinfos[0].jointtype = 1;
21623 vinfos[0].foffset = j0;
21624 vinfos[0].indices[0] = _ij0[0];
21625 vinfos[0].indices[1] = _ij0[1];
21626 vinfos[0].maxsolutions = _nj0;
21627 vinfos[1].jointtype = 1;
21628 vinfos[1].foffset = j1;
21629 vinfos[1].indices[0] = _ij1[0];
21630 vinfos[1].indices[1] = _ij1[1];
21631 vinfos[1].maxsolutions = _nj1;
21632 vinfos[2].jointtype = 1;
21633 vinfos[2].foffset = j2;
21634 vinfos[2].indices[0] = _ij2[0];
21635 vinfos[2].indices[1] = _ij2[1];
21636 vinfos[2].maxsolutions = _nj2;
21637 vinfos[3].jointtype = 1;
21638 vinfos[3].foffset = j3;
21639 vinfos[3].indices[0] = _ij3[0];
21640 vinfos[3].indices[1] = _ij3[1];
21641 vinfos[3].maxsolutions = _nj3;
21642 vinfos[4].jointtype = 1;
21643 vinfos[4].foffset = j4;
21644 vinfos[4].indices[0] = _ij4[0];
21645 vinfos[4].indices[1] = _ij4[1];
21646 vinfos[4].maxsolutions = _nj4;
21647 vinfos[5].jointtype = 1;
21648 vinfos[5].foffset = j5;
21649 vinfos[5].indices[0] = _ij5[0];
21650 vinfos[5].indices[1] = _ij5[1];
21651 vinfos[5].maxsolutions = _nj5;
21652 vinfos[6].jointtype = 1;
21653 vinfos[6].foffset = j6;
21654 vinfos[6].indices[0] = _ij6[0];
21655 vinfos[6].indices[1] = _ij6[1];
21656 vinfos[6].maxsolutions = _nj6;
21657 std::vector<int> vfree(0);
21658 solutions.AddSolution(vinfos,vfree);
21659 }
21660 }
21661 }
21662 
21663 }
21664 
21665 }
21666 
21667 } else
21668 {
21669 {
21670 IkReal j3array[1], cj3array[1], sj3array[1];
21671 bool j3valid[1]={false};
21672 _nj3 = 1;
21673 IkReal x6836=((sj5)*(sj6));
21674 IkReal x6837=((cj6)*(sj5));
21675 IkReal x6838=((IkReal(1.00000000000000))*(cj0));
21676 IkReal x6839=((IkReal(1.00000000000000))*(cj5));
21677 if( IKabs(((((r01)*(sj0)*(x6837)))+(((IkReal(-1.00000000000000))*(r11)*(x6837)*(x6838)))+(((r00)*(sj0)*(x6836)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6839)))+(((IkReal(-1.00000000000000))*(r10)*(x6836)*(x6838))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x6839)))+(((r21)*(x6837)))+(((r20)*(x6836))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r01)*(sj0)*(x6837)))+(((IkReal(-1.00000000000000))*(r11)*(x6837)*(x6838)))+(((r00)*(sj0)*(x6836)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6839)))+(((IkReal(-1.00000000000000))*(r10)*(x6836)*(x6838)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x6839)))+(((r21)*(x6837)))+(((r20)*(x6836)))))))-1) <= IKFAST_SINCOS_THRESH )
21678     continue;
21679 j3array[0]=IKatan2(((((r01)*(sj0)*(x6837)))+(((IkReal(-1.00000000000000))*(r11)*(x6837)*(x6838)))+(((r00)*(sj0)*(x6836)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6839)))+(((IkReal(-1.00000000000000))*(r10)*(x6836)*(x6838)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x6839)))+(((r21)*(x6837)))+(((r20)*(x6836)))))));
21680 sj3array[0]=IKsin(j3array[0]);
21681 cj3array[0]=IKcos(j3array[0]);
21682 if( j3array[0] > IKPI )
21683 {
21684     j3array[0]-=IK2PI;
21685 }
21686 else if( j3array[0] < -IKPI )
21687 {    j3array[0]+=IK2PI;
21688 }
21689 j3valid[0] = true;
21690 for(int ij3 = 0; ij3 < 1; ++ij3)
21691 {
21692 if( !j3valid[ij3] )
21693 {
21694     continue;
21695 }
21696 _ij3[0] = ij3; _ij3[1] = -1;
21697 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21698 {
21699 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21700 {
21701     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21702 }
21703 }
21704 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21705 {
21706 IkReal evalcond[6];
21707 IkReal x6840=IKsin(j3);
21708 IkReal x6841=IKcos(j3);
21709 IkReal x6842=((sj0)*(sj5));
21710 IkReal x6843=((r00)*(sj6));
21711 IkReal x6844=((cj6)*(r01));
21712 IkReal x6845=((cj4)*(cj5));
21713 IkReal x6846=((IkReal(1.00000000000000))*(cj0));
21714 IkReal x6847=((cj5)*(r12));
21715 IkReal x6848=((IkReal(1.00000000000000))*(sj0));
21716 IkReal x6849=((cj6)*(r11));
21717 IkReal x6850=((cj5)*(r02));
21718 IkReal x6851=((IkReal(1.00000000000000))*(cj1));
21719 IkReal x6852=((cj6)*(sj4));
21720 IkReal x6853=((cj6)*(r21));
21721 IkReal x6854=((r20)*(sj6));
21722 IkReal x6855=((r10)*(sj6));
21723 IkReal x6856=((sj4)*(sj6));
21724 IkReal x6857=((cj4)*(r02));
21725 IkReal x6858=((IkReal(1.00000000000000))*(cj4)*(r12));
21726 IkReal x6859=((IkReal(1.00000000000000))*(x6840));
21727 IkReal x6860=((cj0)*(x6856));
21728 evalcond[0]=((((sj5)*(x6853)))+(((sj5)*(x6854)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x6841))));
21729 evalcond[1]=((((x6845)*(x6853)))+(((IkReal(-1.00000000000000))*(sj1)*(x6859)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x6852)))+(((IkReal(-1.00000000000000))*(r21)*(x6856)))+(((x6845)*(x6854))));
21730 evalcond[2]=((((IkReal(-1.00000000000000))*(x6848)*(x6850)))+(((x6842)*(x6844)))+(((IkReal(-1.00000000000000))*(sj5)*(x6846)*(x6849)))+(((x6842)*(x6843)))+(((IkReal(-1.00000000000000))*(sj5)*(x6846)*(x6855)))+(((IkReal(-1.00000000000000))*(x6859)))+(((cj0)*(x6847))));
21731 evalcond[3]=((((IkReal(-1.00000000000000))*(x6842)*(x6849)))+(((IkReal(-1.00000000000000))*(sj5)*(x6843)*(x6846)))+(((IkReal(-1.00000000000000))*(x6841)*(x6851)))+(((IkReal(-1.00000000000000))*(x6842)*(x6855)))+(((cj0)*(x6850)))+(((IkReal(-1.00000000000000))*(sj5)*(x6844)*(x6846)))+(((sj0)*(x6847))));
21732 evalcond[4]=((((r11)*(x6860)))+(((r00)*(sj0)*(x6852)))+(((x6842)*(x6857)))+(x6841)+(((IkReal(-1.00000000000000))*(r10)*(x6846)*(x6852)))+(((IkReal(-1.00000000000000))*(r01)*(x6848)*(x6856)))+(((IkReal(-1.00000000000000))*(x6845)*(x6846)*(x6855)))+(((IkReal(-1.00000000000000))*(x6845)*(x6846)*(x6849)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x6846)))+(((sj0)*(x6843)*(x6845)))+(((sj0)*(x6844)*(x6845))));
21733 evalcond[5]=((((IkReal(-1.00000000000000))*(x6842)*(x6858)))+(((IkReal(-1.00000000000000))*(x6840)*(x6851)))+(((IkReal(-1.00000000000000))*(x6844)*(x6845)*(x6846)))+(((r01)*(x6860)))+(((IkReal(-1.00000000000000))*(x6845)*(x6848)*(x6849)))+(((IkReal(-1.00000000000000))*(x6845)*(x6848)*(x6855)))+(((IkReal(-1.00000000000000))*(sj5)*(x6846)*(x6857)))+(((IkReal(-1.00000000000000))*(r10)*(x6848)*(x6852)))+(((r11)*(sj0)*(x6856)))+(((IkReal(-1.00000000000000))*(r00)*(x6846)*(x6852)))+(((IkReal(-1.00000000000000))*(x6843)*(x6845)*(x6846))));
21734 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
21735 {
21736 continue;
21737 }
21738 }
21739 
21740 {
21741 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21742 vinfos[0].jointtype = 1;
21743 vinfos[0].foffset = j0;
21744 vinfos[0].indices[0] = _ij0[0];
21745 vinfos[0].indices[1] = _ij0[1];
21746 vinfos[0].maxsolutions = _nj0;
21747 vinfos[1].jointtype = 1;
21748 vinfos[1].foffset = j1;
21749 vinfos[1].indices[0] = _ij1[0];
21750 vinfos[1].indices[1] = _ij1[1];
21751 vinfos[1].maxsolutions = _nj1;
21752 vinfos[2].jointtype = 1;
21753 vinfos[2].foffset = j2;
21754 vinfos[2].indices[0] = _ij2[0];
21755 vinfos[2].indices[1] = _ij2[1];
21756 vinfos[2].maxsolutions = _nj2;
21757 vinfos[3].jointtype = 1;
21758 vinfos[3].foffset = j3;
21759 vinfos[3].indices[0] = _ij3[0];
21760 vinfos[3].indices[1] = _ij3[1];
21761 vinfos[3].maxsolutions = _nj3;
21762 vinfos[4].jointtype = 1;
21763 vinfos[4].foffset = j4;
21764 vinfos[4].indices[0] = _ij4[0];
21765 vinfos[4].indices[1] = _ij4[1];
21766 vinfos[4].maxsolutions = _nj4;
21767 vinfos[5].jointtype = 1;
21768 vinfos[5].foffset = j5;
21769 vinfos[5].indices[0] = _ij5[0];
21770 vinfos[5].indices[1] = _ij5[1];
21771 vinfos[5].maxsolutions = _nj5;
21772 vinfos[6].jointtype = 1;
21773 vinfos[6].foffset = j6;
21774 vinfos[6].indices[0] = _ij6[0];
21775 vinfos[6].indices[1] = _ij6[1];
21776 vinfos[6].maxsolutions = _nj6;
21777 std::vector<int> vfree(0);
21778 solutions.AddSolution(vinfos,vfree);
21779 }
21780 }
21781 }
21782 
21783 }
21784 
21785 }
21786 
21787 } else
21788 {
21789 {
21790 IkReal j3array[1], cj3array[1], sj3array[1];
21791 bool j3valid[1]={false};
21792 _nj3 = 1;
21793 IkReal x6861=((r20)*(sj6));
21794 IkReal x6862=((cj4)*(cj5));
21795 IkReal x6863=((cj6)*(r21));
21796 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6861)*(x6862)))+(((x6862)*(x6863))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((sj5)*(x6863)))+(((sj5)*(x6861)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH )
21797     continue;
21798 j3array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6861)*(x6862)))+(((x6862)*(x6863)))))), ((gconst11)*(((((sj5)*(x6863)))+(((sj5)*(x6861)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))));
21799 sj3array[0]=IKsin(j3array[0]);
21800 cj3array[0]=IKcos(j3array[0]);
21801 if( j3array[0] > IKPI )
21802 {
21803     j3array[0]-=IK2PI;
21804 }
21805 else if( j3array[0] < -IKPI )
21806 {    j3array[0]+=IK2PI;
21807 }
21808 j3valid[0] = true;
21809 for(int ij3 = 0; ij3 < 1; ++ij3)
21810 {
21811 if( !j3valid[ij3] )
21812 {
21813     continue;
21814 }
21815 _ij3[0] = ij3; _ij3[1] = -1;
21816 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
21817 {
21818 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
21819 {
21820     j3valid[iij3]=false; _ij3[1] = iij3; break; 
21821 }
21822 }
21823 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
21824 {
21825 IkReal evalcond[6];
21826 IkReal x6864=IKsin(j3);
21827 IkReal x6865=IKcos(j3);
21828 IkReal x6866=((sj0)*(sj5));
21829 IkReal x6867=((r00)*(sj6));
21830 IkReal x6868=((cj6)*(r01));
21831 IkReal x6869=((cj4)*(cj5));
21832 IkReal x6870=((IkReal(1.00000000000000))*(cj0));
21833 IkReal x6871=((cj5)*(r12));
21834 IkReal x6872=((IkReal(1.00000000000000))*(sj0));
21835 IkReal x6873=((cj6)*(r11));
21836 IkReal x6874=((cj5)*(r02));
21837 IkReal x6875=((IkReal(1.00000000000000))*(cj1));
21838 IkReal x6876=((cj6)*(sj4));
21839 IkReal x6877=((cj6)*(r21));
21840 IkReal x6878=((r20)*(sj6));
21841 IkReal x6879=((r10)*(sj6));
21842 IkReal x6880=((sj4)*(sj6));
21843 IkReal x6881=((cj4)*(r02));
21844 IkReal x6882=((IkReal(1.00000000000000))*(cj4)*(r12));
21845 IkReal x6883=((IkReal(1.00000000000000))*(x6864));
21846 IkReal x6884=((cj0)*(x6880));
21847 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x6865)))+(((sj5)*(x6878)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6877))));
21848 evalcond[1]=((((r20)*(x6876)))+(((x6869)*(x6878)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x6880)))+(((IkReal(-1.00000000000000))*(sj1)*(x6883)))+(((x6869)*(x6877))));
21849 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x6870)*(x6879)))+(((x6866)*(x6867)))+(((IkReal(-1.00000000000000))*(sj5)*(x6870)*(x6873)))+(((IkReal(-1.00000000000000))*(x6872)*(x6874)))+(((cj0)*(x6871)))+(((IkReal(-1.00000000000000))*(x6883)))+(((x6866)*(x6868))));
21850 evalcond[3]=((((IkReal(-1.00000000000000))*(x6866)*(x6873)))+(((cj0)*(x6874)))+(((IkReal(-1.00000000000000))*(x6866)*(x6879)))+(((IkReal(-1.00000000000000))*(sj5)*(x6868)*(x6870)))+(((IkReal(-1.00000000000000))*(x6865)*(x6875)))+(((IkReal(-1.00000000000000))*(sj5)*(x6867)*(x6870)))+(((sj0)*(x6871))));
21851 evalcond[4]=((((sj0)*(x6867)*(x6869)))+(((IkReal(-1.00000000000000))*(x6869)*(x6870)*(x6873)))+(((IkReal(-1.00000000000000))*(r10)*(x6870)*(x6876)))+(((r11)*(x6884)))+(((IkReal(-1.00000000000000))*(x6869)*(x6870)*(x6879)))+(x6865)+(((r00)*(sj0)*(x6876)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x6870)))+(((sj0)*(x6868)*(x6869)))+(((IkReal(-1.00000000000000))*(r01)*(x6872)*(x6880)))+(((x6866)*(x6881))));
21852 evalcond[5]=((((IkReal(-1.00000000000000))*(x6868)*(x6869)*(x6870)))+(((r01)*(x6884)))+(((IkReal(-1.00000000000000))*(sj5)*(x6870)*(x6881)))+(((IkReal(-1.00000000000000))*(x6866)*(x6882)))+(((r11)*(sj0)*(x6880)))+(((IkReal(-1.00000000000000))*(x6869)*(x6872)*(x6873)))+(((IkReal(-1.00000000000000))*(x6869)*(x6872)*(x6879)))+(((IkReal(-1.00000000000000))*(r10)*(x6872)*(x6876)))+(((IkReal(-1.00000000000000))*(x6864)*(x6875)))+(((IkReal(-1.00000000000000))*(r00)*(x6870)*(x6876)))+(((IkReal(-1.00000000000000))*(x6867)*(x6869)*(x6870))));
21853 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
21854 {
21855 continue;
21856 }
21857 }
21858 
21859 {
21860 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
21861 vinfos[0].jointtype = 1;
21862 vinfos[0].foffset = j0;
21863 vinfos[0].indices[0] = _ij0[0];
21864 vinfos[0].indices[1] = _ij0[1];
21865 vinfos[0].maxsolutions = _nj0;
21866 vinfos[1].jointtype = 1;
21867 vinfos[1].foffset = j1;
21868 vinfos[1].indices[0] = _ij1[0];
21869 vinfos[1].indices[1] = _ij1[1];
21870 vinfos[1].maxsolutions = _nj1;
21871 vinfos[2].jointtype = 1;
21872 vinfos[2].foffset = j2;
21873 vinfos[2].indices[0] = _ij2[0];
21874 vinfos[2].indices[1] = _ij2[1];
21875 vinfos[2].maxsolutions = _nj2;
21876 vinfos[3].jointtype = 1;
21877 vinfos[3].foffset = j3;
21878 vinfos[3].indices[0] = _ij3[0];
21879 vinfos[3].indices[1] = _ij3[1];
21880 vinfos[3].maxsolutions = _nj3;
21881 vinfos[4].jointtype = 1;
21882 vinfos[4].foffset = j4;
21883 vinfos[4].indices[0] = _ij4[0];
21884 vinfos[4].indices[1] = _ij4[1];
21885 vinfos[4].maxsolutions = _nj4;
21886 vinfos[5].jointtype = 1;
21887 vinfos[5].foffset = j5;
21888 vinfos[5].indices[0] = _ij5[0];
21889 vinfos[5].indices[1] = _ij5[1];
21890 vinfos[5].maxsolutions = _nj5;
21891 vinfos[6].jointtype = 1;
21892 vinfos[6].foffset = j6;
21893 vinfos[6].indices[0] = _ij6[0];
21894 vinfos[6].indices[1] = _ij6[1];
21895 vinfos[6].maxsolutions = _nj6;
21896 std::vector<int> vfree(0);
21897 solutions.AddSolution(vinfos,vfree);
21898 }
21899 }
21900 }
21901 
21902 }
21903 
21904 }
21905 
21906 } else
21907 {
21908 IkReal x6885=((IkReal(1.00000000000000))*(cj0));
21909 IkReal x6886=((cj4)*(sj6));
21910 IkReal x6887=((sj0)*(sj4));
21911 IkReal x6888=((cj5)*(sj6));
21912 IkReal x6889=((sj4)*(sj5));
21913 IkReal x6890=((r12)*(sj5));
21914 IkReal x6891=((IkReal(0.374290000000000))*(cj5));
21915 IkReal x6892=((r02)*(sj0));
21916 IkReal x6893=((IkReal(1.00000000000000))*(sj0));
21917 IkReal x6894=((cj0)*(r10));
21918 IkReal x6895=((cj4)*(cj6));
21919 IkReal x6896=((r00)*(sj0));
21920 IkReal x6897=((cj6)*(r21));
21921 IkReal x6898=((IkReal(0.374290000000000))*(sj5));
21922 IkReal x6899=((cj0)*(r00));
21923 IkReal x6900=((IkReal(0.0100000000000000))*(sj5));
21924 IkReal x6901=((cj0)*(r02));
21925 IkReal x6902=((cj5)*(sj4));
21926 IkReal x6903=((cj6)*(r01));
21927 IkReal x6904=((cj6)*(r11));
21928 IkReal x6905=((r01)*(sj0));
21929 IkReal x6906=((r10)*(sj0));
21930 IkReal x6907=((IkReal(0.0100000000000000))*(cj5)*(cj6));
21931 IkReal x6908=((sj6)*(x6898));
21932 IkReal x6909=((cj0)*(cj6)*(x6898));
21933 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
21934 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x6895)))+(((r21)*(x6886)))+(cj1)+(((r20)*(sj4)*(x6888)))+(((r22)*(x6889)))+(((x6897)*(x6902))));
21935 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x6891)))+(((IkReal(0.364420000000000))*(sj1)))+(((x6897)*(x6898)))+(((r20)*(x6908)))+(((IkReal(-1.00000000000000))*(r22)*(x6900)))+(((IkReal(-0.0100000000000000))*(r20)*(x6888)))+(((IkReal(-0.0100000000000000))*(cj5)*(x6897)))+(pz));
21936 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x6885)*(x6886)))+(((x6886)*(x6905)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x6885)*(x6888)))+(((IkReal(-1.00000000000000))*(r00)*(x6893)*(x6895)))+(((x6894)*(x6895)))+(((r00)*(x6887)*(x6888)))+(((IkReal(-1.00000000000000))*(x6885)*(x6902)*(x6904)))+(((IkReal(-1.00000000000000))*(r12)*(x6885)*(x6889)))+(((cj5)*(x6887)*(x6903)))+(((r02)*(sj5)*(x6887))));
21937 evalcond[4]=((((IkReal(-1.00000000000000))*(cj5)*(x6887)*(x6904)))+(((x6895)*(x6906)))+(((IkReal(-1.00000000000000))*(x6885)*(x6902)*(x6903)))+(((IkReal(-1.00000000000000))*(r11)*(x6886)*(x6893)))+(((IkReal(-1.00000000000000))*(r10)*(x6887)*(x6888)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x6885)*(x6888)))+(((x6895)*(x6899)))+(((IkReal(-1.00000000000000))*(r02)*(x6885)*(x6889)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r01)*(x6885)*(x6886)))+(((IkReal(-1.00000000000000))*(x6887)*(x6890))));
21938 evalcond[5]=((IkReal(-0.0690000000000000))+(((sj0)*(x6898)*(x6903)))+(((IkReal(0.0100000000000000))*(cj0)*(x6890)))+(((IkReal(-1.00000000000000))*(x6891)*(x6892)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6904)))+(((IkReal(-0.0100000000000000))*(x6888)*(x6896)))+(((IkReal(-1.00000000000000))*(py)*(x6885)))+(((IkReal(-1.00000000000000))*(x6894)*(x6908)))+(((IkReal(-1.00000000000000))*(x6892)*(x6900)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x6903)))+(((cj0)*(r12)*(x6891)))+(((IkReal(0.0100000000000000))*(x6888)*(x6894)))+(((x6896)*(x6908)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x6898)*(x6904))));
21939 evalcond[6]=((IkReal(0.0690000000000000))+(((x6891)*(x6901)))+(((IkReal(0.0100000000000000))*(x6888)*(x6899)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x6904)))+(((IkReal(0.0100000000000000))*(x6888)*(x6906)))+(((r12)*(sj0)*(x6891)))+(((IkReal(-1.00000000000000))*(x6906)*(x6908)))+(((IkReal(-1.00000000000000))*(py)*(x6893)))+(((IkReal(-1.00000000000000))*(sj0)*(x6898)*(x6904)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x6903)))+(((x6900)*(x6901)))+(((IkReal(-1.00000000000000))*(px)*(x6885)))+(((IkReal(-1.00000000000000))*(cj0)*(x6898)*(x6903)))+(((IkReal(-1.00000000000000))*(x6899)*(x6908)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(0.0100000000000000))*(sj0)*(x6890))));
21940 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
21941 {
21942 {
21943 IkReal dummyeval[1];
21944 IkReal gconst12;
21945 gconst12=IKsign(sj1);
21946 dummyeval[0]=sj1;
21947 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21948 {
21949 {
21950 IkReal dummyeval[1];
21951 dummyeval[0]=sj1;
21952 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21953 {
21954 {
21955 IkReal dummyeval[1];
21956 dummyeval[0]=cj1;
21957 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
21958 {
21959 {
21960 IkReal evalcond[9];
21961 IkReal x6910=((IkReal(1.00000000000000))*(cj0));
21962 IkReal x6911=((cj4)*(sj6));
21963 IkReal x6912=((sj0)*(sj6));
21964 IkReal x6913=((cj5)*(sj4));
21965 IkReal x6914=((IkReal(0.374290000000000))*(sj5));
21966 IkReal x6915=((sj4)*(sj5));
21967 IkReal x6916=((cj0)*(cj6));
21968 IkReal x6917=((IkReal(0.0100000000000000))*(cj5));
21969 IkReal x6918=((cj4)*(sj5));
21970 IkReal x6919=((cj5)*(sj0));
21971 IkReal x6920=((IkReal(0.374290000000000))*(r02));
21972 IkReal x6921=((r20)*(sj6));
21973 IkReal x6922=((cj6)*(r21));
21974 IkReal x6923=((IkReal(1.00000000000000))*(sj0));
21975 IkReal x6924=((cj0)*(sj6));
21976 IkReal x6925=((cj4)*(cj6));
21977 IkReal x6926=((IkReal(0.374290000000000))*(r12));
21978 IkReal x6927=((cj0)*(cj5));
21979 IkReal x6928=((cj6)*(sj5));
21980 IkReal x6929=((cj6)*(r01));
21981 IkReal x6930=((r00)*(sj6));
21982 IkReal x6931=((IkReal(0.0100000000000000))*(sj5));
21983 IkReal x6932=((cj6)*(r11));
21984 IkReal x6933=((IkReal(1.00000000000000))*(r10));
21985 IkReal x6934=((r02)*(sj0));
21986 IkReal x6935=((cj6)*(sj4));
21987 IkReal x6936=((r12)*(x6923));
21988 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
21989 evalcond[1]=((((r21)*(x6911)))+(((IkReal(-1.00000000000000))*(r20)*(x6925)))+(((x6913)*(x6921)))+(((r22)*(x6915)))+(((x6913)*(x6922))));
21990 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x6914)*(x6922)))+(((IkReal(-1.00000000000000))*(x6917)*(x6922)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x6931)))+(((x6914)*(x6921)))+(((IkReal(-1.00000000000000))*(x6917)*(x6921))));
21991 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x6912)*(x6933)))+(((IkReal(-1.00000000000000))*(sj5)*(x6910)*(x6930)))+(((r12)*(x6919)))+(((r02)*(x6927)))+(((IkReal(-1.00000000000000))*(r01)*(x6910)*(x6928)))+(((IkReal(-1.00000000000000))*(r11)*(x6923)*(x6928))));
21992 evalcond[4]=((((r00)*(x6912)*(x6913)))+(((x6915)*(x6934)))+(((cj4)*(r10)*(x6916)))+(((r01)*(sj0)*(x6911)))+(((IkReal(-1.00000000000000))*(r12)*(x6910)*(x6915)))+(((sj0)*(x6913)*(x6929)))+(((IkReal(-1.00000000000000))*(r11)*(x6910)*(x6911)))+(((IkReal(-1.00000000000000))*(r00)*(x6923)*(x6925)))+(((IkReal(-1.00000000000000))*(x6910)*(x6913)*(x6932)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6910)*(x6913))));
21993 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x6910)*(x6911)))+(((IkReal(-1.00000000000000))*(r11)*(x6911)*(x6923)))+(((IkReal(-1.00000000000000))*(x6913)*(x6923)*(x6932)))+(((IkReal(-1.00000000000000))*(x6915)*(x6936)))+(((r10)*(sj0)*(x6925)))+(((IkReal(-1.00000000000000))*(r02)*(x6910)*(x6915)))+(((IkReal(-1.00000000000000))*(x6910)*(x6913)*(x6930)))+(((cj4)*(r00)*(x6916)))+(((IkReal(-1.00000000000000))*(x6910)*(x6913)*(x6929)))+(((IkReal(-1.00000000000000))*(x6912)*(x6913)*(x6933))));
21994 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x6914)*(x6916)))+(((cj0)*(r12)*(x6931)))+(((IkReal(-1.00000000000000))*(sj0)*(x6917)*(x6929)))+(((r11)*(x6916)*(x6917)))+(((IkReal(-1.00000000000000))*(r00)*(x6912)*(x6917)))+(((r00)*(x6912)*(x6914)))+(((x6926)*(x6927)))+(((IkReal(-1.00000000000000))*(x6919)*(x6920)))+(((IkReal(-1.00000000000000))*(r10)*(x6914)*(x6924)))+(((IkReal(-1.00000000000000))*(x6931)*(x6934)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x6910)))+(((sj0)*(x6914)*(x6929)))+(((r10)*(x6917)*(x6924))));
21995 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x6910)*(x6925)))+(((IkReal(-1.00000000000000))*(r02)*(x6910)*(x6918)))+(((IkReal(-1.00000000000000))*(r11)*(x6919)*(x6925)))+(((IkReal(-1.00000000000000))*(r00)*(x6910)*(x6935)))+(((IkReal(-1.00000000000000))*(x6918)*(x6936)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x6910)*(x6911)))+(((IkReal(-1.00000000000000))*(r10)*(x6923)*(x6935)))+(((IkReal(-1.00000000000000))*(x6911)*(x6919)*(x6933)))+(((r11)*(sj4)*(x6912)))+(((r01)*(sj4)*(x6924))));
21996 evalcond[8]=((IkReal(0.0690000000000000))+(((cj0)*(r02)*(x6931)))+(((sj0)*(x6917)*(x6932)))+(((r10)*(x6912)*(x6917)))+(((IkReal(-1.00000000000000))*(r10)*(x6912)*(x6914)))+(((IkReal(-1.00000000000000))*(py)*(x6923)))+(((IkReal(-1.00000000000000))*(r01)*(x6914)*(x6916)))+(((x6920)*(x6927)))+(((r12)*(sj0)*(x6931)))+(((IkReal(-1.00000000000000))*(px)*(x6910)))+(((IkReal(-1.00000000000000))*(sj0)*(x6914)*(x6932)))+(((r01)*(x6916)*(x6917)))+(((r00)*(x6917)*(x6924)))+(((x6919)*(x6926)))+(((IkReal(-1.00000000000000))*(r00)*(x6914)*(x6924))));
21997 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
21998 {
21999 {
22000 IkReal j3array[1], cj3array[1], sj3array[1];
22001 bool j3valid[1]={false};
22002 _nj3 = 1;
22003 IkReal x6937=((r20)*(sj6));
22004 IkReal x6938=((cj4)*(cj5));
22005 IkReal x6939=((cj6)*(r21));
22006 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6937)*(x6938)))+(((x6938)*(x6939))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6939)))+(((sj5)*(x6937))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6937)*(x6938)))+(((x6938)*(x6939)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6939)))+(((sj5)*(x6937)))))-1) <= IKFAST_SINCOS_THRESH )
22007     continue;
22008 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x6937)*(x6938)))+(((x6938)*(x6939)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x6939)))+(((sj5)*(x6937)))));
22009 sj3array[0]=IKsin(j3array[0]);
22010 cj3array[0]=IKcos(j3array[0]);
22011 if( j3array[0] > IKPI )
22012 {
22013     j3array[0]-=IK2PI;
22014 }
22015 else if( j3array[0] < -IKPI )
22016 {    j3array[0]+=IK2PI;
22017 }
22018 j3valid[0] = true;
22019 for(int ij3 = 0; ij3 < 1; ++ij3)
22020 {
22021 if( !j3valid[ij3] )
22022 {
22023     continue;
22024 }
22025 _ij3[0] = ij3; _ij3[1] = -1;
22026 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22027 {
22028 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22029 {
22030     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22031 }
22032 }
22033 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22034 {
22035 IkReal evalcond[4];
22036 IkReal x6940=IKsin(j3);
22037 IkReal x6941=((sj0)*(sj5));
22038 IkReal x6942=((r00)*(sj6));
22039 IkReal x6943=((cj6)*(r01));
22040 IkReal x6944=((cj5)*(sj0));
22041 IkReal x6945=((cj0)*(cj5));
22042 IkReal x6946=((cj6)*(sj4));
22043 IkReal x6947=((sj4)*(sj6));
22044 IkReal x6948=((cj0)*(r11));
22045 IkReal x6949=((cj4)*(cj6));
22046 IkReal x6950=((cj4)*(sj6));
22047 IkReal x6951=((IkReal(1.00000000000000))*(cj0));
22048 IkReal x6952=((cj4)*(sj5));
22049 IkReal x6953=((sj5)*(sj6));
22050 IkReal x6954=((cj6)*(sj5));
22051 IkReal x6955=((IkReal(1.00000000000000))*(IKcos(j3)));
22052 evalcond[0]=((((IkReal(-1.00000000000000))*(x6955)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x6953)))+(((r21)*(x6954))));
22053 evalcond[1]=((((IkReal(-1.00000000000000))*(x6940)))+(((r20)*(x6946)))+(((IkReal(-1.00000000000000))*(r21)*(x6947)))+(((r22)*(x6952)))+(((cj5)*(r20)*(x6950)))+(((cj5)*(r21)*(x6949))));
22054 evalcond[2]=((((x6941)*(x6942)))+(x6940)+(((x6941)*(x6943)))+(((r12)*(x6945)))+(((IkReal(-1.00000000000000))*(x6948)*(x6954)))+(((IkReal(-1.00000000000000))*(r02)*(x6944)))+(((IkReal(-1.00000000000000))*(r10)*(x6951)*(x6953))));
22055 evalcond[3]=((((IkReal(-1.00000000000000))*(x6955)))+(((cj4)*(x6942)*(x6944)))+(((IkReal(-1.00000000000000))*(r10)*(x6945)*(x6950)))+(((x6947)*(x6948)))+(((IkReal(-1.00000000000000))*(r10)*(x6946)*(x6951)))+(((r00)*(sj0)*(x6946)))+(((IkReal(-1.00000000000000))*(r12)*(x6951)*(x6952)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x6947)))+(((cj4)*(r02)*(x6941)))+(((IkReal(-1.00000000000000))*(r11)*(x6945)*(x6949)))+(((cj4)*(x6943)*(x6944))));
22056 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
22057 {
22058 continue;
22059 }
22060 }
22061 
22062 {
22063 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22064 vinfos[0].jointtype = 1;
22065 vinfos[0].foffset = j0;
22066 vinfos[0].indices[0] = _ij0[0];
22067 vinfos[0].indices[1] = _ij0[1];
22068 vinfos[0].maxsolutions = _nj0;
22069 vinfos[1].jointtype = 1;
22070 vinfos[1].foffset = j1;
22071 vinfos[1].indices[0] = _ij1[0];
22072 vinfos[1].indices[1] = _ij1[1];
22073 vinfos[1].maxsolutions = _nj1;
22074 vinfos[2].jointtype = 1;
22075 vinfos[2].foffset = j2;
22076 vinfos[2].indices[0] = _ij2[0];
22077 vinfos[2].indices[1] = _ij2[1];
22078 vinfos[2].maxsolutions = _nj2;
22079 vinfos[3].jointtype = 1;
22080 vinfos[3].foffset = j3;
22081 vinfos[3].indices[0] = _ij3[0];
22082 vinfos[3].indices[1] = _ij3[1];
22083 vinfos[3].maxsolutions = _nj3;
22084 vinfos[4].jointtype = 1;
22085 vinfos[4].foffset = j4;
22086 vinfos[4].indices[0] = _ij4[0];
22087 vinfos[4].indices[1] = _ij4[1];
22088 vinfos[4].maxsolutions = _nj4;
22089 vinfos[5].jointtype = 1;
22090 vinfos[5].foffset = j5;
22091 vinfos[5].indices[0] = _ij5[0];
22092 vinfos[5].indices[1] = _ij5[1];
22093 vinfos[5].maxsolutions = _nj5;
22094 vinfos[6].jointtype = 1;
22095 vinfos[6].foffset = j6;
22096 vinfos[6].indices[0] = _ij6[0];
22097 vinfos[6].indices[1] = _ij6[1];
22098 vinfos[6].maxsolutions = _nj6;
22099 std::vector<int> vfree(0);
22100 solutions.AddSolution(vinfos,vfree);
22101 }
22102 }
22103 }
22104 
22105 } else
22106 {
22107 IkReal x6956=((IkReal(1.00000000000000))*(cj0));
22108 IkReal x6957=((cj4)*(sj6));
22109 IkReal x6958=((sj0)*(sj6));
22110 IkReal x6959=((cj5)*(sj4));
22111 IkReal x6960=((IkReal(0.374290000000000))*(sj5));
22112 IkReal x6961=((sj4)*(sj5));
22113 IkReal x6962=((cj0)*(cj6));
22114 IkReal x6963=((IkReal(0.0100000000000000))*(cj5));
22115 IkReal x6964=((cj4)*(sj5));
22116 IkReal x6965=((cj5)*(sj0));
22117 IkReal x6966=((IkReal(0.374290000000000))*(r02));
22118 IkReal x6967=((r20)*(sj6));
22119 IkReal x6968=((cj6)*(r21));
22120 IkReal x6969=((IkReal(1.00000000000000))*(sj0));
22121 IkReal x6970=((cj0)*(sj6));
22122 IkReal x6971=((cj4)*(cj6));
22123 IkReal x6972=((IkReal(0.374290000000000))*(r12));
22124 IkReal x6973=((cj0)*(cj5));
22125 IkReal x6974=((cj6)*(sj5));
22126 IkReal x6975=((cj6)*(r01));
22127 IkReal x6976=((r00)*(sj6));
22128 IkReal x6977=((IkReal(0.0100000000000000))*(sj5));
22129 IkReal x6978=((cj6)*(r11));
22130 IkReal x6979=((IkReal(1.00000000000000))*(r10));
22131 IkReal x6980=((r02)*(sj0));
22132 IkReal x6981=((cj6)*(sj4));
22133 IkReal x6982=((r12)*(x6969));
22134 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
22135 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x6971)))+(((r21)*(x6957)))+(((x6959)*(x6968)))+(((r22)*(x6961)))+(((x6959)*(x6967))));
22136 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(r22)*(x6977)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x6963)*(x6968)))+(((IkReal(-1.00000000000000))*(x6963)*(x6967)))+(((x6960)*(x6967)))+(((x6960)*(x6968))));
22137 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x6956)*(x6974)))+(((IkReal(-1.00000000000000))*(r11)*(x6969)*(x6974)))+(((IkReal(-1.00000000000000))*(sj5)*(x6958)*(x6979)))+(((r02)*(x6973)))+(((r12)*(x6965)))+(((IkReal(-1.00000000000000))*(sj5)*(x6956)*(x6976))));
22138 evalcond[4]=((((r00)*(x6958)*(x6959)))+(((IkReal(-1.00000000000000))*(r11)*(x6956)*(x6957)))+(((cj4)*(r10)*(x6962)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x6956)*(x6959)))+(((IkReal(-1.00000000000000))*(r12)*(x6956)*(x6961)))+(((IkReal(-1.00000000000000))*(r00)*(x6969)*(x6971)))+(((r01)*(sj0)*(x6957)))+(((IkReal(-1.00000000000000))*(x6956)*(x6959)*(x6978)))+(((sj0)*(x6959)*(x6975)))+(((x6961)*(x6980))));
22139 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x6956)*(x6957)))+(((cj4)*(r00)*(x6962)))+(((r10)*(sj0)*(x6971)))+(((IkReal(-1.00000000000000))*(r11)*(x6957)*(x6969)))+(((IkReal(-1.00000000000000))*(x6958)*(x6959)*(x6979)))+(((IkReal(-1.00000000000000))*(x6956)*(x6959)*(x6975)))+(((IkReal(-1.00000000000000))*(x6959)*(x6969)*(x6978)))+(((IkReal(-1.00000000000000))*(r02)*(x6956)*(x6961)))+(((IkReal(-1.00000000000000))*(x6961)*(x6982)))+(((IkReal(-1.00000000000000))*(x6956)*(x6959)*(x6976))));
22140 evalcond[6]=((IkReal(-0.0690000000000000))+(((r11)*(x6962)*(x6963)))+(((r10)*(x6963)*(x6970)))+(((IkReal(-1.00000000000000))*(sj0)*(x6963)*(x6975)))+(((sj0)*(x6960)*(x6975)))+(((IkReal(-1.00000000000000))*(r10)*(x6960)*(x6970)))+(((IkReal(-1.00000000000000))*(x6977)*(x6980)))+(((IkReal(-1.00000000000000))*(py)*(x6956)))+(((IkReal(-1.00000000000000))*(x6965)*(x6966)))+(((x6972)*(x6973)))+(((cj0)*(r12)*(x6977)))+(((IkReal(-1.00000000000000))*(r00)*(x6958)*(x6963)))+(((r00)*(x6958)*(x6960)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x6960)*(x6962))));
22141 evalcond[7]=((((r01)*(sj4)*(x6970)))+(((IkReal(-1.00000000000000))*(r10)*(x6969)*(x6981)))+(((IkReal(-1.00000000000000))*(r00)*(x6956)*(x6981)))+(((IkReal(-1.00000000000000))*(r11)*(x6965)*(x6971)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x6956)*(x6957)))+(((r11)*(sj4)*(x6958)))+(((IkReal(-1.00000000000000))*(r02)*(x6956)*(x6964)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x6956)*(x6971)))+(((IkReal(-1.00000000000000))*(x6964)*(x6982)))+(((IkReal(-1.00000000000000))*(x6957)*(x6965)*(x6979))));
22142 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x6960)*(x6962)))+(((x6966)*(x6973)))+(((sj0)*(x6963)*(x6978)))+(((cj0)*(r02)*(x6977)))+(((r00)*(x6963)*(x6970)))+(((x6965)*(x6972)))+(((r12)*(sj0)*(x6977)))+(((IkReal(-1.00000000000000))*(r10)*(x6958)*(x6960)))+(((IkReal(-1.00000000000000))*(px)*(x6956)))+(((IkReal(-1.00000000000000))*(r00)*(x6960)*(x6970)))+(((IkReal(-1.00000000000000))*(py)*(x6969)))+(((IkReal(-1.00000000000000))*(sj0)*(x6960)*(x6978)))+(((r01)*(x6962)*(x6963)))+(((r10)*(x6958)*(x6963))));
22143 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
22144 {
22145 {
22146 IkReal j3array[1], cj3array[1], sj3array[1];
22147 bool j3valid[1]={false};
22148 _nj3 = 1;
22149 IkReal x6983=((IkReal(1.00000000000000))*(sj5));
22150 IkReal x6984=((cj6)*(r21));
22151 IkReal x6985=((r20)*(sj6));
22152 IkReal x6986=((IkReal(1.00000000000000))*(cj4)*(cj5));
22153 if( IKabs(((((IkReal(-1.00000000000000))*(x6984)*(x6986)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6983)))+(((IkReal(-1.00000000000000))*(x6985)*(x6986)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x6983)*(x6984)))+(((IkReal(-1.00000000000000))*(x6983)*(x6985)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x6984)*(x6986)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6983)))+(((IkReal(-1.00000000000000))*(x6985)*(x6986)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x6983)*(x6984)))+(((IkReal(-1.00000000000000))*(x6983)*(x6985)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
22154     continue;
22155 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x6984)*(x6986)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x6983)))+(((IkReal(-1.00000000000000))*(x6985)*(x6986)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x6983)*(x6984)))+(((IkReal(-1.00000000000000))*(x6983)*(x6985)))+(((cj5)*(r22)))));
22156 sj3array[0]=IKsin(j3array[0]);
22157 cj3array[0]=IKcos(j3array[0]);
22158 if( j3array[0] > IKPI )
22159 {
22160     j3array[0]-=IK2PI;
22161 }
22162 else if( j3array[0] < -IKPI )
22163 {    j3array[0]+=IK2PI;
22164 }
22165 j3valid[0] = true;
22166 for(int ij3 = 0; ij3 < 1; ++ij3)
22167 {
22168 if( !j3valid[ij3] )
22169 {
22170     continue;
22171 }
22172 _ij3[0] = ij3; _ij3[1] = -1;
22173 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22174 {
22175 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22176 {
22177     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22178 }
22179 }
22180 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22181 {
22182 IkReal evalcond[4];
22183 IkReal x6987=IKsin(j3);
22184 IkReal x6988=IKcos(j3);
22185 IkReal x6989=((sj0)*(sj5));
22186 IkReal x6990=((r00)*(sj6));
22187 IkReal x6991=((cj6)*(r01));
22188 IkReal x6992=((cj0)*(cj5));
22189 IkReal x6993=((IkReal(1.00000000000000))*(cj5));
22190 IkReal x6994=((cj4)*(cj5));
22191 IkReal x6995=((cj6)*(sj4));
22192 IkReal x6996=((sj4)*(sj6));
22193 IkReal x6997=((cj0)*(r11));
22194 IkReal x6998=((IkReal(1.00000000000000))*(cj4));
22195 IkReal x6999=((cj6)*(r21));
22196 IkReal x7000=((r20)*(sj6));
22197 IkReal x7001=((cj0)*(sj5));
22198 IkReal x7002=((r10)*(sj6));
22199 evalcond[0]=((((sj5)*(x7000)))+(x6988)+(((sj5)*(x6999)))+(((IkReal(-1.00000000000000))*(r22)*(x6993))));
22200 evalcond[1]=((((x6994)*(x6999)))+(((r20)*(x6995)))+(((IkReal(-1.00000000000000))*(r21)*(x6996)))+(((cj4)*(r22)*(sj5)))+(x6987)+(((x6994)*(x7000))));
22201 evalcond[2]=((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x6997)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x6993)))+(((r12)*(x6992)))+(x6987)+(((IkReal(-1.00000000000000))*(x7001)*(x7002)))+(((x6989)*(x6990)))+(((x6989)*(x6991))));
22202 evalcond[3]=((((IkReal(-1.00000000000000))*(x6992)*(x6998)*(x7002)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x6996)))+(((x6996)*(x6997)))+(((cj4)*(r02)*(x6989)))+(((IkReal(-1.00000000000000))*(x6988)))+(((r00)*(sj0)*(x6995)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x6995)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x6992)*(x6998)))+(((sj0)*(x6990)*(x6994)))+(((IkReal(-1.00000000000000))*(r12)*(x6998)*(x7001)))+(((sj0)*(x6991)*(x6994))));
22203 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
22204 {
22205 continue;
22206 }
22207 }
22208 
22209 {
22210 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22211 vinfos[0].jointtype = 1;
22212 vinfos[0].foffset = j0;
22213 vinfos[0].indices[0] = _ij0[0];
22214 vinfos[0].indices[1] = _ij0[1];
22215 vinfos[0].maxsolutions = _nj0;
22216 vinfos[1].jointtype = 1;
22217 vinfos[1].foffset = j1;
22218 vinfos[1].indices[0] = _ij1[0];
22219 vinfos[1].indices[1] = _ij1[1];
22220 vinfos[1].maxsolutions = _nj1;
22221 vinfos[2].jointtype = 1;
22222 vinfos[2].foffset = j2;
22223 vinfos[2].indices[0] = _ij2[0];
22224 vinfos[2].indices[1] = _ij2[1];
22225 vinfos[2].maxsolutions = _nj2;
22226 vinfos[3].jointtype = 1;
22227 vinfos[3].foffset = j3;
22228 vinfos[3].indices[0] = _ij3[0];
22229 vinfos[3].indices[1] = _ij3[1];
22230 vinfos[3].maxsolutions = _nj3;
22231 vinfos[4].jointtype = 1;
22232 vinfos[4].foffset = j4;
22233 vinfos[4].indices[0] = _ij4[0];
22234 vinfos[4].indices[1] = _ij4[1];
22235 vinfos[4].maxsolutions = _nj4;
22236 vinfos[5].jointtype = 1;
22237 vinfos[5].foffset = j5;
22238 vinfos[5].indices[0] = _ij5[0];
22239 vinfos[5].indices[1] = _ij5[1];
22240 vinfos[5].maxsolutions = _nj5;
22241 vinfos[6].jointtype = 1;
22242 vinfos[6].foffset = j6;
22243 vinfos[6].indices[0] = _ij6[0];
22244 vinfos[6].indices[1] = _ij6[1];
22245 vinfos[6].maxsolutions = _nj6;
22246 std::vector<int> vfree(0);
22247 solutions.AddSolution(vinfos,vfree);
22248 }
22249 }
22250 }
22251 
22252 } else
22253 {
22254 if( 1 )
22255 {
22256 continue;
22257 
22258 } else
22259 {
22260 }
22261 }
22262 }
22263 }
22264 
22265 } else
22266 {
22267 {
22268 IkReal j3array[1], cj3array[1], sj3array[1];
22269 bool j3valid[1]={false};
22270 _nj3 = 1;
22271 IkReal x7003=((cj5)*(r02));
22272 IkReal x7004=((cj0)*(sj5));
22273 IkReal x7005=((r10)*(sj6));
22274 IkReal x7006=((IkReal(1.00000000000000))*(cj6));
22275 IkReal x7007=((sj0)*(sj5));
22276 IkReal x7008=((cj5)*(r12));
22277 IkReal x7009=((IkReal(1.00000000000000))*(r00)*(sj6));
22278 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x7008)))+(((x7004)*(x7005)))+(((IkReal(-1.00000000000000))*(r01)*(x7006)*(x7007)))+(((cj6)*(r11)*(x7004)))+(((sj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7007)*(x7009))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x7004)*(x7006)))+(((cj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7005)*(x7007)))+(((sj0)*(x7008)))+(((IkReal(-1.00000000000000))*(r11)*(x7006)*(x7007)))+(((IkReal(-1.00000000000000))*(x7004)*(x7009))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x7008)))+(((x7004)*(x7005)))+(((IkReal(-1.00000000000000))*(r01)*(x7006)*(x7007)))+(((cj6)*(r11)*(x7004)))+(((sj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7007)*(x7009)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x7004)*(x7006)))+(((cj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7005)*(x7007)))+(((sj0)*(x7008)))+(((IkReal(-1.00000000000000))*(r11)*(x7006)*(x7007)))+(((IkReal(-1.00000000000000))*(x7004)*(x7009)))))))-1) <= IKFAST_SINCOS_THRESH )
22279     continue;
22280 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x7008)))+(((x7004)*(x7005)))+(((IkReal(-1.00000000000000))*(r01)*(x7006)*(x7007)))+(((cj6)*(r11)*(x7004)))+(((sj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7007)*(x7009)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x7004)*(x7006)))+(((cj0)*(x7003)))+(((IkReal(-1.00000000000000))*(x7005)*(x7007)))+(((sj0)*(x7008)))+(((IkReal(-1.00000000000000))*(r11)*(x7006)*(x7007)))+(((IkReal(-1.00000000000000))*(x7004)*(x7009)))))));
22281 sj3array[0]=IKsin(j3array[0]);
22282 cj3array[0]=IKcos(j3array[0]);
22283 if( j3array[0] > IKPI )
22284 {
22285     j3array[0]-=IK2PI;
22286 }
22287 else if( j3array[0] < -IKPI )
22288 {    j3array[0]+=IK2PI;
22289 }
22290 j3valid[0] = true;
22291 for(int ij3 = 0; ij3 < 1; ++ij3)
22292 {
22293 if( !j3valid[ij3] )
22294 {
22295     continue;
22296 }
22297 _ij3[0] = ij3; _ij3[1] = -1;
22298 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22299 {
22300 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22301 {
22302     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22303 }
22304 }
22305 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22306 {
22307 IkReal evalcond[6];
22308 IkReal x7010=IKsin(j3);
22309 IkReal x7011=IKcos(j3);
22310 IkReal x7012=((sj0)*(sj5));
22311 IkReal x7013=((r00)*(sj6));
22312 IkReal x7014=((IkReal(1.00000000000000))*(cj4));
22313 IkReal x7015=((cj6)*(r01));
22314 IkReal x7016=((cj0)*(cj5));
22315 IkReal x7017=((cj5)*(sj0));
22316 IkReal x7018=((cj6)*(r11));
22317 IkReal x7019=((cj0)*(sj5));
22318 IkReal x7020=((IkReal(1.00000000000000))*(cj1));
22319 IkReal x7021=((cj6)*(sj4));
22320 IkReal x7022=((IkReal(1.00000000000000))*(sj1));
22321 IkReal x7023=((cj4)*(cj5));
22322 IkReal x7024=((cj6)*(r21));
22323 IkReal x7025=((r20)*(sj6));
22324 IkReal x7026=((r10)*(sj6));
22325 IkReal x7027=((IkReal(1.00000000000000))*(cj0));
22326 IkReal x7028=((cj0)*(sj4)*(sj6));
22327 IkReal x7029=((sj0)*(sj4)*(sj6));
22328 evalcond[0]=((((IkReal(-1.00000000000000))*(x7011)*(x7022)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7024)))+(((sj5)*(x7025))));
22329 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x7021)))+(((x7023)*(x7024)))+(((x7023)*(x7025)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x7010)*(x7022))));
22330 evalcond[2]=((((x7012)*(x7015)))+(((r12)*(x7016)))+(x7010)+(((x7012)*(x7013)))+(((IkReal(-1.00000000000000))*(x7019)*(x7026)))+(((IkReal(-1.00000000000000))*(r02)*(x7017)))+(((IkReal(-1.00000000000000))*(x7018)*(x7019))));
22331 evalcond[3]=((((r12)*(x7017)))+(((IkReal(-1.00000000000000))*(x7015)*(x7019)))+(((IkReal(-1.00000000000000))*(x7012)*(x7018)))+(((r02)*(x7016)))+(((IkReal(-1.00000000000000))*(x7013)*(x7019)))+(((IkReal(-1.00000000000000))*(x7011)*(x7020)))+(((IkReal(-1.00000000000000))*(x7012)*(x7026))));
22332 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x7021)*(x7027)))+(((r00)*(sj0)*(x7021)))+(((cj4)*(x7015)*(x7017)))+(((IkReal(-1.00000000000000))*(r01)*(x7029)))+(((cj4)*(r02)*(x7012)))+(((cj4)*(x7013)*(x7017)))+(((IkReal(-1.00000000000000))*(x7011)))+(((IkReal(-1.00000000000000))*(x7014)*(x7016)*(x7026)))+(((IkReal(-1.00000000000000))*(x7014)*(x7016)*(x7018)))+(((r11)*(x7028)))+(((IkReal(-1.00000000000000))*(r12)*(x7014)*(x7019))));
22333 evalcond[5]=((((IkReal(-1.00000000000000))*(x7014)*(x7017)*(x7026)))+(((IkReal(-1.00000000000000))*(x7013)*(x7014)*(x7016)))+(((IkReal(-1.00000000000000))*(r02)*(x7014)*(x7019)))+(((IkReal(-1.00000000000000))*(x7014)*(x7017)*(x7018)))+(((IkReal(-1.00000000000000))*(x7014)*(x7015)*(x7016)))+(((r01)*(x7028)))+(((IkReal(-1.00000000000000))*(r00)*(x7021)*(x7027)))+(((IkReal(-1.00000000000000))*(x7010)*(x7020)))+(((IkReal(-1.00000000000000))*(r12)*(x7012)*(x7014)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7021)))+(((r11)*(x7029))));
22334 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22335 {
22336 continue;
22337 }
22338 }
22339 
22340 {
22341 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22342 vinfos[0].jointtype = 1;
22343 vinfos[0].foffset = j0;
22344 vinfos[0].indices[0] = _ij0[0];
22345 vinfos[0].indices[1] = _ij0[1];
22346 vinfos[0].maxsolutions = _nj0;
22347 vinfos[1].jointtype = 1;
22348 vinfos[1].foffset = j1;
22349 vinfos[1].indices[0] = _ij1[0];
22350 vinfos[1].indices[1] = _ij1[1];
22351 vinfos[1].maxsolutions = _nj1;
22352 vinfos[2].jointtype = 1;
22353 vinfos[2].foffset = j2;
22354 vinfos[2].indices[0] = _ij2[0];
22355 vinfos[2].indices[1] = _ij2[1];
22356 vinfos[2].maxsolutions = _nj2;
22357 vinfos[3].jointtype = 1;
22358 vinfos[3].foffset = j3;
22359 vinfos[3].indices[0] = _ij3[0];
22360 vinfos[3].indices[1] = _ij3[1];
22361 vinfos[3].maxsolutions = _nj3;
22362 vinfos[4].jointtype = 1;
22363 vinfos[4].foffset = j4;
22364 vinfos[4].indices[0] = _ij4[0];
22365 vinfos[4].indices[1] = _ij4[1];
22366 vinfos[4].maxsolutions = _nj4;
22367 vinfos[5].jointtype = 1;
22368 vinfos[5].foffset = j5;
22369 vinfos[5].indices[0] = _ij5[0];
22370 vinfos[5].indices[1] = _ij5[1];
22371 vinfos[5].maxsolutions = _nj5;
22372 vinfos[6].jointtype = 1;
22373 vinfos[6].foffset = j6;
22374 vinfos[6].indices[0] = _ij6[0];
22375 vinfos[6].indices[1] = _ij6[1];
22376 vinfos[6].maxsolutions = _nj6;
22377 std::vector<int> vfree(0);
22378 solutions.AddSolution(vinfos,vfree);
22379 }
22380 }
22381 }
22382 
22383 }
22384 
22385 }
22386 
22387 } else
22388 {
22389 {
22390 IkReal j3array[1], cj3array[1], sj3array[1];
22391 bool j3valid[1]={false};
22392 _nj3 = 1;
22393 IkReal x7030=((sj5)*(sj6));
22394 IkReal x7031=((IkReal(1.00000000000000))*(sj0));
22395 IkReal x7032=((cj6)*(sj5));
22396 IkReal x7033=((IkReal(1.00000000000000))*(cj5));
22397 if( IKabs(((((IkReal(-1.00000000000000))*(r00)*(x7030)*(x7031)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7033)))+(((cj0)*(r11)*(x7032)))+(((cj0)*(r10)*(x7030)))+(((IkReal(-1.00000000000000))*(r01)*(x7031)*(x7032))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x7033)))+(((r21)*(x7032)))+(((r20)*(x7030))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r00)*(x7030)*(x7031)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7033)))+(((cj0)*(r11)*(x7032)))+(((cj0)*(r10)*(x7030)))+(((IkReal(-1.00000000000000))*(r01)*(x7031)*(x7032)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x7033)))+(((r21)*(x7032)))+(((r20)*(x7030)))))))-1) <= IKFAST_SINCOS_THRESH )
22398     continue;
22399 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r00)*(x7030)*(x7031)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7033)))+(((cj0)*(r11)*(x7032)))+(((cj0)*(r10)*(x7030)))+(((IkReal(-1.00000000000000))*(r01)*(x7031)*(x7032)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x7033)))+(((r21)*(x7032)))+(((r20)*(x7030)))))));
22400 sj3array[0]=IKsin(j3array[0]);
22401 cj3array[0]=IKcos(j3array[0]);
22402 if( j3array[0] > IKPI )
22403 {
22404     j3array[0]-=IK2PI;
22405 }
22406 else if( j3array[0] < -IKPI )
22407 {    j3array[0]+=IK2PI;
22408 }
22409 j3valid[0] = true;
22410 for(int ij3 = 0; ij3 < 1; ++ij3)
22411 {
22412 if( !j3valid[ij3] )
22413 {
22414     continue;
22415 }
22416 _ij3[0] = ij3; _ij3[1] = -1;
22417 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22418 {
22419 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22420 {
22421     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22422 }
22423 }
22424 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22425 {
22426 IkReal evalcond[6];
22427 IkReal x7034=IKsin(j3);
22428 IkReal x7035=IKcos(j3);
22429 IkReal x7036=((sj0)*(sj5));
22430 IkReal x7037=((r00)*(sj6));
22431 IkReal x7038=((IkReal(1.00000000000000))*(cj4));
22432 IkReal x7039=((cj6)*(r01));
22433 IkReal x7040=((cj0)*(cj5));
22434 IkReal x7041=((cj5)*(sj0));
22435 IkReal x7042=((cj6)*(r11));
22436 IkReal x7043=((cj0)*(sj5));
22437 IkReal x7044=((IkReal(1.00000000000000))*(cj1));
22438 IkReal x7045=((cj6)*(sj4));
22439 IkReal x7046=((IkReal(1.00000000000000))*(sj1));
22440 IkReal x7047=((cj4)*(cj5));
22441 IkReal x7048=((cj6)*(r21));
22442 IkReal x7049=((r20)*(sj6));
22443 IkReal x7050=((r10)*(sj6));
22444 IkReal x7051=((IkReal(1.00000000000000))*(cj0));
22445 IkReal x7052=((cj0)*(sj4)*(sj6));
22446 IkReal x7053=((sj0)*(sj4)*(sj6));
22447 evalcond[0]=((((IkReal(-1.00000000000000))*(x7035)*(x7046)))+(((sj5)*(x7049)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7048))));
22448 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x7034)*(x7046)))+(((x7047)*(x7048)))+(((r20)*(x7045)))+(((x7047)*(x7049))));
22449 evalcond[2]=((((x7036)*(x7037)))+(((IkReal(-1.00000000000000))*(x7043)*(x7050)))+(((IkReal(-1.00000000000000))*(r02)*(x7041)))+(x7034)+(((r12)*(x7040)))+(((x7036)*(x7039)))+(((IkReal(-1.00000000000000))*(x7042)*(x7043))));
22450 evalcond[3]=((((IkReal(-1.00000000000000))*(x7039)*(x7043)))+(((IkReal(-1.00000000000000))*(x7037)*(x7043)))+(((IkReal(-1.00000000000000))*(x7035)*(x7044)))+(((IkReal(-1.00000000000000))*(x7036)*(x7042)))+(((IkReal(-1.00000000000000))*(x7036)*(x7050)))+(((r12)*(x7041)))+(((r02)*(x7040))));
22451 evalcond[4]=((((cj4)*(r02)*(x7036)))+(((IkReal(-1.00000000000000))*(r10)*(x7045)*(x7051)))+(((cj4)*(x7039)*(x7041)))+(((r11)*(x7052)))+(((IkReal(-1.00000000000000))*(x7038)*(x7040)*(x7042)))+(((IkReal(-1.00000000000000))*(x7038)*(x7040)*(x7050)))+(((IkReal(-1.00000000000000))*(x7035)))+(((IkReal(-1.00000000000000))*(r01)*(x7053)))+(((r00)*(sj0)*(x7045)))+(((cj4)*(x7037)*(x7041)))+(((IkReal(-1.00000000000000))*(r12)*(x7038)*(x7043))));
22452 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x7036)*(x7038)))+(((IkReal(-1.00000000000000))*(x7034)*(x7044)))+(((IkReal(-1.00000000000000))*(x7038)*(x7041)*(x7042)))+(((IkReal(-1.00000000000000))*(x7038)*(x7039)*(x7040)))+(((IkReal(-1.00000000000000))*(x7038)*(x7041)*(x7050)))+(((r01)*(x7052)))+(((IkReal(-1.00000000000000))*(r00)*(x7045)*(x7051)))+(((r11)*(x7053)))+(((IkReal(-1.00000000000000))*(x7037)*(x7038)*(x7040)))+(((IkReal(-1.00000000000000))*(r02)*(x7038)*(x7043)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7045))));
22453 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22454 {
22455 continue;
22456 }
22457 }
22458 
22459 {
22460 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22461 vinfos[0].jointtype = 1;
22462 vinfos[0].foffset = j0;
22463 vinfos[0].indices[0] = _ij0[0];
22464 vinfos[0].indices[1] = _ij0[1];
22465 vinfos[0].maxsolutions = _nj0;
22466 vinfos[1].jointtype = 1;
22467 vinfos[1].foffset = j1;
22468 vinfos[1].indices[0] = _ij1[0];
22469 vinfos[1].indices[1] = _ij1[1];
22470 vinfos[1].maxsolutions = _nj1;
22471 vinfos[2].jointtype = 1;
22472 vinfos[2].foffset = j2;
22473 vinfos[2].indices[0] = _ij2[0];
22474 vinfos[2].indices[1] = _ij2[1];
22475 vinfos[2].maxsolutions = _nj2;
22476 vinfos[3].jointtype = 1;
22477 vinfos[3].foffset = j3;
22478 vinfos[3].indices[0] = _ij3[0];
22479 vinfos[3].indices[1] = _ij3[1];
22480 vinfos[3].maxsolutions = _nj3;
22481 vinfos[4].jointtype = 1;
22482 vinfos[4].foffset = j4;
22483 vinfos[4].indices[0] = _ij4[0];
22484 vinfos[4].indices[1] = _ij4[1];
22485 vinfos[4].maxsolutions = _nj4;
22486 vinfos[5].jointtype = 1;
22487 vinfos[5].foffset = j5;
22488 vinfos[5].indices[0] = _ij5[0];
22489 vinfos[5].indices[1] = _ij5[1];
22490 vinfos[5].maxsolutions = _nj5;
22491 vinfos[6].jointtype = 1;
22492 vinfos[6].foffset = j6;
22493 vinfos[6].indices[0] = _ij6[0];
22494 vinfos[6].indices[1] = _ij6[1];
22495 vinfos[6].maxsolutions = _nj6;
22496 std::vector<int> vfree(0);
22497 solutions.AddSolution(vinfos,vfree);
22498 }
22499 }
22500 }
22501 
22502 }
22503 
22504 }
22505 
22506 } else
22507 {
22508 {
22509 IkReal j3array[1], cj3array[1], sj3array[1];
22510 bool j3valid[1]={false};
22511 _nj3 = 1;
22512 IkReal x7054=((r20)*(sj6));
22513 IkReal x7055=((cj4)*(cj5));
22514 IkReal x7056=((cj6)*(r21));
22515 if( IKabs(((gconst12)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x7055)*(x7056)))+(((x7054)*(x7055))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((sj5)*(x7054)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7056))))))) < IKFAST_ATAN2_MAGTHRESH )
22516     continue;
22517 j3array[0]=IKatan2(((gconst12)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x7055)*(x7056)))+(((x7054)*(x7055)))))), ((gconst12)*(((((sj5)*(x7054)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7056)))))));
22518 sj3array[0]=IKsin(j3array[0]);
22519 cj3array[0]=IKcos(j3array[0]);
22520 if( j3array[0] > IKPI )
22521 {
22522     j3array[0]-=IK2PI;
22523 }
22524 else if( j3array[0] < -IKPI )
22525 {    j3array[0]+=IK2PI;
22526 }
22527 j3valid[0] = true;
22528 for(int ij3 = 0; ij3 < 1; ++ij3)
22529 {
22530 if( !j3valid[ij3] )
22531 {
22532     continue;
22533 }
22534 _ij3[0] = ij3; _ij3[1] = -1;
22535 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22536 {
22537 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22538 {
22539     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22540 }
22541 }
22542 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22543 {
22544 IkReal evalcond[6];
22545 IkReal x7057=IKsin(j3);
22546 IkReal x7058=IKcos(j3);
22547 IkReal x7059=((sj0)*(sj5));
22548 IkReal x7060=((r00)*(sj6));
22549 IkReal x7061=((IkReal(1.00000000000000))*(cj4));
22550 IkReal x7062=((cj6)*(r01));
22551 IkReal x7063=((cj0)*(cj5));
22552 IkReal x7064=((cj5)*(sj0));
22553 IkReal x7065=((cj6)*(r11));
22554 IkReal x7066=((cj0)*(sj5));
22555 IkReal x7067=((IkReal(1.00000000000000))*(cj1));
22556 IkReal x7068=((cj6)*(sj4));
22557 IkReal x7069=((IkReal(1.00000000000000))*(sj1));
22558 IkReal x7070=((cj4)*(cj5));
22559 IkReal x7071=((cj6)*(r21));
22560 IkReal x7072=((r20)*(sj6));
22561 IkReal x7073=((r10)*(sj6));
22562 IkReal x7074=((IkReal(1.00000000000000))*(cj0));
22563 IkReal x7075=((cj0)*(sj4)*(sj6));
22564 IkReal x7076=((sj0)*(sj4)*(sj6));
22565 evalcond[0]=((((sj5)*(x7072)))+(((IkReal(-1.00000000000000))*(x7058)*(x7069)))+(((sj5)*(x7071)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
22566 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7068)))+(((x7070)*(x7071)))+(((IkReal(-1.00000000000000))*(x7057)*(x7069)))+(((x7070)*(x7072))));
22567 evalcond[2]=((((x7059)*(x7062)))+(((x7059)*(x7060)))+(((r12)*(x7063)))+(x7057)+(((IkReal(-1.00000000000000))*(r02)*(x7064)))+(((IkReal(-1.00000000000000))*(x7066)*(x7073)))+(((IkReal(-1.00000000000000))*(x7065)*(x7066))));
22568 evalcond[3]=((((IkReal(-1.00000000000000))*(x7060)*(x7066)))+(((IkReal(-1.00000000000000))*(x7059)*(x7073)))+(((r12)*(x7064)))+(((IkReal(-1.00000000000000))*(x7059)*(x7065)))+(((IkReal(-1.00000000000000))*(x7058)*(x7067)))+(((r02)*(x7063)))+(((IkReal(-1.00000000000000))*(x7062)*(x7066))));
22569 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x7061)*(x7066)))+(((IkReal(-1.00000000000000))*(x7061)*(x7063)*(x7065)))+(((r00)*(sj0)*(x7068)))+(((r11)*(x7075)))+(((IkReal(-1.00000000000000))*(x7058)))+(((cj4)*(x7062)*(x7064)))+(((IkReal(-1.00000000000000))*(x7061)*(x7063)*(x7073)))+(((IkReal(-1.00000000000000))*(r10)*(x7068)*(x7074)))+(((cj4)*(r02)*(x7059)))+(((IkReal(-1.00000000000000))*(r01)*(x7076)))+(((cj4)*(x7060)*(x7064))));
22570 evalcond[5]=((((IkReal(-1.00000000000000))*(x7061)*(x7062)*(x7063)))+(((IkReal(-1.00000000000000))*(r02)*(x7061)*(x7066)))+(((IkReal(-1.00000000000000))*(x7060)*(x7061)*(x7063)))+(((IkReal(-1.00000000000000))*(x7061)*(x7064)*(x7073)))+(((r01)*(x7075)))+(((IkReal(-1.00000000000000))*(r00)*(x7068)*(x7074)))+(((IkReal(-1.00000000000000))*(r12)*(x7059)*(x7061)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7068)))+(((IkReal(-1.00000000000000))*(x7057)*(x7067)))+(((IkReal(-1.00000000000000))*(x7061)*(x7064)*(x7065)))+(((r11)*(x7076))));
22571 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22572 {
22573 continue;
22574 }
22575 }
22576 
22577 {
22578 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22579 vinfos[0].jointtype = 1;
22580 vinfos[0].foffset = j0;
22581 vinfos[0].indices[0] = _ij0[0];
22582 vinfos[0].indices[1] = _ij0[1];
22583 vinfos[0].maxsolutions = _nj0;
22584 vinfos[1].jointtype = 1;
22585 vinfos[1].foffset = j1;
22586 vinfos[1].indices[0] = _ij1[0];
22587 vinfos[1].indices[1] = _ij1[1];
22588 vinfos[1].maxsolutions = _nj1;
22589 vinfos[2].jointtype = 1;
22590 vinfos[2].foffset = j2;
22591 vinfos[2].indices[0] = _ij2[0];
22592 vinfos[2].indices[1] = _ij2[1];
22593 vinfos[2].maxsolutions = _nj2;
22594 vinfos[3].jointtype = 1;
22595 vinfos[3].foffset = j3;
22596 vinfos[3].indices[0] = _ij3[0];
22597 vinfos[3].indices[1] = _ij3[1];
22598 vinfos[3].maxsolutions = _nj3;
22599 vinfos[4].jointtype = 1;
22600 vinfos[4].foffset = j4;
22601 vinfos[4].indices[0] = _ij4[0];
22602 vinfos[4].indices[1] = _ij4[1];
22603 vinfos[4].maxsolutions = _nj4;
22604 vinfos[5].jointtype = 1;
22605 vinfos[5].foffset = j5;
22606 vinfos[5].indices[0] = _ij5[0];
22607 vinfos[5].indices[1] = _ij5[1];
22608 vinfos[5].maxsolutions = _nj5;
22609 vinfos[6].jointtype = 1;
22610 vinfos[6].foffset = j6;
22611 vinfos[6].indices[0] = _ij6[0];
22612 vinfos[6].indices[1] = _ij6[1];
22613 vinfos[6].maxsolutions = _nj6;
22614 std::vector<int> vfree(0);
22615 solutions.AddSolution(vinfos,vfree);
22616 }
22617 }
22618 }
22619 
22620 }
22621 
22622 }
22623 
22624 } else
22625 {
22626 if( 1 )
22627 {
22628 continue;
22629 
22630 } else
22631 {
22632 }
22633 }
22634 }
22635 }
22636 }
22637 }
22638 }
22639 }
22640 
22641 } else
22642 {
22643 {
22644 IkReal j3array[1], cj3array[1], sj3array[1];
22645 bool j3valid[1]={false};
22646 _nj3 = 1;
22647 IkReal x7077=((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30);
22648 IkReal x7078=((sj5)*(sj6));
22649 IkReal x7079=((r00)*(sj0));
22650 IkReal x7080=((cj1)*(cj2));
22651 IkReal x7081=((cj0)*(r10));
22652 IkReal x7082=((cj6)*(sj5));
22653 IkReal x7083=((r01)*(sj0));
22654 IkReal x7084=((IkReal(1.00000000000000))*(cj0));
22655 IkReal x7085=((cj5)*(r12));
22656 IkReal x7086=((IkReal(1.00000000000000))*(cj5));
22657 IkReal x7087=((r02)*(sj0));
22658 if( IKabs(((x7077)*(((((cj0)*(x7085)))+(((IkReal(-1.00000000000000))*(x7086)*(x7087)))+(((IkReal(-1.00000000000000))*(r11)*(x7082)*(x7084)))+(((IkReal(-1.00000000000000))*(x7078)*(x7081)))+(((x7078)*(x7079)))+(((x7082)*(x7083))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x7077)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((cj5)*(x7080)*(x7087)))+(((cj0)*(r11)*(x7080)*(x7082)))+(((IkReal(-1.00000000000000))*(x7078)*(x7079)*(x7080)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x7086)))+(((r21)*(sj2)*(x7082)))+(((r20)*(sj2)*(x7078)))+(((IkReal(-1.00000000000000))*(x7080)*(x7082)*(x7083)))+(((x7078)*(x7080)*(x7081)))+(((IkReal(-1.00000000000000))*(x7080)*(x7084)*(x7085))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x7077)*(((((cj0)*(x7085)))+(((IkReal(-1.00000000000000))*(x7086)*(x7087)))+(((IkReal(-1.00000000000000))*(r11)*(x7082)*(x7084)))+(((IkReal(-1.00000000000000))*(x7078)*(x7081)))+(((x7078)*(x7079)))+(((x7082)*(x7083)))))))+IKsqr(((x7077)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((cj5)*(x7080)*(x7087)))+(((cj0)*(r11)*(x7080)*(x7082)))+(((IkReal(-1.00000000000000))*(x7078)*(x7079)*(x7080)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x7086)))+(((r21)*(sj2)*(x7082)))+(((r20)*(sj2)*(x7078)))+(((IkReal(-1.00000000000000))*(x7080)*(x7082)*(x7083)))+(((x7078)*(x7080)*(x7081)))+(((IkReal(-1.00000000000000))*(x7080)*(x7084)*(x7085)))))))-1) <= IKFAST_SINCOS_THRESH )
22659     continue;
22660 j3array[0]=IKatan2(((x7077)*(((((cj0)*(x7085)))+(((IkReal(-1.00000000000000))*(x7086)*(x7087)))+(((IkReal(-1.00000000000000))*(r11)*(x7082)*(x7084)))+(((IkReal(-1.00000000000000))*(x7078)*(x7081)))+(((x7078)*(x7079)))+(((x7082)*(x7083)))))), ((x7077)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((cj5)*(x7080)*(x7087)))+(((cj0)*(r11)*(x7080)*(x7082)))+(((IkReal(-1.00000000000000))*(x7078)*(x7079)*(x7080)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x7086)))+(((r21)*(sj2)*(x7082)))+(((r20)*(sj2)*(x7078)))+(((IkReal(-1.00000000000000))*(x7080)*(x7082)*(x7083)))+(((x7078)*(x7080)*(x7081)))+(((IkReal(-1.00000000000000))*(x7080)*(x7084)*(x7085)))))));
22661 sj3array[0]=IKsin(j3array[0]);
22662 cj3array[0]=IKcos(j3array[0]);
22663 if( j3array[0] > IKPI )
22664 {
22665     j3array[0]-=IK2PI;
22666 }
22667 else if( j3array[0] < -IKPI )
22668 {    j3array[0]+=IK2PI;
22669 }
22670 j3valid[0] = true;
22671 for(int ij3 = 0; ij3 < 1; ++ij3)
22672 {
22673 if( !j3valid[ij3] )
22674 {
22675     continue;
22676 }
22677 _ij3[0] = ij3; _ij3[1] = -1;
22678 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22679 {
22680 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22681 {
22682     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22683 }
22684 }
22685 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22686 {
22687 IkReal evalcond[6];
22688 IkReal x7088=IKcos(j3);
22689 IkReal x7089=IKsin(j3);
22690 IkReal x7090=((sj0)*(sj5));
22691 IkReal x7091=((r00)*(sj6));
22692 IkReal x7092=((IkReal(1.00000000000000))*(cj4));
22693 IkReal x7093=((cj6)*(r01));
22694 IkReal x7094=((cj0)*(cj5));
22695 IkReal x7095=((cj5)*(sj0));
22696 IkReal x7096=((cj6)*(r11));
22697 IkReal x7097=((cj6)*(sj4));
22698 IkReal x7098=((IkReal(1.00000000000000))*(cj1));
22699 IkReal x7099=((cj4)*(cj5));
22700 IkReal x7100=((cj6)*(r21));
22701 IkReal x7101=((r20)*(sj6));
22702 IkReal x7102=((r10)*(sj6));
22703 IkReal x7103=((cj0)*(sj5));
22704 IkReal x7104=((IkReal(1.00000000000000))*(cj0));
22705 IkReal x7105=((IkReal(1.00000000000000))*(x7103));
22706 IkReal x7106=((IkReal(1.00000000000000))*(x7089));
22707 IkReal x7107=((cj0)*(sj4)*(sj6));
22708 IkReal x7108=((cj2)*(x7089));
22709 IkReal x7109=((sj0)*(sj4)*(sj6));
22710 IkReal x7110=((IkReal(1.00000000000000))*(sj1)*(x7088));
22711 evalcond[0]=((((sj5)*(x7101)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x7110)))+(((IkReal(-1.00000000000000))*(x7098)*(x7108)))+(((sj5)*(x7100))));
22712 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(sj1)*(x7106)))+(((cj1)*(cj2)*(x7088)))+(((cj4)*(r22)*(sj5)))+(((x7099)*(x7100)))+(((x7099)*(x7101)))+(((r20)*(x7097))));
22713 evalcond[2]=((((IkReal(-1.00000000000000))*(x7096)*(x7105)))+(((r12)*(x7094)))+(((IkReal(-1.00000000000000))*(x7102)*(x7105)))+(((x7090)*(x7091)))+(((x7090)*(x7093)))+(((IkReal(-1.00000000000000))*(sj2)*(x7106)))+(((IkReal(-1.00000000000000))*(r02)*(x7095))));
22714 evalcond[3]=((((IkReal(-1.00000000000000))*(x7088)*(x7098)))+(((IkReal(-1.00000000000000))*(x7090)*(x7096)))+(((r12)*(x7095)))+(((sj1)*(x7108)))+(((IkReal(-1.00000000000000))*(x7091)*(x7105)))+(((IkReal(-1.00000000000000))*(x7090)*(x7102)))+(((r02)*(x7094)))+(((IkReal(-1.00000000000000))*(x7093)*(x7105))));
22715 evalcond[4]=((((cj4)*(r02)*(x7090)))+(((sj2)*(x7088)))+(((r11)*(x7107)))+(((r00)*(sj0)*(x7097)))+(((IkReal(-1.00000000000000))*(r10)*(x7097)*(x7104)))+(((cj4)*(x7093)*(x7095)))+(((IkReal(-1.00000000000000))*(x7092)*(x7094)*(x7096)))+(((cj4)*(x7091)*(x7095)))+(((IkReal(-1.00000000000000))*(x7092)*(x7094)*(x7102)))+(((IkReal(-1.00000000000000))*(r12)*(x7092)*(x7103)))+(((IkReal(-1.00000000000000))*(r01)*(x7109))));
22716 evalcond[5]=((((IkReal(-1.00000000000000))*(cj2)*(x7110)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7097)))+(((IkReal(-1.00000000000000))*(r00)*(x7097)*(x7104)))+(((IkReal(-1.00000000000000))*(x7089)*(x7098)))+(((IkReal(-1.00000000000000))*(x7092)*(x7095)*(x7102)))+(((IkReal(-1.00000000000000))*(x7091)*(x7092)*(x7094)))+(((IkReal(-1.00000000000000))*(x7092)*(x7095)*(x7096)))+(((IkReal(-1.00000000000000))*(r12)*(x7090)*(x7092)))+(((r11)*(x7109)))+(((r01)*(x7107)))+(((IkReal(-1.00000000000000))*(x7092)*(x7093)*(x7094)))+(((IkReal(-1.00000000000000))*(r02)*(x7092)*(x7103))));
22717 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22718 {
22719 continue;
22720 }
22721 }
22722 
22723 {
22724 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22725 vinfos[0].jointtype = 1;
22726 vinfos[0].foffset = j0;
22727 vinfos[0].indices[0] = _ij0[0];
22728 vinfos[0].indices[1] = _ij0[1];
22729 vinfos[0].maxsolutions = _nj0;
22730 vinfos[1].jointtype = 1;
22731 vinfos[1].foffset = j1;
22732 vinfos[1].indices[0] = _ij1[0];
22733 vinfos[1].indices[1] = _ij1[1];
22734 vinfos[1].maxsolutions = _nj1;
22735 vinfos[2].jointtype = 1;
22736 vinfos[2].foffset = j2;
22737 vinfos[2].indices[0] = _ij2[0];
22738 vinfos[2].indices[1] = _ij2[1];
22739 vinfos[2].maxsolutions = _nj2;
22740 vinfos[3].jointtype = 1;
22741 vinfos[3].foffset = j3;
22742 vinfos[3].indices[0] = _ij3[0];
22743 vinfos[3].indices[1] = _ij3[1];
22744 vinfos[3].maxsolutions = _nj3;
22745 vinfos[4].jointtype = 1;
22746 vinfos[4].foffset = j4;
22747 vinfos[4].indices[0] = _ij4[0];
22748 vinfos[4].indices[1] = _ij4[1];
22749 vinfos[4].maxsolutions = _nj4;
22750 vinfos[5].jointtype = 1;
22751 vinfos[5].foffset = j5;
22752 vinfos[5].indices[0] = _ij5[0];
22753 vinfos[5].indices[1] = _ij5[1];
22754 vinfos[5].maxsolutions = _nj5;
22755 vinfos[6].jointtype = 1;
22756 vinfos[6].foffset = j6;
22757 vinfos[6].indices[0] = _ij6[0];
22758 vinfos[6].indices[1] = _ij6[1];
22759 vinfos[6].maxsolutions = _nj6;
22760 std::vector<int> vfree(0);
22761 solutions.AddSolution(vinfos,vfree);
22762 }
22763 }
22764 }
22765 
22766 }
22767 
22768 }
22769 
22770 } else
22771 {
22772 {
22773 IkReal j3array[1], cj3array[1], sj3array[1];
22774 bool j3valid[1]={false};
22775 _nj3 = 1;
22776 IkReal x7111=(cj1)*(cj1);
22777 IkReal x7112=(sj1)*(sj1);
22778 IkReal x7113=((r00)*(sj6));
22779 IkReal x7114=((cj6)*(r01));
22780 IkReal x7115=((IkReal(1.00000000000000))*(cj1));
22781 IkReal x7116=((cj5)*(r22));
22782 IkReal x7117=((sj5)*(sj6));
22783 IkReal x7118=((r10)*(sj0));
22784 IkReal x7119=((cj1)*(cj5));
22785 IkReal x7120=((cj0)*(r02));
22786 IkReal x7121=((r12)*(sj0));
22787 IkReal x7122=((IkReal(1.00000000000000))*(sj1));
22788 IkReal x7123=((cj6)*(sj5));
22789 IkReal x7124=((cj0)*(sj5));
22790 IkReal x7125=((r11)*(sj0));
22791 IkReal x7126=((sj1)*(x7124));
22792 if( IKabs(((((IKabs(((((cj2)*(x7111)))+(((cj2)*(x7112))))) != 0)?((IkReal)1/(((((cj2)*(x7111)))+(((cj2)*(x7112)))))):(IkReal)1.0e30))*(((((sj1)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7116)))+(((IkReal(-1.00000000000000))*(cj5)*(x7121)*(x7122)))+(((sj1)*(x7117)*(x7118)))+(((cj1)*(r21)*(x7123)))+(((x7113)*(x7126)))+(((x7114)*(x7126)))+(((IkReal(-1.00000000000000))*(cj5)*(x7120)*(x7122)))+(((cj1)*(r20)*(x7117))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x7112)+(x7111))) != 0)?((IkReal)1/(((x7112)+(x7111)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x7123)))+(((IkReal(-1.00000000000000))*(x7114)*(x7115)*(x7124)))+(((r20)*(sj1)*(x7117)))+(((IkReal(-1.00000000000000))*(x7113)*(x7115)*(x7124)))+(((x7119)*(x7121)))+(((IkReal(-1.00000000000000))*(x7116)*(x7122)))+(((IkReal(-1.00000000000000))*(x7115)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7117)*(x7118)))+(((x7119)*(x7120))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x7111)))+(((cj2)*(x7112))))) != 0)?((IkReal)1/(((((cj2)*(x7111)))+(((cj2)*(x7112)))))):(IkReal)1.0e30))*(((((sj1)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7116)))+(((IkReal(-1.00000000000000))*(cj5)*(x7121)*(x7122)))+(((sj1)*(x7117)*(x7118)))+(((cj1)*(r21)*(x7123)))+(((x7113)*(x7126)))+(((x7114)*(x7126)))+(((IkReal(-1.00000000000000))*(cj5)*(x7120)*(x7122)))+(((cj1)*(r20)*(x7117)))))))+IKsqr(((((IKabs(((x7112)+(x7111))) != 0)?((IkReal)1/(((x7112)+(x7111)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x7123)))+(((IkReal(-1.00000000000000))*(x7114)*(x7115)*(x7124)))+(((r20)*(sj1)*(x7117)))+(((IkReal(-1.00000000000000))*(x7113)*(x7115)*(x7124)))+(((x7119)*(x7121)))+(((IkReal(-1.00000000000000))*(x7116)*(x7122)))+(((IkReal(-1.00000000000000))*(x7115)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7117)*(x7118)))+(((x7119)*(x7120)))))))-1) <= IKFAST_SINCOS_THRESH )
22793     continue;
22794 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x7111)))+(((cj2)*(x7112))))) != 0)?((IkReal)1/(((((cj2)*(x7111)))+(((cj2)*(x7112)))))):(IkReal)1.0e30))*(((((sj1)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7116)))+(((IkReal(-1.00000000000000))*(cj5)*(x7121)*(x7122)))+(((sj1)*(x7117)*(x7118)))+(((cj1)*(r21)*(x7123)))+(((x7113)*(x7126)))+(((x7114)*(x7126)))+(((IkReal(-1.00000000000000))*(cj5)*(x7120)*(x7122)))+(((cj1)*(r20)*(x7117)))))), ((((IKabs(((x7112)+(x7111))) != 0)?((IkReal)1/(((x7112)+(x7111)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x7123)))+(((IkReal(-1.00000000000000))*(x7114)*(x7115)*(x7124)))+(((r20)*(sj1)*(x7117)))+(((IkReal(-1.00000000000000))*(x7113)*(x7115)*(x7124)))+(((x7119)*(x7121)))+(((IkReal(-1.00000000000000))*(x7116)*(x7122)))+(((IkReal(-1.00000000000000))*(x7115)*(x7123)*(x7125)))+(((IkReal(-1.00000000000000))*(x7115)*(x7117)*(x7118)))+(((x7119)*(x7120)))))));
22795 sj3array[0]=IKsin(j3array[0]);
22796 cj3array[0]=IKcos(j3array[0]);
22797 if( j3array[0] > IKPI )
22798 {
22799     j3array[0]-=IK2PI;
22800 }
22801 else if( j3array[0] < -IKPI )
22802 {    j3array[0]+=IK2PI;
22803 }
22804 j3valid[0] = true;
22805 for(int ij3 = 0; ij3 < 1; ++ij3)
22806 {
22807 if( !j3valid[ij3] )
22808 {
22809     continue;
22810 }
22811 _ij3[0] = ij3; _ij3[1] = -1;
22812 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22813 {
22814 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22815 {
22816     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22817 }
22818 }
22819 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22820 {
22821 IkReal evalcond[6];
22822 IkReal x7127=IKcos(j3);
22823 IkReal x7128=IKsin(j3);
22824 IkReal x7129=((sj0)*(sj5));
22825 IkReal x7130=((r00)*(sj6));
22826 IkReal x7131=((IkReal(1.00000000000000))*(cj4));
22827 IkReal x7132=((cj6)*(r01));
22828 IkReal x7133=((cj0)*(cj5));
22829 IkReal x7134=((cj5)*(sj0));
22830 IkReal x7135=((cj6)*(r11));
22831 IkReal x7136=((cj6)*(sj4));
22832 IkReal x7137=((IkReal(1.00000000000000))*(cj1));
22833 IkReal x7138=((cj4)*(cj5));
22834 IkReal x7139=((cj6)*(r21));
22835 IkReal x7140=((r20)*(sj6));
22836 IkReal x7141=((r10)*(sj6));
22837 IkReal x7142=((cj0)*(sj5));
22838 IkReal x7143=((IkReal(1.00000000000000))*(cj0));
22839 IkReal x7144=((IkReal(1.00000000000000))*(x7142));
22840 IkReal x7145=((IkReal(1.00000000000000))*(x7128));
22841 IkReal x7146=((cj0)*(sj4)*(sj6));
22842 IkReal x7147=((cj2)*(x7128));
22843 IkReal x7148=((sj0)*(sj4)*(sj6));
22844 IkReal x7149=((IkReal(1.00000000000000))*(sj1)*(x7127));
22845 evalcond[0]=((((IkReal(-1.00000000000000))*(x7137)*(x7147)))+(((sj5)*(x7139)))+(((IkReal(-1.00000000000000))*(x7149)))+(((sj5)*(x7140)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
22846 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x7138)*(x7140)))+(((r20)*(x7136)))+(((cj4)*(r22)*(sj5)))+(((x7138)*(x7139)))+(((cj1)*(cj2)*(x7127)))+(((IkReal(-1.00000000000000))*(sj1)*(x7145))));
22847 evalcond[2]=((((IkReal(-1.00000000000000))*(x7141)*(x7144)))+(((IkReal(-1.00000000000000))*(sj2)*(x7145)))+(((r12)*(x7133)))+(((IkReal(-1.00000000000000))*(r02)*(x7134)))+(((x7129)*(x7132)))+(((IkReal(-1.00000000000000))*(x7135)*(x7144)))+(((x7129)*(x7130))));
22848 evalcond[3]=((((IkReal(-1.00000000000000))*(x7129)*(x7135)))+(((IkReal(-1.00000000000000))*(x7127)*(x7137)))+(((IkReal(-1.00000000000000))*(x7129)*(x7141)))+(((IkReal(-1.00000000000000))*(x7132)*(x7144)))+(((IkReal(-1.00000000000000))*(x7130)*(x7144)))+(((sj1)*(x7147)))+(((r02)*(x7133)))+(((r12)*(x7134))));
22849 evalcond[4]=((((r11)*(x7146)))+(((cj4)*(x7132)*(x7134)))+(((IkReal(-1.00000000000000))*(r12)*(x7131)*(x7142)))+(((IkReal(-1.00000000000000))*(r10)*(x7136)*(x7143)))+(((r00)*(sj0)*(x7136)))+(((sj2)*(x7127)))+(((IkReal(-1.00000000000000))*(x7131)*(x7133)*(x7141)))+(((cj4)*(r02)*(x7129)))+(((IkReal(-1.00000000000000))*(r01)*(x7148)))+(((IkReal(-1.00000000000000))*(x7131)*(x7133)*(x7135)))+(((cj4)*(x7130)*(x7134))));
22850 evalcond[5]=((((IkReal(-1.00000000000000))*(cj2)*(x7149)))+(((IkReal(-1.00000000000000))*(x7128)*(x7137)))+(((IkReal(-1.00000000000000))*(r00)*(x7136)*(x7143)))+(((r01)*(x7146)))+(((r11)*(x7148)))+(((IkReal(-1.00000000000000))*(x7131)*(x7134)*(x7141)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7136)))+(((IkReal(-1.00000000000000))*(x7131)*(x7134)*(x7135)))+(((IkReal(-1.00000000000000))*(r12)*(x7129)*(x7131)))+(((IkReal(-1.00000000000000))*(x7130)*(x7131)*(x7133)))+(((IkReal(-1.00000000000000))*(r02)*(x7131)*(x7142)))+(((IkReal(-1.00000000000000))*(x7131)*(x7132)*(x7133))));
22851 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22852 {
22853 continue;
22854 }
22855 }
22856 
22857 {
22858 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22859 vinfos[0].jointtype = 1;
22860 vinfos[0].foffset = j0;
22861 vinfos[0].indices[0] = _ij0[0];
22862 vinfos[0].indices[1] = _ij0[1];
22863 vinfos[0].maxsolutions = _nj0;
22864 vinfos[1].jointtype = 1;
22865 vinfos[1].foffset = j1;
22866 vinfos[1].indices[0] = _ij1[0];
22867 vinfos[1].indices[1] = _ij1[1];
22868 vinfos[1].maxsolutions = _nj1;
22869 vinfos[2].jointtype = 1;
22870 vinfos[2].foffset = j2;
22871 vinfos[2].indices[0] = _ij2[0];
22872 vinfos[2].indices[1] = _ij2[1];
22873 vinfos[2].maxsolutions = _nj2;
22874 vinfos[3].jointtype = 1;
22875 vinfos[3].foffset = j3;
22876 vinfos[3].indices[0] = _ij3[0];
22877 vinfos[3].indices[1] = _ij3[1];
22878 vinfos[3].maxsolutions = _nj3;
22879 vinfos[4].jointtype = 1;
22880 vinfos[4].foffset = j4;
22881 vinfos[4].indices[0] = _ij4[0];
22882 vinfos[4].indices[1] = _ij4[1];
22883 vinfos[4].maxsolutions = _nj4;
22884 vinfos[5].jointtype = 1;
22885 vinfos[5].foffset = j5;
22886 vinfos[5].indices[0] = _ij5[0];
22887 vinfos[5].indices[1] = _ij5[1];
22888 vinfos[5].maxsolutions = _nj5;
22889 vinfos[6].jointtype = 1;
22890 vinfos[6].foffset = j6;
22891 vinfos[6].indices[0] = _ij6[0];
22892 vinfos[6].indices[1] = _ij6[1];
22893 vinfos[6].maxsolutions = _nj6;
22894 std::vector<int> vfree(0);
22895 solutions.AddSolution(vinfos,vfree);
22896 }
22897 }
22898 }
22899 
22900 }
22901 
22902 }
22903 
22904 } else
22905 {
22906 {
22907 IkReal j3array[1], cj3array[1], sj3array[1];
22908 bool j3valid[1]={false};
22909 _nj3 = 1;
22910 IkReal x7150=((sj1)*(sj6));
22911 IkReal x7151=((r20)*(sj5));
22912 IkReal x7152=((IkReal(1.00000000000000))*(r21));
22913 IkReal x7153=((cj5)*(cj6));
22914 IkReal x7154=((r22)*(sj5));
22915 IkReal x7155=((cj4)*(sj1));
22916 IkReal x7156=((cj1)*(cj2));
22917 IkReal x7157=((cj5)*(r20));
22918 IkReal x7158=((cj4)*(x7156));
22919 IkReal x7159=((IkReal(1.00000000000000))*(cj5)*(r22));
22920 IkReal x7160=((cj6)*(r20)*(sj4));
22921 IkReal x7161=((cj6)*(r21)*(sj5));
22922 if( IKabs(((gconst4)*(((((cj4)*(x7150)*(x7157)))+(((r21)*(x7153)*(x7155)))+(((IkReal(-1.00000000000000))*(x7156)*(x7159)))+(((sj6)*(x7151)*(x7156)))+(((sj1)*(x7160)))+(((x7154)*(x7155)))+(((IkReal(-1.00000000000000))*(sj4)*(x7150)*(x7152)))+(((x7156)*(x7161))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(x7152)*(x7153)*(x7158)))+(((x7150)*(x7151)))+(((IkReal(-1.00000000000000))*(sj1)*(x7159)))+(((IkReal(-1.00000000000000))*(x7156)*(x7160)))+(((IkReal(-1.00000000000000))*(sj6)*(x7157)*(x7158)))+(((IkReal(-1.00000000000000))*(x7154)*(x7158)))+(((sj1)*(x7161)))+(((r21)*(sj4)*(sj6)*(x7156))))))) < IKFAST_ATAN2_MAGTHRESH )
22923     continue;
22924 j3array[0]=IKatan2(((gconst4)*(((((cj4)*(x7150)*(x7157)))+(((r21)*(x7153)*(x7155)))+(((IkReal(-1.00000000000000))*(x7156)*(x7159)))+(((sj6)*(x7151)*(x7156)))+(((sj1)*(x7160)))+(((x7154)*(x7155)))+(((IkReal(-1.00000000000000))*(sj4)*(x7150)*(x7152)))+(((x7156)*(x7161)))))), ((gconst4)*(((((IkReal(-1.00000000000000))*(x7152)*(x7153)*(x7158)))+(((x7150)*(x7151)))+(((IkReal(-1.00000000000000))*(sj1)*(x7159)))+(((IkReal(-1.00000000000000))*(x7156)*(x7160)))+(((IkReal(-1.00000000000000))*(sj6)*(x7157)*(x7158)))+(((IkReal(-1.00000000000000))*(x7154)*(x7158)))+(((sj1)*(x7161)))+(((r21)*(sj4)*(sj6)*(x7156)))))));
22925 sj3array[0]=IKsin(j3array[0]);
22926 cj3array[0]=IKcos(j3array[0]);
22927 if( j3array[0] > IKPI )
22928 {
22929     j3array[0]-=IK2PI;
22930 }
22931 else if( j3array[0] < -IKPI )
22932 {    j3array[0]+=IK2PI;
22933 }
22934 j3valid[0] = true;
22935 for(int ij3 = 0; ij3 < 1; ++ij3)
22936 {
22937 if( !j3valid[ij3] )
22938 {
22939     continue;
22940 }
22941 _ij3[0] = ij3; _ij3[1] = -1;
22942 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
22943 {
22944 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
22945 {
22946     j3valid[iij3]=false; _ij3[1] = iij3; break; 
22947 }
22948 }
22949 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
22950 {
22951 IkReal evalcond[6];
22952 IkReal x7162=IKcos(j3);
22953 IkReal x7163=IKsin(j3);
22954 IkReal x7164=((sj0)*(sj5));
22955 IkReal x7165=((r00)*(sj6));
22956 IkReal x7166=((IkReal(1.00000000000000))*(cj4));
22957 IkReal x7167=((cj6)*(r01));
22958 IkReal x7168=((cj0)*(cj5));
22959 IkReal x7169=((cj5)*(sj0));
22960 IkReal x7170=((cj6)*(r11));
22961 IkReal x7171=((cj6)*(sj4));
22962 IkReal x7172=((IkReal(1.00000000000000))*(cj1));
22963 IkReal x7173=((cj4)*(cj5));
22964 IkReal x7174=((cj6)*(r21));
22965 IkReal x7175=((r20)*(sj6));
22966 IkReal x7176=((r10)*(sj6));
22967 IkReal x7177=((cj0)*(sj5));
22968 IkReal x7178=((IkReal(1.00000000000000))*(cj0));
22969 IkReal x7179=((IkReal(1.00000000000000))*(x7177));
22970 IkReal x7180=((IkReal(1.00000000000000))*(x7163));
22971 IkReal x7181=((cj0)*(sj4)*(sj6));
22972 IkReal x7182=((cj2)*(x7163));
22973 IkReal x7183=((sj0)*(sj4)*(sj6));
22974 IkReal x7184=((IkReal(1.00000000000000))*(sj1)*(x7162));
22975 evalcond[0]=((((IkReal(-1.00000000000000))*(x7184)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7174)))+(((IkReal(-1.00000000000000))*(x7172)*(x7182)))+(((sj5)*(x7175))));
22976 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj1)*(cj2)*(x7162)))+(((x7173)*(x7175)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7171)))+(((x7173)*(x7174)))+(((IkReal(-1.00000000000000))*(sj1)*(x7180))));
22977 evalcond[2]=((((x7164)*(x7167)))+(((x7164)*(x7165)))+(((IkReal(-1.00000000000000))*(x7176)*(x7179)))+(((IkReal(-1.00000000000000))*(sj2)*(x7180)))+(((r12)*(x7168)))+(((IkReal(-1.00000000000000))*(x7170)*(x7179)))+(((IkReal(-1.00000000000000))*(r02)*(x7169))));
22978 evalcond[3]=((((IkReal(-1.00000000000000))*(x7165)*(x7179)))+(((r12)*(x7169)))+(((IkReal(-1.00000000000000))*(x7162)*(x7172)))+(((sj1)*(x7182)))+(((r02)*(x7168)))+(((IkReal(-1.00000000000000))*(x7164)*(x7170)))+(((IkReal(-1.00000000000000))*(x7164)*(x7176)))+(((IkReal(-1.00000000000000))*(x7167)*(x7179))));
22979 evalcond[4]=((((cj4)*(r02)*(x7164)))+(((IkReal(-1.00000000000000))*(x7166)*(x7168)*(x7176)))+(((IkReal(-1.00000000000000))*(r12)*(x7166)*(x7177)))+(((r00)*(sj0)*(x7171)))+(((IkReal(-1.00000000000000))*(r10)*(x7171)*(x7178)))+(((sj2)*(x7162)))+(((cj4)*(x7167)*(x7169)))+(((IkReal(-1.00000000000000))*(x7166)*(x7168)*(x7170)))+(((IkReal(-1.00000000000000))*(r01)*(x7183)))+(((cj4)*(x7165)*(x7169)))+(((r11)*(x7181))));
22980 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7171)))+(((IkReal(-1.00000000000000))*(x7166)*(x7169)*(x7176)))+(((IkReal(-1.00000000000000))*(r02)*(x7166)*(x7177)))+(((IkReal(-1.00000000000000))*(r00)*(x7171)*(x7178)))+(((IkReal(-1.00000000000000))*(x7166)*(x7167)*(x7168)))+(((IkReal(-1.00000000000000))*(r12)*(x7164)*(x7166)))+(((IkReal(-1.00000000000000))*(x7165)*(x7166)*(x7168)))+(((r11)*(x7183)))+(((IkReal(-1.00000000000000))*(cj2)*(x7184)))+(((IkReal(-1.00000000000000))*(x7166)*(x7169)*(x7170)))+(((r01)*(x7181)))+(((IkReal(-1.00000000000000))*(x7163)*(x7172))));
22981 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
22982 {
22983 continue;
22984 }
22985 }
22986 
22987 {
22988 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
22989 vinfos[0].jointtype = 1;
22990 vinfos[0].foffset = j0;
22991 vinfos[0].indices[0] = _ij0[0];
22992 vinfos[0].indices[1] = _ij0[1];
22993 vinfos[0].maxsolutions = _nj0;
22994 vinfos[1].jointtype = 1;
22995 vinfos[1].foffset = j1;
22996 vinfos[1].indices[0] = _ij1[0];
22997 vinfos[1].indices[1] = _ij1[1];
22998 vinfos[1].maxsolutions = _nj1;
22999 vinfos[2].jointtype = 1;
23000 vinfos[2].foffset = j2;
23001 vinfos[2].indices[0] = _ij2[0];
23002 vinfos[2].indices[1] = _ij2[1];
23003 vinfos[2].maxsolutions = _nj2;
23004 vinfos[3].jointtype = 1;
23005 vinfos[3].foffset = j3;
23006 vinfos[3].indices[0] = _ij3[0];
23007 vinfos[3].indices[1] = _ij3[1];
23008 vinfos[3].maxsolutions = _nj3;
23009 vinfos[4].jointtype = 1;
23010 vinfos[4].foffset = j4;
23011 vinfos[4].indices[0] = _ij4[0];
23012 vinfos[4].indices[1] = _ij4[1];
23013 vinfos[4].maxsolutions = _nj4;
23014 vinfos[5].jointtype = 1;
23015 vinfos[5].foffset = j5;
23016 vinfos[5].indices[0] = _ij5[0];
23017 vinfos[5].indices[1] = _ij5[1];
23018 vinfos[5].maxsolutions = _nj5;
23019 vinfos[6].jointtype = 1;
23020 vinfos[6].foffset = j6;
23021 vinfos[6].indices[0] = _ij6[0];
23022 vinfos[6].indices[1] = _ij6[1];
23023 vinfos[6].maxsolutions = _nj6;
23024 std::vector<int> vfree(0);
23025 solutions.AddSolution(vinfos,vfree);
23026 }
23027 }
23028 }
23029 
23030 }
23031 
23032 }
23033 }
23034 }
23035 
23036 }
23037 
23038 }
23039 
23040 } else
23041 {
23042 {
23043 IkReal j4array[1], cj4array[1], sj4array[1];
23044 bool j4valid[1]={false};
23045 _nj4 = 1;
23046 IkReal x7185=((cj5)*(sj0));
23047 IkReal x7186=((cj2)*(sj6));
23048 IkReal x7187=((IkReal(1.00000000000000))*(cj0));
23049 IkReal x7188=((cj2)*(cj6));
23050 IkReal x7189=((cj1)*(cj6)*(sj2));
23051 IkReal x7190=((r10)*(x7187));
23052 IkReal x7191=((cj1)*(sj2)*(sj6));
23053 IkReal x7192=((cj1)*(sj2)*(sj5));
23054 if( IKabs(((gconst0)*(((((r00)*(sj0)*(x7189)))+(((IkReal(-1.00000000000000))*(x7189)*(x7190)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x7191)))+(((r20)*(x7188)))+(((cj0)*(r11)*(x7191)))+(((IkReal(-1.00000000000000))*(r21)*(x7186))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(cj5)*(x7190)*(x7191)))+(((cj2)*(r22)*(sj5)))+(((cj5)*(r20)*(x7186)))+(((cj5)*(r21)*(x7188)))+(((r02)*(sj0)*(x7192)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7187)*(x7189)))+(((IkReal(-1.00000000000000))*(r12)*(x7187)*(x7192)))+(((r00)*(x7185)*(x7191)))+(((r01)*(x7185)*(x7189))))))) < IKFAST_ATAN2_MAGTHRESH )
23055     continue;
23056 j4array[0]=IKatan2(((gconst0)*(((((r00)*(sj0)*(x7189)))+(((IkReal(-1.00000000000000))*(x7189)*(x7190)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x7191)))+(((r20)*(x7188)))+(((cj0)*(r11)*(x7191)))+(((IkReal(-1.00000000000000))*(r21)*(x7186)))))), ((gconst0)*(((((IkReal(-1.00000000000000))*(cj5)*(x7190)*(x7191)))+(((cj2)*(r22)*(sj5)))+(((cj5)*(r20)*(x7186)))+(((cj5)*(r21)*(x7188)))+(((r02)*(sj0)*(x7192)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7187)*(x7189)))+(((IkReal(-1.00000000000000))*(r12)*(x7187)*(x7192)))+(((r00)*(x7185)*(x7191)))+(((r01)*(x7185)*(x7189)))))));
23057 sj4array[0]=IKsin(j4array[0]);
23058 cj4array[0]=IKcos(j4array[0]);
23059 if( j4array[0] > IKPI )
23060 {
23061     j4array[0]-=IK2PI;
23062 }
23063 else if( j4array[0] < -IKPI )
23064 {    j4array[0]+=IK2PI;
23065 }
23066 j4valid[0] = true;
23067 for(int ij4 = 0; ij4 < 1; ++ij4)
23068 {
23069 if( !j4valid[ij4] )
23070 {
23071     continue;
23072 }
23073 _ij4[0] = ij4; _ij4[1] = -1;
23074 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
23075 {
23076 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
23077 {
23078     j4valid[iij4]=false; _ij4[1] = iij4; break; 
23079 }
23080 }
23081 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
23082 {
23083 IkReal evalcond[3];
23084 IkReal x7193=IKsin(j4);
23085 IkReal x7194=IKcos(j4);
23086 IkReal x7195=((r00)*(sj6));
23087 IkReal x7196=((cj6)*(r01));
23088 IkReal x7197=((IkReal(1.00000000000000))*(cj0));
23089 IkReal x7198=((IkReal(1.00000000000000))*(sj0));
23090 IkReal x7199=((r10)*(sj6));
23091 IkReal x7200=((sj5)*(x7193));
23092 IkReal x7201=((IkReal(1.00000000000000))*(cj6)*(r11));
23093 IkReal x7202=((cj5)*(x7193));
23094 IkReal x7203=((cj6)*(x7194));
23095 IkReal x7204=((sj0)*(x7202));
23096 IkReal x7205=((r01)*(sj6)*(x7194));
23097 IkReal x7206=((r11)*(sj6)*(x7194));
23098 evalcond[0]=((((IkReal(-1.00000000000000))*(r20)*(x7203)))+(((IkReal(-1.00000000000000))*(cj1)*(sj2)))+(((cj6)*(r21)*(x7202)))+(((r21)*(sj6)*(x7194)))+(((r22)*(x7200)))+(((r20)*(sj6)*(x7202))));
23099 evalcond[1]=((((IkReal(-1.00000000000000))*(x7197)*(x7199)*(x7202)))+(((sj0)*(x7205)))+(((IkReal(-1.00000000000000))*(x7197)*(x7206)))+(((IkReal(-1.00000000000000))*(r00)*(x7198)*(x7203)))+(((x7195)*(x7204)))+(((IkReal(-1.00000000000000))*(r12)*(x7197)*(x7200)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7197)*(x7202)))+(((r02)*(sj0)*(x7200)))+(cj2)+(((x7196)*(x7204)))+(((cj0)*(r10)*(x7203))));
23100 evalcond[2]=((((IkReal(-1.00000000000000))*(x7196)*(x7197)*(x7202)))+(((IkReal(-1.00000000000000))*(x7195)*(x7197)*(x7202)))+(((IkReal(-1.00000000000000))*(r12)*(x7198)*(x7200)))+(((IkReal(-1.00000000000000))*(x7198)*(x7199)*(x7202)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7198)*(x7202)))+(((IkReal(-1.00000000000000))*(r02)*(x7197)*(x7200)))+(((cj0)*(r00)*(x7203)))+(((IkReal(-1.00000000000000))*(x7198)*(x7206)))+(((r10)*(sj0)*(x7203)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x7197)*(x7205))));
23101 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
23102 {
23103 continue;
23104 }
23105 }
23106 
23107 {
23108 IkReal dummyeval[1];
23109 IkReal gconst4;
23110 gconst4=IKsign((((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2))))));
23111 dummyeval[0]=(((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2)))));
23112 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23113 {
23114 {
23115 IkReal dummyeval[2];
23116 IkReal x7207=(cj1)*(cj1);
23117 IkReal x7208=(sj1)*(sj1);
23118 dummyeval[0]=((((cj2)*(x7207)))+(((cj2)*(x7208))));
23119 dummyeval[1]=((x7208)+(x7207));
23120 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
23121 {
23122 {
23123 IkReal dummyeval[2];
23124 dummyeval[0]=sj2;
23125 dummyeval[1]=sj1;
23126 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
23127 {
23128 {
23129 IkReal evalcond[9];
23130 IkReal x7209=((cj5)*(sj4));
23131 IkReal x7210=((IkReal(1.00000000000000))*(sj6));
23132 IkReal x7211=((r10)*(sj0));
23133 IkReal x7212=((sj4)*(sj5));
23134 IkReal x7213=((cj4)*(cj5));
23135 IkReal x7214=((IkReal(1.00000000000000))*(r02));
23136 IkReal x7215=((IkReal(0.374290000000000))*(cj0));
23137 IkReal x7216=((cj5)*(r12));
23138 IkReal x7217=((cj6)*(sj5));
23139 IkReal x7218=((cj0)*(r11));
23140 IkReal x7219=((cj5)*(sj0));
23141 IkReal x7220=((r20)*(sj6));
23142 IkReal x7221=((IkReal(1.00000000000000))*(sj0));
23143 IkReal x7222=((IkReal(1.00000000000000))*(cj6));
23144 IkReal x7223=((IkReal(0.0100000000000000))*(cj5));
23145 IkReal x7224=((IkReal(0.0100000000000000))*(sj5));
23146 IkReal x7225=((sj5)*(sj6));
23147 IkReal x7226=((cj0)*(r10));
23148 IkReal x7227=((cj4)*(cj6));
23149 IkReal x7228=((cj0)*(r01));
23150 IkReal x7229=((cj0)*(r00));
23151 IkReal x7230=((cj6)*(r21));
23152 IkReal x7231=((IkReal(0.374290000000000))*(sj0));
23153 IkReal x7232=((IkReal(0.374290000000000))*(sj5));
23154 IkReal x7233=((cj6)*(r11));
23155 IkReal x7234=((sj0)*(sj4));
23156 IkReal x7235=((cj4)*(sj5));
23157 IkReal x7236=((cj4)*(sj6));
23158 IkReal x7237=((IkReal(1.00000000000000))*(cj0));
23159 IkReal x7238=((r02)*(sj0));
23160 IkReal x7239=((r00)*(sj0)*(sj6));
23161 IkReal x7240=((cj6)*(r01)*(sj0));
23162 IkReal x7241=((r00)*(x7227));
23163 IkReal x7242=((r12)*(x7237));
23164 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
23165 evalcond[1]=((((x7209)*(x7230)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7222)))+(((r22)*(x7212)))+(((r21)*(x7236)))+(((x7209)*(x7220))));
23166 evalcond[2]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(0.374290000000000))*(r21)*(x7217)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x7220)*(x7232)))+(((IkReal(-1.00000000000000))*(x7223)*(x7230)))+(((IkReal(-1.00000000000000))*(x7220)*(x7223)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x7224)))+(((IkReal(0.0690000000000000))*(cj1))));
23167 evalcond[3]=((((r01)*(sj0)*(x7217)))+(((cj0)*(x7216)))+(((IkReal(-1.00000000000000))*(x7214)*(x7219)))+(((IkReal(-1.00000000000000))*(x7217)*(x7218)))+(((r00)*(sj0)*(x7225)))+(((IkReal(-1.00000000000000))*(sj5)*(x7210)*(x7226))));
23168 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x7209)*(x7210)*(x7226)))+(((x7209)*(x7239)))+(((x7226)*(x7227)))+(((IkReal(-1.00000000000000))*(x7221)*(x7241)))+(((x7212)*(x7238)))+(((x7209)*(x7240)))+(((IkReal(-1.00000000000000))*(cj4)*(x7210)*(x7218)))+(((IkReal(-1.00000000000000))*(x7212)*(x7242)))+(((r01)*(sj0)*(x7236)))+(((IkReal(-1.00000000000000))*(x7209)*(x7218)*(x7222))));
23169 evalcond[5]=((((x7235)*(x7238)))+(((IkReal(-1.00000000000000))*(x7210)*(x7213)*(x7226)))+(((x7213)*(x7239)))+(((IkReal(-1.00000000000000))*(r01)*(x7210)*(x7234)))+(((x7213)*(x7240)))+(((sj4)*(sj6)*(x7218)))+(((IkReal(-1.00000000000000))*(x7235)*(x7242)))+(((IkReal(-1.00000000000000))*(sj4)*(x7222)*(x7226)))+(((IkReal(-1.00000000000000))*(x7213)*(x7218)*(x7222)))+(((cj6)*(r00)*(x7234))));
23170 evalcond[6]=((((IkReal(-1.00000000000000))*(x7209)*(x7210)*(x7211)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x7210)))+(((IkReal(-1.00000000000000))*(x7209)*(x7210)*(x7229)))+(((IkReal(-1.00000000000000))*(x7209)*(x7221)*(x7233)))+(((x7227)*(x7229)))+(((IkReal(-1.00000000000000))*(cj0)*(x7212)*(x7214)))+(((x7211)*(x7227)))+(((IkReal(-1.00000000000000))*(r12)*(x7212)*(x7221)))+(((IkReal(-1.00000000000000))*(cj4)*(x7210)*(x7228)))+(((IkReal(-1.00000000000000))*(x7209)*(x7222)*(x7228))));
23171 evalcond[7]=((((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x7219)))+(((IkReal(-1.00000000000000))*(x7224)*(x7238)))+(((IkReal(-1.00000000000000))*(py)*(x7237)))+(((cj0)*(r12)*(x7224)))+(((r01)*(x7217)*(x7231)))+(((IkReal(-0.374290000000000))*(r02)*(x7219)))+(((sj6)*(x7223)*(x7226)))+(((IkReal(-1.00000000000000))*(r11)*(x7215)*(x7217)))+(((cj6)*(x7218)*(x7223)))+(((r00)*(x7225)*(x7231)))+(((x7215)*(x7216)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7219)))+(((IkReal(-1.00000000000000))*(r10)*(x7215)*(x7225))));
23172 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-0.0690000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(py)*(x7221)))+(((IkReal(-1.00000000000000))*(px)*(x7237)))+(((IkReal(-1.00000000000000))*(r11)*(x7217)*(x7231)))+(((cj5)*(r02)*(x7215)))+(((cj0)*(r02)*(x7224)))+(((sj6)*(x7211)*(x7223)))+(((IkReal(-0.374290000000000))*(x7211)*(x7225)))+(((IkReal(-1.00000000000000))*(r01)*(x7215)*(x7217)))+(((x7216)*(x7231)))+(((IkReal(0.0100000000000000))*(x7219)*(x7233)))+(((IkReal(-1.00000000000000))*(r00)*(x7215)*(x7225)))+(((r12)*(sj0)*(x7224)))+(((cj6)*(x7223)*(x7228)))+(((IkReal(0.364420000000000))*(cj1)))+(((sj6)*(x7223)*(x7229))));
23173 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
23174 {
23175 {
23176 IkReal dummyeval[1];
23177 IkReal gconst5;
23178 gconst5=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
23179 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
23180 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23181 {
23182 {
23183 IkReal dummyeval[1];
23184 IkReal gconst6;
23185 gconst6=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
23186 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
23187 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23188 {
23189 continue;
23190 
23191 } else
23192 {
23193 {
23194 IkReal j3array[1], cj3array[1], sj3array[1];
23195 bool j3valid[1]={false};
23196 _nj3 = 1;
23197 IkReal x7243=((sj5)*(sj6));
23198 IkReal x7244=((IkReal(1.00000000000000))*(sj0));
23199 IkReal x7245=((cj5)*(r12));
23200 IkReal x7246=((cj0)*(r00));
23201 IkReal x7247=((cj0)*(cj1));
23202 IkReal x7248=((cj6)*(sj5));
23203 IkReal x7249=((cj5)*(r02));
23204 IkReal x7250=((IkReal(1.00000000000000))*(cj1));
23205 IkReal x7251=((sj0)*(sj1));
23206 IkReal x7252=((cj0)*(sj1));
23207 IkReal x7253=((cj5)*(r22));
23208 if( IKabs(((gconst6)*(((((cj1)*(r20)*(x7243)))+(((IkReal(-1.00000000000000))*(x7249)*(x7252)))+(((IkReal(-1.00000000000000))*(x7250)*(x7253)))+(((r11)*(x7248)*(x7251)))+(((sj1)*(x7243)*(x7246)))+(((r01)*(x7248)*(x7252)))+(((cj1)*(r21)*(x7248)))+(((r10)*(x7243)*(x7251)))+(((IkReal(-1.00000000000000))*(sj1)*(x7244)*(x7245))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((IkReal(-1.00000000000000))*(sj1)*(x7253)))+(((r21)*(sj1)*(x7248)))+(((r20)*(sj1)*(x7243)))+(((x7247)*(x7249)))+(((IkReal(-1.00000000000000))*(r01)*(x7247)*(x7248)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x7244)*(x7248)))+(((cj1)*(sj0)*(x7245)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x7243)*(x7244)))+(((IkReal(-1.00000000000000))*(x7243)*(x7246)*(x7250))))))) < IKFAST_ATAN2_MAGTHRESH )
23209     continue;
23210 j3array[0]=IKatan2(((gconst6)*(((((cj1)*(r20)*(x7243)))+(((IkReal(-1.00000000000000))*(x7249)*(x7252)))+(((IkReal(-1.00000000000000))*(x7250)*(x7253)))+(((r11)*(x7248)*(x7251)))+(((sj1)*(x7243)*(x7246)))+(((r01)*(x7248)*(x7252)))+(((cj1)*(r21)*(x7248)))+(((r10)*(x7243)*(x7251)))+(((IkReal(-1.00000000000000))*(sj1)*(x7244)*(x7245)))))), ((gconst6)*(((((IkReal(-1.00000000000000))*(sj1)*(x7253)))+(((r21)*(sj1)*(x7248)))+(((r20)*(sj1)*(x7243)))+(((x7247)*(x7249)))+(((IkReal(-1.00000000000000))*(r01)*(x7247)*(x7248)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x7244)*(x7248)))+(((cj1)*(sj0)*(x7245)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x7243)*(x7244)))+(((IkReal(-1.00000000000000))*(x7243)*(x7246)*(x7250)))))));
23211 sj3array[0]=IKsin(j3array[0]);
23212 cj3array[0]=IKcos(j3array[0]);
23213 if( j3array[0] > IKPI )
23214 {
23215     j3array[0]-=IK2PI;
23216 }
23217 else if( j3array[0] < -IKPI )
23218 {    j3array[0]+=IK2PI;
23219 }
23220 j3valid[0] = true;
23221 for(int ij3 = 0; ij3 < 1; ++ij3)
23222 {
23223 if( !j3valid[ij3] )
23224 {
23225     continue;
23226 }
23227 _ij3[0] = ij3; _ij3[1] = -1;
23228 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
23229 {
23230 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
23231 {
23232     j3valid[iij3]=false; _ij3[1] = iij3; break; 
23233 }
23234 }
23235 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
23236 {
23237 IkReal evalcond[4];
23238 IkReal x7254=IKcos(j3);
23239 IkReal x7255=IKsin(j3);
23240 IkReal x7256=((IkReal(1.00000000000000))*(cj4));
23241 IkReal x7257=((sj0)*(sj5));
23242 IkReal x7258=((cj0)*(cj5));
23243 IkReal x7259=((cj6)*(r01));
23244 IkReal x7260=((r00)*(sj6));
23245 IkReal x7261=((cj6)*(r11));
23246 IkReal x7262=((cj5)*(sj0));
23247 IkReal x7263=((cj6)*(sj4));
23248 IkReal x7264=((sj4)*(sj6));
23249 IkReal x7265=((cj4)*(cj5));
23250 IkReal x7266=((cj6)*(r21));
23251 IkReal x7267=((r20)*(sj6));
23252 IkReal x7268=((r10)*(sj6));
23253 IkReal x7269=((cj1)*(x7254));
23254 IkReal x7270=((IkReal(1.00000000000000))*(cj0)*(sj5));
23255 IkReal x7271=((IkReal(1.00000000000000))*(x7255));
23256 IkReal x7272=((IkReal(1.00000000000000))*(sj1)*(x7254));
23257 IkReal x7273=((cj1)*(x7271));
23258 IkReal x7274=((x7272)+(x7273));
23259 evalcond[0]=((((sj5)*(x7267)))+(((sj5)*(x7266)))+(((IkReal(-1.00000000000000))*(x7274)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
23260 evalcond[1]=((((x7265)*(x7266)))+(((IkReal(-1.00000000000000))*(sj1)*(x7271)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7263)))+(x7269)+(((x7265)*(x7267)))+(((IkReal(-1.00000000000000))*(r21)*(x7264))));
23261 evalcond[2]=((((IkReal(-1.00000000000000))*(x7269)))+(((sj1)*(x7255)))+(((r02)*(x7258)))+(((r12)*(x7262)))+(((IkReal(-1.00000000000000))*(x7259)*(x7270)))+(((IkReal(-1.00000000000000))*(x7260)*(x7270)))+(((IkReal(-1.00000000000000))*(x7257)*(x7268)))+(((IkReal(-1.00000000000000))*(x7257)*(x7261))));
23262 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7263)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7263)))+(((IkReal(-1.00000000000000))*(x7256)*(x7261)*(x7262)))+(((IkReal(-1.00000000000000))*(x7256)*(x7258)*(x7259)))+(((IkReal(-1.00000000000000))*(x7256)*(x7262)*(x7268)))+(((IkReal(-1.00000000000000))*(x7274)))+(((cj0)*(r01)*(x7264)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7256)))+(((IkReal(-1.00000000000000))*(x7256)*(x7258)*(x7260)))+(((IkReal(-1.00000000000000))*(r12)*(x7256)*(x7257)))+(((r11)*(sj0)*(x7264))));
23263 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
23264 {
23265 continue;
23266 }
23267 }
23268 
23269 {
23270 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
23271 vinfos[0].jointtype = 1;
23272 vinfos[0].foffset = j0;
23273 vinfos[0].indices[0] = _ij0[0];
23274 vinfos[0].indices[1] = _ij0[1];
23275 vinfos[0].maxsolutions = _nj0;
23276 vinfos[1].jointtype = 1;
23277 vinfos[1].foffset = j1;
23278 vinfos[1].indices[0] = _ij1[0];
23279 vinfos[1].indices[1] = _ij1[1];
23280 vinfos[1].maxsolutions = _nj1;
23281 vinfos[2].jointtype = 1;
23282 vinfos[2].foffset = j2;
23283 vinfos[2].indices[0] = _ij2[0];
23284 vinfos[2].indices[1] = _ij2[1];
23285 vinfos[2].maxsolutions = _nj2;
23286 vinfos[3].jointtype = 1;
23287 vinfos[3].foffset = j3;
23288 vinfos[3].indices[0] = _ij3[0];
23289 vinfos[3].indices[1] = _ij3[1];
23290 vinfos[3].maxsolutions = _nj3;
23291 vinfos[4].jointtype = 1;
23292 vinfos[4].foffset = j4;
23293 vinfos[4].indices[0] = _ij4[0];
23294 vinfos[4].indices[1] = _ij4[1];
23295 vinfos[4].maxsolutions = _nj4;
23296 vinfos[5].jointtype = 1;
23297 vinfos[5].foffset = j5;
23298 vinfos[5].indices[0] = _ij5[0];
23299 vinfos[5].indices[1] = _ij5[1];
23300 vinfos[5].maxsolutions = _nj5;
23301 vinfos[6].jointtype = 1;
23302 vinfos[6].foffset = j6;
23303 vinfos[6].indices[0] = _ij6[0];
23304 vinfos[6].indices[1] = _ij6[1];
23305 vinfos[6].maxsolutions = _nj6;
23306 std::vector<int> vfree(0);
23307 solutions.AddSolution(vinfos,vfree);
23308 }
23309 }
23310 }
23311 
23312 }
23313 
23314 }
23315 
23316 } else
23317 {
23318 {
23319 IkReal j3array[1], cj3array[1], sj3array[1];
23320 bool j3valid[1]={false};
23321 _nj3 = 1;
23322 IkReal x7275=((sj1)*(sj5));
23323 IkReal x7276=((r20)*(sj6));
23324 IkReal x7277=((cj4)*(r22));
23325 IkReal x7278=((IkReal(1.00000000000000))*(cj1));
23326 IkReal x7279=((cj5)*(sj1));
23327 IkReal x7280=((cj6)*(r21));
23328 IkReal x7281=((cj1)*(sj5));
23329 IkReal x7282=((cj4)*(cj5));
23330 IkReal x7283=((cj6)*(r20)*(sj4));
23331 IkReal x7284=((r21)*(sj4)*(sj6));
23332 if( IKabs(((gconst5)*(((((x7276)*(x7281)))+(((x7280)*(x7281)))+(((x7275)*(x7277)))+(((sj1)*(x7283)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x7278)))+(((cj4)*(x7279)*(x7280)))+(((cj4)*(x7276)*(x7279)))+(((IkReal(-1.00000000000000))*(sj1)*(x7284))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(r22)*(x7279)))+(((IkReal(-1.00000000000000))*(x7278)*(x7280)*(x7282)))+(((cj1)*(x7284)))+(((x7275)*(x7280)))+(((IkReal(-1.00000000000000))*(sj5)*(x7277)*(x7278)))+(((IkReal(-1.00000000000000))*(x7276)*(x7278)*(x7282)))+(((x7275)*(x7276)))+(((IkReal(-1.00000000000000))*(x7278)*(x7283))))))) < IKFAST_ATAN2_MAGTHRESH )
23333     continue;
23334 j3array[0]=IKatan2(((gconst5)*(((((x7276)*(x7281)))+(((x7280)*(x7281)))+(((x7275)*(x7277)))+(((sj1)*(x7283)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x7278)))+(((cj4)*(x7279)*(x7280)))+(((cj4)*(x7276)*(x7279)))+(((IkReal(-1.00000000000000))*(sj1)*(x7284)))))), ((gconst5)*(((((IkReal(-1.00000000000000))*(r22)*(x7279)))+(((IkReal(-1.00000000000000))*(x7278)*(x7280)*(x7282)))+(((cj1)*(x7284)))+(((x7275)*(x7280)))+(((IkReal(-1.00000000000000))*(sj5)*(x7277)*(x7278)))+(((IkReal(-1.00000000000000))*(x7276)*(x7278)*(x7282)))+(((x7275)*(x7276)))+(((IkReal(-1.00000000000000))*(x7278)*(x7283)))))));
23335 sj3array[0]=IKsin(j3array[0]);
23336 cj3array[0]=IKcos(j3array[0]);
23337 if( j3array[0] > IKPI )
23338 {
23339     j3array[0]-=IK2PI;
23340 }
23341 else if( j3array[0] < -IKPI )
23342 {    j3array[0]+=IK2PI;
23343 }
23344 j3valid[0] = true;
23345 for(int ij3 = 0; ij3 < 1; ++ij3)
23346 {
23347 if( !j3valid[ij3] )
23348 {
23349     continue;
23350 }
23351 _ij3[0] = ij3; _ij3[1] = -1;
23352 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
23353 {
23354 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
23355 {
23356     j3valid[iij3]=false; _ij3[1] = iij3; break; 
23357 }
23358 }
23359 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
23360 {
23361 IkReal evalcond[4];
23362 IkReal x7285=IKcos(j3);
23363 IkReal x7286=IKsin(j3);
23364 IkReal x7287=((IkReal(1.00000000000000))*(cj4));
23365 IkReal x7288=((sj0)*(sj5));
23366 IkReal x7289=((cj0)*(cj5));
23367 IkReal x7290=((cj6)*(r01));
23368 IkReal x7291=((r00)*(sj6));
23369 IkReal x7292=((cj6)*(r11));
23370 IkReal x7293=((cj5)*(sj0));
23371 IkReal x7294=((cj6)*(sj4));
23372 IkReal x7295=((sj4)*(sj6));
23373 IkReal x7296=((cj4)*(cj5));
23374 IkReal x7297=((cj6)*(r21));
23375 IkReal x7298=((r20)*(sj6));
23376 IkReal x7299=((r10)*(sj6));
23377 IkReal x7300=((cj1)*(x7285));
23378 IkReal x7301=((IkReal(1.00000000000000))*(cj0)*(sj5));
23379 IkReal x7302=((IkReal(1.00000000000000))*(x7286));
23380 IkReal x7303=((IkReal(1.00000000000000))*(sj1)*(x7285));
23381 IkReal x7304=((cj1)*(x7302));
23382 IkReal x7305=((x7303)+(x7304));
23383 evalcond[0]=((((sj5)*(x7298)))+(((sj5)*(x7297)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x7305))));
23384 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x7302)))+(((IkReal(-1.00000000000000))*(r21)*(x7295)))+(((cj4)*(r22)*(sj5)))+(x7300)+(((x7296)*(x7297)))+(((r20)*(x7294)))+(((x7296)*(x7298))));
23385 evalcond[2]=((((sj1)*(x7286)))+(((IkReal(-1.00000000000000))*(x7288)*(x7292)))+(((IkReal(-1.00000000000000))*(x7290)*(x7301)))+(((r02)*(x7289)))+(((r12)*(x7293)))+(((IkReal(-1.00000000000000))*(x7300)))+(((IkReal(-1.00000000000000))*(x7291)*(x7301)))+(((IkReal(-1.00000000000000))*(x7288)*(x7299))));
23386 evalcond[3]=((((IkReal(-1.00000000000000))*(x7287)*(x7292)*(x7293)))+(((IkReal(-1.00000000000000))*(x7287)*(x7293)*(x7299)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7294)))+(((IkReal(-1.00000000000000))*(x7287)*(x7289)*(x7290)))+(((IkReal(-1.00000000000000))*(r12)*(x7287)*(x7288)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7294)))+(((cj0)*(r01)*(x7295)))+(((r11)*(sj0)*(x7295)))+(((IkReal(-1.00000000000000))*(x7305)))+(((IkReal(-1.00000000000000))*(x7287)*(x7289)*(x7291)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7287))));
23387 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
23388 {
23389 continue;
23390 }
23391 }
23392 
23393 {
23394 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
23395 vinfos[0].jointtype = 1;
23396 vinfos[0].foffset = j0;
23397 vinfos[0].indices[0] = _ij0[0];
23398 vinfos[0].indices[1] = _ij0[1];
23399 vinfos[0].maxsolutions = _nj0;
23400 vinfos[1].jointtype = 1;
23401 vinfos[1].foffset = j1;
23402 vinfos[1].indices[0] = _ij1[0];
23403 vinfos[1].indices[1] = _ij1[1];
23404 vinfos[1].maxsolutions = _nj1;
23405 vinfos[2].jointtype = 1;
23406 vinfos[2].foffset = j2;
23407 vinfos[2].indices[0] = _ij2[0];
23408 vinfos[2].indices[1] = _ij2[1];
23409 vinfos[2].maxsolutions = _nj2;
23410 vinfos[3].jointtype = 1;
23411 vinfos[3].foffset = j3;
23412 vinfos[3].indices[0] = _ij3[0];
23413 vinfos[3].indices[1] = _ij3[1];
23414 vinfos[3].maxsolutions = _nj3;
23415 vinfos[4].jointtype = 1;
23416 vinfos[4].foffset = j4;
23417 vinfos[4].indices[0] = _ij4[0];
23418 vinfos[4].indices[1] = _ij4[1];
23419 vinfos[4].maxsolutions = _nj4;
23420 vinfos[5].jointtype = 1;
23421 vinfos[5].foffset = j5;
23422 vinfos[5].indices[0] = _ij5[0];
23423 vinfos[5].indices[1] = _ij5[1];
23424 vinfos[5].maxsolutions = _nj5;
23425 vinfos[6].jointtype = 1;
23426 vinfos[6].foffset = j6;
23427 vinfos[6].indices[0] = _ij6[0];
23428 vinfos[6].indices[1] = _ij6[1];
23429 vinfos[6].maxsolutions = _nj6;
23430 std::vector<int> vfree(0);
23431 solutions.AddSolution(vinfos,vfree);
23432 }
23433 }
23434 }
23435 
23436 }
23437 
23438 }
23439 
23440 } else
23441 {
23442 IkReal x7306=((cj5)*(sj4));
23443 IkReal x7307=((IkReal(1.00000000000000))*(sj6));
23444 IkReal x7308=((r10)*(sj0));
23445 IkReal x7309=((sj4)*(sj5));
23446 IkReal x7310=((cj4)*(cj5));
23447 IkReal x7311=((IkReal(1.00000000000000))*(r02));
23448 IkReal x7312=((IkReal(0.374290000000000))*(cj0));
23449 IkReal x7313=((cj5)*(r12));
23450 IkReal x7314=((cj6)*(sj5));
23451 IkReal x7315=((cj0)*(r11));
23452 IkReal x7316=((cj5)*(sj0));
23453 IkReal x7317=((r20)*(sj6));
23454 IkReal x7318=((IkReal(1.00000000000000))*(sj0));
23455 IkReal x7319=((IkReal(1.00000000000000))*(cj6));
23456 IkReal x7320=((IkReal(0.0100000000000000))*(cj5));
23457 IkReal x7321=((IkReal(0.0100000000000000))*(sj5));
23458 IkReal x7322=((sj5)*(sj6));
23459 IkReal x7323=((cj0)*(r10));
23460 IkReal x7324=((cj4)*(cj6));
23461 IkReal x7325=((cj0)*(r01));
23462 IkReal x7326=((cj0)*(r00));
23463 IkReal x7327=((cj6)*(r21));
23464 IkReal x7328=((IkReal(0.374290000000000))*(sj0));
23465 IkReal x7329=((IkReal(0.374290000000000))*(sj5));
23466 IkReal x7330=((cj6)*(r11));
23467 IkReal x7331=((sj0)*(sj4));
23468 IkReal x7332=((cj4)*(sj5));
23469 IkReal x7333=((cj4)*(sj6));
23470 IkReal x7334=((IkReal(1.00000000000000))*(cj0));
23471 IkReal x7335=((r02)*(sj0));
23472 IkReal x7336=((r00)*(sj0)*(sj6));
23473 IkReal x7337=((cj6)*(r01)*(sj0));
23474 IkReal x7338=((r00)*(x7324));
23475 IkReal x7339=((r12)*(x7334));
23476 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
23477 evalcond[1]=((((x7306)*(x7317)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7319)))+(((x7306)*(x7327)))+(((r22)*(x7309)))+(((r21)*(x7333))));
23478 evalcond[2]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.0690000000000000))*(cj1)))+(((IkReal(0.374290000000000))*(r21)*(x7314)))+(((IkReal(-1.00000000000000))*(x7317)*(x7320)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x7321)))+(pz)+(((IkReal(-1.00000000000000))*(x7320)*(x7327)))+(((x7317)*(x7329))));
23479 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x7307)*(x7323)))+(((IkReal(-1.00000000000000))*(x7311)*(x7316)))+(((r00)*(sj0)*(x7322)))+(((r01)*(sj0)*(x7314)))+(((cj0)*(x7313)))+(((IkReal(-1.00000000000000))*(x7314)*(x7315))));
23480 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x7306)*(x7315)*(x7319)))+(((x7323)*(x7324)))+(((r01)*(sj0)*(x7333)))+(((x7306)*(x7337)))+(((IkReal(-1.00000000000000))*(cj4)*(x7307)*(x7315)))+(((x7309)*(x7335)))+(((IkReal(-1.00000000000000))*(x7309)*(x7339)))+(((x7306)*(x7336)))+(((IkReal(-1.00000000000000))*(x7318)*(x7338)))+(((IkReal(-1.00000000000000))*(x7306)*(x7307)*(x7323))));
23481 evalcond[5]=((((IkReal(-1.00000000000000))*(x7307)*(x7310)*(x7323)))+(((sj4)*(sj6)*(x7315)))+(((x7310)*(x7337)))+(((cj6)*(r00)*(x7331)))+(((IkReal(-1.00000000000000))*(x7332)*(x7339)))+(((x7332)*(x7335)))+(((IkReal(-1.00000000000000))*(x7310)*(x7315)*(x7319)))+(((IkReal(-1.00000000000000))*(sj4)*(x7319)*(x7323)))+(((x7310)*(x7336)))+(((IkReal(-1.00000000000000))*(r01)*(x7307)*(x7331))));
23482 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x7307)*(x7325)))+(((x7324)*(x7326)))+(((x7308)*(x7324)))+(((IkReal(-1.00000000000000))*(x7306)*(x7307)*(x7326)))+(((IkReal(-1.00000000000000))*(r12)*(x7309)*(x7318)))+(((IkReal(-1.00000000000000))*(x7306)*(x7307)*(x7308)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x7307)))+(((IkReal(-1.00000000000000))*(x7306)*(x7318)*(x7330)))+(((IkReal(-1.00000000000000))*(cj0)*(x7309)*(x7311)))+(((IkReal(-1.00000000000000))*(x7306)*(x7319)*(x7325))));
23483 evalcond[7]=((((sj6)*(x7320)*(x7323)))+(((IkReal(-1.00000000000000))*(x7321)*(x7335)))+(((IkReal(-1.00000000000000))*(r11)*(x7312)*(x7314)))+(((cj0)*(r12)*(x7321)))+(((r01)*(x7314)*(x7328)))+(((x7312)*(x7313)))+(((r00)*(x7322)*(x7328)))+(((IkReal(-1.00000000000000))*(r10)*(x7312)*(x7322)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x7316)))+(((IkReal(-1.00000000000000))*(py)*(x7334)))+(((px)*(sj0)))+(((cj6)*(x7315)*(x7320)))+(((IkReal(-0.374290000000000))*(r02)*(x7316)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7316))));
23484 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-0.374290000000000))*(x7308)*(x7322)))+(((cj5)*(r02)*(x7312)))+(((sj6)*(x7308)*(x7320)))+(((IkReal(0.0690000000000000))*(sj1)))+(((x7313)*(x7328)))+(((sj6)*(x7320)*(x7326)))+(((IkReal(-1.00000000000000))*(r11)*(x7314)*(x7328)))+(((r12)*(sj0)*(x7321)))+(((IkReal(-1.00000000000000))*(r00)*(x7312)*(x7322)))+(((IkReal(-1.00000000000000))*(py)*(x7318)))+(((IkReal(-1.00000000000000))*(px)*(x7334)))+(((cj0)*(r02)*(x7321)))+(((IkReal(-1.00000000000000))*(r01)*(x7312)*(x7314)))+(((IkReal(0.0100000000000000))*(x7316)*(x7330)))+(((cj6)*(x7320)*(x7325)))+(((IkReal(0.364420000000000))*(cj1))));
23485 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
23486 {
23487 {
23488 IkReal dummyeval[1];
23489 IkReal gconst7;
23490 gconst7=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
23491 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
23492 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23493 {
23494 {
23495 IkReal dummyeval[1];
23496 IkReal gconst8;
23497 gconst8=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
23498 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
23499 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23500 {
23501 continue;
23502 
23503 } else
23504 {
23505 {
23506 IkReal j3array[1], cj3array[1], sj3array[1];
23507 bool j3valid[1]={false};
23508 _nj3 = 1;
23509 IkReal x7340=((IkReal(1.00000000000000))*(sj0));
23510 IkReal x7341=((cj6)*(r21));
23511 IkReal x7342=((cj0)*(r00));
23512 IkReal x7343=((cj5)*(sj1));
23513 IkReal x7344=((r12)*(sj0));
23514 IkReal x7345=((cj1)*(cj5));
23515 IkReal x7346=((cj0)*(r02));
23516 IkReal x7347=((sj1)*(sj5));
23517 IkReal x7348=((cj6)*(r11));
23518 IkReal x7349=((cj1)*(sj5));
23519 IkReal x7350=((sj6)*(x7347));
23520 IkReal x7351=((IkReal(1.00000000000000))*(x7349));
23521 IkReal x7352=((cj0)*(cj6)*(r01));
23522 if( IKabs(((gconst8)*(((((x7343)*(x7344)))+(((IkReal(-1.00000000000000))*(x7342)*(x7350)))+(((IkReal(-1.00000000000000))*(x7341)*(x7351)))+(((IkReal(-1.00000000000000))*(x7340)*(x7347)*(x7348)))+(((x7343)*(x7346)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x7351)))+(((r22)*(x7345)))+(((IkReal(-1.00000000000000))*(x7347)*(x7352)))+(((IkReal(-1.00000000000000))*(r10)*(x7340)*(x7350))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((x7341)*(x7347)))+(((r20)*(x7350)))+(((x7344)*(x7345)))+(((IkReal(-1.00000000000000))*(sj6)*(x7342)*(x7351)))+(((IkReal(-1.00000000000000))*(x7340)*(x7348)*(x7349)))+(((x7345)*(x7346)))+(((IkReal(-1.00000000000000))*(r22)*(x7343)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x7340)*(x7349)))+(((IkReal(-1.00000000000000))*(x7351)*(x7352))))))) < IKFAST_ATAN2_MAGTHRESH )
23523     continue;
23524 j3array[0]=IKatan2(((gconst8)*(((((x7343)*(x7344)))+(((IkReal(-1.00000000000000))*(x7342)*(x7350)))+(((IkReal(-1.00000000000000))*(x7341)*(x7351)))+(((IkReal(-1.00000000000000))*(x7340)*(x7347)*(x7348)))+(((x7343)*(x7346)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x7351)))+(((r22)*(x7345)))+(((IkReal(-1.00000000000000))*(x7347)*(x7352)))+(((IkReal(-1.00000000000000))*(r10)*(x7340)*(x7350)))))), ((gconst8)*(((((x7341)*(x7347)))+(((r20)*(x7350)))+(((x7344)*(x7345)))+(((IkReal(-1.00000000000000))*(sj6)*(x7342)*(x7351)))+(((IkReal(-1.00000000000000))*(x7340)*(x7348)*(x7349)))+(((x7345)*(x7346)))+(((IkReal(-1.00000000000000))*(r22)*(x7343)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x7340)*(x7349)))+(((IkReal(-1.00000000000000))*(x7351)*(x7352)))))));
23525 sj3array[0]=IKsin(j3array[0]);
23526 cj3array[0]=IKcos(j3array[0]);
23527 if( j3array[0] > IKPI )
23528 {
23529     j3array[0]-=IK2PI;
23530 }
23531 else if( j3array[0] < -IKPI )
23532 {    j3array[0]+=IK2PI;
23533 }
23534 j3valid[0] = true;
23535 for(int ij3 = 0; ij3 < 1; ++ij3)
23536 {
23537 if( !j3valid[ij3] )
23538 {
23539     continue;
23540 }
23541 _ij3[0] = ij3; _ij3[1] = -1;
23542 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
23543 {
23544 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
23545 {
23546     j3valid[iij3]=false; _ij3[1] = iij3; break; 
23547 }
23548 }
23549 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
23550 {
23551 IkReal evalcond[4];
23552 IkReal x7353=IKsin(j3);
23553 IkReal x7354=IKcos(j3);
23554 IkReal x7355=((IkReal(1.00000000000000))*(cj4));
23555 IkReal x7356=((sj0)*(sj5));
23556 IkReal x7357=((cj0)*(cj5));
23557 IkReal x7358=((cj6)*(r01));
23558 IkReal x7359=((r00)*(sj6));
23559 IkReal x7360=((cj6)*(r11));
23560 IkReal x7361=((cj5)*(sj0));
23561 IkReal x7362=((cj6)*(sj4));
23562 IkReal x7363=((sj4)*(sj6));
23563 IkReal x7364=((cj4)*(cj5));
23564 IkReal x7365=((cj6)*(r21));
23565 IkReal x7366=((r20)*(sj6));
23566 IkReal x7367=((r10)*(sj6));
23567 IkReal x7368=((cj1)*(x7353));
23568 IkReal x7369=((IkReal(1.00000000000000))*(cj0)*(sj5));
23569 IkReal x7370=((IkReal(1.00000000000000))*(x7354));
23570 IkReal x7371=((IkReal(1.00000000000000))*(sj1)*(x7353));
23571 IkReal x7372=((cj1)*(x7370));
23572 IkReal x7373=((x7372)+(x7371));
23573 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x7370)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7365)))+(((sj5)*(x7366)))+(x7368));
23574 evalcond[1]=((((IkReal(-1.00000000000000))*(x7373)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7362)))+(((x7364)*(x7365)))+(((IkReal(-1.00000000000000))*(r21)*(x7363)))+(((x7364)*(x7366))));
23575 evalcond[2]=((((r12)*(x7361)))+(((IkReal(-1.00000000000000))*(x7356)*(x7367)))+(((IkReal(-1.00000000000000))*(x7373)))+(((IkReal(-1.00000000000000))*(x7359)*(x7369)))+(((IkReal(-1.00000000000000))*(x7358)*(x7369)))+(((r02)*(x7357)))+(((IkReal(-1.00000000000000))*(x7356)*(x7360))));
23576 evalcond[3]=((((IkReal(-1.00000000000000))*(x7355)*(x7357)*(x7358)))+(((r11)*(sj0)*(x7363)))+(((IkReal(-1.00000000000000))*(x7355)*(x7357)*(x7359)))+(((IkReal(-1.00000000000000))*(r12)*(x7355)*(x7356)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7355)))+(((IkReal(-1.00000000000000))*(x7355)*(x7360)*(x7361)))+(((cj0)*(r01)*(x7363)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7362)))+(((IkReal(-1.00000000000000))*(x7355)*(x7361)*(x7367)))+(((sj1)*(x7354)))+(((IkReal(-1.00000000000000))*(x7368)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7362))));
23577 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
23578 {
23579 continue;
23580 }
23581 }
23582 
23583 {
23584 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
23585 vinfos[0].jointtype = 1;
23586 vinfos[0].foffset = j0;
23587 vinfos[0].indices[0] = _ij0[0];
23588 vinfos[0].indices[1] = _ij0[1];
23589 vinfos[0].maxsolutions = _nj0;
23590 vinfos[1].jointtype = 1;
23591 vinfos[1].foffset = j1;
23592 vinfos[1].indices[0] = _ij1[0];
23593 vinfos[1].indices[1] = _ij1[1];
23594 vinfos[1].maxsolutions = _nj1;
23595 vinfos[2].jointtype = 1;
23596 vinfos[2].foffset = j2;
23597 vinfos[2].indices[0] = _ij2[0];
23598 vinfos[2].indices[1] = _ij2[1];
23599 vinfos[2].maxsolutions = _nj2;
23600 vinfos[3].jointtype = 1;
23601 vinfos[3].foffset = j3;
23602 vinfos[3].indices[0] = _ij3[0];
23603 vinfos[3].indices[1] = _ij3[1];
23604 vinfos[3].maxsolutions = _nj3;
23605 vinfos[4].jointtype = 1;
23606 vinfos[4].foffset = j4;
23607 vinfos[4].indices[0] = _ij4[0];
23608 vinfos[4].indices[1] = _ij4[1];
23609 vinfos[4].maxsolutions = _nj4;
23610 vinfos[5].jointtype = 1;
23611 vinfos[5].foffset = j5;
23612 vinfos[5].indices[0] = _ij5[0];
23613 vinfos[5].indices[1] = _ij5[1];
23614 vinfos[5].maxsolutions = _nj5;
23615 vinfos[6].jointtype = 1;
23616 vinfos[6].foffset = j6;
23617 vinfos[6].indices[0] = _ij6[0];
23618 vinfos[6].indices[1] = _ij6[1];
23619 vinfos[6].maxsolutions = _nj6;
23620 std::vector<int> vfree(0);
23621 solutions.AddSolution(vinfos,vfree);
23622 }
23623 }
23624 }
23625 
23626 }
23627 
23628 }
23629 
23630 } else
23631 {
23632 {
23633 IkReal j3array[1], cj3array[1], sj3array[1];
23634 bool j3valid[1]={false};
23635 _nj3 = 1;
23636 IkReal x7374=((sj1)*(sj6));
23637 IkReal x7375=((r20)*(sj5));
23638 IkReal x7376=((IkReal(1.00000000000000))*(r21));
23639 IkReal x7377=((cj1)*(cj6));
23640 IkReal x7378=((r20)*(sj4));
23641 IkReal x7379=((cj6)*(sj1));
23642 IkReal x7380=((cj4)*(cj5));
23643 IkReal x7381=((cj1)*(sj6));
23644 IkReal x7382=((cj5)*(r22));
23645 IkReal x7383=((cj4)*(r22)*(sj5));
23646 if( IKabs(((gconst7)*(((((cj1)*(x7382)))+(((IkReal(-1.00000000000000))*(sj4)*(x7374)*(x7376)))+(((IkReal(-1.00000000000000))*(x7375)*(x7381)))+(((r20)*(x7374)*(x7380)))+(((x7378)*(x7379)))+(((sj1)*(x7383)))+(((r21)*(x7379)*(x7380)))+(((IkReal(-1.00000000000000))*(sj5)*(x7376)*(x7377))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((r21)*(x7377)*(x7380)))+(((cj1)*(x7383)))+(((x7374)*(x7375)))+(((x7377)*(x7378)))+(((r20)*(x7380)*(x7381)))+(((r21)*(sj5)*(x7379)))+(((IkReal(-1.00000000000000))*(sj1)*(x7382)))+(((IkReal(-1.00000000000000))*(sj4)*(x7376)*(x7381))))))) < IKFAST_ATAN2_MAGTHRESH )
23647     continue;
23648 j3array[0]=IKatan2(((gconst7)*(((((cj1)*(x7382)))+(((IkReal(-1.00000000000000))*(sj4)*(x7374)*(x7376)))+(((IkReal(-1.00000000000000))*(x7375)*(x7381)))+(((r20)*(x7374)*(x7380)))+(((x7378)*(x7379)))+(((sj1)*(x7383)))+(((r21)*(x7379)*(x7380)))+(((IkReal(-1.00000000000000))*(sj5)*(x7376)*(x7377)))))), ((gconst7)*(((((r21)*(x7377)*(x7380)))+(((cj1)*(x7383)))+(((x7374)*(x7375)))+(((x7377)*(x7378)))+(((r20)*(x7380)*(x7381)))+(((r21)*(sj5)*(x7379)))+(((IkReal(-1.00000000000000))*(sj1)*(x7382)))+(((IkReal(-1.00000000000000))*(sj4)*(x7376)*(x7381)))))));
23649 sj3array[0]=IKsin(j3array[0]);
23650 cj3array[0]=IKcos(j3array[0]);
23651 if( j3array[0] > IKPI )
23652 {
23653     j3array[0]-=IK2PI;
23654 }
23655 else if( j3array[0] < -IKPI )
23656 {    j3array[0]+=IK2PI;
23657 }
23658 j3valid[0] = true;
23659 for(int ij3 = 0; ij3 < 1; ++ij3)
23660 {
23661 if( !j3valid[ij3] )
23662 {
23663     continue;
23664 }
23665 _ij3[0] = ij3; _ij3[1] = -1;
23666 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
23667 {
23668 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
23669 {
23670     j3valid[iij3]=false; _ij3[1] = iij3; break; 
23671 }
23672 }
23673 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
23674 {
23675 IkReal evalcond[4];
23676 IkReal x7384=IKsin(j3);
23677 IkReal x7385=IKcos(j3);
23678 IkReal x7386=((IkReal(1.00000000000000))*(cj4));
23679 IkReal x7387=((sj0)*(sj5));
23680 IkReal x7388=((cj0)*(cj5));
23681 IkReal x7389=((cj6)*(r01));
23682 IkReal x7390=((r00)*(sj6));
23683 IkReal x7391=((cj6)*(r11));
23684 IkReal x7392=((cj5)*(sj0));
23685 IkReal x7393=((cj6)*(sj4));
23686 IkReal x7394=((sj4)*(sj6));
23687 IkReal x7395=((cj4)*(cj5));
23688 IkReal x7396=((cj6)*(r21));
23689 IkReal x7397=((r20)*(sj6));
23690 IkReal x7398=((r10)*(sj6));
23691 IkReal x7399=((cj1)*(x7384));
23692 IkReal x7400=((IkReal(1.00000000000000))*(cj0)*(sj5));
23693 IkReal x7401=((IkReal(1.00000000000000))*(x7385));
23694 IkReal x7402=((IkReal(1.00000000000000))*(sj1)*(x7384));
23695 IkReal x7403=((cj1)*(x7401));
23696 IkReal x7404=((x7403)+(x7402));
23697 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x7401)))+(((sj5)*(x7396)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x7399)+(((sj5)*(x7397))));
23698 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x7394)))+(((x7395)*(x7396)))+(((r20)*(x7393)))+(((IkReal(-1.00000000000000))*(x7404)))+(((cj4)*(r22)*(sj5)))+(((x7395)*(x7397))));
23699 evalcond[2]=((((r02)*(x7388)))+(((IkReal(-1.00000000000000))*(x7404)))+(((r12)*(x7392)))+(((IkReal(-1.00000000000000))*(x7390)*(x7400)))+(((IkReal(-1.00000000000000))*(x7389)*(x7400)))+(((IkReal(-1.00000000000000))*(x7387)*(x7398)))+(((IkReal(-1.00000000000000))*(x7387)*(x7391))));
23700 evalcond[3]=((((IkReal(-1.00000000000000))*(x7386)*(x7391)*(x7392)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7393)))+(((IkReal(-1.00000000000000))*(x7386)*(x7388)*(x7389)))+(((IkReal(-1.00000000000000))*(x7386)*(x7388)*(x7390)))+(((sj1)*(x7385)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7386)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7393)))+(((cj0)*(r01)*(x7394)))+(((r11)*(sj0)*(x7394)))+(((IkReal(-1.00000000000000))*(x7386)*(x7392)*(x7398)))+(((IkReal(-1.00000000000000))*(x7399)))+(((IkReal(-1.00000000000000))*(r12)*(x7386)*(x7387))));
23701 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
23702 {
23703 continue;
23704 }
23705 }
23706 
23707 {
23708 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
23709 vinfos[0].jointtype = 1;
23710 vinfos[0].foffset = j0;
23711 vinfos[0].indices[0] = _ij0[0];
23712 vinfos[0].indices[1] = _ij0[1];
23713 vinfos[0].maxsolutions = _nj0;
23714 vinfos[1].jointtype = 1;
23715 vinfos[1].foffset = j1;
23716 vinfos[1].indices[0] = _ij1[0];
23717 vinfos[1].indices[1] = _ij1[1];
23718 vinfos[1].maxsolutions = _nj1;
23719 vinfos[2].jointtype = 1;
23720 vinfos[2].foffset = j2;
23721 vinfos[2].indices[0] = _ij2[0];
23722 vinfos[2].indices[1] = _ij2[1];
23723 vinfos[2].maxsolutions = _nj2;
23724 vinfos[3].jointtype = 1;
23725 vinfos[3].foffset = j3;
23726 vinfos[3].indices[0] = _ij3[0];
23727 vinfos[3].indices[1] = _ij3[1];
23728 vinfos[3].maxsolutions = _nj3;
23729 vinfos[4].jointtype = 1;
23730 vinfos[4].foffset = j4;
23731 vinfos[4].indices[0] = _ij4[0];
23732 vinfos[4].indices[1] = _ij4[1];
23733 vinfos[4].maxsolutions = _nj4;
23734 vinfos[5].jointtype = 1;
23735 vinfos[5].foffset = j5;
23736 vinfos[5].indices[0] = _ij5[0];
23737 vinfos[5].indices[1] = _ij5[1];
23738 vinfos[5].maxsolutions = _nj5;
23739 vinfos[6].jointtype = 1;
23740 vinfos[6].foffset = j6;
23741 vinfos[6].indices[0] = _ij6[0];
23742 vinfos[6].indices[1] = _ij6[1];
23743 vinfos[6].maxsolutions = _nj6;
23744 std::vector<int> vfree(0);
23745 solutions.AddSolution(vinfos,vfree);
23746 }
23747 }
23748 }
23749 
23750 }
23751 
23752 }
23753 
23754 } else
23755 {
23756 IkReal x7405=((IkReal(1.00000000000000))*(cj0));
23757 IkReal x7406=((cj4)*(sj6));
23758 IkReal x7407=((sj0)*(sj4));
23759 IkReal x7408=((cj5)*(sj6));
23760 IkReal x7409=((sj4)*(sj5));
23761 IkReal x7410=((r12)*(sj5));
23762 IkReal x7411=((IkReal(0.374290000000000))*(cj5));
23763 IkReal x7412=((r02)*(sj0));
23764 IkReal x7413=((cj6)*(r21));
23765 IkReal x7414=((IkReal(0.0100000000000000))*(cj5));
23766 IkReal x7415=((IkReal(1.00000000000000))*(sj0));
23767 IkReal x7416=((cj0)*(r10));
23768 IkReal x7417=((cj4)*(cj6));
23769 IkReal x7418=((r00)*(sj0));
23770 IkReal x7419=((IkReal(0.374290000000000))*(sj5));
23771 IkReal x7420=((cj0)*(r00));
23772 IkReal x7421=((IkReal(0.0100000000000000))*(sj5));
23773 IkReal x7422=((cj0)*(r02));
23774 IkReal x7423=((cj5)*(sj4));
23775 IkReal x7424=((cj6)*(r01));
23776 IkReal x7425=((cj6)*(r11));
23777 IkReal x7426=((r10)*(sj0));
23778 IkReal x7427=((sj6)*(x7419));
23779 IkReal x7428=((cj0)*(cj6)*(x7419));
23780 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
23781 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)))+(((x7413)*(x7423)))+(((r20)*(sj4)*(x7408)))+(((r21)*(x7406)))+(((r22)*(x7409)))+(((IkReal(-1.00000000000000))*(r20)*(x7417))));
23782 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x7421)))+(((IkReal(-1.00000000000000))*(x7413)*(x7414)))+(pz)+(((r20)*(x7427)))+(((x7413)*(x7419)))+(((IkReal(0.0690000000000000))*(cj2)))+(((IkReal(-0.0100000000000000))*(r20)*(x7408)))+(((IkReal(-1.00000000000000))*(r22)*(x7411))));
23783 evalcond[3]=((((r01)*(sj0)*(x7406)))+(((r00)*(x7407)*(x7408)))+(((cj5)*(x7407)*(x7424)))+(((x7416)*(x7417)))+(((IkReal(-1.00000000000000))*(r11)*(x7405)*(x7406)))+(cj2)+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7405)*(x7408)))+(((IkReal(-1.00000000000000))*(r00)*(x7415)*(x7417)))+(((r02)*(sj5)*(x7407)))+(((IkReal(-1.00000000000000))*(r12)*(x7405)*(x7409)))+(((IkReal(-1.00000000000000))*(x7405)*(x7423)*(x7425))));
23784 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x7406)*(x7415)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7405)*(x7408)))+(((IkReal(-1.00000000000000))*(r02)*(x7405)*(x7409)))+(((x7417)*(x7420)))+(((IkReal(-1.00000000000000))*(r10)*(x7407)*(x7408)))+(((IkReal(-1.00000000000000))*(x7405)*(x7423)*(x7424)))+(((IkReal(-1.00000000000000))*(x7407)*(x7410)))+(((x7417)*(x7426)))+(((IkReal(-1.00000000000000))*(cj5)*(x7407)*(x7425)))+(((IkReal(-1.00000000000000))*(r01)*(x7405)*(x7406))));
23785 evalcond[5]=((((IkReal(-0.0100000000000000))*(x7408)*(x7418)))+(((IkReal(0.0100000000000000))*(x7408)*(x7416)))+(((IkReal(0.0100000000000000))*(cj0)*(x7410)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(py)*(x7405)))+(((cj0)*(r12)*(x7411)))+(((IkReal(-1.00000000000000))*(cj0)*(x7419)*(x7425)))+(((IkReal(-1.00000000000000))*(x7412)*(x7421)))+(((sj0)*(x7419)*(x7424)))+(((x7418)*(x7427)))+(((IkReal(-1.00000000000000))*(sj0)*(x7414)*(x7424)))+(((IkReal(-1.00000000000000))*(x7416)*(x7427)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x7411)*(x7412)))+(((cj0)*(x7414)*(x7425))));
23786 evalcond[6]=((IkReal(0.433420000000000))+(((cj0)*(x7414)*(x7424)))+(((IkReal(0.0100000000000000))*(x7408)*(x7420)))+(((IkReal(0.0100000000000000))*(sj0)*(x7410)))+(((IkReal(-1.00000000000000))*(x7420)*(x7427)))+(((x7421)*(x7422)))+(((IkReal(-1.00000000000000))*(px)*(x7405)))+(((IkReal(-1.00000000000000))*(py)*(x7415)))+(((IkReal(-1.00000000000000))*(x7426)*(x7427)))+(((IkReal(-1.00000000000000))*(cj0)*(x7419)*(x7424)))+(((IkReal(-1.00000000000000))*(sj0)*(x7419)*(x7425)))+(((x7411)*(x7422)))+(((IkReal(0.0100000000000000))*(x7408)*(x7426)))+(((sj0)*(x7414)*(x7425)))+(((r12)*(sj0)*(x7411))));
23787 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
23788 {
23789 {
23790 IkReal dummyeval[1];
23791 IkReal gconst9;
23792 gconst9=IKsign(cj2);
23793 dummyeval[0]=cj2;
23794 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23795 {
23796 {
23797 IkReal dummyeval[1];
23798 dummyeval[0]=cj2;
23799 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23800 {
23801 {
23802 IkReal dummyeval[1];
23803 dummyeval[0]=sj2;
23804 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
23805 {
23806 {
23807 IkReal evalcond[9];
23808 IkReal x7429=((cj5)*(sj4));
23809 IkReal x7430=((IkReal(1.00000000000000))*(sj6));
23810 IkReal x7431=((r10)*(sj0));
23811 IkReal x7432=((sj4)*(sj5));
23812 IkReal x7433=((cj5)*(cj6));
23813 IkReal x7434=((r01)*(sj0));
23814 IkReal x7435=((IkReal(1.00000000000000))*(r02));
23815 IkReal x7436=((IkReal(0.374290000000000))*(cj0));
23816 IkReal x7437=((cj5)*(r12));
23817 IkReal x7438=((cj6)*(sj5));
23818 IkReal x7439=((cj0)*(r11));
23819 IkReal x7440=((cj5)*(sj0));
23820 IkReal x7441=((r20)*(sj6));
23821 IkReal x7442=((IkReal(1.00000000000000))*(sj0));
23822 IkReal x7443=((cj4)*(cj5));
23823 IkReal x7444=((IkReal(1.00000000000000))*(cj6));
23824 IkReal x7445=((IkReal(0.0100000000000000))*(sj5));
23825 IkReal x7446=((sj5)*(sj6));
23826 IkReal x7447=((cj0)*(r10));
23827 IkReal x7448=((cj4)*(cj6));
23828 IkReal x7449=((cj0)*(r01));
23829 IkReal x7450=((IkReal(1.00000000000000))*(cj4));
23830 IkReal x7451=((cj0)*(r00));
23831 IkReal x7452=((IkReal(0.374290000000000))*(sj0));
23832 IkReal x7453=((cj0)*(r12));
23833 IkReal x7454=((IkReal(0.374290000000000))*(sj5));
23834 IkReal x7455=((cj4)*(sj6));
23835 IkReal x7456=((IkReal(1.00000000000000))*(cj0));
23836 IkReal x7457=((r02)*(sj0));
23837 IkReal x7458=((IkReal(0.0100000000000000))*(cj5));
23838 IkReal x7459=((r11)*(sj0));
23839 IkReal x7460=((r00)*(sj0)*(sj6));
23840 IkReal x7461=((r00)*(x7448));
23841 IkReal x7462=((sj6)*(x7458));
23842 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
23843 evalcond[1]=((((x7429)*(x7441)))+(((r21)*(x7455)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7444)))+(((r22)*(x7432)))+(((cj6)*(r21)*(x7429))));
23844 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x7438)))+(((IkReal(-1.00000000000000))*(x7441)*(x7458)))+(((IkReal(-0.0100000000000000))*(r21)*(x7433)))+(((x7441)*(x7454)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x7445))));
23845 evalcond[3]=((((r00)*(sj0)*(x7446)))+(((IkReal(-1.00000000000000))*(x7438)*(x7439)))+(((x7434)*(x7438)))+(((IkReal(-1.00000000000000))*(sj5)*(x7430)*(x7447)))+(((cj0)*(x7437)))+(((IkReal(-1.00000000000000))*(x7435)*(x7440))));
23846 evalcond[4]=((IkReal(1.00000000000000))+(((x7447)*(x7448)))+(((IkReal(-1.00000000000000))*(x7429)*(x7430)*(x7447)))+(((x7434)*(x7455)))+(((IkReal(-1.00000000000000))*(x7442)*(x7461)))+(((IkReal(-1.00000000000000))*(x7432)*(x7453)))+(((cj6)*(x7429)*(x7434)))+(((x7432)*(x7457)))+(((IkReal(-1.00000000000000))*(cj4)*(x7430)*(x7439)))+(((IkReal(-1.00000000000000))*(x7429)*(x7439)*(x7444)))+(((x7429)*(x7460))));
23847 evalcond[5]=((((cj4)*(sj5)*(x7457)))+(((cj4)*(x7433)*(x7434)))+(((IkReal(-1.00000000000000))*(sj5)*(x7450)*(x7453)))+(((r00)*(x7440)*(x7455)))+(((IkReal(-1.00000000000000))*(sj4)*(x7430)*(x7434)))+(((IkReal(-1.00000000000000))*(x7430)*(x7443)*(x7447)))+(((IkReal(-1.00000000000000))*(sj4)*(x7444)*(x7447)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x7433)*(x7439)*(x7450)))+(((sj4)*(sj6)*(x7439))));
23848 evalcond[6]=((((x7431)*(x7448)))+(((IkReal(-1.00000000000000))*(x7429)*(x7430)*(x7451)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7429)*(x7442)))+(((IkReal(-1.00000000000000))*(r12)*(x7432)*(x7442)))+(((IkReal(-1.00000000000000))*(cj4)*(x7430)*(x7459)))+(((IkReal(-1.00000000000000))*(x7429)*(x7444)*(x7449)))+(((x7448)*(x7451)))+(((IkReal(-1.00000000000000))*(cj0)*(x7432)*(x7435)))+(((IkReal(-1.00000000000000))*(x7429)*(x7430)*(x7431)))+(((IkReal(-1.00000000000000))*(cj4)*(x7430)*(x7449))));
23849 evalcond[7]=((((IkReal(-1.00000000000000))*(py)*(x7456)))+(((IkReal(-1.00000000000000))*(r11)*(x7436)*(x7438)))+(((IkReal(-0.374290000000000))*(r02)*(x7440)))+(((IkReal(0.0100000000000000))*(x7433)*(x7439)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7440)))+(((IkReal(-0.0100000000000000))*(x7433)*(x7434)))+(((x7436)*(x7437)))+(((r00)*(x7446)*(x7452)))+(((x7447)*(x7462)))+(((px)*(sj0)))+(((IkReal(0.374290000000000))*(x7434)*(x7438)))+(((IkReal(-1.00000000000000))*(x7445)*(x7457)))+(((IkReal(-1.00000000000000))*(r10)*(x7436)*(x7446)))+(((x7445)*(x7453))));
23850 evalcond[8]=((IkReal(0.433420000000000))+(((cj5)*(r02)*(x7436)))+(((IkReal(-1.00000000000000))*(py)*(x7442)))+(((IkReal(-0.374290000000000))*(x7431)*(x7446)))+(((x7431)*(x7462)))+(((x7451)*(x7462)))+(((IkReal(-1.00000000000000))*(r01)*(x7436)*(x7438)))+(((IkReal(-1.00000000000000))*(r00)*(x7436)*(x7446)))+(((IkReal(0.0100000000000000))*(x7433)*(x7449)))+(((IkReal(0.0100000000000000))*(x7433)*(x7459)))+(((IkReal(-1.00000000000000))*(r11)*(x7438)*(x7452)))+(((x7437)*(x7452)))+(((cj0)*(r02)*(x7445)))+(((IkReal(-1.00000000000000))*(px)*(x7456)))+(((r12)*(sj0)*(x7445))));
23851 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
23852 {
23853 {
23854 IkReal j3array[1], cj3array[1], sj3array[1];
23855 bool j3valid[1]={false};
23856 _nj3 = 1;
23857 IkReal x7463=((IkReal(1.00000000000000))*(cj4));
23858 IkReal x7464=((cj6)*(r21));
23859 IkReal x7465=((r20)*(sj6));
23860 if( IKabs(((((sj5)*(x7465)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7464))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7464)))+(((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7465)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x7465)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7464)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7464)))+(((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7465)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
23861     continue;
23862 j3array[0]=IKatan2(((((sj5)*(x7465)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7464)))), ((((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7464)))+(((IkReal(-1.00000000000000))*(cj5)*(x7463)*(x7465)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7463)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
23863 sj3array[0]=IKsin(j3array[0]);
23864 cj3array[0]=IKcos(j3array[0]);
23865 if( j3array[0] > IKPI )
23866 {
23867     j3array[0]-=IK2PI;
23868 }
23869 else if( j3array[0] < -IKPI )
23870 {    j3array[0]+=IK2PI;
23871 }
23872 j3valid[0] = true;
23873 for(int ij3 = 0; ij3 < 1; ++ij3)
23874 {
23875 if( !j3valid[ij3] )
23876 {
23877     continue;
23878 }
23879 _ij3[0] = ij3; _ij3[1] = -1;
23880 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
23881 {
23882 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
23883 {
23884     j3valid[iij3]=false; _ij3[1] = iij3; break; 
23885 }
23886 }
23887 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
23888 {
23889 IkReal evalcond[4];
23890 IkReal x7466=IKcos(j3);
23891 IkReal x7467=((IkReal(1.00000000000000))*(cj4));
23892 IkReal x7468=((sj0)*(sj5));
23893 IkReal x7469=((cj0)*(cj5));
23894 IkReal x7470=((cj6)*(r01));
23895 IkReal x7471=((r00)*(sj6));
23896 IkReal x7472=((cj6)*(r11));
23897 IkReal x7473=((cj5)*(sj0));
23898 IkReal x7474=((cj6)*(sj4));
23899 IkReal x7475=((sj4)*(sj6));
23900 IkReal x7476=((cj4)*(cj5));
23901 IkReal x7477=((cj6)*(r21));
23902 IkReal x7478=((r20)*(sj6));
23903 IkReal x7479=((r10)*(sj6));
23904 IkReal x7480=((IkReal(1.00000000000000))*(IKsin(j3)));
23905 IkReal x7481=((IkReal(1.00000000000000))*(cj0)*(sj5));
23906 evalcond[0]=((((sj5)*(x7477)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7478)))+(((IkReal(-1.00000000000000))*(x7480))));
23907 evalcond[1]=((((x7476)*(x7477)))+(((x7476)*(x7478)))+(((IkReal(-1.00000000000000))*(r21)*(x7475)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7474)))+(x7466));
23908 evalcond[2]=((((IkReal(-1.00000000000000))*(x7471)*(x7481)))+(((IkReal(-1.00000000000000))*(x7468)*(x7472)))+(((IkReal(-1.00000000000000))*(x7468)*(x7479)))+(((IkReal(-1.00000000000000))*(x7470)*(x7481)))+(((IkReal(-1.00000000000000))*(x7466)))+(((r12)*(x7473)))+(((r02)*(x7469))));
23909 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x7467)*(x7468)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7467)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7474)))+(((IkReal(-1.00000000000000))*(x7467)*(x7469)*(x7470)))+(((r11)*(sj0)*(x7475)))+(((IkReal(-1.00000000000000))*(x7467)*(x7472)*(x7473)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7474)))+(((IkReal(-1.00000000000000))*(x7480)))+(((cj0)*(r01)*(x7475)))+(((IkReal(-1.00000000000000))*(x7467)*(x7473)*(x7479)))+(((IkReal(-1.00000000000000))*(x7467)*(x7469)*(x7471))));
23910 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
23911 {
23912 continue;
23913 }
23914 }
23915 
23916 {
23917 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
23918 vinfos[0].jointtype = 1;
23919 vinfos[0].foffset = j0;
23920 vinfos[0].indices[0] = _ij0[0];
23921 vinfos[0].indices[1] = _ij0[1];
23922 vinfos[0].maxsolutions = _nj0;
23923 vinfos[1].jointtype = 1;
23924 vinfos[1].foffset = j1;
23925 vinfos[1].indices[0] = _ij1[0];
23926 vinfos[1].indices[1] = _ij1[1];
23927 vinfos[1].maxsolutions = _nj1;
23928 vinfos[2].jointtype = 1;
23929 vinfos[2].foffset = j2;
23930 vinfos[2].indices[0] = _ij2[0];
23931 vinfos[2].indices[1] = _ij2[1];
23932 vinfos[2].maxsolutions = _nj2;
23933 vinfos[3].jointtype = 1;
23934 vinfos[3].foffset = j3;
23935 vinfos[3].indices[0] = _ij3[0];
23936 vinfos[3].indices[1] = _ij3[1];
23937 vinfos[3].maxsolutions = _nj3;
23938 vinfos[4].jointtype = 1;
23939 vinfos[4].foffset = j4;
23940 vinfos[4].indices[0] = _ij4[0];
23941 vinfos[4].indices[1] = _ij4[1];
23942 vinfos[4].maxsolutions = _nj4;
23943 vinfos[5].jointtype = 1;
23944 vinfos[5].foffset = j5;
23945 vinfos[5].indices[0] = _ij5[0];
23946 vinfos[5].indices[1] = _ij5[1];
23947 vinfos[5].maxsolutions = _nj5;
23948 vinfos[6].jointtype = 1;
23949 vinfos[6].foffset = j6;
23950 vinfos[6].indices[0] = _ij6[0];
23951 vinfos[6].indices[1] = _ij6[1];
23952 vinfos[6].maxsolutions = _nj6;
23953 std::vector<int> vfree(0);
23954 solutions.AddSolution(vinfos,vfree);
23955 }
23956 }
23957 }
23958 
23959 } else
23960 {
23961 IkReal x7482=((cj5)*(sj4));
23962 IkReal x7483=((IkReal(1.00000000000000))*(sj6));
23963 IkReal x7484=((r10)*(sj0));
23964 IkReal x7485=((sj4)*(sj5));
23965 IkReal x7486=((cj5)*(cj6));
23966 IkReal x7487=((r01)*(sj0));
23967 IkReal x7488=((IkReal(1.00000000000000))*(r02));
23968 IkReal x7489=((IkReal(0.374290000000000))*(cj0));
23969 IkReal x7490=((cj5)*(r12));
23970 IkReal x7491=((cj6)*(sj5));
23971 IkReal x7492=((cj0)*(r11));
23972 IkReal x7493=((cj5)*(sj0));
23973 IkReal x7494=((r20)*(sj6));
23974 IkReal x7495=((IkReal(1.00000000000000))*(sj0));
23975 IkReal x7496=((cj4)*(cj5));
23976 IkReal x7497=((IkReal(1.00000000000000))*(cj6));
23977 IkReal x7498=((IkReal(0.0100000000000000))*(sj5));
23978 IkReal x7499=((sj5)*(sj6));
23979 IkReal x7500=((cj0)*(r10));
23980 IkReal x7501=((cj4)*(cj6));
23981 IkReal x7502=((cj0)*(r01));
23982 IkReal x7503=((IkReal(1.00000000000000))*(cj4));
23983 IkReal x7504=((cj0)*(r00));
23984 IkReal x7505=((IkReal(0.374290000000000))*(sj0));
23985 IkReal x7506=((cj0)*(r12));
23986 IkReal x7507=((IkReal(0.374290000000000))*(sj5));
23987 IkReal x7508=((cj4)*(sj6));
23988 IkReal x7509=((IkReal(1.00000000000000))*(cj0));
23989 IkReal x7510=((r02)*(sj0));
23990 IkReal x7511=((IkReal(0.0100000000000000))*(cj5));
23991 IkReal x7512=((r11)*(sj0));
23992 IkReal x7513=((r00)*(sj0)*(sj6));
23993 IkReal x7514=((r00)*(x7501));
23994 IkReal x7515=((sj6)*(x7511));
23995 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
23996 evalcond[1]=((((r21)*(x7508)))+(((r22)*(x7485)))+(((x7482)*(x7494)))+(((cj6)*(r21)*(x7482)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7497))));
23997 evalcond[2]=((IkReal(-0.0690000000000000))+(((x7494)*(x7507)))+(((IkReal(0.374290000000000))*(r21)*(x7491)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x7498)))+(pz)+(((IkReal(-1.00000000000000))*(x7494)*(x7511)))+(((IkReal(-0.0100000000000000))*(r21)*(x7486))));
23998 evalcond[3]=((((IkReal(-1.00000000000000))*(x7491)*(x7492)))+(((x7487)*(x7491)))+(((IkReal(-1.00000000000000))*(x7488)*(x7493)))+(((r00)*(sj0)*(x7499)))+(((cj0)*(x7490)))+(((IkReal(-1.00000000000000))*(sj5)*(x7483)*(x7500))));
23999 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x7482)*(x7492)*(x7497)))+(((x7485)*(x7510)))+(((IkReal(-1.00000000000000))*(cj4)*(x7483)*(x7492)))+(((cj6)*(x7482)*(x7487)))+(((x7500)*(x7501)))+(((x7482)*(x7513)))+(((IkReal(-1.00000000000000))*(x7485)*(x7506)))+(((IkReal(-1.00000000000000))*(x7482)*(x7483)*(x7500)))+(((IkReal(-1.00000000000000))*(x7495)*(x7514)))+(((x7487)*(x7508))));
24000 evalcond[5]=((((IkReal(-1.00000000000000))*(x7483)*(x7496)*(x7500)))+(((r00)*(x7493)*(x7508)))+(((cj4)*(sj5)*(x7510)))+(((cj4)*(x7486)*(x7487)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((sj4)*(sj6)*(x7492)))+(((IkReal(-1.00000000000000))*(sj4)*(x7497)*(x7500)))+(((IkReal(-1.00000000000000))*(x7486)*(x7492)*(x7503)))+(((IkReal(-1.00000000000000))*(sj5)*(x7503)*(x7506)))+(((IkReal(-1.00000000000000))*(sj4)*(x7483)*(x7487))));
24001 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x7483)*(x7512)))+(((x7484)*(x7501)))+(((IkReal(-1.00000000000000))*(cj4)*(x7483)*(x7502)))+(((IkReal(-1.00000000000000))*(x7482)*(x7483)*(x7504)))+(((x7501)*(x7504)))+(((IkReal(-1.00000000000000))*(x7482)*(x7483)*(x7484)))+(((IkReal(-1.00000000000000))*(r12)*(x7485)*(x7495)))+(((IkReal(-1.00000000000000))*(cj0)*(x7485)*(x7488)))+(((IkReal(-1.00000000000000))*(x7482)*(x7497)*(x7502)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7482)*(x7495))));
24002 evalcond[7]=((((IkReal(-1.00000000000000))*(x7498)*(x7510)))+(((IkReal(-1.00000000000000))*(r10)*(x7489)*(x7499)))+(((x7489)*(x7490)))+(((IkReal(-0.374290000000000))*(r02)*(x7493)))+(((IkReal(-1.00000000000000))*(py)*(x7509)))+(((x7500)*(x7515)))+(((IkReal(-0.0100000000000000))*(x7486)*(x7487)))+(((IkReal(-1.00000000000000))*(r11)*(x7489)*(x7491)))+(((IkReal(0.374290000000000))*(x7487)*(x7491)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7493)))+(((x7498)*(x7506)))+(((r00)*(x7499)*(x7505)))+(((IkReal(0.0100000000000000))*(x7486)*(x7492))));
24003 evalcond[8]=((IkReal(0.433420000000000))+(((x7490)*(x7505)))+(((r12)*(sj0)*(x7498)))+(((x7504)*(x7515)))+(((IkReal(-1.00000000000000))*(r11)*(x7491)*(x7505)))+(((cj0)*(r02)*(x7498)))+(((IkReal(-1.00000000000000))*(r00)*(x7489)*(x7499)))+(((IkReal(-1.00000000000000))*(py)*(x7495)))+(((IkReal(-1.00000000000000))*(r01)*(x7489)*(x7491)))+(((IkReal(-0.374290000000000))*(x7484)*(x7499)))+(((x7484)*(x7515)))+(((cj5)*(r02)*(x7489)))+(((IkReal(0.0100000000000000))*(x7486)*(x7502)))+(((IkReal(0.0100000000000000))*(x7486)*(x7512)))+(((IkReal(-1.00000000000000))*(px)*(x7509))));
24004 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
24005 {
24006 {
24007 IkReal j3array[1], cj3array[1], sj3array[1];
24008 bool j3valid[1]={false};
24009 _nj3 = 1;
24010 IkReal x7516=((IkReal(1.00000000000000))*(r21));
24011 IkReal x7517=((cj4)*(cj5));
24012 IkReal x7518=((r20)*(sj6));
24013 if( IKabs(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7516)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj5)*(x7518))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r21)*(x7517)))+(((x7517)*(x7518)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7516))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7516)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj5)*(x7518)))))+IKsqr(((((cj6)*(r21)*(x7517)))+(((x7517)*(x7518)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7516)))))-1) <= IKFAST_SINCOS_THRESH )
24014     continue;
24015 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7516)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj5)*(x7518)))), ((((cj6)*(r21)*(x7517)))+(((x7517)*(x7518)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7516)))));
24016 sj3array[0]=IKsin(j3array[0]);
24017 cj3array[0]=IKcos(j3array[0]);
24018 if( j3array[0] > IKPI )
24019 {
24020     j3array[0]-=IK2PI;
24021 }
24022 else if( j3array[0] < -IKPI )
24023 {    j3array[0]+=IK2PI;
24024 }
24025 j3valid[0] = true;
24026 for(int ij3 = 0; ij3 < 1; ++ij3)
24027 {
24028 if( !j3valid[ij3] )
24029 {
24030     continue;
24031 }
24032 _ij3[0] = ij3; _ij3[1] = -1;
24033 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24034 {
24035 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24036 {
24037     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24038 }
24039 }
24040 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24041 {
24042 IkReal evalcond[4];
24043 IkReal x7519=IKsin(j3);
24044 IkReal x7520=((IkReal(1.00000000000000))*(cj4));
24045 IkReal x7521=((sj0)*(sj5));
24046 IkReal x7522=((cj0)*(cj5));
24047 IkReal x7523=((cj6)*(r01));
24048 IkReal x7524=((r00)*(sj6));
24049 IkReal x7525=((cj6)*(r11));
24050 IkReal x7526=((cj5)*(sj0));
24051 IkReal x7527=((cj6)*(sj4));
24052 IkReal x7528=((sj4)*(sj6));
24053 IkReal x7529=((cj4)*(cj5));
24054 IkReal x7530=((cj6)*(r21));
24055 IkReal x7531=((r20)*(sj6));
24056 IkReal x7532=((r10)*(sj6));
24057 IkReal x7533=((IkReal(1.00000000000000))*(IKcos(j3)));
24058 IkReal x7534=((IkReal(1.00000000000000))*(cj0)*(sj5));
24059 evalcond[0]=((x7519)+(((sj5)*(x7530)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7531))));
24060 evalcond[1]=((((r20)*(x7527)))+(((x7529)*(x7531)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x7528)))+(((x7529)*(x7530)))+(((IkReal(-1.00000000000000))*(x7533))));
24061 evalcond[2]=((((IkReal(-1.00000000000000))*(x7521)*(x7532)))+(((IkReal(-1.00000000000000))*(x7524)*(x7534)))+(((r02)*(x7522)))+(((IkReal(-1.00000000000000))*(x7521)*(x7525)))+(((IkReal(-1.00000000000000))*(x7523)*(x7534)))+(((r12)*(x7526)))+(((IkReal(-1.00000000000000))*(x7533))));
24062 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x7520)*(x7521)))+(((IkReal(-1.00000000000000))*(x7520)*(x7526)*(x7532)))+(((IkReal(-1.00000000000000))*(x7519)))+(((IkReal(-1.00000000000000))*(x7520)*(x7522)*(x7523)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7527)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7527)))+(((r11)*(sj0)*(x7528)))+(((IkReal(-1.00000000000000))*(x7520)*(x7525)*(x7526)))+(((IkReal(-1.00000000000000))*(x7520)*(x7522)*(x7524)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7520)))+(((cj0)*(r01)*(x7528))));
24063 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
24064 {
24065 continue;
24066 }
24067 }
24068 
24069 {
24070 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24071 vinfos[0].jointtype = 1;
24072 vinfos[0].foffset = j0;
24073 vinfos[0].indices[0] = _ij0[0];
24074 vinfos[0].indices[1] = _ij0[1];
24075 vinfos[0].maxsolutions = _nj0;
24076 vinfos[1].jointtype = 1;
24077 vinfos[1].foffset = j1;
24078 vinfos[1].indices[0] = _ij1[0];
24079 vinfos[1].indices[1] = _ij1[1];
24080 vinfos[1].maxsolutions = _nj1;
24081 vinfos[2].jointtype = 1;
24082 vinfos[2].foffset = j2;
24083 vinfos[2].indices[0] = _ij2[0];
24084 vinfos[2].indices[1] = _ij2[1];
24085 vinfos[2].maxsolutions = _nj2;
24086 vinfos[3].jointtype = 1;
24087 vinfos[3].foffset = j3;
24088 vinfos[3].indices[0] = _ij3[0];
24089 vinfos[3].indices[1] = _ij3[1];
24090 vinfos[3].maxsolutions = _nj3;
24091 vinfos[4].jointtype = 1;
24092 vinfos[4].foffset = j4;
24093 vinfos[4].indices[0] = _ij4[0];
24094 vinfos[4].indices[1] = _ij4[1];
24095 vinfos[4].maxsolutions = _nj4;
24096 vinfos[5].jointtype = 1;
24097 vinfos[5].foffset = j5;
24098 vinfos[5].indices[0] = _ij5[0];
24099 vinfos[5].indices[1] = _ij5[1];
24100 vinfos[5].maxsolutions = _nj5;
24101 vinfos[6].jointtype = 1;
24102 vinfos[6].foffset = j6;
24103 vinfos[6].indices[0] = _ij6[0];
24104 vinfos[6].indices[1] = _ij6[1];
24105 vinfos[6].maxsolutions = _nj6;
24106 std::vector<int> vfree(0);
24107 solutions.AddSolution(vinfos,vfree);
24108 }
24109 }
24110 }
24111 
24112 } else
24113 {
24114 IkReal x7535=((IkReal(1.00000000000000))*(cj0));
24115 IkReal x7536=((cj4)*(sj6));
24116 IkReal x7537=((sj0)*(sj4));
24117 IkReal x7538=((cj5)*(sj6));
24118 IkReal x7539=((sj4)*(sj5));
24119 IkReal x7540=((r12)*(sj5));
24120 IkReal x7541=((IkReal(0.374290000000000))*(cj5));
24121 IkReal x7542=((r02)*(sj0));
24122 IkReal x7543=((r20)*(sj4));
24123 IkReal x7544=((IkReal(1.00000000000000))*(sj0));
24124 IkReal x7545=((IkReal(1.00000000000000))*(cj5));
24125 IkReal x7546=((cj0)*(r10));
24126 IkReal x7547=((cj4)*(cj6));
24127 IkReal x7548=((r00)*(sj0));
24128 IkReal x7549=((cj6)*(r21));
24129 IkReal x7550=((IkReal(0.374290000000000))*(sj5));
24130 IkReal x7551=((cj0)*(r00));
24131 IkReal x7552=((IkReal(0.0100000000000000))*(sj5));
24132 IkReal x7553=((cj0)*(r02));
24133 IkReal x7554=((cj5)*(sj4));
24134 IkReal x7555=((cj6)*(r01));
24135 IkReal x7556=((cj6)*(r11));
24136 IkReal x7557=((r01)*(sj0));
24137 IkReal x7558=((r10)*(sj0));
24138 IkReal x7559=((IkReal(0.0100000000000000))*(cj5)*(cj6));
24139 IkReal x7560=((sj6)*(x7550));
24140 IkReal x7561=((cj0)*(cj6)*(x7550));
24141 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
24142 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x7545)))+(((r20)*(sj5)*(sj6)))+(((sj5)*(x7549))));
24143 evalcond[2]=((IkReal(-1.00000000000000))+(((x7549)*(x7554)))+(((r22)*(x7539)))+(((r21)*(x7536)))+(((x7538)*(x7543)))+(((IkReal(-1.00000000000000))*(r20)*(x7547))));
24144 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x7538)))+(((IkReal(-0.0100000000000000))*(cj5)*(x7549)))+(((x7549)*(x7550)))+(((IkReal(-1.00000000000000))*(r22)*(x7552)))+(((IkReal(-1.00000000000000))*(r22)*(x7541)))+(pz)+(((r20)*(x7560))));
24145 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x7547)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x7536)))+(((cj6)*(x7543))));
24146 evalcond[5]=((((r00)*(x7537)*(x7538)))+(((IkReal(-1.00000000000000))*(x7535)*(x7554)*(x7556)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7535)*(x7538)))+(((cj5)*(x7537)*(x7555)))+(((IkReal(-1.00000000000000))*(r12)*(x7535)*(x7539)))+(((IkReal(-1.00000000000000))*(r11)*(x7535)*(x7536)))+(((x7546)*(x7547)))+(((IkReal(-1.00000000000000))*(r00)*(x7544)*(x7547)))+(((r02)*(sj5)*(x7537)))+(((x7536)*(x7557))));
24147 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(x7537)*(x7538)))+(((IkReal(-1.00000000000000))*(r01)*(x7535)*(x7536)))+(((IkReal(-1.00000000000000))*(x7535)*(x7554)*(x7555)))+(((x7547)*(x7551)))+(((IkReal(-1.00000000000000))*(x7537)*(x7540)))+(((x7547)*(x7558)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7535)*(x7538)))+(((IkReal(-1.00000000000000))*(r02)*(x7535)*(x7539)))+(((IkReal(-1.00000000000000))*(x7537)*(x7545)*(x7556)))+(((IkReal(-1.00000000000000))*(r11)*(x7536)*(x7544))));
24148 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x7546)*(x7560)))+(((cj0)*(r12)*(x7541)))+(((IkReal(-0.0100000000000000))*(x7538)*(x7548)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7556)))+(((IkReal(-1.00000000000000))*(py)*(x7535)))+(((sj0)*(x7550)*(x7555)))+(((IkReal(-1.00000000000000))*(x7541)*(x7542)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x7555)))+(((x7548)*(x7560)))+(((IkReal(0.0100000000000000))*(x7538)*(x7546)))+(((IkReal(0.0100000000000000))*(cj0)*(x7540)))+(((IkReal(-1.00000000000000))*(x7542)*(x7552)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x7550)*(x7556))));
24149 evalcond[8]=((IkReal(0.433420000000000))+(((x7541)*(x7553)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7555)))+(((IkReal(-1.00000000000000))*(x7551)*(x7560)))+(((IkReal(0.0100000000000000))*(sj0)*(x7540)))+(((r12)*(sj0)*(x7541)))+(((IkReal(0.0100000000000000))*(x7538)*(x7558)))+(((IkReal(-1.00000000000000))*(cj0)*(x7550)*(x7555)))+(((x7552)*(x7553)))+(((IkReal(-1.00000000000000))*(py)*(x7544)))+(((IkReal(-1.00000000000000))*(x7558)*(x7560)))+(((IkReal(-1.00000000000000))*(sj0)*(x7550)*(x7556)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x7556)))+(((IkReal(-1.00000000000000))*(px)*(x7535)))+(((IkReal(0.0100000000000000))*(x7538)*(x7551))));
24150 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
24151 {
24152 {
24153 IkReal j3array[1], cj3array[1], sj3array[1];
24154 bool j3valid[1]={false};
24155 _nj3 = 1;
24156 IkReal x7562=((cj0)*(cj5));
24157 IkReal x7563=((IkReal(1.00000000000000))*(cj0));
24158 IkReal x7564=((cj6)*(r11));
24159 IkReal x7565=((r10)*(sj6));
24160 IkReal x7566=((cj5)*(sj0));
24161 IkReal x7567=((r00)*(sj5)*(sj6));
24162 IkReal x7568=((cj6)*(r01)*(sj5));
24163 IkReal x7569=((IkReal(1.00000000000000))*(sj0)*(sj5));
24164 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7565)))+(((r12)*(x7562)))+(((sj0)*(x7567)))+(((sj0)*(x7568)))+(((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7564)))+(((IkReal(-1.00000000000000))*(r02)*(x7566))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x7563)*(x7567)))+(((IkReal(-1.00000000000000))*(x7564)*(x7569)))+(((r12)*(x7566)))+(((r02)*(x7562)))+(((IkReal(-1.00000000000000))*(x7565)*(x7569)))+(((IkReal(-1.00000000000000))*(x7563)*(x7568))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7565)))+(((r12)*(x7562)))+(((sj0)*(x7567)))+(((sj0)*(x7568)))+(((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7564)))+(((IkReal(-1.00000000000000))*(r02)*(x7566)))))+IKsqr(((((IkReal(-1.00000000000000))*(x7563)*(x7567)))+(((IkReal(-1.00000000000000))*(x7564)*(x7569)))+(((r12)*(x7566)))+(((r02)*(x7562)))+(((IkReal(-1.00000000000000))*(x7565)*(x7569)))+(((IkReal(-1.00000000000000))*(x7563)*(x7568)))))-1) <= IKFAST_SINCOS_THRESH )
24165     continue;
24166 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7565)))+(((r12)*(x7562)))+(((sj0)*(x7567)))+(((sj0)*(x7568)))+(((IkReal(-1.00000000000000))*(sj5)*(x7563)*(x7564)))+(((IkReal(-1.00000000000000))*(r02)*(x7566)))), ((((IkReal(-1.00000000000000))*(x7563)*(x7567)))+(((IkReal(-1.00000000000000))*(x7564)*(x7569)))+(((r12)*(x7566)))+(((r02)*(x7562)))+(((IkReal(-1.00000000000000))*(x7565)*(x7569)))+(((IkReal(-1.00000000000000))*(x7563)*(x7568)))));
24167 sj3array[0]=IKsin(j3array[0]);
24168 cj3array[0]=IKcos(j3array[0]);
24169 if( j3array[0] > IKPI )
24170 {
24171     j3array[0]-=IK2PI;
24172 }
24173 else if( j3array[0] < -IKPI )
24174 {    j3array[0]+=IK2PI;
24175 }
24176 j3valid[0] = true;
24177 for(int ij3 = 0; ij3 < 1; ++ij3)
24178 {
24179 if( !j3valid[ij3] )
24180 {
24181     continue;
24182 }
24183 _ij3[0] = ij3; _ij3[1] = -1;
24184 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24185 {
24186 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24187 {
24188     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24189 }
24190 }
24191 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24192 {
24193 IkReal evalcond[4];
24194 IkReal x7570=IKcos(j3);
24195 IkReal x7571=((sj0)*(sj5));
24196 IkReal x7572=((r00)*(sj6));
24197 IkReal x7573=((cj6)*(sj0));
24198 IkReal x7574=((IkReal(1.00000000000000))*(cj4));
24199 IkReal x7575=((r00)*(sj4));
24200 IkReal x7576=((cj0)*(cj5));
24201 IkReal x7577=((cj5)*(sj0));
24202 IkReal x7578=((cj6)*(r11));
24203 IkReal x7579=((r10)*(sj6));
24204 IkReal x7580=((cj0)*(sj5));
24205 IkReal x7581=((r10)*(sj4));
24206 IkReal x7582=((IkReal(1.00000000000000))*(IKsin(j3)));
24207 IkReal x7583=((cj4)*(cj5)*(r01));
24208 IkReal x7584=((IkReal(1.00000000000000))*(cj0)*(cj6));
24209 IkReal x7585=((cj0)*(sj4)*(sj6));
24210 IkReal x7586=((sj0)*(sj4)*(sj6));
24211 evalcond[0]=((((IkReal(-1.00000000000000))*(x7582)))+(((IkReal(-1.00000000000000))*(r02)*(x7577)))+(((IkReal(-1.00000000000000))*(x7578)*(x7580)))+(((cj6)*(r01)*(x7571)))+(((IkReal(-1.00000000000000))*(x7579)*(x7580)))+(((x7571)*(x7572)))+(((r12)*(x7576))));
24212 evalcond[1]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x7580)))+(((IkReal(-1.00000000000000))*(x7571)*(x7578)))+(((IkReal(-1.00000000000000))*(x7571)*(x7579)))+(((IkReal(-1.00000000000000))*(x7570)))+(((r12)*(x7577)))+(((r02)*(x7576)))+(((IkReal(-1.00000000000000))*(x7572)*(x7580))));
24213 evalcond[2]=((((cj4)*(r02)*(x7571)))+(((IkReal(-1.00000000000000))*(x7574)*(x7576)*(x7579)))+(((r11)*(x7585)))+(((IkReal(-1.00000000000000))*(x7581)*(x7584)))+(((IkReal(-1.00000000000000))*(x7574)*(x7576)*(x7578)))+(((IkReal(-1.00000000000000))*(r01)*(x7586)))+(((x7573)*(x7575)))+(((IkReal(-1.00000000000000))*(r12)*(x7574)*(x7580)))+(((x7573)*(x7583)))+(((cj4)*(x7572)*(x7577)))+(x7570));
24214 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x7571)*(x7574)))+(((IkReal(-1.00000000000000))*(x7582)))+(((IkReal(-1.00000000000000))*(r02)*(x7574)*(x7580)))+(((IkReal(-1.00000000000000))*(x7574)*(x7577)*(x7579)))+(((IkReal(-1.00000000000000))*(x7572)*(x7574)*(x7576)))+(((r11)*(x7586)))+(((r01)*(x7585)))+(((IkReal(-1.00000000000000))*(x7573)*(x7581)))+(((IkReal(-1.00000000000000))*(x7575)*(x7584)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x7574)*(x7576)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7573)*(x7574))));
24215 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
24216 {
24217 continue;
24218 }
24219 }
24220 
24221 {
24222 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24223 vinfos[0].jointtype = 1;
24224 vinfos[0].foffset = j0;
24225 vinfos[0].indices[0] = _ij0[0];
24226 vinfos[0].indices[1] = _ij0[1];
24227 vinfos[0].maxsolutions = _nj0;
24228 vinfos[1].jointtype = 1;
24229 vinfos[1].foffset = j1;
24230 vinfos[1].indices[0] = _ij1[0];
24231 vinfos[1].indices[1] = _ij1[1];
24232 vinfos[1].maxsolutions = _nj1;
24233 vinfos[2].jointtype = 1;
24234 vinfos[2].foffset = j2;
24235 vinfos[2].indices[0] = _ij2[0];
24236 vinfos[2].indices[1] = _ij2[1];
24237 vinfos[2].maxsolutions = _nj2;
24238 vinfos[3].jointtype = 1;
24239 vinfos[3].foffset = j3;
24240 vinfos[3].indices[0] = _ij3[0];
24241 vinfos[3].indices[1] = _ij3[1];
24242 vinfos[3].maxsolutions = _nj3;
24243 vinfos[4].jointtype = 1;
24244 vinfos[4].foffset = j4;
24245 vinfos[4].indices[0] = _ij4[0];
24246 vinfos[4].indices[1] = _ij4[1];
24247 vinfos[4].maxsolutions = _nj4;
24248 vinfos[5].jointtype = 1;
24249 vinfos[5].foffset = j5;
24250 vinfos[5].indices[0] = _ij5[0];
24251 vinfos[5].indices[1] = _ij5[1];
24252 vinfos[5].maxsolutions = _nj5;
24253 vinfos[6].jointtype = 1;
24254 vinfos[6].foffset = j6;
24255 vinfos[6].indices[0] = _ij6[0];
24256 vinfos[6].indices[1] = _ij6[1];
24257 vinfos[6].maxsolutions = _nj6;
24258 std::vector<int> vfree(0);
24259 solutions.AddSolution(vinfos,vfree);
24260 }
24261 }
24262 }
24263 
24264 } else
24265 {
24266 IkReal x7587=((IkReal(1.00000000000000))*(cj0));
24267 IkReal x7588=((cj4)*(sj6));
24268 IkReal x7589=((sj0)*(sj4));
24269 IkReal x7590=((cj5)*(sj6));
24270 IkReal x7591=((sj4)*(sj5));
24271 IkReal x7592=((r12)*(sj5));
24272 IkReal x7593=((IkReal(0.374290000000000))*(cj5));
24273 IkReal x7594=((r02)*(sj0));
24274 IkReal x7595=((r20)*(sj4));
24275 IkReal x7596=((IkReal(1.00000000000000))*(sj0));
24276 IkReal x7597=((IkReal(1.00000000000000))*(cj5));
24277 IkReal x7598=((cj0)*(r10));
24278 IkReal x7599=((cj4)*(cj6));
24279 IkReal x7600=((r00)*(sj0));
24280 IkReal x7601=((cj6)*(r21));
24281 IkReal x7602=((IkReal(0.374290000000000))*(sj5));
24282 IkReal x7603=((cj0)*(r00));
24283 IkReal x7604=((IkReal(0.0100000000000000))*(sj5));
24284 IkReal x7605=((cj0)*(r02));
24285 IkReal x7606=((cj5)*(sj4));
24286 IkReal x7607=((cj6)*(r01));
24287 IkReal x7608=((cj6)*(r11));
24288 IkReal x7609=((r01)*(sj0));
24289 IkReal x7610=((r10)*(sj0));
24290 IkReal x7611=((IkReal(0.0100000000000000))*(cj5)*(cj6));
24291 IkReal x7612=((sj6)*(x7602));
24292 IkReal x7613=((cj0)*(cj6)*(x7602));
24293 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
24294 evalcond[1]=((((sj5)*(x7601)))+(((IkReal(-1.00000000000000))*(r22)*(x7597)))+(((r20)*(sj5)*(sj6))));
24295 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x7599)))+(((x7601)*(x7606)))+(((r21)*(x7588)))+(((r22)*(x7591)))+(((x7590)*(x7595))));
24296 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x7601)))+(((x7601)*(x7602)))+(((IkReal(-0.0100000000000000))*(r20)*(x7590)))+(((IkReal(-1.00000000000000))*(r22)*(x7604)))+(pz)+(((r20)*(x7612)))+(((IkReal(-1.00000000000000))*(r22)*(x7593))));
24297 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x7599)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x7595)))+(((cj5)*(r20)*(x7588))));
24298 evalcond[5]=((((cj5)*(x7589)*(x7607)))+(((IkReal(-1.00000000000000))*(r11)*(x7587)*(x7588)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7587)*(x7590)))+(((IkReal(-1.00000000000000))*(r12)*(x7587)*(x7591)))+(((r02)*(sj5)*(x7589)))+(((x7588)*(x7609)))+(((IkReal(-1.00000000000000))*(x7587)*(x7606)*(x7608)))+(((x7598)*(x7599)))+(((r00)*(x7589)*(x7590)))+(((IkReal(-1.00000000000000))*(r00)*(x7596)*(x7599))));
24299 evalcond[6]=((((x7599)*(x7603)))+(((IkReal(-1.00000000000000))*(r01)*(x7587)*(x7588)))+(((IkReal(-1.00000000000000))*(r10)*(x7589)*(x7590)))+(((IkReal(-1.00000000000000))*(x7587)*(x7606)*(x7607)))+(((IkReal(-1.00000000000000))*(x7589)*(x7592)))+(((x7599)*(x7610)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7587)*(x7590)))+(((IkReal(-1.00000000000000))*(r11)*(x7588)*(x7596)))+(((IkReal(-1.00000000000000))*(r02)*(x7587)*(x7591)))+(((IkReal(-1.00000000000000))*(x7589)*(x7597)*(x7608))));
24300 evalcond[7]=((IkReal(-0.0690000000000000))+(((sj0)*(x7602)*(x7607)))+(((IkReal(-0.0100000000000000))*(x7590)*(x7600)))+(((IkReal(-1.00000000000000))*(py)*(x7587)))+(((IkReal(-1.00000000000000))*(x7594)*(x7604)))+(((IkReal(0.0100000000000000))*(cj0)*(x7592)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x7607)))+(((x7600)*(x7612)))+(((IkReal(0.0100000000000000))*(x7590)*(x7598)))+(((cj0)*(r12)*(x7593)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7608)))+(((IkReal(-1.00000000000000))*(cj0)*(x7602)*(x7608)))+(((IkReal(-1.00000000000000))*(x7598)*(x7612)))+(((IkReal(-1.00000000000000))*(x7593)*(x7594))));
24301 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(x7610)*(x7612)))+(((x7593)*(x7605)))+(((IkReal(-1.00000000000000))*(cj0)*(x7602)*(x7607)))+(((IkReal(0.0100000000000000))*(sj0)*(x7592)))+(((IkReal(-1.00000000000000))*(px)*(x7587)))+(((r12)*(sj0)*(x7593)))+(((IkReal(-1.00000000000000))*(x7603)*(x7612)))+(((IkReal(-1.00000000000000))*(sj0)*(x7602)*(x7608)))+(((IkReal(0.0100000000000000))*(x7590)*(x7603)))+(((IkReal(-1.00000000000000))*(py)*(x7596)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7607)))+(((IkReal(0.0100000000000000))*(x7590)*(x7610)))+(((x7604)*(x7605)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x7608))));
24302 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
24303 {
24304 {
24305 IkReal j3array[1], cj3array[1], sj3array[1];
24306 bool j3valid[1]={false};
24307 _nj3 = 1;
24308 IkReal x7614=((cj5)*(r02));
24309 IkReal x7615=((cj0)*(sj5));
24310 IkReal x7616=((r10)*(sj6));
24311 IkReal x7617=((IkReal(1.00000000000000))*(cj6));
24312 IkReal x7618=((sj0)*(sj5));
24313 IkReal x7619=((cj5)*(r12));
24314 IkReal x7620=((IkReal(1.00000000000000))*(r00)*(sj6));
24315 if( IKabs(((((IkReal(-1.00000000000000))*(r01)*(x7617)*(x7618)))+(((sj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7618)*(x7620)))+(((x7615)*(x7616)))+(((IkReal(-1.00000000000000))*(cj0)*(x7619)))+(((cj6)*(r11)*(x7615))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r01)*(x7615)*(x7617)))+(((IkReal(-1.00000000000000))*(x7615)*(x7620)))+(((sj0)*(x7619)))+(((cj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7616)*(x7618)))+(((IkReal(-1.00000000000000))*(r11)*(x7617)*(x7618))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x7617)*(x7618)))+(((sj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7618)*(x7620)))+(((x7615)*(x7616)))+(((IkReal(-1.00000000000000))*(cj0)*(x7619)))+(((cj6)*(r11)*(x7615)))))+IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x7615)*(x7617)))+(((IkReal(-1.00000000000000))*(x7615)*(x7620)))+(((sj0)*(x7619)))+(((cj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7616)*(x7618)))+(((IkReal(-1.00000000000000))*(r11)*(x7617)*(x7618)))))-1) <= IKFAST_SINCOS_THRESH )
24316     continue;
24317 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r01)*(x7617)*(x7618)))+(((sj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7618)*(x7620)))+(((x7615)*(x7616)))+(((IkReal(-1.00000000000000))*(cj0)*(x7619)))+(((cj6)*(r11)*(x7615)))), ((((IkReal(-1.00000000000000))*(r01)*(x7615)*(x7617)))+(((IkReal(-1.00000000000000))*(x7615)*(x7620)))+(((sj0)*(x7619)))+(((cj0)*(x7614)))+(((IkReal(-1.00000000000000))*(x7616)*(x7618)))+(((IkReal(-1.00000000000000))*(r11)*(x7617)*(x7618)))));
24318 sj3array[0]=IKsin(j3array[0]);
24319 cj3array[0]=IKcos(j3array[0]);
24320 if( j3array[0] > IKPI )
24321 {
24322     j3array[0]-=IK2PI;
24323 }
24324 else if( j3array[0] < -IKPI )
24325 {    j3array[0]+=IK2PI;
24326 }
24327 j3valid[0] = true;
24328 for(int ij3 = 0; ij3 < 1; ++ij3)
24329 {
24330 if( !j3valid[ij3] )
24331 {
24332     continue;
24333 }
24334 _ij3[0] = ij3; _ij3[1] = -1;
24335 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24336 {
24337 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24338 {
24339     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24340 }
24341 }
24342 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24343 {
24344 IkReal evalcond[4];
24345 IkReal x7621=IKsin(j3);
24346 IkReal x7622=((sj0)*(sj5));
24347 IkReal x7623=((r00)*(sj6));
24348 IkReal x7624=((IkReal(1.00000000000000))*(cj4));
24349 IkReal x7625=((cj6)*(sj0));
24350 IkReal x7626=((r00)*(sj4));
24351 IkReal x7627=((cj0)*(cj5));
24352 IkReal x7628=((cj6)*(r01));
24353 IkReal x7629=((cj5)*(sj0));
24354 IkReal x7630=((cj0)*(sj5));
24355 IkReal x7631=((cj6)*(r11));
24356 IkReal x7632=((r10)*(sj6));
24357 IkReal x7633=((r10)*(sj4));
24358 IkReal x7634=((IkReal(1.00000000000000))*(IKcos(j3)));
24359 IkReal x7635=((cj0)*(sj4)*(sj6));
24360 IkReal x7636=((sj0)*(sj4)*(sj6));
24361 IkReal x7637=((IkReal(1.00000000000000))*(cj0)*(cj6));
24362 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x7629)))+(((x7622)*(x7628)))+(((r12)*(x7627)))+(((x7622)*(x7623)))+(x7621)+(((IkReal(-1.00000000000000))*(x7630)*(x7631)))+(((IkReal(-1.00000000000000))*(x7630)*(x7632))));
24363 evalcond[1]=((((IkReal(-1.00000000000000))*(x7628)*(x7630)))+(((IkReal(-1.00000000000000))*(x7634)))+(((IkReal(-1.00000000000000))*(x7622)*(x7632)))+(((IkReal(-1.00000000000000))*(x7623)*(x7630)))+(((r12)*(x7629)))+(((IkReal(-1.00000000000000))*(x7622)*(x7631)))+(((r02)*(x7627))));
24364 evalcond[2]=((((IkReal(-1.00000000000000))*(x7624)*(x7627)*(x7632)))+(((IkReal(-1.00000000000000))*(x7624)*(x7627)*(x7631)))+(((cj4)*(r02)*(x7622)))+(((x7625)*(x7626)))+(((IkReal(-1.00000000000000))*(x7634)))+(((cj4)*(x7623)*(x7629)))+(((r11)*(x7635)))+(((IkReal(-1.00000000000000))*(r01)*(x7636)))+(((IkReal(-1.00000000000000))*(x7633)*(x7637)))+(((IkReal(-1.00000000000000))*(r12)*(x7624)*(x7630)))+(((cj4)*(cj5)*(r01)*(x7625))));
24365 evalcond[3]=((((r11)*(x7636)))+(((IkReal(-1.00000000000000))*(x7626)*(x7637)))+(((IkReal(-1.00000000000000))*(x7624)*(x7627)*(x7628)))+(((IkReal(-1.00000000000000))*(r02)*(x7624)*(x7630)))+(((IkReal(-1.00000000000000))*(x7625)*(x7633)))+(((r01)*(x7635)))+(((IkReal(-1.00000000000000))*(r12)*(x7622)*(x7624)))+(((IkReal(-1.00000000000000))*(x7624)*(x7629)*(x7632)))+(((IkReal(-1.00000000000000))*(x7621)))+(((IkReal(-1.00000000000000))*(x7623)*(x7624)*(x7627)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7624)*(x7625))));
24366 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
24367 {
24368 continue;
24369 }
24370 }
24371 
24372 {
24373 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24374 vinfos[0].jointtype = 1;
24375 vinfos[0].foffset = j0;
24376 vinfos[0].indices[0] = _ij0[0];
24377 vinfos[0].indices[1] = _ij0[1];
24378 vinfos[0].maxsolutions = _nj0;
24379 vinfos[1].jointtype = 1;
24380 vinfos[1].foffset = j1;
24381 vinfos[1].indices[0] = _ij1[0];
24382 vinfos[1].indices[1] = _ij1[1];
24383 vinfos[1].maxsolutions = _nj1;
24384 vinfos[2].jointtype = 1;
24385 vinfos[2].foffset = j2;
24386 vinfos[2].indices[0] = _ij2[0];
24387 vinfos[2].indices[1] = _ij2[1];
24388 vinfos[2].maxsolutions = _nj2;
24389 vinfos[3].jointtype = 1;
24390 vinfos[3].foffset = j3;
24391 vinfos[3].indices[0] = _ij3[0];
24392 vinfos[3].indices[1] = _ij3[1];
24393 vinfos[3].maxsolutions = _nj3;
24394 vinfos[4].jointtype = 1;
24395 vinfos[4].foffset = j4;
24396 vinfos[4].indices[0] = _ij4[0];
24397 vinfos[4].indices[1] = _ij4[1];
24398 vinfos[4].maxsolutions = _nj4;
24399 vinfos[5].jointtype = 1;
24400 vinfos[5].foffset = j5;
24401 vinfos[5].indices[0] = _ij5[0];
24402 vinfos[5].indices[1] = _ij5[1];
24403 vinfos[5].maxsolutions = _nj5;
24404 vinfos[6].jointtype = 1;
24405 vinfos[6].foffset = j6;
24406 vinfos[6].indices[0] = _ij6[0];
24407 vinfos[6].indices[1] = _ij6[1];
24408 vinfos[6].maxsolutions = _nj6;
24409 std::vector<int> vfree(0);
24410 solutions.AddSolution(vinfos,vfree);
24411 }
24412 }
24413 }
24414 
24415 } else
24416 {
24417 if( 1 )
24418 {
24419 continue;
24420 
24421 } else
24422 {
24423 }
24424 }
24425 }
24426 }
24427 }
24428 }
24429 
24430 } else
24431 {
24432 {
24433 IkReal j3array[1], cj3array[1], sj3array[1];
24434 bool j3valid[1]={false};
24435 _nj3 = 1;
24436 IkReal x7638=((cj0)*(cj5));
24437 IkReal x7639=((IkReal(1.00000000000000))*(cj0));
24438 IkReal x7640=((cj6)*(r11));
24439 IkReal x7641=((r10)*(sj6));
24440 IkReal x7642=((cj5)*(sj0));
24441 IkReal x7643=((r00)*(sj5)*(sj6));
24442 IkReal x7644=((cj6)*(r01)*(sj5));
24443 IkReal x7645=((IkReal(1.00000000000000))*(sj0)*(sj5));
24444 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(x7642)))+(((sj0)*(x7644)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7640)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7641)))+(((r12)*(x7638)))+(((sj0)*(x7643))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r02)*(x7638)))+(((IkReal(-1.00000000000000))*(x7640)*(x7645)))+(((r12)*(x7642)))+(((IkReal(-1.00000000000000))*(x7639)*(x7643)))+(((IkReal(-1.00000000000000))*(x7639)*(x7644)))+(((IkReal(-1.00000000000000))*(x7641)*(x7645))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(x7642)))+(((sj0)*(x7644)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7640)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7641)))+(((r12)*(x7638)))+(((sj0)*(x7643)))))))+IKsqr(((((r02)*(x7638)))+(((IkReal(-1.00000000000000))*(x7640)*(x7645)))+(((r12)*(x7642)))+(((IkReal(-1.00000000000000))*(x7639)*(x7643)))+(((IkReal(-1.00000000000000))*(x7639)*(x7644)))+(((IkReal(-1.00000000000000))*(x7641)*(x7645)))))-1) <= IKFAST_SINCOS_THRESH )
24445     continue;
24446 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(x7642)))+(((sj0)*(x7644)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7640)))+(((IkReal(-1.00000000000000))*(sj5)*(x7639)*(x7641)))+(((r12)*(x7638)))+(((sj0)*(x7643)))))), ((((r02)*(x7638)))+(((IkReal(-1.00000000000000))*(x7640)*(x7645)))+(((r12)*(x7642)))+(((IkReal(-1.00000000000000))*(x7639)*(x7643)))+(((IkReal(-1.00000000000000))*(x7639)*(x7644)))+(((IkReal(-1.00000000000000))*(x7641)*(x7645)))));
24447 sj3array[0]=IKsin(j3array[0]);
24448 cj3array[0]=IKcos(j3array[0]);
24449 if( j3array[0] > IKPI )
24450 {
24451     j3array[0]-=IK2PI;
24452 }
24453 else if( j3array[0] < -IKPI )
24454 {    j3array[0]+=IK2PI;
24455 }
24456 j3valid[0] = true;
24457 for(int ij3 = 0; ij3 < 1; ++ij3)
24458 {
24459 if( !j3valid[ij3] )
24460 {
24461     continue;
24462 }
24463 _ij3[0] = ij3; _ij3[1] = -1;
24464 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24465 {
24466 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24467 {
24468     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24469 }
24470 }
24471 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24472 {
24473 IkReal evalcond[6];
24474 IkReal x7646=IKsin(j3);
24475 IkReal x7647=IKcos(j3);
24476 IkReal x7648=((sj0)*(sj5));
24477 IkReal x7649=((r00)*(sj6));
24478 IkReal x7650=((IkReal(1.00000000000000))*(cj4));
24479 IkReal x7651=((cj6)*(r01));
24480 IkReal x7652=((cj0)*(cj5));
24481 IkReal x7653=((cj5)*(sj0));
24482 IkReal x7654=((cj6)*(r11));
24483 IkReal x7655=((cj0)*(sj5));
24484 IkReal x7656=((cj6)*(sj4));
24485 IkReal x7657=((cj4)*(cj5));
24486 IkReal x7658=((cj6)*(r21));
24487 IkReal x7659=((r20)*(sj6));
24488 IkReal x7660=((r10)*(sj6));
24489 IkReal x7661=((IkReal(1.00000000000000))*(cj0));
24490 IkReal x7662=((IkReal(1.00000000000000))*(x7646));
24491 IkReal x7663=((cj0)*(sj4)*(sj6));
24492 IkReal x7664=((sj0)*(sj4)*(sj6));
24493 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x7662)))+(((sj5)*(x7659)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7658))));
24494 evalcond[1]=((((x7657)*(x7658)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x7657)*(x7659)))+(((r20)*(x7656)))+(((cj4)*(r22)*(sj5)))+(((cj2)*(x7647))));
24495 evalcond[2]=((((x7648)*(x7649)))+(((IkReal(-1.00000000000000))*(x7655)*(x7660)))+(((x7648)*(x7651)))+(((IkReal(-1.00000000000000))*(r02)*(x7653)))+(((r12)*(x7652)))+(((IkReal(-1.00000000000000))*(sj2)*(x7662)))+(((IkReal(-1.00000000000000))*(x7654)*(x7655))));
24496 evalcond[3]=((((IkReal(-1.00000000000000))*(x7647)))+(((IkReal(-1.00000000000000))*(x7648)*(x7654)))+(((IkReal(-1.00000000000000))*(x7648)*(x7660)))+(((r12)*(x7653)))+(((IkReal(-1.00000000000000))*(x7651)*(x7655)))+(((IkReal(-1.00000000000000))*(x7649)*(x7655)))+(((r02)*(x7652))));
24497 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x7650)*(x7655)))+(((r00)*(sj0)*(x7656)))+(((IkReal(-1.00000000000000))*(x7650)*(x7652)*(x7660)))+(((IkReal(-1.00000000000000))*(r01)*(x7664)))+(((cj4)*(r02)*(x7648)))+(((sj2)*(x7647)))+(((IkReal(-1.00000000000000))*(x7650)*(x7652)*(x7654)))+(((cj4)*(x7649)*(x7653)))+(((cj4)*(x7651)*(x7653)))+(((IkReal(-1.00000000000000))*(r10)*(x7656)*(x7661)))+(((r11)*(x7663))));
24498 evalcond[5]=((((r11)*(x7664)))+(((IkReal(-1.00000000000000))*(x7650)*(x7653)*(x7660)))+(((IkReal(-1.00000000000000))*(x7650)*(x7651)*(x7652)))+(((IkReal(-1.00000000000000))*(x7650)*(x7653)*(x7654)))+(((IkReal(-1.00000000000000))*(r12)*(x7648)*(x7650)))+(((r01)*(x7663)))+(((IkReal(-1.00000000000000))*(x7649)*(x7650)*(x7652)))+(((IkReal(-1.00000000000000))*(r02)*(x7650)*(x7655)))+(((IkReal(-1.00000000000000))*(x7662)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7656)))+(((IkReal(-1.00000000000000))*(r00)*(x7656)*(x7661))));
24499 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
24500 {
24501 continue;
24502 }
24503 }
24504 
24505 {
24506 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24507 vinfos[0].jointtype = 1;
24508 vinfos[0].foffset = j0;
24509 vinfos[0].indices[0] = _ij0[0];
24510 vinfos[0].indices[1] = _ij0[1];
24511 vinfos[0].maxsolutions = _nj0;
24512 vinfos[1].jointtype = 1;
24513 vinfos[1].foffset = j1;
24514 vinfos[1].indices[0] = _ij1[0];
24515 vinfos[1].indices[1] = _ij1[1];
24516 vinfos[1].maxsolutions = _nj1;
24517 vinfos[2].jointtype = 1;
24518 vinfos[2].foffset = j2;
24519 vinfos[2].indices[0] = _ij2[0];
24520 vinfos[2].indices[1] = _ij2[1];
24521 vinfos[2].maxsolutions = _nj2;
24522 vinfos[3].jointtype = 1;
24523 vinfos[3].foffset = j3;
24524 vinfos[3].indices[0] = _ij3[0];
24525 vinfos[3].indices[1] = _ij3[1];
24526 vinfos[3].maxsolutions = _nj3;
24527 vinfos[4].jointtype = 1;
24528 vinfos[4].foffset = j4;
24529 vinfos[4].indices[0] = _ij4[0];
24530 vinfos[4].indices[1] = _ij4[1];
24531 vinfos[4].maxsolutions = _nj4;
24532 vinfos[5].jointtype = 1;
24533 vinfos[5].foffset = j5;
24534 vinfos[5].indices[0] = _ij5[0];
24535 vinfos[5].indices[1] = _ij5[1];
24536 vinfos[5].maxsolutions = _nj5;
24537 vinfos[6].jointtype = 1;
24538 vinfos[6].foffset = j6;
24539 vinfos[6].indices[0] = _ij6[0];
24540 vinfos[6].indices[1] = _ij6[1];
24541 vinfos[6].maxsolutions = _nj6;
24542 std::vector<int> vfree(0);
24543 solutions.AddSolution(vinfos,vfree);
24544 }
24545 }
24546 }
24547 
24548 }
24549 
24550 }
24551 
24552 } else
24553 {
24554 {
24555 IkReal j3array[1], cj3array[1], sj3array[1];
24556 bool j3valid[1]={false};
24557 _nj3 = 1;
24558 IkReal x7665=((sj5)*(sj6));
24559 IkReal x7666=((IkReal(1.00000000000000))*(cj6)*(sj5));
24560 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x7665))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x7666)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7665)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7665)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x7666))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x7665)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x7666)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7665)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7665)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x7666)))))-1) <= IKFAST_SINCOS_THRESH )
24561     continue;
24562 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x7665)))))), ((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x7666)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7665)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7665)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x7666)))));
24563 sj3array[0]=IKsin(j3array[0]);
24564 cj3array[0]=IKcos(j3array[0]);
24565 if( j3array[0] > IKPI )
24566 {
24567     j3array[0]-=IK2PI;
24568 }
24569 else if( j3array[0] < -IKPI )
24570 {    j3array[0]+=IK2PI;
24571 }
24572 j3valid[0] = true;
24573 for(int ij3 = 0; ij3 < 1; ++ij3)
24574 {
24575 if( !j3valid[ij3] )
24576 {
24577     continue;
24578 }
24579 _ij3[0] = ij3; _ij3[1] = -1;
24580 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24581 {
24582 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24583 {
24584     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24585 }
24586 }
24587 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24588 {
24589 IkReal evalcond[6];
24590 IkReal x7667=IKsin(j3);
24591 IkReal x7668=IKcos(j3);
24592 IkReal x7669=((sj0)*(sj5));
24593 IkReal x7670=((r00)*(sj6));
24594 IkReal x7671=((IkReal(1.00000000000000))*(cj4));
24595 IkReal x7672=((cj6)*(r01));
24596 IkReal x7673=((cj0)*(cj5));
24597 IkReal x7674=((cj5)*(sj0));
24598 IkReal x7675=((cj6)*(r11));
24599 IkReal x7676=((cj0)*(sj5));
24600 IkReal x7677=((cj6)*(sj4));
24601 IkReal x7678=((cj4)*(cj5));
24602 IkReal x7679=((cj6)*(r21));
24603 IkReal x7680=((r20)*(sj6));
24604 IkReal x7681=((r10)*(sj6));
24605 IkReal x7682=((IkReal(1.00000000000000))*(cj0));
24606 IkReal x7683=((IkReal(1.00000000000000))*(x7667));
24607 IkReal x7684=((cj0)*(sj4)*(sj6));
24608 IkReal x7685=((sj0)*(sj4)*(sj6));
24609 evalcond[0]=((((sj5)*(x7679)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x7683)))+(((sj5)*(x7680))));
24610 evalcond[1]=((((r20)*(x7677)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x7668)))+(((cj4)*(r22)*(sj5)))+(((x7678)*(x7680)))+(((x7678)*(x7679))));
24611 evalcond[2]=((((x7669)*(x7672)))+(((IkReal(-1.00000000000000))*(x7675)*(x7676)))+(((IkReal(-1.00000000000000))*(r02)*(x7674)))+(((IkReal(-1.00000000000000))*(sj2)*(x7683)))+(((x7669)*(x7670)))+(((r12)*(x7673)))+(((IkReal(-1.00000000000000))*(x7676)*(x7681))));
24612 evalcond[3]=((((IkReal(-1.00000000000000))*(x7672)*(x7676)))+(((r12)*(x7674)))+(((IkReal(-1.00000000000000))*(x7670)*(x7676)))+(((IkReal(-1.00000000000000))*(x7669)*(x7681)))+(((IkReal(-1.00000000000000))*(x7669)*(x7675)))+(((IkReal(-1.00000000000000))*(x7668)))+(((r02)*(x7673))));
24613 evalcond[4]=((((IkReal(-1.00000000000000))*(x7671)*(x7673)*(x7681)))+(((IkReal(-1.00000000000000))*(r12)*(x7671)*(x7676)))+(((sj2)*(x7668)))+(((cj4)*(x7670)*(x7674)))+(((cj4)*(x7672)*(x7674)))+(((r00)*(sj0)*(x7677)))+(((IkReal(-1.00000000000000))*(r01)*(x7685)))+(((cj4)*(r02)*(x7669)))+(((r11)*(x7684)))+(((IkReal(-1.00000000000000))*(r10)*(x7677)*(x7682)))+(((IkReal(-1.00000000000000))*(x7671)*(x7673)*(x7675))));
24614 evalcond[5]=((((IkReal(-1.00000000000000))*(x7671)*(x7672)*(x7673)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7677)))+(((IkReal(-1.00000000000000))*(x7683)))+(((IkReal(-1.00000000000000))*(x7671)*(x7674)*(x7681)))+(((IkReal(-1.00000000000000))*(r02)*(x7671)*(x7676)))+(((IkReal(-1.00000000000000))*(x7671)*(x7674)*(x7675)))+(((IkReal(-1.00000000000000))*(x7670)*(x7671)*(x7673)))+(((IkReal(-1.00000000000000))*(r12)*(x7669)*(x7671)))+(((r01)*(x7684)))+(((IkReal(-1.00000000000000))*(r00)*(x7677)*(x7682)))+(((r11)*(x7685))));
24615 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
24616 {
24617 continue;
24618 }
24619 }
24620 
24621 {
24622 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24623 vinfos[0].jointtype = 1;
24624 vinfos[0].foffset = j0;
24625 vinfos[0].indices[0] = _ij0[0];
24626 vinfos[0].indices[1] = _ij0[1];
24627 vinfos[0].maxsolutions = _nj0;
24628 vinfos[1].jointtype = 1;
24629 vinfos[1].foffset = j1;
24630 vinfos[1].indices[0] = _ij1[0];
24631 vinfos[1].indices[1] = _ij1[1];
24632 vinfos[1].maxsolutions = _nj1;
24633 vinfos[2].jointtype = 1;
24634 vinfos[2].foffset = j2;
24635 vinfos[2].indices[0] = _ij2[0];
24636 vinfos[2].indices[1] = _ij2[1];
24637 vinfos[2].maxsolutions = _nj2;
24638 vinfos[3].jointtype = 1;
24639 vinfos[3].foffset = j3;
24640 vinfos[3].indices[0] = _ij3[0];
24641 vinfos[3].indices[1] = _ij3[1];
24642 vinfos[3].maxsolutions = _nj3;
24643 vinfos[4].jointtype = 1;
24644 vinfos[4].foffset = j4;
24645 vinfos[4].indices[0] = _ij4[0];
24646 vinfos[4].indices[1] = _ij4[1];
24647 vinfos[4].maxsolutions = _nj4;
24648 vinfos[5].jointtype = 1;
24649 vinfos[5].foffset = j5;
24650 vinfos[5].indices[0] = _ij5[0];
24651 vinfos[5].indices[1] = _ij5[1];
24652 vinfos[5].maxsolutions = _nj5;
24653 vinfos[6].jointtype = 1;
24654 vinfos[6].foffset = j6;
24655 vinfos[6].indices[0] = _ij6[0];
24656 vinfos[6].indices[1] = _ij6[1];
24657 vinfos[6].maxsolutions = _nj6;
24658 std::vector<int> vfree(0);
24659 solutions.AddSolution(vinfos,vfree);
24660 }
24661 }
24662 }
24663 
24664 }
24665 
24666 }
24667 
24668 } else
24669 {
24670 {
24671 IkReal j3array[1], cj3array[1], sj3array[1];
24672 bool j3valid[1]={false};
24673 _nj3 = 1;
24674 IkReal x7686=((IkReal(1.00000000000000))*(cj4));
24675 IkReal x7687=((cj6)*(r21));
24676 IkReal x7688=((r20)*(sj6));
24677 if( IKabs(((gconst9)*(((((sj5)*(x7687)))+(((sj5)*(x7688)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7686)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x7686)*(x7688)))+(((IkReal(-1.00000000000000))*(cj5)*(x7686)*(x7687)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
24678     continue;
24679 j3array[0]=IKatan2(((gconst9)*(((((sj5)*(x7687)))+(((sj5)*(x7688)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7686)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x7686)*(x7688)))+(((IkReal(-1.00000000000000))*(cj5)*(x7686)*(x7687)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
24680 sj3array[0]=IKsin(j3array[0]);
24681 cj3array[0]=IKcos(j3array[0]);
24682 if( j3array[0] > IKPI )
24683 {
24684     j3array[0]-=IK2PI;
24685 }
24686 else if( j3array[0] < -IKPI )
24687 {    j3array[0]+=IK2PI;
24688 }
24689 j3valid[0] = true;
24690 for(int ij3 = 0; ij3 < 1; ++ij3)
24691 {
24692 if( !j3valid[ij3] )
24693 {
24694     continue;
24695 }
24696 _ij3[0] = ij3; _ij3[1] = -1;
24697 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24698 {
24699 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24700 {
24701     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24702 }
24703 }
24704 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24705 {
24706 IkReal evalcond[6];
24707 IkReal x7689=IKsin(j3);
24708 IkReal x7690=IKcos(j3);
24709 IkReal x7691=((sj0)*(sj5));
24710 IkReal x7692=((r00)*(sj6));
24711 IkReal x7693=((IkReal(1.00000000000000))*(cj4));
24712 IkReal x7694=((cj6)*(r01));
24713 IkReal x7695=((cj0)*(cj5));
24714 IkReal x7696=((cj5)*(sj0));
24715 IkReal x7697=((cj6)*(r11));
24716 IkReal x7698=((cj0)*(sj5));
24717 IkReal x7699=((cj6)*(sj4));
24718 IkReal x7700=((cj4)*(cj5));
24719 IkReal x7701=((cj6)*(r21));
24720 IkReal x7702=((r20)*(sj6));
24721 IkReal x7703=((r10)*(sj6));
24722 IkReal x7704=((IkReal(1.00000000000000))*(cj0));
24723 IkReal x7705=((IkReal(1.00000000000000))*(x7689));
24724 IkReal x7706=((cj0)*(sj4)*(sj6));
24725 IkReal x7707=((sj0)*(sj4)*(sj6));
24726 evalcond[0]=((((sj5)*(x7702)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x7705)))+(((sj5)*(x7701))));
24727 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x7690)))+(((x7700)*(x7701)))+(((r20)*(x7699)))+(((cj4)*(r22)*(sj5)))+(((x7700)*(x7702))));
24728 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x7705)))+(((x7691)*(x7694)))+(((IkReal(-1.00000000000000))*(x7698)*(x7703)))+(((x7691)*(x7692)))+(((r12)*(x7695)))+(((IkReal(-1.00000000000000))*(r02)*(x7696)))+(((IkReal(-1.00000000000000))*(x7697)*(x7698))));
24729 evalcond[3]=((((IkReal(-1.00000000000000))*(x7694)*(x7698)))+(((r12)*(x7696)))+(((IkReal(-1.00000000000000))*(x7691)*(x7703)))+(((IkReal(-1.00000000000000))*(x7690)))+(((r02)*(x7695)))+(((IkReal(-1.00000000000000))*(x7691)*(x7697)))+(((IkReal(-1.00000000000000))*(x7692)*(x7698))));
24730 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x7707)))+(((IkReal(-1.00000000000000))*(x7693)*(x7695)*(x7703)))+(((r00)*(sj0)*(x7699)))+(((IkReal(-1.00000000000000))*(r10)*(x7699)*(x7704)))+(((IkReal(-1.00000000000000))*(r12)*(x7693)*(x7698)))+(((sj2)*(x7690)))+(((cj4)*(x7694)*(x7696)))+(((r11)*(x7706)))+(((IkReal(-1.00000000000000))*(x7693)*(x7695)*(x7697)))+(((cj4)*(x7692)*(x7696)))+(((cj4)*(r02)*(x7691))));
24731 evalcond[5]=((((r01)*(x7706)))+(((r11)*(x7707)))+(((IkReal(-1.00000000000000))*(x7705)))+(((IkReal(-1.00000000000000))*(x7693)*(x7696)*(x7703)))+(((IkReal(-1.00000000000000))*(r00)*(x7699)*(x7704)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7699)))+(((IkReal(-1.00000000000000))*(r02)*(x7693)*(x7698)))+(((IkReal(-1.00000000000000))*(x7693)*(x7696)*(x7697)))+(((IkReal(-1.00000000000000))*(r12)*(x7691)*(x7693)))+(((IkReal(-1.00000000000000))*(x7693)*(x7694)*(x7695)))+(((IkReal(-1.00000000000000))*(x7692)*(x7693)*(x7695))));
24732 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
24733 {
24734 continue;
24735 }
24736 }
24737 
24738 {
24739 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24740 vinfos[0].jointtype = 1;
24741 vinfos[0].foffset = j0;
24742 vinfos[0].indices[0] = _ij0[0];
24743 vinfos[0].indices[1] = _ij0[1];
24744 vinfos[0].maxsolutions = _nj0;
24745 vinfos[1].jointtype = 1;
24746 vinfos[1].foffset = j1;
24747 vinfos[1].indices[0] = _ij1[0];
24748 vinfos[1].indices[1] = _ij1[1];
24749 vinfos[1].maxsolutions = _nj1;
24750 vinfos[2].jointtype = 1;
24751 vinfos[2].foffset = j2;
24752 vinfos[2].indices[0] = _ij2[0];
24753 vinfos[2].indices[1] = _ij2[1];
24754 vinfos[2].maxsolutions = _nj2;
24755 vinfos[3].jointtype = 1;
24756 vinfos[3].foffset = j3;
24757 vinfos[3].indices[0] = _ij3[0];
24758 vinfos[3].indices[1] = _ij3[1];
24759 vinfos[3].maxsolutions = _nj3;
24760 vinfos[4].jointtype = 1;
24761 vinfos[4].foffset = j4;
24762 vinfos[4].indices[0] = _ij4[0];
24763 vinfos[4].indices[1] = _ij4[1];
24764 vinfos[4].maxsolutions = _nj4;
24765 vinfos[5].jointtype = 1;
24766 vinfos[5].foffset = j5;
24767 vinfos[5].indices[0] = _ij5[0];
24768 vinfos[5].indices[1] = _ij5[1];
24769 vinfos[5].maxsolutions = _nj5;
24770 vinfos[6].jointtype = 1;
24771 vinfos[6].foffset = j6;
24772 vinfos[6].indices[0] = _ij6[0];
24773 vinfos[6].indices[1] = _ij6[1];
24774 vinfos[6].maxsolutions = _nj6;
24775 std::vector<int> vfree(0);
24776 solutions.AddSolution(vinfos,vfree);
24777 }
24778 }
24779 }
24780 
24781 }
24782 
24783 }
24784 
24785 } else
24786 {
24787 IkReal x7708=((IkReal(1.00000000000000))*(cj0));
24788 IkReal x7709=((cj4)*(sj6));
24789 IkReal x7710=((sj0)*(sj4));
24790 IkReal x7711=((cj5)*(sj6));
24791 IkReal x7712=((sj4)*(sj5));
24792 IkReal x7713=((r12)*(sj5));
24793 IkReal x7714=((IkReal(0.374290000000000))*(cj5));
24794 IkReal x7715=((r02)*(sj0));
24795 IkReal x7716=((IkReal(1.00000000000000))*(sj0));
24796 IkReal x7717=((cj0)*(r10));
24797 IkReal x7718=((cj4)*(cj6));
24798 IkReal x7719=((r00)*(sj0));
24799 IkReal x7720=((cj6)*(r21));
24800 IkReal x7721=((IkReal(0.374290000000000))*(sj5));
24801 IkReal x7722=((cj0)*(r00));
24802 IkReal x7723=((IkReal(0.0100000000000000))*(sj5));
24803 IkReal x7724=((cj0)*(r02));
24804 IkReal x7725=((cj5)*(sj4));
24805 IkReal x7726=((cj6)*(r01));
24806 IkReal x7727=((cj6)*(r11));
24807 IkReal x7728=((r01)*(sj0));
24808 IkReal x7729=((r10)*(sj0));
24809 IkReal x7730=((IkReal(0.0100000000000000))*(cj5)*(cj6));
24810 IkReal x7731=((sj6)*(x7721));
24811 IkReal x7732=((cj0)*(cj6)*(x7721));
24812 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
24813 evalcond[1]=((sj2)+(((x7720)*(x7725)))+(((r20)*(sj4)*(x7711)))+(((IkReal(-1.00000000000000))*(r20)*(x7718)))+(((r22)*(x7712)))+(((r21)*(x7709))));
24814 evalcond[2]=((((IkReal(-0.0100000000000000))*(r20)*(x7711)))+(((IkReal(-0.0690000000000000))*(cj2)))+(((x7720)*(x7721)))+(((IkReal(-0.0100000000000000))*(cj5)*(x7720)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x7723)))+(((r20)*(x7731)))+(((IkReal(-1.00000000000000))*(r22)*(x7714))));
24815 evalcond[3]=((((x7709)*(x7728)))+(((IkReal(-1.00000000000000))*(r12)*(x7708)*(x7712)))+(((IkReal(-1.00000000000000))*(x7708)*(x7725)*(x7727)))+(cj2)+(((cj5)*(x7710)*(x7726)))+(((r00)*(x7710)*(x7711)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7708)*(x7711)))+(((x7717)*(x7718)))+(((r02)*(sj5)*(x7710)))+(((IkReal(-1.00000000000000))*(r11)*(x7708)*(x7709)))+(((IkReal(-1.00000000000000))*(r00)*(x7716)*(x7718))));
24816 evalcond[4]=((((IkReal(-1.00000000000000))*(x7708)*(x7725)*(x7726)))+(((IkReal(-1.00000000000000))*(r10)*(x7710)*(x7711)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7708)*(x7711)))+(((x7718)*(x7729)))+(((IkReal(-1.00000000000000))*(r02)*(x7708)*(x7712)))+(((IkReal(-1.00000000000000))*(r11)*(x7709)*(x7716)))+(((IkReal(-1.00000000000000))*(r01)*(x7708)*(x7709)))+(((x7718)*(x7722)))+(((IkReal(-1.00000000000000))*(x7710)*(x7713)))+(((IkReal(-1.00000000000000))*(cj5)*(x7710)*(x7727))));
24817 evalcond[5]=((((IkReal(0.0100000000000000))*(cj0)*(x7713)))+(((IkReal(-1.00000000000000))*(x7714)*(x7715)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x7726)))+(((IkReal(0.0100000000000000))*(x7711)*(x7717)))+(((IkReal(-1.00000000000000))*(x7717)*(x7731)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7727)))+(((x7719)*(x7731)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(py)*(x7708)))+(((IkReal(-1.00000000000000))*(x7715)*(x7723)))+(((IkReal(-1.00000000000000))*(cj0)*(x7721)*(x7727)))+(((cj0)*(r12)*(x7714)))+(((IkReal(-0.0100000000000000))*(x7711)*(x7719)))+(((px)*(sj0)))+(((sj0)*(x7721)*(x7726))));
24818 evalcond[6]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(x7722)*(x7731)))+(((IkReal(0.0100000000000000))*(x7711)*(x7729)))+(((IkReal(-1.00000000000000))*(py)*(x7716)))+(((IkReal(0.0100000000000000))*(x7711)*(x7722)))+(((IkReal(0.0100000000000000))*(sj0)*(x7713)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x7727)))+(((IkReal(-1.00000000000000))*(px)*(x7708)))+(((r12)*(sj0)*(x7714)))+(((IkReal(-1.00000000000000))*(cj0)*(x7721)*(x7726)))+(((IkReal(-1.00000000000000))*(sj0)*(x7721)*(x7727)))+(((x7723)*(x7724)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7726)))+(((IkReal(-1.00000000000000))*(x7729)*(x7731)))+(((x7714)*(x7724))));
24819 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
24820 {
24821 {
24822 IkReal dummyeval[1];
24823 IkReal gconst10;
24824 gconst10=IKsign(cj2);
24825 dummyeval[0]=cj2;
24826 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
24827 {
24828 {
24829 IkReal dummyeval[1];
24830 dummyeval[0]=cj2;
24831 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
24832 {
24833 {
24834 IkReal dummyeval[1];
24835 dummyeval[0]=sj2;
24836 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
24837 {
24838 {
24839 IkReal evalcond[9];
24840 IkReal x7733=((cj5)*(sj4));
24841 IkReal x7734=((IkReal(1.00000000000000))*(sj6));
24842 IkReal x7735=((r10)*(sj0));
24843 IkReal x7736=((sj4)*(sj5));
24844 IkReal x7737=((cj5)*(cj6));
24845 IkReal x7738=((r01)*(sj0));
24846 IkReal x7739=((IkReal(1.00000000000000))*(r02));
24847 IkReal x7740=((IkReal(0.374290000000000))*(cj0));
24848 IkReal x7741=((cj5)*(r12));
24849 IkReal x7742=((cj6)*(sj5));
24850 IkReal x7743=((cj0)*(r11));
24851 IkReal x7744=((cj5)*(sj0));
24852 IkReal x7745=((r20)*(sj6));
24853 IkReal x7746=((IkReal(1.00000000000000))*(sj0));
24854 IkReal x7747=((cj4)*(cj5));
24855 IkReal x7748=((IkReal(1.00000000000000))*(cj6));
24856 IkReal x7749=((IkReal(0.0100000000000000))*(sj5));
24857 IkReal x7750=((sj5)*(sj6));
24858 IkReal x7751=((cj0)*(r10));
24859 IkReal x7752=((cj4)*(cj6));
24860 IkReal x7753=((cj0)*(r01));
24861 IkReal x7754=((IkReal(1.00000000000000))*(cj4));
24862 IkReal x7755=((cj0)*(r00));
24863 IkReal x7756=((IkReal(0.374290000000000))*(sj0));
24864 IkReal x7757=((cj0)*(r12));
24865 IkReal x7758=((IkReal(0.374290000000000))*(sj5));
24866 IkReal x7759=((cj4)*(sj6));
24867 IkReal x7760=((IkReal(1.00000000000000))*(cj0));
24868 IkReal x7761=((r02)*(sj0));
24869 IkReal x7762=((IkReal(0.0100000000000000))*(cj5));
24870 IkReal x7763=((r11)*(sj0));
24871 IkReal x7764=((r00)*(sj0)*(sj6));
24872 IkReal x7765=((r00)*(x7752));
24873 IkReal x7766=((sj6)*(x7762));
24874 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
24875 evalcond[1]=((((r22)*(x7736)))+(((x7733)*(x7745)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7748)))+(((cj6)*(r21)*(x7733)))+(((r21)*(x7759))));
24876 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x7737)))+(((x7745)*(x7758)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x7749)))+(((IkReal(0.374290000000000))*(r21)*(x7742)))+(((IkReal(-1.00000000000000))*(x7745)*(x7762))));
24877 evalcond[3]=((((IkReal(-1.00000000000000))*(x7742)*(x7743)))+(((IkReal(-1.00000000000000))*(sj5)*(x7734)*(x7751)))+(((IkReal(-1.00000000000000))*(x7739)*(x7744)))+(((x7738)*(x7742)))+(((cj0)*(x7741)))+(((r00)*(sj0)*(x7750))));
24878 evalcond[4]=((IkReal(1.00000000000000))+(((x7736)*(x7761)))+(((IkReal(-1.00000000000000))*(x7733)*(x7734)*(x7751)))+(((IkReal(-1.00000000000000))*(x7736)*(x7757)))+(((x7733)*(x7764)))+(((x7751)*(x7752)))+(((cj6)*(x7733)*(x7738)))+(((IkReal(-1.00000000000000))*(x7733)*(x7743)*(x7748)))+(((IkReal(-1.00000000000000))*(cj4)*(x7734)*(x7743)))+(((x7738)*(x7759)))+(((IkReal(-1.00000000000000))*(x7746)*(x7765))));
24879 evalcond[5]=((((IkReal(-1.00000000000000))*(x7734)*(x7747)*(x7751)))+(((IkReal(-1.00000000000000))*(x7737)*(x7743)*(x7754)))+(((IkReal(-1.00000000000000))*(sj4)*(x7734)*(x7738)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(sj5)*(x7761)))+(((r00)*(x7744)*(x7759)))+(((IkReal(-1.00000000000000))*(sj5)*(x7754)*(x7757)))+(((sj4)*(sj6)*(x7743)))+(((IkReal(-1.00000000000000))*(sj4)*(x7748)*(x7751)))+(((cj4)*(x7737)*(x7738))));
24880 evalcond[6]=((((x7735)*(x7752)))+(((x7752)*(x7755)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7733)*(x7746)))+(((IkReal(-1.00000000000000))*(r12)*(x7736)*(x7746)))+(((IkReal(-1.00000000000000))*(x7733)*(x7734)*(x7755)))+(((IkReal(-1.00000000000000))*(cj4)*(x7734)*(x7753)))+(((IkReal(-1.00000000000000))*(cj4)*(x7734)*(x7763)))+(((IkReal(-1.00000000000000))*(cj0)*(x7736)*(x7739)))+(((IkReal(-1.00000000000000))*(x7733)*(x7734)*(x7735)))+(((IkReal(-1.00000000000000))*(x7733)*(x7748)*(x7753))));
24881 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x7740)*(x7742)))+(((IkReal(-0.374290000000000))*(r02)*(x7744)))+(((x7740)*(x7741)))+(((IkReal(0.0100000000000000))*(x7737)*(x7743)))+(((IkReal(-1.00000000000000))*(py)*(x7760)))+(((IkReal(-1.00000000000000))*(x7749)*(x7761)))+(((IkReal(0.374290000000000))*(x7738)*(x7742)))+(((IkReal(-1.00000000000000))*(r10)*(x7740)*(x7750)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7744)))+(((x7751)*(x7766)))+(((px)*(sj0)))+(((r00)*(x7750)*(x7756)))+(((x7749)*(x7757)))+(((IkReal(-0.0100000000000000))*(x7737)*(x7738))));
24882 evalcond[8]=((IkReal(-0.295420000000000))+(((r12)*(sj0)*(x7749)))+(((x7735)*(x7766)))+(((IkReal(0.0100000000000000))*(x7737)*(x7763)))+(((IkReal(-1.00000000000000))*(r11)*(x7742)*(x7756)))+(((x7741)*(x7756)))+(((IkReal(-1.00000000000000))*(r00)*(x7740)*(x7750)))+(((IkReal(-1.00000000000000))*(py)*(x7746)))+(((cj0)*(r02)*(x7749)))+(((IkReal(0.0100000000000000))*(x7737)*(x7753)))+(((IkReal(-0.374290000000000))*(x7735)*(x7750)))+(((IkReal(-1.00000000000000))*(px)*(x7760)))+(((x7755)*(x7766)))+(((cj5)*(r02)*(x7740)))+(((IkReal(-1.00000000000000))*(r01)*(x7740)*(x7742))));
24883 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
24884 {
24885 {
24886 IkReal j3array[1], cj3array[1], sj3array[1];
24887 bool j3valid[1]={false};
24888 _nj3 = 1;
24889 IkReal x7767=((IkReal(1.00000000000000))*(r21));
24890 IkReal x7768=((cj4)*(cj5));
24891 IkReal x7769=((r20)*(sj6));
24892 if( IKabs(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7767)))+(((IkReal(-1.00000000000000))*(sj5)*(x7769)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7767)))+(((x7768)*(x7769)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x7768))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7767)))+(((IkReal(-1.00000000000000))*(sj5)*(x7769)))+(((cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7767)))+(((x7768)*(x7769)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x7768)))))-1) <= IKFAST_SINCOS_THRESH )
24893     continue;
24894 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7767)))+(((IkReal(-1.00000000000000))*(sj5)*(x7769)))+(((cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7767)))+(((x7768)*(x7769)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x7768)))));
24895 sj3array[0]=IKsin(j3array[0]);
24896 cj3array[0]=IKcos(j3array[0]);
24897 if( j3array[0] > IKPI )
24898 {
24899     j3array[0]-=IK2PI;
24900 }
24901 else if( j3array[0] < -IKPI )
24902 {    j3array[0]+=IK2PI;
24903 }
24904 j3valid[0] = true;
24905 for(int ij3 = 0; ij3 < 1; ++ij3)
24906 {
24907 if( !j3valid[ij3] )
24908 {
24909     continue;
24910 }
24911 _ij3[0] = ij3; _ij3[1] = -1;
24912 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
24913 {
24914 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
24915 {
24916     j3valid[iij3]=false; _ij3[1] = iij3; break; 
24917 }
24918 }
24919 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
24920 {
24921 IkReal evalcond[4];
24922 IkReal x7770=IKcos(j3);
24923 IkReal x7771=IKsin(j3);
24924 IkReal x7772=((IkReal(1.00000000000000))*(cj4));
24925 IkReal x7773=((sj0)*(sj5));
24926 IkReal x7774=((cj0)*(cj5));
24927 IkReal x7775=((cj6)*(r01));
24928 IkReal x7776=((r00)*(sj6));
24929 IkReal x7777=((cj6)*(r11));
24930 IkReal x7778=((cj5)*(sj0));
24931 IkReal x7779=((cj6)*(sj4));
24932 IkReal x7780=((sj4)*(sj6));
24933 IkReal x7781=((cj4)*(cj5));
24934 IkReal x7782=((cj6)*(r21));
24935 IkReal x7783=((r20)*(sj6));
24936 IkReal x7784=((r10)*(sj6));
24937 IkReal x7785=((IkReal(1.00000000000000))*(cj0)*(sj5));
24938 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x7771)+(((sj5)*(x7782)))+(((sj5)*(x7783))));
24939 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x7780)))+(((x7781)*(x7782)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x7779)))+(((IkReal(-1.00000000000000))*(x7770)))+(((x7781)*(x7783))));
24940 evalcond[2]=((((IkReal(-1.00000000000000))*(x7773)*(x7777)))+(((IkReal(-1.00000000000000))*(x7773)*(x7784)))+(((IkReal(-1.00000000000000))*(x7776)*(x7785)))+(((IkReal(-1.00000000000000))*(x7775)*(x7785)))+(x7770)+(((r12)*(x7778)))+(((r02)*(x7774))));
24941 evalcond[3]=((((IkReal(-1.00000000000000))*(x7772)*(x7778)*(x7784)))+(((IkReal(-1.00000000000000))*(x7772)*(x7774)*(x7776)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7779)))+(((IkReal(-1.00000000000000))*(x7772)*(x7774)*(x7775)))+(((r11)*(sj0)*(x7780)))+(x7771)+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7779)))+(((cj0)*(r01)*(x7780)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7772)))+(((IkReal(-1.00000000000000))*(r12)*(x7772)*(x7773)))+(((IkReal(-1.00000000000000))*(x7772)*(x7777)*(x7778))));
24942 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
24943 {
24944 continue;
24945 }
24946 }
24947 
24948 {
24949 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
24950 vinfos[0].jointtype = 1;
24951 vinfos[0].foffset = j0;
24952 vinfos[0].indices[0] = _ij0[0];
24953 vinfos[0].indices[1] = _ij0[1];
24954 vinfos[0].maxsolutions = _nj0;
24955 vinfos[1].jointtype = 1;
24956 vinfos[1].foffset = j1;
24957 vinfos[1].indices[0] = _ij1[0];
24958 vinfos[1].indices[1] = _ij1[1];
24959 vinfos[1].maxsolutions = _nj1;
24960 vinfos[2].jointtype = 1;
24961 vinfos[2].foffset = j2;
24962 vinfos[2].indices[0] = _ij2[0];
24963 vinfos[2].indices[1] = _ij2[1];
24964 vinfos[2].maxsolutions = _nj2;
24965 vinfos[3].jointtype = 1;
24966 vinfos[3].foffset = j3;
24967 vinfos[3].indices[0] = _ij3[0];
24968 vinfos[3].indices[1] = _ij3[1];
24969 vinfos[3].maxsolutions = _nj3;
24970 vinfos[4].jointtype = 1;
24971 vinfos[4].foffset = j4;
24972 vinfos[4].indices[0] = _ij4[0];
24973 vinfos[4].indices[1] = _ij4[1];
24974 vinfos[4].maxsolutions = _nj4;
24975 vinfos[5].jointtype = 1;
24976 vinfos[5].foffset = j5;
24977 vinfos[5].indices[0] = _ij5[0];
24978 vinfos[5].indices[1] = _ij5[1];
24979 vinfos[5].maxsolutions = _nj5;
24980 vinfos[6].jointtype = 1;
24981 vinfos[6].foffset = j6;
24982 vinfos[6].indices[0] = _ij6[0];
24983 vinfos[6].indices[1] = _ij6[1];
24984 vinfos[6].maxsolutions = _nj6;
24985 std::vector<int> vfree(0);
24986 solutions.AddSolution(vinfos,vfree);
24987 }
24988 }
24989 }
24990 
24991 } else
24992 {
24993 IkReal x7786=((cj5)*(sj4));
24994 IkReal x7787=((IkReal(1.00000000000000))*(sj6));
24995 IkReal x7788=((r10)*(sj0));
24996 IkReal x7789=((sj4)*(sj5));
24997 IkReal x7790=((cj5)*(cj6));
24998 IkReal x7791=((r01)*(sj0));
24999 IkReal x7792=((IkReal(1.00000000000000))*(r02));
25000 IkReal x7793=((IkReal(0.374290000000000))*(cj0));
25001 IkReal x7794=((cj5)*(r12));
25002 IkReal x7795=((cj6)*(sj5));
25003 IkReal x7796=((cj0)*(r11));
25004 IkReal x7797=((cj5)*(sj0));
25005 IkReal x7798=((r20)*(sj6));
25006 IkReal x7799=((IkReal(1.00000000000000))*(sj0));
25007 IkReal x7800=((cj4)*(cj5));
25008 IkReal x7801=((IkReal(1.00000000000000))*(cj6));
25009 IkReal x7802=((IkReal(0.0100000000000000))*(sj5));
25010 IkReal x7803=((sj5)*(sj6));
25011 IkReal x7804=((cj0)*(r10));
25012 IkReal x7805=((cj4)*(cj6));
25013 IkReal x7806=((cj0)*(r01));
25014 IkReal x7807=((IkReal(1.00000000000000))*(cj4));
25015 IkReal x7808=((cj0)*(r00));
25016 IkReal x7809=((IkReal(0.374290000000000))*(sj0));
25017 IkReal x7810=((cj0)*(r12));
25018 IkReal x7811=((IkReal(0.374290000000000))*(sj5));
25019 IkReal x7812=((cj4)*(sj6));
25020 IkReal x7813=((IkReal(1.00000000000000))*(cj0));
25021 IkReal x7814=((r02)*(sj0));
25022 IkReal x7815=((IkReal(0.0100000000000000))*(cj5));
25023 IkReal x7816=((r11)*(sj0));
25024 IkReal x7817=((r00)*(sj0)*(sj6));
25025 IkReal x7818=((r00)*(x7805));
25026 IkReal x7819=((sj6)*(x7815));
25027 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
25028 evalcond[1]=((((r21)*(x7812)))+(((x7786)*(x7798)))+(((cj6)*(r21)*(x7786)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x7801)))+(((r22)*(x7789))));
25029 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x7802)))+(((IkReal(0.374290000000000))*(r21)*(x7795)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x7798)*(x7811)))+(pz)+(((IkReal(-0.0100000000000000))*(r21)*(x7790)))+(((IkReal(-1.00000000000000))*(x7798)*(x7815))));
25030 evalcond[3]=((((r00)*(sj0)*(x7803)))+(((x7791)*(x7795)))+(((cj0)*(x7794)))+(((IkReal(-1.00000000000000))*(x7792)*(x7797)))+(((IkReal(-1.00000000000000))*(x7795)*(x7796)))+(((IkReal(-1.00000000000000))*(sj5)*(x7787)*(x7804))));
25031 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x7789)*(x7810)))+(((x7786)*(x7817)))+(((cj6)*(x7786)*(x7791)))+(((IkReal(-1.00000000000000))*(x7786)*(x7787)*(x7804)))+(((x7789)*(x7814)))+(((x7791)*(x7812)))+(((IkReal(-1.00000000000000))*(x7799)*(x7818)))+(((IkReal(-1.00000000000000))*(x7786)*(x7796)*(x7801)))+(((x7804)*(x7805)))+(((IkReal(-1.00000000000000))*(cj4)*(x7787)*(x7796))));
25032 evalcond[5]=((((IkReal(-1.00000000000000))*(x7790)*(x7796)*(x7807)))+(((r00)*(x7797)*(x7812)))+(((sj4)*(sj6)*(x7796)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x7787)*(x7800)*(x7804)))+(((IkReal(-1.00000000000000))*(sj5)*(x7807)*(x7810)))+(((IkReal(-1.00000000000000))*(sj4)*(x7787)*(x7791)))+(((cj4)*(x7790)*(x7791)))+(((IkReal(-1.00000000000000))*(sj4)*(x7801)*(x7804)))+(((cj4)*(sj5)*(x7814))));
25033 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x7787)*(x7806)))+(((IkReal(-1.00000000000000))*(cj4)*(x7787)*(x7816)))+(((x7805)*(x7808)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x7786)*(x7799)))+(((IkReal(-1.00000000000000))*(x7786)*(x7787)*(x7788)))+(((x7788)*(x7805)))+(((IkReal(-1.00000000000000))*(cj0)*(x7789)*(x7792)))+(((IkReal(-1.00000000000000))*(x7786)*(x7787)*(x7808)))+(((IkReal(-1.00000000000000))*(x7786)*(x7801)*(x7806)))+(((IkReal(-1.00000000000000))*(r12)*(x7789)*(x7799))));
25034 evalcond[7]=((((r00)*(x7803)*(x7809)))+(((IkReal(-0.0100000000000000))*(x7790)*(x7791)))+(((IkReal(-1.00000000000000))*(x7802)*(x7814)))+(((x7793)*(x7794)))+(((IkReal(-1.00000000000000))*(py)*(x7813)))+(((x7804)*(x7819)))+(((IkReal(-0.374290000000000))*(r02)*(x7797)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x7797)))+(((IkReal(0.0100000000000000))*(x7790)*(x7796)))+(((IkReal(0.374290000000000))*(x7791)*(x7795)))+(((IkReal(-1.00000000000000))*(r10)*(x7793)*(x7803)))+(((x7802)*(x7810)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x7793)*(x7795))));
25035 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(py)*(x7799)))+(((cj5)*(r02)*(x7793)))+(((cj0)*(r02)*(x7802)))+(((r12)*(sj0)*(x7802)))+(((x7788)*(x7819)))+(((x7794)*(x7809)))+(((IkReal(-1.00000000000000))*(r11)*(x7795)*(x7809)))+(((IkReal(-0.374290000000000))*(x7788)*(x7803)))+(((x7808)*(x7819)))+(((IkReal(-1.00000000000000))*(px)*(x7813)))+(((IkReal(-1.00000000000000))*(r01)*(x7793)*(x7795)))+(((IkReal(0.0100000000000000))*(x7790)*(x7806)))+(((IkReal(0.0100000000000000))*(x7790)*(x7816)))+(((IkReal(-1.00000000000000))*(r00)*(x7793)*(x7803))));
25036 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
25037 {
25038 {
25039 IkReal j3array[1], cj3array[1], sj3array[1];
25040 bool j3valid[1]={false};
25041 _nj3 = 1;
25042 IkReal x7820=((IkReal(1.00000000000000))*(cj4));
25043 IkReal x7821=((cj6)*(r21));
25044 IkReal x7822=((r20)*(sj6));
25045 if( IKabs(((((sj5)*(x7821)))+(((sj5)*(x7822)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7822)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7820)))+(((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7821)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x7821)))+(((sj5)*(x7822)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7822)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7820)))+(((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7821)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
25046     continue;
25047 j3array[0]=IKatan2(((((sj5)*(x7821)))+(((sj5)*(x7822)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7822)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x7820)))+(((IkReal(-1.00000000000000))*(cj5)*(x7820)*(x7821)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
25048 sj3array[0]=IKsin(j3array[0]);
25049 cj3array[0]=IKcos(j3array[0]);
25050 if( j3array[0] > IKPI )
25051 {
25052     j3array[0]-=IK2PI;
25053 }
25054 else if( j3array[0] < -IKPI )
25055 {    j3array[0]+=IK2PI;
25056 }
25057 j3valid[0] = true;
25058 for(int ij3 = 0; ij3 < 1; ++ij3)
25059 {
25060 if( !j3valid[ij3] )
25061 {
25062     continue;
25063 }
25064 _ij3[0] = ij3; _ij3[1] = -1;
25065 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25066 {
25067 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25068 {
25069     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25070 }
25071 }
25072 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25073 {
25074 IkReal evalcond[4];
25075 IkReal x7823=IKcos(j3);
25076 IkReal x7824=IKsin(j3);
25077 IkReal x7825=((IkReal(1.00000000000000))*(cj4));
25078 IkReal x7826=((sj0)*(sj5));
25079 IkReal x7827=((cj0)*(cj5));
25080 IkReal x7828=((cj6)*(r01));
25081 IkReal x7829=((r00)*(sj6));
25082 IkReal x7830=((cj6)*(r11));
25083 IkReal x7831=((cj5)*(sj0));
25084 IkReal x7832=((cj6)*(sj4));
25085 IkReal x7833=((sj4)*(sj6));
25086 IkReal x7834=((cj4)*(cj5));
25087 IkReal x7835=((cj6)*(r21));
25088 IkReal x7836=((r20)*(sj6));
25089 IkReal x7837=((r10)*(sj6));
25090 IkReal x7838=((IkReal(1.00000000000000))*(cj0)*(sj5));
25091 evalcond[0]=((((sj5)*(x7836)))+(((sj5)*(x7835)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x7824))));
25092 evalcond[1]=((x7823)+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x7833)))+(((x7834)*(x7836)))+(((x7834)*(x7835)))+(((r20)*(x7832))));
25093 evalcond[2]=((((IkReal(-1.00000000000000))*(x7829)*(x7838)))+(((IkReal(-1.00000000000000))*(x7828)*(x7838)))+(((IkReal(-1.00000000000000))*(x7826)*(x7830)))+(x7823)+(((IkReal(-1.00000000000000))*(x7826)*(x7837)))+(((r12)*(x7831)))+(((r02)*(x7827))));
25094 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r00)*(x7832)))+(((IkReal(-1.00000000000000))*(r12)*(x7825)*(x7826)))+(x7824)+(((r11)*(sj0)*(x7833)))+(((IkReal(-1.00000000000000))*(x7825)*(x7827)*(x7829)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x7825)))+(((IkReal(-1.00000000000000))*(x7825)*(x7831)*(x7837)))+(((IkReal(-1.00000000000000))*(x7825)*(x7827)*(x7828)))+(((cj0)*(r01)*(x7833)))+(((IkReal(-1.00000000000000))*(x7825)*(x7830)*(x7831)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7832))));
25095 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
25096 {
25097 continue;
25098 }
25099 }
25100 
25101 {
25102 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25103 vinfos[0].jointtype = 1;
25104 vinfos[0].foffset = j0;
25105 vinfos[0].indices[0] = _ij0[0];
25106 vinfos[0].indices[1] = _ij0[1];
25107 vinfos[0].maxsolutions = _nj0;
25108 vinfos[1].jointtype = 1;
25109 vinfos[1].foffset = j1;
25110 vinfos[1].indices[0] = _ij1[0];
25111 vinfos[1].indices[1] = _ij1[1];
25112 vinfos[1].maxsolutions = _nj1;
25113 vinfos[2].jointtype = 1;
25114 vinfos[2].foffset = j2;
25115 vinfos[2].indices[0] = _ij2[0];
25116 vinfos[2].indices[1] = _ij2[1];
25117 vinfos[2].maxsolutions = _nj2;
25118 vinfos[3].jointtype = 1;
25119 vinfos[3].foffset = j3;
25120 vinfos[3].indices[0] = _ij3[0];
25121 vinfos[3].indices[1] = _ij3[1];
25122 vinfos[3].maxsolutions = _nj3;
25123 vinfos[4].jointtype = 1;
25124 vinfos[4].foffset = j4;
25125 vinfos[4].indices[0] = _ij4[0];
25126 vinfos[4].indices[1] = _ij4[1];
25127 vinfos[4].maxsolutions = _nj4;
25128 vinfos[5].jointtype = 1;
25129 vinfos[5].foffset = j5;
25130 vinfos[5].indices[0] = _ij5[0];
25131 vinfos[5].indices[1] = _ij5[1];
25132 vinfos[5].maxsolutions = _nj5;
25133 vinfos[6].jointtype = 1;
25134 vinfos[6].foffset = j6;
25135 vinfos[6].indices[0] = _ij6[0];
25136 vinfos[6].indices[1] = _ij6[1];
25137 vinfos[6].maxsolutions = _nj6;
25138 std::vector<int> vfree(0);
25139 solutions.AddSolution(vinfos,vfree);
25140 }
25141 }
25142 }
25143 
25144 } else
25145 {
25146 IkReal x7839=((IkReal(1.00000000000000))*(cj0));
25147 IkReal x7840=((cj4)*(sj6));
25148 IkReal x7841=((sj0)*(sj4));
25149 IkReal x7842=((cj5)*(sj6));
25150 IkReal x7843=((sj4)*(sj5));
25151 IkReal x7844=((r12)*(sj5));
25152 IkReal x7845=((IkReal(0.374290000000000))*(cj5));
25153 IkReal x7846=((r02)*(sj0));
25154 IkReal x7847=((r20)*(sj4));
25155 IkReal x7848=((IkReal(1.00000000000000))*(sj0));
25156 IkReal x7849=((IkReal(1.00000000000000))*(cj5));
25157 IkReal x7850=((cj0)*(r10));
25158 IkReal x7851=((cj4)*(cj6));
25159 IkReal x7852=((r00)*(sj0));
25160 IkReal x7853=((cj6)*(r21));
25161 IkReal x7854=((IkReal(0.374290000000000))*(sj5));
25162 IkReal x7855=((cj0)*(r00));
25163 IkReal x7856=((IkReal(0.0100000000000000))*(sj5));
25164 IkReal x7857=((cj0)*(r02));
25165 IkReal x7858=((cj5)*(sj4));
25166 IkReal x7859=((cj6)*(r01));
25167 IkReal x7860=((cj6)*(r11));
25168 IkReal x7861=((r01)*(sj0));
25169 IkReal x7862=((r10)*(sj0));
25170 IkReal x7863=((IkReal(0.0100000000000000))*(cj5)*(cj6));
25171 IkReal x7864=((sj6)*(x7854));
25172 IkReal x7865=((cj0)*(cj6)*(x7854));
25173 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
25174 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x7849)))+(((sj5)*(x7853)))+(((r20)*(sj5)*(sj6))));
25175 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x7851)))+(((x7842)*(x7847)))+(((r22)*(x7843)))+(((r21)*(x7840)))+(((x7853)*(x7858))));
25176 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x7845)))+(((IkReal(-0.0100000000000000))*(cj5)*(x7853)))+(((IkReal(-0.0100000000000000))*(r20)*(x7842)))+(((r20)*(x7864)))+(((x7853)*(x7854)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x7856))));
25177 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x7847)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x7840)))+(((cj5)*(r21)*(x7851))));
25178 evalcond[5]=((((r02)*(sj5)*(x7841)))+(((IkReal(-1.00000000000000))*(r00)*(x7848)*(x7851)))+(((IkReal(-1.00000000000000))*(r11)*(x7839)*(x7840)))+(((IkReal(-1.00000000000000))*(r12)*(x7839)*(x7843)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7839)*(x7842)))+(((IkReal(-1.00000000000000))*(x7839)*(x7858)*(x7860)))+(((cj5)*(x7841)*(x7859)))+(((r00)*(x7841)*(x7842)))+(((x7840)*(x7861)))+(((x7850)*(x7851))));
25179 evalcond[6]=((((x7851)*(x7862)))+(((IkReal(-1.00000000000000))*(x7841)*(x7849)*(x7860)))+(((IkReal(-1.00000000000000))*(x7841)*(x7844)))+(((IkReal(-1.00000000000000))*(r10)*(x7841)*(x7842)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7839)*(x7842)))+(((IkReal(-1.00000000000000))*(r02)*(x7839)*(x7843)))+(((IkReal(-1.00000000000000))*(r11)*(x7840)*(x7848)))+(((IkReal(-1.00000000000000))*(x7839)*(x7858)*(x7859)))+(((x7851)*(x7855)))+(((IkReal(-1.00000000000000))*(r01)*(x7839)*(x7840))));
25180 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(x7842)*(x7850)))+(((x7852)*(x7864)))+(((IkReal(-1.00000000000000))*(py)*(x7839)))+(((IkReal(0.0100000000000000))*(cj0)*(x7844)))+(((IkReal(-1.00000000000000))*(x7850)*(x7864)))+(((sj0)*(x7854)*(x7859)))+(((cj0)*(r12)*(x7845)))+(((IkReal(-0.0100000000000000))*(x7842)*(x7852)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7860)))+(((IkReal(-1.00000000000000))*(x7845)*(x7846)))+(((IkReal(-1.00000000000000))*(cj0)*(x7854)*(x7860)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x7846)*(x7856)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x7859))));
25181 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x7854)*(x7860)))+(((IkReal(0.0100000000000000))*(sj0)*(x7844)))+(((IkReal(-1.00000000000000))*(x7862)*(x7864)))+(((x7845)*(x7857)))+(((IkReal(-1.00000000000000))*(px)*(x7839)))+(((IkReal(-1.00000000000000))*(py)*(x7848)))+(((IkReal(-1.00000000000000))*(cj0)*(x7854)*(x7859)))+(((r12)*(sj0)*(x7845)))+(((x7856)*(x7857)))+(((IkReal(-1.00000000000000))*(x7855)*(x7864)))+(((IkReal(0.0100000000000000))*(x7842)*(x7862)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x7860)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7859)))+(((IkReal(0.0100000000000000))*(x7842)*(x7855))));
25182 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
25183 {
25184 {
25185 IkReal j3array[1], cj3array[1], sj3array[1];
25186 bool j3valid[1]={false};
25187 _nj3 = 1;
25188 IkReal x7866=((sj0)*(sj5));
25189 IkReal x7867=((r00)*(sj6));
25190 IkReal x7868=((IkReal(1.00000000000000))*(cj5));
25191 IkReal x7869=((cj6)*(r11));
25192 IkReal x7870=((cj6)*(r01));
25193 IkReal x7871=((r10)*(sj6));
25194 IkReal x7872=((cj0)*(sj5));
25195 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7868)))+(((x7866)*(x7867)))+(((x7866)*(x7870)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x7869)*(x7872)))+(((IkReal(-1.00000000000000))*(x7871)*(x7872))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x7867)*(x7872)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7868)))+(((x7866)*(x7871)))+(((x7866)*(x7869)))+(((x7870)*(x7872)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7868))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7868)))+(((x7866)*(x7867)))+(((x7866)*(x7870)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x7869)*(x7872)))+(((IkReal(-1.00000000000000))*(x7871)*(x7872)))))+IKsqr(((((x7867)*(x7872)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7868)))+(((x7866)*(x7871)))+(((x7866)*(x7869)))+(((x7870)*(x7872)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7868)))))-1) <= IKFAST_SINCOS_THRESH )
25196     continue;
25197 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7868)))+(((x7866)*(x7867)))+(((x7866)*(x7870)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x7869)*(x7872)))+(((IkReal(-1.00000000000000))*(x7871)*(x7872)))), ((((x7867)*(x7872)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7868)))+(((x7866)*(x7871)))+(((x7866)*(x7869)))+(((x7870)*(x7872)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7868)))));
25198 sj3array[0]=IKsin(j3array[0]);
25199 cj3array[0]=IKcos(j3array[0]);
25200 if( j3array[0] > IKPI )
25201 {
25202     j3array[0]-=IK2PI;
25203 }
25204 else if( j3array[0] < -IKPI )
25205 {    j3array[0]+=IK2PI;
25206 }
25207 j3valid[0] = true;
25208 for(int ij3 = 0; ij3 < 1; ++ij3)
25209 {
25210 if( !j3valid[ij3] )
25211 {
25212     continue;
25213 }
25214 _ij3[0] = ij3; _ij3[1] = -1;
25215 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25216 {
25217 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25218 {
25219     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25220 }
25221 }
25222 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25223 {
25224 IkReal evalcond[4];
25225 IkReal x7873=IKcos(j3);
25226 IkReal x7874=IKsin(j3);
25227 IkReal x7875=((sj0)*(sj5));
25228 IkReal x7876=((r00)*(sj6));
25229 IkReal x7877=((cj6)*(sj0));
25230 IkReal x7878=((IkReal(1.00000000000000))*(cj4));
25231 IkReal x7879=((r00)*(sj4));
25232 IkReal x7880=((cj0)*(cj5));
25233 IkReal x7881=((cj5)*(sj0));
25234 IkReal x7882=((cj6)*(r11));
25235 IkReal x7883=((r10)*(sj6));
25236 IkReal x7884=((cj0)*(sj5));
25237 IkReal x7885=((r10)*(sj4));
25238 IkReal x7886=((cj4)*(cj5)*(r01));
25239 IkReal x7887=((IkReal(1.00000000000000))*(cj0)*(cj6));
25240 IkReal x7888=((cj0)*(sj4)*(sj6));
25241 IkReal x7889=((sj0)*(sj4)*(sj6));
25242 evalcond[0]=((((x7875)*(x7876)))+(((r12)*(x7880)))+(((cj6)*(r01)*(x7875)))+(((IkReal(-1.00000000000000))*(r02)*(x7881)))+(((IkReal(-1.00000000000000))*(x7883)*(x7884)))+(((IkReal(-1.00000000000000))*(x7874)))+(((IkReal(-1.00000000000000))*(x7882)*(x7884))));
25243 evalcond[1]=((((IkReal(-1.00000000000000))*(x7875)*(x7883)))+(((IkReal(-1.00000000000000))*(x7876)*(x7884)))+(((r02)*(x7880)))+(((r12)*(x7881)))+(((IkReal(-1.00000000000000))*(x7875)*(x7882)))+(x7873)+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x7884))));
25244 evalcond[2]=((((cj4)*(r02)*(x7875)))+(((IkReal(-1.00000000000000))*(x7885)*(x7887)))+(((r11)*(x7888)))+(((IkReal(-1.00000000000000))*(r01)*(x7889)))+(((IkReal(-1.00000000000000))*(r12)*(x7878)*(x7884)))+(((IkReal(-1.00000000000000))*(x7878)*(x7880)*(x7883)))+(x7873)+(((cj4)*(x7876)*(x7881)))+(((IkReal(-1.00000000000000))*(x7878)*(x7880)*(x7882)))+(((x7877)*(x7879)))+(((x7877)*(x7886))));
25245 evalcond[3]=((((IkReal(-1.00000000000000))*(x7877)*(x7885)))+(((r11)*(x7889)))+(((IkReal(-1.00000000000000))*(x7879)*(x7887)))+(((IkReal(-1.00000000000000))*(r12)*(x7875)*(x7878)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x7878)*(x7880)))+(x7874)+(((IkReal(-1.00000000000000))*(r02)*(x7878)*(x7884)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7877)*(x7878)))+(((IkReal(-1.00000000000000))*(x7878)*(x7881)*(x7883)))+(((IkReal(-1.00000000000000))*(x7876)*(x7878)*(x7880)))+(((r01)*(x7888))));
25246 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
25247 {
25248 continue;
25249 }
25250 }
25251 
25252 {
25253 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25254 vinfos[0].jointtype = 1;
25255 vinfos[0].foffset = j0;
25256 vinfos[0].indices[0] = _ij0[0];
25257 vinfos[0].indices[1] = _ij0[1];
25258 vinfos[0].maxsolutions = _nj0;
25259 vinfos[1].jointtype = 1;
25260 vinfos[1].foffset = j1;
25261 vinfos[1].indices[0] = _ij1[0];
25262 vinfos[1].indices[1] = _ij1[1];
25263 vinfos[1].maxsolutions = _nj1;
25264 vinfos[2].jointtype = 1;
25265 vinfos[2].foffset = j2;
25266 vinfos[2].indices[0] = _ij2[0];
25267 vinfos[2].indices[1] = _ij2[1];
25268 vinfos[2].maxsolutions = _nj2;
25269 vinfos[3].jointtype = 1;
25270 vinfos[3].foffset = j3;
25271 vinfos[3].indices[0] = _ij3[0];
25272 vinfos[3].indices[1] = _ij3[1];
25273 vinfos[3].maxsolutions = _nj3;
25274 vinfos[4].jointtype = 1;
25275 vinfos[4].foffset = j4;
25276 vinfos[4].indices[0] = _ij4[0];
25277 vinfos[4].indices[1] = _ij4[1];
25278 vinfos[4].maxsolutions = _nj4;
25279 vinfos[5].jointtype = 1;
25280 vinfos[5].foffset = j5;
25281 vinfos[5].indices[0] = _ij5[0];
25282 vinfos[5].indices[1] = _ij5[1];
25283 vinfos[5].maxsolutions = _nj5;
25284 vinfos[6].jointtype = 1;
25285 vinfos[6].foffset = j6;
25286 vinfos[6].indices[0] = _ij6[0];
25287 vinfos[6].indices[1] = _ij6[1];
25288 vinfos[6].maxsolutions = _nj6;
25289 std::vector<int> vfree(0);
25290 solutions.AddSolution(vinfos,vfree);
25291 }
25292 }
25293 }
25294 
25295 } else
25296 {
25297 IkReal x7890=((IkReal(1.00000000000000))*(cj0));
25298 IkReal x7891=((cj4)*(sj6));
25299 IkReal x7892=((sj0)*(sj4));
25300 IkReal x7893=((cj5)*(sj6));
25301 IkReal x7894=((sj4)*(sj5));
25302 IkReal x7895=((r12)*(sj5));
25303 IkReal x7896=((IkReal(0.374290000000000))*(cj5));
25304 IkReal x7897=((r02)*(sj0));
25305 IkReal x7898=((r20)*(sj4));
25306 IkReal x7899=((IkReal(1.00000000000000))*(sj0));
25307 IkReal x7900=((IkReal(1.00000000000000))*(cj5));
25308 IkReal x7901=((cj0)*(r10));
25309 IkReal x7902=((cj4)*(cj6));
25310 IkReal x7903=((r00)*(sj0));
25311 IkReal x7904=((cj6)*(r21));
25312 IkReal x7905=((IkReal(0.374290000000000))*(sj5));
25313 IkReal x7906=((cj0)*(r00));
25314 IkReal x7907=((IkReal(0.0100000000000000))*(sj5));
25315 IkReal x7908=((cj0)*(r02));
25316 IkReal x7909=((cj5)*(sj4));
25317 IkReal x7910=((cj6)*(r01));
25318 IkReal x7911=((cj6)*(r11));
25319 IkReal x7912=((r01)*(sj0));
25320 IkReal x7913=((r10)*(sj0));
25321 IkReal x7914=((IkReal(0.0100000000000000))*(cj5)*(cj6));
25322 IkReal x7915=((sj6)*(x7905));
25323 IkReal x7916=((cj0)*(cj6)*(x7905));
25324 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
25325 evalcond[1]=((((sj5)*(x7904)))+(((IkReal(-1.00000000000000))*(r22)*(x7900)))+(((r20)*(sj5)*(sj6))));
25326 evalcond[2]=((IkReal(-1.00000000000000))+(((r21)*(x7891)))+(((x7904)*(x7909)))+(((x7893)*(x7898)))+(((r22)*(x7894)))+(((IkReal(-1.00000000000000))*(r20)*(x7902))));
25327 evalcond[3]=((((x7904)*(x7905)))+(((IkReal(-0.0100000000000000))*(cj5)*(x7904)))+(((IkReal(-1.00000000000000))*(r22)*(x7896)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x7893)))+(((r20)*(x7915)))+(((IkReal(-1.00000000000000))*(r22)*(x7907))));
25328 evalcond[4]=((((cj5)*(r20)*(x7891)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x7902)))+(((cj6)*(x7898))));
25329 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x7890)*(x7894)))+(((cj5)*(x7892)*(x7910)))+(((r02)*(sj5)*(x7892)))+(((IkReal(-1.00000000000000))*(r00)*(x7899)*(x7902)))+(((IkReal(-1.00000000000000))*(r11)*(x7890)*(x7891)))+(((x7901)*(x7902)))+(((r00)*(x7892)*(x7893)))+(((IkReal(-1.00000000000000))*(x7890)*(x7909)*(x7911)))+(((x7891)*(x7912)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x7890)*(x7893))));
25330 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x7890)*(x7891)))+(((IkReal(-1.00000000000000))*(x7892)*(x7900)*(x7911)))+(((IkReal(-1.00000000000000))*(r10)*(x7892)*(x7893)))+(((IkReal(-1.00000000000000))*(r11)*(x7891)*(x7899)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x7890)*(x7893)))+(((IkReal(-1.00000000000000))*(x7890)*(x7909)*(x7910)))+(((IkReal(-1.00000000000000))*(r02)*(x7890)*(x7894)))+(((x7902)*(x7906)))+(((x7902)*(x7913)))+(((IkReal(-1.00000000000000))*(x7892)*(x7895))));
25331 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-0.0100000000000000))*(x7893)*(x7903)))+(((IkReal(-1.00000000000000))*(x7897)*(x7907)))+(((IkReal(-1.00000000000000))*(x7896)*(x7897)))+(((cj0)*(r12)*(x7896)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x7910)))+(((IkReal(0.0100000000000000))*(x7893)*(x7901)))+(((IkReal(-1.00000000000000))*(py)*(x7890)))+(((IkReal(-1.00000000000000))*(x7901)*(x7915)))+(((IkReal(-1.00000000000000))*(cj0)*(x7905)*(x7911)))+(((sj0)*(x7905)*(x7910)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7911)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(x7895)))+(((x7903)*(x7915))));
25332 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x7905)*(x7911)))+(((IkReal(-1.00000000000000))*(py)*(x7899)))+(((IkReal(-1.00000000000000))*(x7906)*(x7915)))+(((IkReal(-1.00000000000000))*(cj0)*(x7905)*(x7910)))+(((IkReal(-1.00000000000000))*(x7913)*(x7915)))+(((x7907)*(x7908)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x7910)))+(((IkReal(-1.00000000000000))*(px)*(x7890)))+(((x7896)*(x7908)))+(((IkReal(0.0100000000000000))*(x7893)*(x7913)))+(((IkReal(0.0100000000000000))*(x7893)*(x7906)))+(((IkReal(0.0100000000000000))*(sj0)*(x7895)))+(((r12)*(sj0)*(x7896)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x7911))));
25333 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
25334 {
25335 {
25336 IkReal j3array[1], cj3array[1], sj3array[1];
25337 bool j3valid[1]={false};
25338 _nj3 = 1;
25339 IkReal x7917=((IkReal(1.00000000000000))*(cj5));
25340 IkReal x7918=((r10)*(sj5)*(sj6));
25341 IkReal x7919=((cj6)*(sj0)*(sj5));
25342 IkReal x7920=((r00)*(sj5)*(sj6));
25343 IkReal x7921=((cj0)*(cj6)*(sj5));
25344 if( IKabs(((((IkReal(-1.00000000000000))*(sj0)*(x7920)))+(((r11)*(x7921)))+(((cj0)*(x7918)))+(((IkReal(-1.00000000000000))*(r01)*(x7919)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7917))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(x7920)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7917)))+(((r01)*(x7921)))+(((r11)*(x7919)))+(((sj0)*(x7918)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7917))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj0)*(x7920)))+(((r11)*(x7921)))+(((cj0)*(x7918)))+(((IkReal(-1.00000000000000))*(r01)*(x7919)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7917)))))+IKsqr(((((cj0)*(x7920)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7917)))+(((r01)*(x7921)))+(((r11)*(x7919)))+(((sj0)*(x7918)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7917)))))-1) <= IKFAST_SINCOS_THRESH )
25345     continue;
25346 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj0)*(x7920)))+(((r11)*(x7921)))+(((cj0)*(x7918)))+(((IkReal(-1.00000000000000))*(r01)*(x7919)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x7917)))), ((((cj0)*(x7920)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7917)))+(((r01)*(x7921)))+(((r11)*(x7919)))+(((sj0)*(x7918)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7917)))));
25347 sj3array[0]=IKsin(j3array[0]);
25348 cj3array[0]=IKcos(j3array[0]);
25349 if( j3array[0] > IKPI )
25350 {
25351     j3array[0]-=IK2PI;
25352 }
25353 else if( j3array[0] < -IKPI )
25354 {    j3array[0]+=IK2PI;
25355 }
25356 j3valid[0] = true;
25357 for(int ij3 = 0; ij3 < 1; ++ij3)
25358 {
25359 if( !j3valid[ij3] )
25360 {
25361     continue;
25362 }
25363 _ij3[0] = ij3; _ij3[1] = -1;
25364 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25365 {
25366 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25367 {
25368     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25369 }
25370 }
25371 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25372 {
25373 IkReal evalcond[4];
25374 IkReal x7922=IKcos(j3);
25375 IkReal x7923=IKsin(j3);
25376 IkReal x7924=((sj0)*(sj5));
25377 IkReal x7925=((r00)*(sj6));
25378 IkReal x7926=((IkReal(1.00000000000000))*(cj4));
25379 IkReal x7927=((cj6)*(sj0));
25380 IkReal x7928=((r00)*(sj4));
25381 IkReal x7929=((cj0)*(cj5));
25382 IkReal x7930=((cj6)*(r01));
25383 IkReal x7931=((cj5)*(sj0));
25384 IkReal x7932=((cj0)*(sj5));
25385 IkReal x7933=((cj6)*(r11));
25386 IkReal x7934=((r10)*(sj6));
25387 IkReal x7935=((r10)*(sj4));
25388 IkReal x7936=((cj0)*(sj4)*(sj6));
25389 IkReal x7937=((sj0)*(sj4)*(sj6));
25390 IkReal x7938=((IkReal(1.00000000000000))*(cj0)*(cj6));
25391 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x7931)))+(((x7924)*(x7930)))+(((IkReal(-1.00000000000000))*(x7932)*(x7934)))+(((r12)*(x7929)))+(((x7924)*(x7925)))+(x7923)+(((IkReal(-1.00000000000000))*(x7932)*(x7933))));
25392 evalcond[1]=((((IkReal(-1.00000000000000))*(x7924)*(x7934)))+(((r02)*(x7929)))+(((r12)*(x7931)))+(((IkReal(-1.00000000000000))*(x7925)*(x7932)))+(((IkReal(-1.00000000000000))*(x7924)*(x7933)))+(((IkReal(-1.00000000000000))*(x7930)*(x7932)))+(x7922));
25393 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x7926)*(x7932)))+(((IkReal(-1.00000000000000))*(x7926)*(x7929)*(x7933)))+(((cj4)*(r02)*(x7924)))+(((IkReal(-1.00000000000000))*(x7935)*(x7938)))+(((x7927)*(x7928)))+(((IkReal(-1.00000000000000))*(r01)*(x7937)))+(((cj4)*(x7925)*(x7931)))+(((IkReal(-1.00000000000000))*(x7922)))+(((r11)*(x7936)))+(((cj4)*(cj5)*(r01)*(x7927)))+(((IkReal(-1.00000000000000))*(x7926)*(x7929)*(x7934))));
25394 evalcond[3]=((((IkReal(-1.00000000000000))*(x7927)*(x7935)))+(((IkReal(-1.00000000000000))*(r12)*(x7924)*(x7926)))+(((r11)*(x7937)))+(((IkReal(-1.00000000000000))*(x7926)*(x7929)*(x7930)))+(((r01)*(x7936)))+(((IkReal(-1.00000000000000))*(r02)*(x7926)*(x7932)))+(((IkReal(-1.00000000000000))*(x7925)*(x7926)*(x7929)))+(x7923)+(((IkReal(-1.00000000000000))*(x7928)*(x7938)))+(((IkReal(-1.00000000000000))*(x7926)*(x7931)*(x7934)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x7926)*(x7927))));
25395 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
25396 {
25397 continue;
25398 }
25399 }
25400 
25401 {
25402 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25403 vinfos[0].jointtype = 1;
25404 vinfos[0].foffset = j0;
25405 vinfos[0].indices[0] = _ij0[0];
25406 vinfos[0].indices[1] = _ij0[1];
25407 vinfos[0].maxsolutions = _nj0;
25408 vinfos[1].jointtype = 1;
25409 vinfos[1].foffset = j1;
25410 vinfos[1].indices[0] = _ij1[0];
25411 vinfos[1].indices[1] = _ij1[1];
25412 vinfos[1].maxsolutions = _nj1;
25413 vinfos[2].jointtype = 1;
25414 vinfos[2].foffset = j2;
25415 vinfos[2].indices[0] = _ij2[0];
25416 vinfos[2].indices[1] = _ij2[1];
25417 vinfos[2].maxsolutions = _nj2;
25418 vinfos[3].jointtype = 1;
25419 vinfos[3].foffset = j3;
25420 vinfos[3].indices[0] = _ij3[0];
25421 vinfos[3].indices[1] = _ij3[1];
25422 vinfos[3].maxsolutions = _nj3;
25423 vinfos[4].jointtype = 1;
25424 vinfos[4].foffset = j4;
25425 vinfos[4].indices[0] = _ij4[0];
25426 vinfos[4].indices[1] = _ij4[1];
25427 vinfos[4].maxsolutions = _nj4;
25428 vinfos[5].jointtype = 1;
25429 vinfos[5].foffset = j5;
25430 vinfos[5].indices[0] = _ij5[0];
25431 vinfos[5].indices[1] = _ij5[1];
25432 vinfos[5].maxsolutions = _nj5;
25433 vinfos[6].jointtype = 1;
25434 vinfos[6].foffset = j6;
25435 vinfos[6].indices[0] = _ij6[0];
25436 vinfos[6].indices[1] = _ij6[1];
25437 vinfos[6].maxsolutions = _nj6;
25438 std::vector<int> vfree(0);
25439 solutions.AddSolution(vinfos,vfree);
25440 }
25441 }
25442 }
25443 
25444 } else
25445 {
25446 if( 1 )
25447 {
25448 continue;
25449 
25450 } else
25451 {
25452 }
25453 }
25454 }
25455 }
25456 }
25457 }
25458 
25459 } else
25460 {
25461 {
25462 IkReal j3array[1], cj3array[1], sj3array[1];
25463 bool j3valid[1]={false};
25464 _nj3 = 1;
25465 IkReal x7939=((sj0)*(sj5));
25466 IkReal x7940=((r00)*(sj6));
25467 IkReal x7941=((IkReal(1.00000000000000))*(cj5));
25468 IkReal x7942=((cj6)*(r11));
25469 IkReal x7943=((cj6)*(r01));
25470 IkReal x7944=((cj0)*(sj5));
25471 IkReal x7945=((r10)*(sj6));
25472 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x7942)*(x7944)))+(((x7939)*(x7943)))+(((cj0)*(cj5)*(r12)))+(((x7939)*(x7940)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7941)))+(((IkReal(-1.00000000000000))*(x7944)*(x7945))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7941)))+(((x7939)*(x7942)))+(((x7943)*(x7944)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7941)))+(((x7940)*(x7944)))+(((x7939)*(x7945))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x7942)*(x7944)))+(((x7939)*(x7943)))+(((cj0)*(cj5)*(r12)))+(((x7939)*(x7940)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7941)))+(((IkReal(-1.00000000000000))*(x7944)*(x7945)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7941)))+(((x7939)*(x7942)))+(((x7943)*(x7944)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7941)))+(((x7940)*(x7944)))+(((x7939)*(x7945)))))-1) <= IKFAST_SINCOS_THRESH )
25473     continue;
25474 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x7942)*(x7944)))+(((x7939)*(x7943)))+(((cj0)*(cj5)*(r12)))+(((x7939)*(x7940)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x7941)))+(((IkReal(-1.00000000000000))*(x7944)*(x7945)))))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7941)))+(((x7939)*(x7942)))+(((x7943)*(x7944)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7941)))+(((x7940)*(x7944)))+(((x7939)*(x7945)))));
25475 sj3array[0]=IKsin(j3array[0]);
25476 cj3array[0]=IKcos(j3array[0]);
25477 if( j3array[0] > IKPI )
25478 {
25479     j3array[0]-=IK2PI;
25480 }
25481 else if( j3array[0] < -IKPI )
25482 {    j3array[0]+=IK2PI;
25483 }
25484 j3valid[0] = true;
25485 for(int ij3 = 0; ij3 < 1; ++ij3)
25486 {
25487 if( !j3valid[ij3] )
25488 {
25489     continue;
25490 }
25491 _ij3[0] = ij3; _ij3[1] = -1;
25492 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25493 {
25494 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25495 {
25496     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25497 }
25498 }
25499 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25500 {
25501 IkReal evalcond[6];
25502 IkReal x7946=IKsin(j3);
25503 IkReal x7947=IKcos(j3);
25504 IkReal x7948=((sj0)*(sj5));
25505 IkReal x7949=((r00)*(sj6));
25506 IkReal x7950=((IkReal(1.00000000000000))*(cj4));
25507 IkReal x7951=((cj6)*(r01));
25508 IkReal x7952=((cj0)*(cj5));
25509 IkReal x7953=((cj5)*(sj0));
25510 IkReal x7954=((cj6)*(r11));
25511 IkReal x7955=((cj6)*(sj4));
25512 IkReal x7956=((cj0)*(sj5));
25513 IkReal x7957=((cj4)*(cj5));
25514 IkReal x7958=((cj6)*(r21));
25515 IkReal x7959=((r20)*(sj6));
25516 IkReal x7960=((r10)*(sj6));
25517 IkReal x7961=((IkReal(1.00000000000000))*(cj0));
25518 IkReal x7962=((cj0)*(sj4)*(sj6));
25519 IkReal x7963=((sj0)*(sj4)*(sj6));
25520 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7959)))+(((cj2)*(x7946)))+(((sj5)*(x7958))));
25521 evalcond[1]=((((r20)*(x7955)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x7947)))+(((x7957)*(x7959)))+(((x7957)*(x7958))));
25522 evalcond[2]=((((IkReal(-1.00000000000000))*(x7956)*(x7960)))+(((x7948)*(x7951)))+(((IkReal(-1.00000000000000))*(x7954)*(x7956)))+(((IkReal(-1.00000000000000))*(sj2)*(x7946)))+(((r12)*(x7952)))+(((x7948)*(x7949)))+(((IkReal(-1.00000000000000))*(r02)*(x7953))));
25523 evalcond[3]=((((r12)*(x7953)))+(x7947)+(((IkReal(-1.00000000000000))*(x7951)*(x7956)))+(((IkReal(-1.00000000000000))*(x7949)*(x7956)))+(((r02)*(x7952)))+(((IkReal(-1.00000000000000))*(x7948)*(x7960)))+(((IkReal(-1.00000000000000))*(x7948)*(x7954))));
25524 evalcond[4]=((((cj4)*(r02)*(x7948)))+(((IkReal(-1.00000000000000))*(x7950)*(x7952)*(x7954)))+(((r00)*(sj0)*(x7955)))+(((IkReal(-1.00000000000000))*(r10)*(x7955)*(x7961)))+(((r11)*(x7962)))+(((sj2)*(x7947)))+(((IkReal(-1.00000000000000))*(r12)*(x7950)*(x7956)))+(((IkReal(-1.00000000000000))*(x7950)*(x7952)*(x7960)))+(((cj4)*(x7951)*(x7953)))+(((IkReal(-1.00000000000000))*(r01)*(x7963)))+(((cj4)*(x7949)*(x7953))));
25525 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x7955)*(x7961)))+(((r01)*(x7962)))+(x7946)+(((IkReal(-1.00000000000000))*(x7950)*(x7953)*(x7954)))+(((IkReal(-1.00000000000000))*(r02)*(x7950)*(x7956)))+(((IkReal(-1.00000000000000))*(x7950)*(x7953)*(x7960)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7955)))+(((r11)*(x7963)))+(((IkReal(-1.00000000000000))*(x7949)*(x7950)*(x7952)))+(((IkReal(-1.00000000000000))*(r12)*(x7948)*(x7950)))+(((IkReal(-1.00000000000000))*(x7950)*(x7951)*(x7952))));
25526 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
25527 {
25528 continue;
25529 }
25530 }
25531 
25532 {
25533 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25534 vinfos[0].jointtype = 1;
25535 vinfos[0].foffset = j0;
25536 vinfos[0].indices[0] = _ij0[0];
25537 vinfos[0].indices[1] = _ij0[1];
25538 vinfos[0].maxsolutions = _nj0;
25539 vinfos[1].jointtype = 1;
25540 vinfos[1].foffset = j1;
25541 vinfos[1].indices[0] = _ij1[0];
25542 vinfos[1].indices[1] = _ij1[1];
25543 vinfos[1].maxsolutions = _nj1;
25544 vinfos[2].jointtype = 1;
25545 vinfos[2].foffset = j2;
25546 vinfos[2].indices[0] = _ij2[0];
25547 vinfos[2].indices[1] = _ij2[1];
25548 vinfos[2].maxsolutions = _nj2;
25549 vinfos[3].jointtype = 1;
25550 vinfos[3].foffset = j3;
25551 vinfos[3].indices[0] = _ij3[0];
25552 vinfos[3].indices[1] = _ij3[1];
25553 vinfos[3].maxsolutions = _nj3;
25554 vinfos[4].jointtype = 1;
25555 vinfos[4].foffset = j4;
25556 vinfos[4].indices[0] = _ij4[0];
25557 vinfos[4].indices[1] = _ij4[1];
25558 vinfos[4].maxsolutions = _nj4;
25559 vinfos[5].jointtype = 1;
25560 vinfos[5].foffset = j5;
25561 vinfos[5].indices[0] = _ij5[0];
25562 vinfos[5].indices[1] = _ij5[1];
25563 vinfos[5].maxsolutions = _nj5;
25564 vinfos[6].jointtype = 1;
25565 vinfos[6].foffset = j6;
25566 vinfos[6].indices[0] = _ij6[0];
25567 vinfos[6].indices[1] = _ij6[1];
25568 vinfos[6].maxsolutions = _nj6;
25569 std::vector<int> vfree(0);
25570 solutions.AddSolution(vinfos,vfree);
25571 }
25572 }
25573 }
25574 
25575 }
25576 
25577 }
25578 
25579 } else
25580 {
25581 {
25582 IkReal j3array[1], cj3array[1], sj3array[1];
25583 bool j3valid[1]={false};
25584 _nj3 = 1;
25585 IkReal x7964=((cj6)*(sj5));
25586 IkReal x7965=((IkReal(1.00000000000000))*(cj5));
25587 IkReal x7966=((sj5)*(sj6));
25588 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x7966)))+(((IkReal(-1.00000000000000))*(r21)*(x7964)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7965)))+(((r11)*(sj0)*(x7964)))+(((cj0)*(r01)*(x7964)))+(((cj0)*(r00)*(x7966)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7965)))+(((r10)*(sj0)*(x7966))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x7966)))+(((IkReal(-1.00000000000000))*(r21)*(x7964)))+(((cj5)*(r22)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7965)))+(((r11)*(sj0)*(x7964)))+(((cj0)*(r01)*(x7964)))+(((cj0)*(r00)*(x7966)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7965)))+(((r10)*(sj0)*(x7966)))))-1) <= IKFAST_SINCOS_THRESH )
25589     continue;
25590 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x7966)))+(((IkReal(-1.00000000000000))*(r21)*(x7964)))+(((cj5)*(r22)))))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x7965)))+(((r11)*(sj0)*(x7964)))+(((cj0)*(r01)*(x7964)))+(((cj0)*(r00)*(x7966)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x7965)))+(((r10)*(sj0)*(x7966)))));
25591 sj3array[0]=IKsin(j3array[0]);
25592 cj3array[0]=IKcos(j3array[0]);
25593 if( j3array[0] > IKPI )
25594 {
25595     j3array[0]-=IK2PI;
25596 }
25597 else if( j3array[0] < -IKPI )
25598 {    j3array[0]+=IK2PI;
25599 }
25600 j3valid[0] = true;
25601 for(int ij3 = 0; ij3 < 1; ++ij3)
25602 {
25603 if( !j3valid[ij3] )
25604 {
25605     continue;
25606 }
25607 _ij3[0] = ij3; _ij3[1] = -1;
25608 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25609 {
25610 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25611 {
25612     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25613 }
25614 }
25615 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25616 {
25617 IkReal evalcond[6];
25618 IkReal x7967=IKsin(j3);
25619 IkReal x7968=IKcos(j3);
25620 IkReal x7969=((sj0)*(sj5));
25621 IkReal x7970=((r00)*(sj6));
25622 IkReal x7971=((IkReal(1.00000000000000))*(cj4));
25623 IkReal x7972=((cj6)*(r01));
25624 IkReal x7973=((cj0)*(cj5));
25625 IkReal x7974=((cj5)*(sj0));
25626 IkReal x7975=((cj6)*(r11));
25627 IkReal x7976=((cj6)*(sj4));
25628 IkReal x7977=((cj0)*(sj5));
25629 IkReal x7978=((cj4)*(cj5));
25630 IkReal x7979=((cj6)*(r21));
25631 IkReal x7980=((r20)*(sj6));
25632 IkReal x7981=((r10)*(sj6));
25633 IkReal x7982=((IkReal(1.00000000000000))*(cj0));
25634 IkReal x7983=((cj0)*(sj4)*(sj6));
25635 IkReal x7984=((sj0)*(sj4)*(sj6));
25636 evalcond[0]=((((sj5)*(x7979)))+(((cj2)*(x7967)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x7980))));
25637 evalcond[1]=((((r20)*(x7976)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x7978)*(x7979)))+(((IkReal(-1.00000000000000))*(cj2)*(x7968)))+(((x7978)*(x7980))));
25638 evalcond[2]=((((x7969)*(x7970)))+(((x7969)*(x7972)))+(((r12)*(x7973)))+(((IkReal(-1.00000000000000))*(x7975)*(x7977)))+(((IkReal(-1.00000000000000))*(r02)*(x7974)))+(((IkReal(-1.00000000000000))*(x7977)*(x7981)))+(((IkReal(-1.00000000000000))*(sj2)*(x7967))));
25639 evalcond[3]=((x7968)+(((r02)*(x7973)))+(((IkReal(-1.00000000000000))*(x7970)*(x7977)))+(((IkReal(-1.00000000000000))*(x7969)*(x7981)))+(((r12)*(x7974)))+(((IkReal(-1.00000000000000))*(x7972)*(x7977)))+(((IkReal(-1.00000000000000))*(x7969)*(x7975))));
25640 evalcond[4]=((((cj4)*(r02)*(x7969)))+(((r00)*(sj0)*(x7976)))+(((cj4)*(x7970)*(x7974)))+(((sj2)*(x7968)))+(((IkReal(-1.00000000000000))*(r12)*(x7971)*(x7977)))+(((IkReal(-1.00000000000000))*(r10)*(x7976)*(x7982)))+(((IkReal(-1.00000000000000))*(r01)*(x7984)))+(((IkReal(-1.00000000000000))*(x7971)*(x7973)*(x7975)))+(((IkReal(-1.00000000000000))*(x7971)*(x7973)*(x7981)))+(((cj4)*(x7972)*(x7974)))+(((r11)*(x7983))));
25641 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x7971)*(x7977)))+(x7967)+(((r01)*(x7983)))+(((r11)*(x7984)))+(((IkReal(-1.00000000000000))*(x7970)*(x7971)*(x7973)))+(((IkReal(-1.00000000000000))*(x7971)*(x7974)*(x7981)))+(((IkReal(-1.00000000000000))*(r00)*(x7976)*(x7982)))+(((IkReal(-1.00000000000000))*(x7971)*(x7974)*(x7975)))+(((IkReal(-1.00000000000000))*(x7971)*(x7972)*(x7973)))+(((IkReal(-1.00000000000000))*(r12)*(x7969)*(x7971)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7976))));
25642 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
25643 {
25644 continue;
25645 }
25646 }
25647 
25648 {
25649 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25650 vinfos[0].jointtype = 1;
25651 vinfos[0].foffset = j0;
25652 vinfos[0].indices[0] = _ij0[0];
25653 vinfos[0].indices[1] = _ij0[1];
25654 vinfos[0].maxsolutions = _nj0;
25655 vinfos[1].jointtype = 1;
25656 vinfos[1].foffset = j1;
25657 vinfos[1].indices[0] = _ij1[0];
25658 vinfos[1].indices[1] = _ij1[1];
25659 vinfos[1].maxsolutions = _nj1;
25660 vinfos[2].jointtype = 1;
25661 vinfos[2].foffset = j2;
25662 vinfos[2].indices[0] = _ij2[0];
25663 vinfos[2].indices[1] = _ij2[1];
25664 vinfos[2].maxsolutions = _nj2;
25665 vinfos[3].jointtype = 1;
25666 vinfos[3].foffset = j3;
25667 vinfos[3].indices[0] = _ij3[0];
25668 vinfos[3].indices[1] = _ij3[1];
25669 vinfos[3].maxsolutions = _nj3;
25670 vinfos[4].jointtype = 1;
25671 vinfos[4].foffset = j4;
25672 vinfos[4].indices[0] = _ij4[0];
25673 vinfos[4].indices[1] = _ij4[1];
25674 vinfos[4].maxsolutions = _nj4;
25675 vinfos[5].jointtype = 1;
25676 vinfos[5].foffset = j5;
25677 vinfos[5].indices[0] = _ij5[0];
25678 vinfos[5].indices[1] = _ij5[1];
25679 vinfos[5].maxsolutions = _nj5;
25680 vinfos[6].jointtype = 1;
25681 vinfos[6].foffset = j6;
25682 vinfos[6].indices[0] = _ij6[0];
25683 vinfos[6].indices[1] = _ij6[1];
25684 vinfos[6].maxsolutions = _nj6;
25685 std::vector<int> vfree(0);
25686 solutions.AddSolution(vinfos,vfree);
25687 }
25688 }
25689 }
25690 
25691 }
25692 
25693 }
25694 
25695 } else
25696 {
25697 {
25698 IkReal j3array[1], cj3array[1], sj3array[1];
25699 bool j3valid[1]={false};
25700 _nj3 = 1;
25701 IkReal x7985=((IkReal(1.00000000000000))*(r21));
25702 IkReal x7986=((cj4)*(cj5));
25703 IkReal x7987=((r20)*(sj6));
25704 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7985)))+(((IkReal(-1.00000000000000))*(sj5)*(x7987)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7985)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x7986)*(x7987)))+(((cj6)*(r21)*(x7986))))))) < IKFAST_ATAN2_MAGTHRESH )
25705     continue;
25706 j3array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x7985)))+(((IkReal(-1.00000000000000))*(sj5)*(x7987)))+(((cj5)*(r22)))))), ((gconst10)*(((((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x7985)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x7986)*(x7987)))+(((cj6)*(r21)*(x7986)))))));
25707 sj3array[0]=IKsin(j3array[0]);
25708 cj3array[0]=IKcos(j3array[0]);
25709 if( j3array[0] > IKPI )
25710 {
25711     j3array[0]-=IK2PI;
25712 }
25713 else if( j3array[0] < -IKPI )
25714 {    j3array[0]+=IK2PI;
25715 }
25716 j3valid[0] = true;
25717 for(int ij3 = 0; ij3 < 1; ++ij3)
25718 {
25719 if( !j3valid[ij3] )
25720 {
25721     continue;
25722 }
25723 _ij3[0] = ij3; _ij3[1] = -1;
25724 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25725 {
25726 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25727 {
25728     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25729 }
25730 }
25731 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25732 {
25733 IkReal evalcond[6];
25734 IkReal x7988=IKsin(j3);
25735 IkReal x7989=IKcos(j3);
25736 IkReal x7990=((sj0)*(sj5));
25737 IkReal x7991=((r00)*(sj6));
25738 IkReal x7992=((IkReal(1.00000000000000))*(cj4));
25739 IkReal x7993=((cj6)*(r01));
25740 IkReal x7994=((cj0)*(cj5));
25741 IkReal x7995=((cj5)*(sj0));
25742 IkReal x7996=((cj6)*(r11));
25743 IkReal x7997=((cj6)*(sj4));
25744 IkReal x7998=((cj0)*(sj5));
25745 IkReal x7999=((cj4)*(cj5));
25746 IkReal x8000=((cj6)*(r21));
25747 IkReal x8001=((r20)*(sj6));
25748 IkReal x8002=((r10)*(sj6));
25749 IkReal x8003=((IkReal(1.00000000000000))*(cj0));
25750 IkReal x8004=((cj0)*(sj4)*(sj6));
25751 IkReal x8005=((sj0)*(sj4)*(sj6));
25752 evalcond[0]=((((cj2)*(x7988)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8001)))+(((sj5)*(x8000))));
25753 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x7999)*(x8001)))+(((IkReal(-1.00000000000000))*(cj2)*(x7989)))+(((x7999)*(x8000)))+(((r20)*(x7997))));
25754 evalcond[2]=((((IkReal(-1.00000000000000))*(x7998)*(x8002)))+(((IkReal(-1.00000000000000))*(sj2)*(x7988)))+(((IkReal(-1.00000000000000))*(r02)*(x7995)))+(((IkReal(-1.00000000000000))*(x7996)*(x7998)))+(((x7990)*(x7993)))+(((x7990)*(x7991)))+(((r12)*(x7994))));
25755 evalcond[3]=((((IkReal(-1.00000000000000))*(x7991)*(x7998)))+(((IkReal(-1.00000000000000))*(x7990)*(x8002)))+(x7989)+(((IkReal(-1.00000000000000))*(x7990)*(x7996)))+(((IkReal(-1.00000000000000))*(x7993)*(x7998)))+(((r12)*(x7995)))+(((r02)*(x7994))));
25756 evalcond[4]=((((IkReal(-1.00000000000000))*(x7992)*(x7994)*(x7996)))+(((sj2)*(x7989)))+(((IkReal(-1.00000000000000))*(r10)*(x7997)*(x8003)))+(((IkReal(-1.00000000000000))*(x7992)*(x7994)*(x8002)))+(((r11)*(x8004)))+(((IkReal(-1.00000000000000))*(r01)*(x8005)))+(((cj4)*(r02)*(x7990)))+(((IkReal(-1.00000000000000))*(r12)*(x7992)*(x7998)))+(((cj4)*(x7991)*(x7995)))+(((r00)*(sj0)*(x7997)))+(((cj4)*(x7993)*(x7995))));
25757 evalcond[5]=((((r11)*(x8005)))+(((IkReal(-1.00000000000000))*(x7992)*(x7995)*(x7996)))+(((IkReal(-1.00000000000000))*(x7991)*(x7992)*(x7994)))+(x7988)+(((IkReal(-1.00000000000000))*(r00)*(x7997)*(x8003)))+(((IkReal(-1.00000000000000))*(x7992)*(x7995)*(x8002)))+(((IkReal(-1.00000000000000))*(x7992)*(x7993)*(x7994)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x7997)))+(((r01)*(x8004)))+(((IkReal(-1.00000000000000))*(r12)*(x7990)*(x7992)))+(((IkReal(-1.00000000000000))*(r02)*(x7992)*(x7998))));
25758 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
25759 {
25760 continue;
25761 }
25762 }
25763 
25764 {
25765 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25766 vinfos[0].jointtype = 1;
25767 vinfos[0].foffset = j0;
25768 vinfos[0].indices[0] = _ij0[0];
25769 vinfos[0].indices[1] = _ij0[1];
25770 vinfos[0].maxsolutions = _nj0;
25771 vinfos[1].jointtype = 1;
25772 vinfos[1].foffset = j1;
25773 vinfos[1].indices[0] = _ij1[0];
25774 vinfos[1].indices[1] = _ij1[1];
25775 vinfos[1].maxsolutions = _nj1;
25776 vinfos[2].jointtype = 1;
25777 vinfos[2].foffset = j2;
25778 vinfos[2].indices[0] = _ij2[0];
25779 vinfos[2].indices[1] = _ij2[1];
25780 vinfos[2].maxsolutions = _nj2;
25781 vinfos[3].jointtype = 1;
25782 vinfos[3].foffset = j3;
25783 vinfos[3].indices[0] = _ij3[0];
25784 vinfos[3].indices[1] = _ij3[1];
25785 vinfos[3].maxsolutions = _nj3;
25786 vinfos[4].jointtype = 1;
25787 vinfos[4].foffset = j4;
25788 vinfos[4].indices[0] = _ij4[0];
25789 vinfos[4].indices[1] = _ij4[1];
25790 vinfos[4].maxsolutions = _nj4;
25791 vinfos[5].jointtype = 1;
25792 vinfos[5].foffset = j5;
25793 vinfos[5].indices[0] = _ij5[0];
25794 vinfos[5].indices[1] = _ij5[1];
25795 vinfos[5].maxsolutions = _nj5;
25796 vinfos[6].jointtype = 1;
25797 vinfos[6].foffset = j6;
25798 vinfos[6].indices[0] = _ij6[0];
25799 vinfos[6].indices[1] = _ij6[1];
25800 vinfos[6].maxsolutions = _nj6;
25801 std::vector<int> vfree(0);
25802 solutions.AddSolution(vinfos,vfree);
25803 }
25804 }
25805 }
25806 
25807 }
25808 
25809 }
25810 
25811 } else
25812 {
25813 IkReal x8006=((IkReal(1.00000000000000))*(cj0));
25814 IkReal x8007=((cj4)*(sj6));
25815 IkReal x8008=((sj0)*(sj4));
25816 IkReal x8009=((cj5)*(sj6));
25817 IkReal x8010=((sj4)*(sj5));
25818 IkReal x8011=((r12)*(sj5));
25819 IkReal x8012=((IkReal(0.374290000000000))*(cj5));
25820 IkReal x8013=((r02)*(sj0));
25821 IkReal x8014=((IkReal(1.00000000000000))*(sj0));
25822 IkReal x8015=((cj0)*(r10));
25823 IkReal x8016=((cj4)*(cj6));
25824 IkReal x8017=((r00)*(sj0));
25825 IkReal x8018=((cj6)*(r21));
25826 IkReal x8019=((IkReal(0.374290000000000))*(sj5));
25827 IkReal x8020=((IkReal(0.0100000000000000))*(sj5));
25828 IkReal x8021=((cj0)*(r02));
25829 IkReal x8022=((cj5)*(sj4));
25830 IkReal x8023=((cj6)*(r01));
25831 IkReal x8024=((cj0)*(r00));
25832 IkReal x8025=((cj6)*(r11));
25833 IkReal x8026=((r01)*(sj0));
25834 IkReal x8027=((r10)*(sj0));
25835 IkReal x8028=((IkReal(0.0100000000000000))*(cj5)*(cj6));
25836 IkReal x8029=((sj6)*(x8019));
25837 IkReal x8030=((cj0)*(cj6)*(x8019));
25838 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
25839 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x8016)))+(((r21)*(x8007)))+(((x8018)*(x8022)))+(((IkReal(-1.00000000000000))*(cj1)))+(((r20)*(sj4)*(x8009)))+(((r22)*(x8010))));
25840 evalcond[2]=((((x8018)*(x8019)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x8012)))+(((IkReal(-0.0100000000000000))*(r20)*(x8009)))+(((IkReal(-1.00000000000000))*(r22)*(x8020)))+(((r20)*(x8029)))+(((IkReal(-0.0100000000000000))*(cj5)*(x8018)))+(pz));
25841 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x8006)*(x8007)))+(((x8015)*(x8016)))+(((IkReal(-1.00000000000000))*(r00)*(x8014)*(x8016)))+(((IkReal(-1.00000000000000))*(r12)*(x8006)*(x8010)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x8006)*(x8009)))+(((r02)*(sj5)*(x8008)))+(((x8007)*(x8026)))+(((IkReal(-1.00000000000000))*(x8006)*(x8022)*(x8025)))+(((r00)*(x8008)*(x8009)))+(((cj5)*(x8008)*(x8023))));
25842 evalcond[4]=((((IkReal(-1.00000000000000))*(x8008)*(x8011)))+(((IkReal(-1.00000000000000))*(r01)*(x8006)*(x8007)))+(((IkReal(-1.00000000000000))*(cj5)*(x8008)*(x8025)))+(sj1)+(((IkReal(-1.00000000000000))*(x8006)*(x8022)*(x8023)))+(((x8016)*(x8024)))+(((IkReal(-1.00000000000000))*(r11)*(x8007)*(x8014)))+(((x8016)*(x8027)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x8006)*(x8009)))+(((IkReal(-1.00000000000000))*(r10)*(x8008)*(x8009)))+(((IkReal(-1.00000000000000))*(r02)*(x8006)*(x8010))));
25843 evalcond[5]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x8025)))+(((x8017)*(x8029)))+(((IkReal(0.0100000000000000))*(cj0)*(x8011)))+(((IkReal(0.0100000000000000))*(x8009)*(x8015)))+(((IkReal(-1.00000000000000))*(x8015)*(x8029)))+(((IkReal(-1.00000000000000))*(x8013)*(x8020)))+(((IkReal(-0.0100000000000000))*(x8009)*(x8017)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x8023)))+(((IkReal(-1.00000000000000))*(py)*(x8006)))+(((sj0)*(x8019)*(x8023)))+(((IkReal(-1.00000000000000))*(cj0)*(x8019)*(x8025)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x8012)*(x8013)))+(((cj0)*(r12)*(x8012))));
25844 evalcond[6]=((IkReal(0.0690000000000000))+(((x8012)*(x8021)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x8025)))+(((IkReal(-1.00000000000000))*(px)*(x8006)))+(((r12)*(sj0)*(x8012)))+(((IkReal(-1.00000000000000))*(sj0)*(x8019)*(x8025)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x8023)))+(((IkReal(0.0100000000000000))*(x8009)*(x8027)))+(((IkReal(-1.00000000000000))*(py)*(x8014)))+(((IkReal(0.0100000000000000))*(x8009)*(x8024)))+(((IkReal(0.0100000000000000))*(sj0)*(x8011)))+(((IkReal(-1.00000000000000))*(x8027)*(x8029)))+(((IkReal(-1.00000000000000))*(cj0)*(x8019)*(x8023)))+(((IkReal(-1.00000000000000))*(x8024)*(x8029)))+(((IkReal(0.364420000000000))*(cj1)))+(((x8020)*(x8021))));
25845 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
25846 {
25847 {
25848 IkReal dummyeval[1];
25849 IkReal gconst11;
25850 gconst11=IKsign(sj1);
25851 dummyeval[0]=sj1;
25852 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
25853 {
25854 {
25855 IkReal dummyeval[1];
25856 dummyeval[0]=sj1;
25857 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
25858 {
25859 {
25860 IkReal dummyeval[1];
25861 dummyeval[0]=cj1;
25862 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
25863 {
25864 {
25865 IkReal evalcond[9];
25866 IkReal x8031=((IkReal(1.00000000000000))*(cj0));
25867 IkReal x8032=((cj4)*(sj6));
25868 IkReal x8033=((sj0)*(sj6));
25869 IkReal x8034=((cj5)*(sj4));
25870 IkReal x8035=((IkReal(0.374290000000000))*(sj5));
25871 IkReal x8036=((sj4)*(sj5));
25872 IkReal x8037=((cj0)*(cj6));
25873 IkReal x8038=((IkReal(0.0100000000000000))*(cj5));
25874 IkReal x8039=((cj4)*(sj5));
25875 IkReal x8040=((cj5)*(sj0));
25876 IkReal x8041=((IkReal(0.374290000000000))*(r02));
25877 IkReal x8042=((r20)*(sj6));
25878 IkReal x8043=((cj6)*(r21));
25879 IkReal x8044=((IkReal(1.00000000000000))*(sj0));
25880 IkReal x8045=((cj0)*(sj6));
25881 IkReal x8046=((cj4)*(cj6));
25882 IkReal x8047=((IkReal(0.374290000000000))*(r12));
25883 IkReal x8048=((cj0)*(cj5));
25884 IkReal x8049=((cj6)*(sj5));
25885 IkReal x8050=((cj6)*(r01));
25886 IkReal x8051=((r00)*(sj6));
25887 IkReal x8052=((IkReal(0.0100000000000000))*(sj5));
25888 IkReal x8053=((cj6)*(r11));
25889 IkReal x8054=((IkReal(1.00000000000000))*(r10));
25890 IkReal x8055=((r02)*(sj0));
25891 IkReal x8056=((cj6)*(sj4));
25892 IkReal x8057=((r12)*(x8044));
25893 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
25894 evalcond[1]=((((r21)*(x8032)))+(((x8034)*(x8043)))+(((IkReal(-1.00000000000000))*(r20)*(x8046)))+(((r22)*(x8036)))+(((x8034)*(x8042))));
25895 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x8035)*(x8042)))+(pz)+(((IkReal(-1.00000000000000))*(x8038)*(x8043)))+(((IkReal(-1.00000000000000))*(r22)*(x8052)))+(((x8035)*(x8043)))+(((IkReal(-1.00000000000000))*(x8038)*(x8042))));
25896 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x8031)*(x8049)))+(((IkReal(-1.00000000000000))*(sj5)*(x8033)*(x8054)))+(((r12)*(x8040)))+(((IkReal(-1.00000000000000))*(r11)*(x8044)*(x8049)))+(((IkReal(-1.00000000000000))*(sj5)*(x8031)*(x8051)))+(((r02)*(x8048))));
25897 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x8044)*(x8046)))+(((r01)*(sj0)*(x8032)))+(((IkReal(-1.00000000000000))*(x8031)*(x8034)*(x8053)))+(((sj0)*(x8034)*(x8050)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x8031)*(x8034)))+(((cj4)*(r10)*(x8037)))+(((r00)*(x8033)*(x8034)))+(((IkReal(-1.00000000000000))*(r11)*(x8031)*(x8032)))+(((IkReal(-1.00000000000000))*(r12)*(x8031)*(x8036)))+(((x8036)*(x8055))));
25898 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x8036)*(x8057)))+(((IkReal(-1.00000000000000))*(x8031)*(x8034)*(x8051)))+(((cj4)*(r00)*(x8037)))+(((IkReal(-1.00000000000000))*(r02)*(x8031)*(x8036)))+(((IkReal(-1.00000000000000))*(x8033)*(x8034)*(x8054)))+(((r10)*(sj0)*(x8046)))+(((IkReal(-1.00000000000000))*(r01)*(x8031)*(x8032)))+(((IkReal(-1.00000000000000))*(x8031)*(x8034)*(x8050)))+(((IkReal(-1.00000000000000))*(x8034)*(x8044)*(x8053)))+(((IkReal(-1.00000000000000))*(r11)*(x8032)*(x8044))));
25899 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x8035)*(x8037)))+(((cj0)*(r12)*(x8052)))+(((IkReal(-1.00000000000000))*(sj0)*(x8038)*(x8050)))+(((r00)*(x8033)*(x8035)))+(((IkReal(-1.00000000000000))*(r00)*(x8033)*(x8038)))+(((IkReal(-1.00000000000000))*(r10)*(x8035)*(x8045)))+(((IkReal(-1.00000000000000))*(x8052)*(x8055)))+(((IkReal(-1.00000000000000))*(x8040)*(x8041)))+(((IkReal(-1.00000000000000))*(py)*(x8031)))+(((sj0)*(x8035)*(x8050)))+(((px)*(sj0)))+(((x8047)*(x8048)))+(((r11)*(x8037)*(x8038)))+(((r10)*(x8038)*(x8045))));
25900 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x8040)*(x8046)))+(((IkReal(-1.00000000000000))*(r10)*(x8044)*(x8056)))+(((IkReal(-1.00000000000000))*(x8032)*(x8040)*(x8054)))+(((r01)*(sj4)*(x8045)))+(((r11)*(sj4)*(x8033)))+(((IkReal(-1.00000000000000))*(r00)*(x8031)*(x8056)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8031)*(x8032)))+(((IkReal(-1.00000000000000))*(r02)*(x8031)*(x8039)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x8031)*(x8046)))+(((IkReal(-1.00000000000000))*(x8039)*(x8057))));
25901 evalcond[8]=((IkReal(0.0690000000000000))+(((r12)*(sj0)*(x8052)))+(((r00)*(x8038)*(x8045)))+(((r01)*(x8037)*(x8038)))+(((IkReal(-1.00000000000000))*(px)*(x8031)))+(((IkReal(-1.00000000000000))*(r01)*(x8035)*(x8037)))+(((x8040)*(x8047)))+(((IkReal(-1.00000000000000))*(sj0)*(x8035)*(x8053)))+(((cj0)*(r02)*(x8052)))+(((IkReal(-1.00000000000000))*(r10)*(x8033)*(x8035)))+(((IkReal(-1.00000000000000))*(py)*(x8044)))+(((sj0)*(x8038)*(x8053)))+(((IkReal(-1.00000000000000))*(r00)*(x8035)*(x8045)))+(((x8041)*(x8048)))+(((r10)*(x8033)*(x8038))));
25902 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
25903 {
25904 {
25905 IkReal j3array[1], cj3array[1], sj3array[1];
25906 bool j3valid[1]={false};
25907 _nj3 = 1;
25908 IkReal x8058=((r20)*(sj6));
25909 IkReal x8059=((cj4)*(cj5));
25910 IkReal x8060=((cj6)*(r21));
25911 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8059)*(x8060)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8058)*(x8059))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x8058)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8060))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8059)*(x8060)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8058)*(x8059)))))+IKsqr(((((sj5)*(x8058)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8060)))))-1) <= IKFAST_SINCOS_THRESH )
25912     continue;
25913 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8059)*(x8060)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8058)*(x8059)))), ((((sj5)*(x8058)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8060)))));
25914 sj3array[0]=IKsin(j3array[0]);
25915 cj3array[0]=IKcos(j3array[0]);
25916 if( j3array[0] > IKPI )
25917 {
25918     j3array[0]-=IK2PI;
25919 }
25920 else if( j3array[0] < -IKPI )
25921 {    j3array[0]+=IK2PI;
25922 }
25923 j3valid[0] = true;
25924 for(int ij3 = 0; ij3 < 1; ++ij3)
25925 {
25926 if( !j3valid[ij3] )
25927 {
25928     continue;
25929 }
25930 _ij3[0] = ij3; _ij3[1] = -1;
25931 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
25932 {
25933 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
25934 {
25935     j3valid[iij3]=false; _ij3[1] = iij3; break; 
25936 }
25937 }
25938 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
25939 {
25940 IkReal evalcond[4];
25941 IkReal x8061=IKcos(j3);
25942 IkReal x8062=((sj0)*(sj5));
25943 IkReal x8063=((r00)*(sj6));
25944 IkReal x8064=((cj6)*(r01));
25945 IkReal x8065=((cj5)*(sj0));
25946 IkReal x8066=((cj0)*(cj5));
25947 IkReal x8067=((cj6)*(sj4));
25948 IkReal x8068=((sj4)*(sj6));
25949 IkReal x8069=((cj0)*(r11));
25950 IkReal x8070=((cj4)*(cj6));
25951 IkReal x8071=((cj4)*(sj6));
25952 IkReal x8072=((IkReal(1.00000000000000))*(cj0));
25953 IkReal x8073=((cj4)*(sj5));
25954 IkReal x8074=((sj5)*(sj6));
25955 IkReal x8075=((cj6)*(sj5));
25956 IkReal x8076=((IkReal(1.00000000000000))*(IKsin(j3)));
25957 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r21)*(x8075)))+(((r20)*(x8074)))+(((IkReal(-1.00000000000000))*(x8061))));
25958 evalcond[1]=((((cj5)*(r21)*(x8070)))+(((r20)*(x8067)))+(((IkReal(-1.00000000000000))*(x8076)))+(((cj5)*(r20)*(x8071)))+(((IkReal(-1.00000000000000))*(r21)*(x8068)))+(((r22)*(x8073))));
25959 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x8065)))+(((IkReal(-1.00000000000000))*(x8069)*(x8075)))+(((x8062)*(x8064)))+(((IkReal(-1.00000000000000))*(x8076)))+(((r12)*(x8066)))+(((IkReal(-1.00000000000000))*(r10)*(x8072)*(x8074)))+(((x8062)*(x8063))));
25960 evalcond[3]=((((x8068)*(x8069)))+(((IkReal(-1.00000000000000))*(r11)*(x8066)*(x8070)))+(((IkReal(-1.00000000000000))*(r12)*(x8072)*(x8073)))+(((cj4)*(x8063)*(x8065)))+(((cj4)*(x8064)*(x8065)))+(x8061)+(((cj4)*(r02)*(x8062)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x8068)))+(((IkReal(-1.00000000000000))*(r10)*(x8066)*(x8071)))+(((r00)*(sj0)*(x8067)))+(((IkReal(-1.00000000000000))*(r10)*(x8067)*(x8072))));
25961 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
25962 {
25963 continue;
25964 }
25965 }
25966 
25967 {
25968 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
25969 vinfos[0].jointtype = 1;
25970 vinfos[0].foffset = j0;
25971 vinfos[0].indices[0] = _ij0[0];
25972 vinfos[0].indices[1] = _ij0[1];
25973 vinfos[0].maxsolutions = _nj0;
25974 vinfos[1].jointtype = 1;
25975 vinfos[1].foffset = j1;
25976 vinfos[1].indices[0] = _ij1[0];
25977 vinfos[1].indices[1] = _ij1[1];
25978 vinfos[1].maxsolutions = _nj1;
25979 vinfos[2].jointtype = 1;
25980 vinfos[2].foffset = j2;
25981 vinfos[2].indices[0] = _ij2[0];
25982 vinfos[2].indices[1] = _ij2[1];
25983 vinfos[2].maxsolutions = _nj2;
25984 vinfos[3].jointtype = 1;
25985 vinfos[3].foffset = j3;
25986 vinfos[3].indices[0] = _ij3[0];
25987 vinfos[3].indices[1] = _ij3[1];
25988 vinfos[3].maxsolutions = _nj3;
25989 vinfos[4].jointtype = 1;
25990 vinfos[4].foffset = j4;
25991 vinfos[4].indices[0] = _ij4[0];
25992 vinfos[4].indices[1] = _ij4[1];
25993 vinfos[4].maxsolutions = _nj4;
25994 vinfos[5].jointtype = 1;
25995 vinfos[5].foffset = j5;
25996 vinfos[5].indices[0] = _ij5[0];
25997 vinfos[5].indices[1] = _ij5[1];
25998 vinfos[5].maxsolutions = _nj5;
25999 vinfos[6].jointtype = 1;
26000 vinfos[6].foffset = j6;
26001 vinfos[6].indices[0] = _ij6[0];
26002 vinfos[6].indices[1] = _ij6[1];
26003 vinfos[6].maxsolutions = _nj6;
26004 std::vector<int> vfree(0);
26005 solutions.AddSolution(vinfos,vfree);
26006 }
26007 }
26008 }
26009 
26010 } else
26011 {
26012 IkReal x8077=((IkReal(1.00000000000000))*(cj0));
26013 IkReal x8078=((cj4)*(sj6));
26014 IkReal x8079=((sj0)*(sj6));
26015 IkReal x8080=((cj5)*(sj4));
26016 IkReal x8081=((IkReal(0.374290000000000))*(sj5));
26017 IkReal x8082=((sj4)*(sj5));
26018 IkReal x8083=((cj0)*(cj6));
26019 IkReal x8084=((IkReal(0.0100000000000000))*(cj5));
26020 IkReal x8085=((cj4)*(sj5));
26021 IkReal x8086=((cj5)*(sj0));
26022 IkReal x8087=((IkReal(0.374290000000000))*(r02));
26023 IkReal x8088=((r20)*(sj6));
26024 IkReal x8089=((cj6)*(r21));
26025 IkReal x8090=((IkReal(1.00000000000000))*(sj0));
26026 IkReal x8091=((cj0)*(sj6));
26027 IkReal x8092=((cj4)*(cj6));
26028 IkReal x8093=((IkReal(0.374290000000000))*(r12));
26029 IkReal x8094=((cj0)*(cj5));
26030 IkReal x8095=((cj6)*(sj5));
26031 IkReal x8096=((cj6)*(r01));
26032 IkReal x8097=((r00)*(sj6));
26033 IkReal x8098=((IkReal(0.0100000000000000))*(sj5));
26034 IkReal x8099=((cj6)*(r11));
26035 IkReal x8100=((IkReal(1.00000000000000))*(r10));
26036 IkReal x8101=((r02)*(sj0));
26037 IkReal x8102=((cj6)*(sj4));
26038 IkReal x8103=((r12)*(x8090));
26039 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
26040 evalcond[1]=((((x8080)*(x8089)))+(((r21)*(x8078)))+(((x8080)*(x8088)))+(((r22)*(x8082)))+(((IkReal(-1.00000000000000))*(r20)*(x8092))));
26041 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x8084)*(x8089)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x8081)*(x8088)))+(pz)+(((IkReal(-1.00000000000000))*(x8084)*(x8088)))+(((IkReal(-1.00000000000000))*(r22)*(x8098)))+(((x8081)*(x8089))));
26042 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x8077)*(x8097)))+(((IkReal(-1.00000000000000))*(r11)*(x8090)*(x8095)))+(((r02)*(x8094)))+(((IkReal(-1.00000000000000))*(sj5)*(x8079)*(x8100)))+(((r12)*(x8086)))+(((IkReal(-1.00000000000000))*(r01)*(x8077)*(x8095))));
26043 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x8077)*(x8082)))+(((r00)*(x8079)*(x8080)))+(((IkReal(-1.00000000000000))*(r11)*(x8077)*(x8078)))+(((IkReal(-1.00000000000000))*(x8077)*(x8080)*(x8099)))+(((IkReal(-1.00000000000000))*(r00)*(x8090)*(x8092)))+(((x8082)*(x8101)))+(((cj4)*(r10)*(x8083)))+(((r01)*(sj0)*(x8078)))+(((sj0)*(x8080)*(x8096)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x8077)*(x8080))));
26044 evalcond[5]=((IkReal(-1.00000000000000))+(((r10)*(sj0)*(x8092)))+(((IkReal(-1.00000000000000))*(x8077)*(x8080)*(x8097)))+(((IkReal(-1.00000000000000))*(r02)*(x8077)*(x8082)))+(((IkReal(-1.00000000000000))*(x8077)*(x8080)*(x8096)))+(((IkReal(-1.00000000000000))*(x8079)*(x8080)*(x8100)))+(((IkReal(-1.00000000000000))*(r11)*(x8078)*(x8090)))+(((IkReal(-1.00000000000000))*(x8082)*(x8103)))+(((IkReal(-1.00000000000000))*(r01)*(x8077)*(x8078)))+(((IkReal(-1.00000000000000))*(x8080)*(x8090)*(x8099)))+(((cj4)*(r00)*(x8083))));
26045 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x8079)*(x8084)))+(((IkReal(-1.00000000000000))*(sj0)*(x8084)*(x8096)))+(((cj0)*(r12)*(x8098)))+(((IkReal(-1.00000000000000))*(r10)*(x8081)*(x8091)))+(((sj0)*(x8081)*(x8096)))+(((r10)*(x8084)*(x8091)))+(((r00)*(x8079)*(x8081)))+(((IkReal(-1.00000000000000))*(x8086)*(x8087)))+(((r11)*(x8083)*(x8084)))+(((IkReal(-1.00000000000000))*(py)*(x8077)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x8081)*(x8083)))+(((x8093)*(x8094)))+(((IkReal(-1.00000000000000))*(x8098)*(x8101))));
26046 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8077)*(x8078)))+(((r01)*(sj4)*(x8091)))+(((IkReal(-1.00000000000000))*(r10)*(x8090)*(x8102)))+(((IkReal(-1.00000000000000))*(r00)*(x8077)*(x8102)))+(((r11)*(sj4)*(x8079)))+(((IkReal(-1.00000000000000))*(r11)*(x8086)*(x8092)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x8077)*(x8092)))+(((IkReal(-1.00000000000000))*(r02)*(x8077)*(x8085)))+(((IkReal(-1.00000000000000))*(x8085)*(x8103)))+(((IkReal(-1.00000000000000))*(x8078)*(x8086)*(x8100))));
26047 evalcond[8]=((IkReal(0.0690000000000000))+(((cj0)*(r02)*(x8098)))+(((IkReal(-1.00000000000000))*(r10)*(x8079)*(x8081)))+(((IkReal(-1.00000000000000))*(py)*(x8090)))+(((r12)*(sj0)*(x8098)))+(((r00)*(x8084)*(x8091)))+(((x8086)*(x8093)))+(((IkReal(-1.00000000000000))*(r00)*(x8081)*(x8091)))+(((IkReal(-1.00000000000000))*(px)*(x8077)))+(((r10)*(x8079)*(x8084)))+(((sj0)*(x8084)*(x8099)))+(((IkReal(-1.00000000000000))*(sj0)*(x8081)*(x8099)))+(((IkReal(-1.00000000000000))*(r01)*(x8081)*(x8083)))+(((r01)*(x8083)*(x8084)))+(((x8087)*(x8094))));
26048 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
26049 {
26050 {
26051 IkReal j3array[1], cj3array[1], sj3array[1];
26052 bool j3valid[1]={false};
26053 _nj3 = 1;
26054 IkReal x8104=((IkReal(1.00000000000000))*(sj5));
26055 IkReal x8105=((cj6)*(r21));
26056 IkReal x8106=((r20)*(sj6));
26057 IkReal x8107=((IkReal(1.00000000000000))*(cj4)*(cj5));
26058 if( IKabs(((((IkReal(-1.00000000000000))*(x8105)*(x8107)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8104)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8106)*(x8107)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x8104)*(x8105)))+(((IkReal(-1.00000000000000))*(x8104)*(x8106)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x8105)*(x8107)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8104)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8106)*(x8107)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x8104)*(x8105)))+(((IkReal(-1.00000000000000))*(x8104)*(x8106)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
26059     continue;
26060 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x8105)*(x8107)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8104)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8106)*(x8107)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x8104)*(x8105)))+(((IkReal(-1.00000000000000))*(x8104)*(x8106)))+(((cj5)*(r22)))));
26061 sj3array[0]=IKsin(j3array[0]);
26062 cj3array[0]=IKcos(j3array[0]);
26063 if( j3array[0] > IKPI )
26064 {
26065     j3array[0]-=IK2PI;
26066 }
26067 else if( j3array[0] < -IKPI )
26068 {    j3array[0]+=IK2PI;
26069 }
26070 j3valid[0] = true;
26071 for(int ij3 = 0; ij3 < 1; ++ij3)
26072 {
26073 if( !j3valid[ij3] )
26074 {
26075     continue;
26076 }
26077 _ij3[0] = ij3; _ij3[1] = -1;
26078 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26079 {
26080 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26081 {
26082     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26083 }
26084 }
26085 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26086 {
26087 IkReal evalcond[4];
26088 IkReal x8108=IKsin(j3);
26089 IkReal x8109=IKcos(j3);
26090 IkReal x8110=((sj0)*(sj5));
26091 IkReal x8111=((r00)*(sj6));
26092 IkReal x8112=((cj6)*(r01));
26093 IkReal x8113=((cj5)*(sj0));
26094 IkReal x8114=((cj0)*(cj5));
26095 IkReal x8115=((cj6)*(sj4));
26096 IkReal x8116=((sj4)*(sj6));
26097 IkReal x8117=((cj0)*(r11));
26098 IkReal x8118=((cj4)*(cj6));
26099 IkReal x8119=((cj4)*(sj6));
26100 IkReal x8120=((IkReal(1.00000000000000))*(cj0));
26101 IkReal x8121=((cj4)*(sj5));
26102 IkReal x8122=((sj5)*(sj6));
26103 IkReal x8123=((cj6)*(sj5));
26104 evalcond[0]=((x8109)+(((r21)*(x8123)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x8122))));
26105 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x8116)))+(((cj5)*(r20)*(x8119)))+(x8108)+(((r20)*(x8115)))+(((r22)*(x8121)))+(((cj5)*(r21)*(x8118))));
26106 evalcond[2]=((((IkReal(-1.00000000000000))*(x8108)))+(((r12)*(x8114)))+(((IkReal(-1.00000000000000))*(r10)*(x8120)*(x8122)))+(((x8110)*(x8111)))+(((x8110)*(x8112)))+(((IkReal(-1.00000000000000))*(r02)*(x8113)))+(((IkReal(-1.00000000000000))*(x8117)*(x8123))));
26107 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x8114)*(x8118)))+(((cj4)*(x8111)*(x8113)))+(((IkReal(-1.00000000000000))*(r10)*(x8115)*(x8120)))+(x8109)+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x8116)))+(((x8116)*(x8117)))+(((cj4)*(x8112)*(x8113)))+(((IkReal(-1.00000000000000))*(r10)*(x8114)*(x8119)))+(((cj4)*(r02)*(x8110)))+(((r00)*(sj0)*(x8115)))+(((IkReal(-1.00000000000000))*(r12)*(x8120)*(x8121))));
26108 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
26109 {
26110 continue;
26111 }
26112 }
26113 
26114 {
26115 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26116 vinfos[0].jointtype = 1;
26117 vinfos[0].foffset = j0;
26118 vinfos[0].indices[0] = _ij0[0];
26119 vinfos[0].indices[1] = _ij0[1];
26120 vinfos[0].maxsolutions = _nj0;
26121 vinfos[1].jointtype = 1;
26122 vinfos[1].foffset = j1;
26123 vinfos[1].indices[0] = _ij1[0];
26124 vinfos[1].indices[1] = _ij1[1];
26125 vinfos[1].maxsolutions = _nj1;
26126 vinfos[2].jointtype = 1;
26127 vinfos[2].foffset = j2;
26128 vinfos[2].indices[0] = _ij2[0];
26129 vinfos[2].indices[1] = _ij2[1];
26130 vinfos[2].maxsolutions = _nj2;
26131 vinfos[3].jointtype = 1;
26132 vinfos[3].foffset = j3;
26133 vinfos[3].indices[0] = _ij3[0];
26134 vinfos[3].indices[1] = _ij3[1];
26135 vinfos[3].maxsolutions = _nj3;
26136 vinfos[4].jointtype = 1;
26137 vinfos[4].foffset = j4;
26138 vinfos[4].indices[0] = _ij4[0];
26139 vinfos[4].indices[1] = _ij4[1];
26140 vinfos[4].maxsolutions = _nj4;
26141 vinfos[5].jointtype = 1;
26142 vinfos[5].foffset = j5;
26143 vinfos[5].indices[0] = _ij5[0];
26144 vinfos[5].indices[1] = _ij5[1];
26145 vinfos[5].maxsolutions = _nj5;
26146 vinfos[6].jointtype = 1;
26147 vinfos[6].foffset = j6;
26148 vinfos[6].indices[0] = _ij6[0];
26149 vinfos[6].indices[1] = _ij6[1];
26150 vinfos[6].maxsolutions = _nj6;
26151 std::vector<int> vfree(0);
26152 solutions.AddSolution(vinfos,vfree);
26153 }
26154 }
26155 }
26156 
26157 } else
26158 {
26159 if( 1 )
26160 {
26161 continue;
26162 
26163 } else
26164 {
26165 }
26166 }
26167 }
26168 }
26169 
26170 } else
26171 {
26172 {
26173 IkReal j3array[1], cj3array[1], sj3array[1];
26174 bool j3valid[1]={false};
26175 _nj3 = 1;
26176 IkReal x8124=((cj0)*(cj5));
26177 IkReal x8125=((IkReal(1.00000000000000))*(cj0));
26178 IkReal x8126=((cj6)*(r11));
26179 IkReal x8127=((r10)*(sj6));
26180 IkReal x8128=((cj5)*(sj0));
26181 IkReal x8129=((r00)*(sj5)*(sj6));
26182 IkReal x8130=((cj6)*(r01)*(sj5));
26183 IkReal x8131=((IkReal(1.00000000000000))*(sj0)*(sj5));
26184 if( IKabs(((((r12)*(x8124)))+(((IkReal(-1.00000000000000))*(r02)*(x8128)))+(((sj0)*(x8129)))+(((sj0)*(x8130)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8127)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8126))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x8125)*(x8130)))+(((IkReal(-1.00000000000000))*(x8125)*(x8129)))+(((r12)*(x8128)))+(((IkReal(-1.00000000000000))*(x8127)*(x8131)))+(((IkReal(-1.00000000000000))*(x8126)*(x8131)))+(((r02)*(x8124))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r12)*(x8124)))+(((IkReal(-1.00000000000000))*(r02)*(x8128)))+(((sj0)*(x8129)))+(((sj0)*(x8130)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8127)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8126)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x8125)*(x8130)))+(((IkReal(-1.00000000000000))*(x8125)*(x8129)))+(((r12)*(x8128)))+(((IkReal(-1.00000000000000))*(x8127)*(x8131)))+(((IkReal(-1.00000000000000))*(x8126)*(x8131)))+(((r02)*(x8124)))))))-1) <= IKFAST_SINCOS_THRESH )
26185     continue;
26186 j3array[0]=IKatan2(((((r12)*(x8124)))+(((IkReal(-1.00000000000000))*(r02)*(x8128)))+(((sj0)*(x8129)))+(((sj0)*(x8130)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8127)))+(((IkReal(-1.00000000000000))*(sj5)*(x8125)*(x8126)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x8125)*(x8130)))+(((IkReal(-1.00000000000000))*(x8125)*(x8129)))+(((r12)*(x8128)))+(((IkReal(-1.00000000000000))*(x8127)*(x8131)))+(((IkReal(-1.00000000000000))*(x8126)*(x8131)))+(((r02)*(x8124)))))));
26187 sj3array[0]=IKsin(j3array[0]);
26188 cj3array[0]=IKcos(j3array[0]);
26189 if( j3array[0] > IKPI )
26190 {
26191     j3array[0]-=IK2PI;
26192 }
26193 else if( j3array[0] < -IKPI )
26194 {    j3array[0]+=IK2PI;
26195 }
26196 j3valid[0] = true;
26197 for(int ij3 = 0; ij3 < 1; ++ij3)
26198 {
26199 if( !j3valid[ij3] )
26200 {
26201     continue;
26202 }
26203 _ij3[0] = ij3; _ij3[1] = -1;
26204 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26205 {
26206 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26207 {
26208     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26209 }
26210 }
26211 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26212 {
26213 IkReal evalcond[6];
26214 IkReal x8132=IKsin(j3);
26215 IkReal x8133=IKcos(j3);
26216 IkReal x8134=((sj0)*(sj5));
26217 IkReal x8135=((r00)*(sj6));
26218 IkReal x8136=((cj6)*(r01));
26219 IkReal x8137=((cj4)*(cj5));
26220 IkReal x8138=((IkReal(1.00000000000000))*(cj0));
26221 IkReal x8139=((cj5)*(r12));
26222 IkReal x8140=((IkReal(1.00000000000000))*(sj0));
26223 IkReal x8141=((cj6)*(r11));
26224 IkReal x8142=((cj5)*(r02));
26225 IkReal x8143=((IkReal(1.00000000000000))*(cj1));
26226 IkReal x8144=((cj6)*(sj4));
26227 IkReal x8145=((cj6)*(r21));
26228 IkReal x8146=((r20)*(sj6));
26229 IkReal x8147=((r10)*(sj6));
26230 IkReal x8148=((sj4)*(sj6));
26231 IkReal x8149=((cj4)*(r02));
26232 IkReal x8150=((IkReal(1.00000000000000))*(cj4)*(r12));
26233 IkReal x8151=((IkReal(1.00000000000000))*(x8132));
26234 IkReal x8152=((cj0)*(x8148));
26235 evalcond[0]=((((sj5)*(x8146)))+(((IkReal(-1.00000000000000))*(sj1)*(x8133)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8145))));
26236 evalcond[1]=((((r20)*(x8144)))+(((IkReal(-1.00000000000000))*(r21)*(x8148)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x8151)))+(((x8137)*(x8146)))+(((x8137)*(x8145))));
26237 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x8138)*(x8147)))+(((IkReal(-1.00000000000000))*(x8151)))+(((IkReal(-1.00000000000000))*(x8140)*(x8142)))+(((x8134)*(x8136)))+(((IkReal(-1.00000000000000))*(sj5)*(x8138)*(x8141)))+(((cj0)*(x8139)))+(((x8134)*(x8135))));
26238 evalcond[3]=((((IkReal(-1.00000000000000))*(x8134)*(x8147)))+(((IkReal(-1.00000000000000))*(sj5)*(x8135)*(x8138)))+(((IkReal(-1.00000000000000))*(sj5)*(x8136)*(x8138)))+(((cj0)*(x8142)))+(((IkReal(-1.00000000000000))*(x8134)*(x8141)))+(((sj0)*(x8139)))+(((IkReal(-1.00000000000000))*(x8133)*(x8143))));
26239 evalcond[4]=((((x8134)*(x8149)))+(x8133)+(((IkReal(-1.00000000000000))*(r10)*(x8138)*(x8144)))+(((r11)*(x8152)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x8138)))+(((r00)*(sj0)*(x8144)))+(((IkReal(-1.00000000000000))*(x8137)*(x8138)*(x8141)))+(((sj0)*(x8135)*(x8137)))+(((sj0)*(x8136)*(x8137)))+(((IkReal(-1.00000000000000))*(x8137)*(x8138)*(x8147)))+(((IkReal(-1.00000000000000))*(r01)*(x8140)*(x8148))));
26240 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x8138)*(x8144)))+(((IkReal(-1.00000000000000))*(x8137)*(x8140)*(x8141)))+(((IkReal(-1.00000000000000))*(sj5)*(x8138)*(x8149)))+(((IkReal(-1.00000000000000))*(r10)*(x8140)*(x8144)))+(((IkReal(-1.00000000000000))*(x8137)*(x8140)*(x8147)))+(((r11)*(sj0)*(x8148)))+(((IkReal(-1.00000000000000))*(x8134)*(x8150)))+(((r01)*(x8152)))+(((IkReal(-1.00000000000000))*(x8136)*(x8137)*(x8138)))+(((IkReal(-1.00000000000000))*(x8135)*(x8137)*(x8138)))+(((IkReal(-1.00000000000000))*(x8132)*(x8143))));
26241 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
26242 {
26243 continue;
26244 }
26245 }
26246 
26247 {
26248 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26249 vinfos[0].jointtype = 1;
26250 vinfos[0].foffset = j0;
26251 vinfos[0].indices[0] = _ij0[0];
26252 vinfos[0].indices[1] = _ij0[1];
26253 vinfos[0].maxsolutions = _nj0;
26254 vinfos[1].jointtype = 1;
26255 vinfos[1].foffset = j1;
26256 vinfos[1].indices[0] = _ij1[0];
26257 vinfos[1].indices[1] = _ij1[1];
26258 vinfos[1].maxsolutions = _nj1;
26259 vinfos[2].jointtype = 1;
26260 vinfos[2].foffset = j2;
26261 vinfos[2].indices[0] = _ij2[0];
26262 vinfos[2].indices[1] = _ij2[1];
26263 vinfos[2].maxsolutions = _nj2;
26264 vinfos[3].jointtype = 1;
26265 vinfos[3].foffset = j3;
26266 vinfos[3].indices[0] = _ij3[0];
26267 vinfos[3].indices[1] = _ij3[1];
26268 vinfos[3].maxsolutions = _nj3;
26269 vinfos[4].jointtype = 1;
26270 vinfos[4].foffset = j4;
26271 vinfos[4].indices[0] = _ij4[0];
26272 vinfos[4].indices[1] = _ij4[1];
26273 vinfos[4].maxsolutions = _nj4;
26274 vinfos[5].jointtype = 1;
26275 vinfos[5].foffset = j5;
26276 vinfos[5].indices[0] = _ij5[0];
26277 vinfos[5].indices[1] = _ij5[1];
26278 vinfos[5].maxsolutions = _nj5;
26279 vinfos[6].jointtype = 1;
26280 vinfos[6].foffset = j6;
26281 vinfos[6].indices[0] = _ij6[0];
26282 vinfos[6].indices[1] = _ij6[1];
26283 vinfos[6].maxsolutions = _nj6;
26284 std::vector<int> vfree(0);
26285 solutions.AddSolution(vinfos,vfree);
26286 }
26287 }
26288 }
26289 
26290 }
26291 
26292 }
26293 
26294 } else
26295 {
26296 {
26297 IkReal j3array[1], cj3array[1], sj3array[1];
26298 bool j3valid[1]={false};
26299 _nj3 = 1;
26300 IkReal x8153=((sj5)*(sj6));
26301 IkReal x8154=((cj6)*(sj5));
26302 IkReal x8155=((IkReal(1.00000000000000))*(cj0));
26303 IkReal x8156=((IkReal(1.00000000000000))*(cj5));
26304 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8156)))+(((r01)*(sj0)*(x8154)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x8153)*(x8155)))+(((r00)*(sj0)*(x8153)))+(((IkReal(-1.00000000000000))*(r11)*(x8154)*(x8155))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8153)))+(((r21)*(x8154)))+(((IkReal(-1.00000000000000))*(r22)*(x8156))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8156)))+(((r01)*(sj0)*(x8154)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x8153)*(x8155)))+(((r00)*(sj0)*(x8153)))+(((IkReal(-1.00000000000000))*(r11)*(x8154)*(x8155)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8153)))+(((r21)*(x8154)))+(((IkReal(-1.00000000000000))*(r22)*(x8156)))))))-1) <= IKFAST_SINCOS_THRESH )
26305     continue;
26306 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8156)))+(((r01)*(sj0)*(x8154)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x8153)*(x8155)))+(((r00)*(sj0)*(x8153)))+(((IkReal(-1.00000000000000))*(r11)*(x8154)*(x8155)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8153)))+(((r21)*(x8154)))+(((IkReal(-1.00000000000000))*(r22)*(x8156)))))));
26307 sj3array[0]=IKsin(j3array[0]);
26308 cj3array[0]=IKcos(j3array[0]);
26309 if( j3array[0] > IKPI )
26310 {
26311     j3array[0]-=IK2PI;
26312 }
26313 else if( j3array[0] < -IKPI )
26314 {    j3array[0]+=IK2PI;
26315 }
26316 j3valid[0] = true;
26317 for(int ij3 = 0; ij3 < 1; ++ij3)
26318 {
26319 if( !j3valid[ij3] )
26320 {
26321     continue;
26322 }
26323 _ij3[0] = ij3; _ij3[1] = -1;
26324 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26325 {
26326 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26327 {
26328     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26329 }
26330 }
26331 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26332 {
26333 IkReal evalcond[6];
26334 IkReal x8157=IKsin(j3);
26335 IkReal x8158=IKcos(j3);
26336 IkReal x8159=((sj0)*(sj5));
26337 IkReal x8160=((r00)*(sj6));
26338 IkReal x8161=((cj6)*(r01));
26339 IkReal x8162=((cj4)*(cj5));
26340 IkReal x8163=((IkReal(1.00000000000000))*(cj0));
26341 IkReal x8164=((cj5)*(r12));
26342 IkReal x8165=((IkReal(1.00000000000000))*(sj0));
26343 IkReal x8166=((cj6)*(r11));
26344 IkReal x8167=((cj5)*(r02));
26345 IkReal x8168=((IkReal(1.00000000000000))*(cj1));
26346 IkReal x8169=((cj6)*(sj4));
26347 IkReal x8170=((cj6)*(r21));
26348 IkReal x8171=((r20)*(sj6));
26349 IkReal x8172=((r10)*(sj6));
26350 IkReal x8173=((sj4)*(sj6));
26351 IkReal x8174=((cj4)*(r02));
26352 IkReal x8175=((IkReal(1.00000000000000))*(cj4)*(r12));
26353 IkReal x8176=((IkReal(1.00000000000000))*(x8157));
26354 IkReal x8177=((cj0)*(x8173));
26355 evalcond[0]=((((sj5)*(x8171)))+(((IkReal(-1.00000000000000))*(sj1)*(x8158)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8170))));
26356 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x8176)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x8169)))+(((x8162)*(x8171)))+(((x8162)*(x8170)))+(((IkReal(-1.00000000000000))*(r21)*(x8173))));
26357 evalcond[2]=((((IkReal(-1.00000000000000))*(x8176)))+(((x8159)*(x8160)))+(((IkReal(-1.00000000000000))*(sj5)*(x8163)*(x8172)))+(((IkReal(-1.00000000000000))*(sj5)*(x8163)*(x8166)))+(((cj0)*(x8164)))+(((x8159)*(x8161)))+(((IkReal(-1.00000000000000))*(x8165)*(x8167))));
26358 evalcond[3]=((((IkReal(-1.00000000000000))*(x8158)*(x8168)))+(((IkReal(-1.00000000000000))*(sj5)*(x8161)*(x8163)))+(((sj0)*(x8164)))+(((IkReal(-1.00000000000000))*(x8159)*(x8172)))+(((IkReal(-1.00000000000000))*(x8159)*(x8166)))+(((cj0)*(x8167)))+(((IkReal(-1.00000000000000))*(sj5)*(x8160)*(x8163))));
26359 evalcond[4]=((x8158)+(((IkReal(-1.00000000000000))*(x8162)*(x8163)*(x8166)))+(((x8159)*(x8174)))+(((sj0)*(x8161)*(x8162)))+(((r11)*(x8177)))+(((IkReal(-1.00000000000000))*(r01)*(x8165)*(x8173)))+(((IkReal(-1.00000000000000))*(x8162)*(x8163)*(x8172)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x8163)))+(((r00)*(sj0)*(x8169)))+(((sj0)*(x8160)*(x8162)))+(((IkReal(-1.00000000000000))*(r10)*(x8163)*(x8169))));
26360 evalcond[5]=((((IkReal(-1.00000000000000))*(x8162)*(x8165)*(x8172)))+(((IkReal(-1.00000000000000))*(r10)*(x8165)*(x8169)))+(((IkReal(-1.00000000000000))*(x8157)*(x8168)))+(((r11)*(sj0)*(x8173)))+(((IkReal(-1.00000000000000))*(x8161)*(x8162)*(x8163)))+(((IkReal(-1.00000000000000))*(sj5)*(x8163)*(x8174)))+(((IkReal(-1.00000000000000))*(x8162)*(x8165)*(x8166)))+(((IkReal(-1.00000000000000))*(x8160)*(x8162)*(x8163)))+(((r01)*(x8177)))+(((IkReal(-1.00000000000000))*(x8159)*(x8175)))+(((IkReal(-1.00000000000000))*(r00)*(x8163)*(x8169))));
26361 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
26362 {
26363 continue;
26364 }
26365 }
26366 
26367 {
26368 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26369 vinfos[0].jointtype = 1;
26370 vinfos[0].foffset = j0;
26371 vinfos[0].indices[0] = _ij0[0];
26372 vinfos[0].indices[1] = _ij0[1];
26373 vinfos[0].maxsolutions = _nj0;
26374 vinfos[1].jointtype = 1;
26375 vinfos[1].foffset = j1;
26376 vinfos[1].indices[0] = _ij1[0];
26377 vinfos[1].indices[1] = _ij1[1];
26378 vinfos[1].maxsolutions = _nj1;
26379 vinfos[2].jointtype = 1;
26380 vinfos[2].foffset = j2;
26381 vinfos[2].indices[0] = _ij2[0];
26382 vinfos[2].indices[1] = _ij2[1];
26383 vinfos[2].maxsolutions = _nj2;
26384 vinfos[3].jointtype = 1;
26385 vinfos[3].foffset = j3;
26386 vinfos[3].indices[0] = _ij3[0];
26387 vinfos[3].indices[1] = _ij3[1];
26388 vinfos[3].maxsolutions = _nj3;
26389 vinfos[4].jointtype = 1;
26390 vinfos[4].foffset = j4;
26391 vinfos[4].indices[0] = _ij4[0];
26392 vinfos[4].indices[1] = _ij4[1];
26393 vinfos[4].maxsolutions = _nj4;
26394 vinfos[5].jointtype = 1;
26395 vinfos[5].foffset = j5;
26396 vinfos[5].indices[0] = _ij5[0];
26397 vinfos[5].indices[1] = _ij5[1];
26398 vinfos[5].maxsolutions = _nj5;
26399 vinfos[6].jointtype = 1;
26400 vinfos[6].foffset = j6;
26401 vinfos[6].indices[0] = _ij6[0];
26402 vinfos[6].indices[1] = _ij6[1];
26403 vinfos[6].maxsolutions = _nj6;
26404 std::vector<int> vfree(0);
26405 solutions.AddSolution(vinfos,vfree);
26406 }
26407 }
26408 }
26409 
26410 }
26411 
26412 }
26413 
26414 } else
26415 {
26416 {
26417 IkReal j3array[1], cj3array[1], sj3array[1];
26418 bool j3valid[1]={false};
26419 _nj3 = 1;
26420 IkReal x8178=((r20)*(sj6));
26421 IkReal x8179=((cj4)*(cj5));
26422 IkReal x8180=((cj6)*(r21));
26423 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8178)*(x8179)))+(((x8179)*(x8180))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((sj5)*(x8180)))+(((sj5)*(x8178)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH )
26424     continue;
26425 j3array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8178)*(x8179)))+(((x8179)*(x8180)))))), ((gconst11)*(((((sj5)*(x8180)))+(((sj5)*(x8178)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))));
26426 sj3array[0]=IKsin(j3array[0]);
26427 cj3array[0]=IKcos(j3array[0]);
26428 if( j3array[0] > IKPI )
26429 {
26430     j3array[0]-=IK2PI;
26431 }
26432 else if( j3array[0] < -IKPI )
26433 {    j3array[0]+=IK2PI;
26434 }
26435 j3valid[0] = true;
26436 for(int ij3 = 0; ij3 < 1; ++ij3)
26437 {
26438 if( !j3valid[ij3] )
26439 {
26440     continue;
26441 }
26442 _ij3[0] = ij3; _ij3[1] = -1;
26443 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26444 {
26445 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26446 {
26447     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26448 }
26449 }
26450 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26451 {
26452 IkReal evalcond[6];
26453 IkReal x8181=IKsin(j3);
26454 IkReal x8182=IKcos(j3);
26455 IkReal x8183=((sj0)*(sj5));
26456 IkReal x8184=((r00)*(sj6));
26457 IkReal x8185=((cj6)*(r01));
26458 IkReal x8186=((cj4)*(cj5));
26459 IkReal x8187=((IkReal(1.00000000000000))*(cj0));
26460 IkReal x8188=((cj5)*(r12));
26461 IkReal x8189=((IkReal(1.00000000000000))*(sj0));
26462 IkReal x8190=((cj6)*(r11));
26463 IkReal x8191=((cj5)*(r02));
26464 IkReal x8192=((IkReal(1.00000000000000))*(cj1));
26465 IkReal x8193=((cj6)*(sj4));
26466 IkReal x8194=((cj6)*(r21));
26467 IkReal x8195=((r20)*(sj6));
26468 IkReal x8196=((r10)*(sj6));
26469 IkReal x8197=((sj4)*(sj6));
26470 IkReal x8198=((cj4)*(r02));
26471 IkReal x8199=((IkReal(1.00000000000000))*(cj4)*(r12));
26472 IkReal x8200=((IkReal(1.00000000000000))*(x8181));
26473 IkReal x8201=((cj0)*(x8197));
26474 evalcond[0]=((((sj5)*(x8194)))+(((sj5)*(x8195)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x8182))));
26475 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x8197)))+(((IkReal(-1.00000000000000))*(sj1)*(x8200)))+(((cj4)*(r22)*(sj5)))+(((x8186)*(x8195)))+(((r20)*(x8193)))+(((x8186)*(x8194))));
26476 evalcond[2]=((((IkReal(-1.00000000000000))*(x8200)))+(((cj0)*(x8188)))+(((x8183)*(x8185)))+(((IkReal(-1.00000000000000))*(x8189)*(x8191)))+(((x8183)*(x8184)))+(((IkReal(-1.00000000000000))*(sj5)*(x8187)*(x8196)))+(((IkReal(-1.00000000000000))*(sj5)*(x8187)*(x8190))));
26477 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x8185)*(x8187)))+(((IkReal(-1.00000000000000))*(x8183)*(x8190)))+(((IkReal(-1.00000000000000))*(x8183)*(x8196)))+(((IkReal(-1.00000000000000))*(sj5)*(x8184)*(x8187)))+(((IkReal(-1.00000000000000))*(x8182)*(x8192)))+(((sj0)*(x8188)))+(((cj0)*(x8191))));
26478 evalcond[4]=((((IkReal(-1.00000000000000))*(x8186)*(x8187)*(x8190)))+(((IkReal(-1.00000000000000))*(r01)*(x8189)*(x8197)))+(((IkReal(-1.00000000000000))*(x8186)*(x8187)*(x8196)))+(x8182)+(((sj0)*(x8185)*(x8186)))+(((IkReal(-1.00000000000000))*(r10)*(x8187)*(x8193)))+(((r11)*(x8201)))+(((sj0)*(x8184)*(x8186)))+(((x8183)*(x8198)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x8187)))+(((r00)*(sj0)*(x8193))));
26479 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x8189)*(x8193)))+(((IkReal(-1.00000000000000))*(x8185)*(x8186)*(x8187)))+(((IkReal(-1.00000000000000))*(x8186)*(x8189)*(x8196)))+(((IkReal(-1.00000000000000))*(x8183)*(x8199)))+(((r01)*(x8201)))+(((IkReal(-1.00000000000000))*(sj5)*(x8187)*(x8198)))+(((IkReal(-1.00000000000000))*(x8181)*(x8192)))+(((IkReal(-1.00000000000000))*(x8184)*(x8186)*(x8187)))+(((r11)*(sj0)*(x8197)))+(((IkReal(-1.00000000000000))*(x8186)*(x8189)*(x8190)))+(((IkReal(-1.00000000000000))*(r00)*(x8187)*(x8193))));
26480 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
26481 {
26482 continue;
26483 }
26484 }
26485 
26486 {
26487 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26488 vinfos[0].jointtype = 1;
26489 vinfos[0].foffset = j0;
26490 vinfos[0].indices[0] = _ij0[0];
26491 vinfos[0].indices[1] = _ij0[1];
26492 vinfos[0].maxsolutions = _nj0;
26493 vinfos[1].jointtype = 1;
26494 vinfos[1].foffset = j1;
26495 vinfos[1].indices[0] = _ij1[0];
26496 vinfos[1].indices[1] = _ij1[1];
26497 vinfos[1].maxsolutions = _nj1;
26498 vinfos[2].jointtype = 1;
26499 vinfos[2].foffset = j2;
26500 vinfos[2].indices[0] = _ij2[0];
26501 vinfos[2].indices[1] = _ij2[1];
26502 vinfos[2].maxsolutions = _nj2;
26503 vinfos[3].jointtype = 1;
26504 vinfos[3].foffset = j3;
26505 vinfos[3].indices[0] = _ij3[0];
26506 vinfos[3].indices[1] = _ij3[1];
26507 vinfos[3].maxsolutions = _nj3;
26508 vinfos[4].jointtype = 1;
26509 vinfos[4].foffset = j4;
26510 vinfos[4].indices[0] = _ij4[0];
26511 vinfos[4].indices[1] = _ij4[1];
26512 vinfos[4].maxsolutions = _nj4;
26513 vinfos[5].jointtype = 1;
26514 vinfos[5].foffset = j5;
26515 vinfos[5].indices[0] = _ij5[0];
26516 vinfos[5].indices[1] = _ij5[1];
26517 vinfos[5].maxsolutions = _nj5;
26518 vinfos[6].jointtype = 1;
26519 vinfos[6].foffset = j6;
26520 vinfos[6].indices[0] = _ij6[0];
26521 vinfos[6].indices[1] = _ij6[1];
26522 vinfos[6].maxsolutions = _nj6;
26523 std::vector<int> vfree(0);
26524 solutions.AddSolution(vinfos,vfree);
26525 }
26526 }
26527 }
26528 
26529 }
26530 
26531 }
26532 
26533 } else
26534 {
26535 IkReal x8202=((IkReal(1.00000000000000))*(cj0));
26536 IkReal x8203=((cj4)*(sj6));
26537 IkReal x8204=((sj0)*(sj4));
26538 IkReal x8205=((cj5)*(sj6));
26539 IkReal x8206=((sj4)*(sj5));
26540 IkReal x8207=((r12)*(sj5));
26541 IkReal x8208=((IkReal(0.374290000000000))*(cj5));
26542 IkReal x8209=((r02)*(sj0));
26543 IkReal x8210=((IkReal(1.00000000000000))*(sj0));
26544 IkReal x8211=((cj0)*(r10));
26545 IkReal x8212=((cj4)*(cj6));
26546 IkReal x8213=((r00)*(sj0));
26547 IkReal x8214=((cj6)*(r21));
26548 IkReal x8215=((IkReal(0.374290000000000))*(sj5));
26549 IkReal x8216=((cj0)*(r00));
26550 IkReal x8217=((IkReal(0.0100000000000000))*(sj5));
26551 IkReal x8218=((cj0)*(r02));
26552 IkReal x8219=((cj5)*(sj4));
26553 IkReal x8220=((cj6)*(r01));
26554 IkReal x8221=((cj6)*(r11));
26555 IkReal x8222=((r01)*(sj0));
26556 IkReal x8223=((r10)*(sj0));
26557 IkReal x8224=((IkReal(0.0100000000000000))*(cj5)*(cj6));
26558 IkReal x8225=((sj6)*(x8215));
26559 IkReal x8226=((cj0)*(cj6)*(x8215));
26560 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
26561 evalcond[1]=((((r21)*(x8203)))+(((r22)*(x8206)))+(((x8214)*(x8219)))+(cj1)+(((IkReal(-1.00000000000000))*(r20)*(x8212)))+(((r20)*(sj4)*(x8205))));
26562 evalcond[2]=((((r20)*(x8225)))+(((IkReal(-0.0100000000000000))*(cj5)*(x8214)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x8217)))+(((IkReal(-1.00000000000000))*(r22)*(x8208)))+(pz)+(((x8214)*(x8215)))+(((IkReal(-0.0100000000000000))*(r20)*(x8205))));
26563 evalcond[3]=((((IkReal(-1.00000000000000))*(x8202)*(x8219)*(x8221)))+(((IkReal(-1.00000000000000))*(r11)*(x8202)*(x8203)))+(((x8211)*(x8212)))+(((r02)*(sj5)*(x8204)))+(((IkReal(-1.00000000000000))*(r12)*(x8202)*(x8206)))+(((r00)*(x8204)*(x8205)))+(((cj5)*(x8204)*(x8220)))+(((IkReal(-1.00000000000000))*(r00)*(x8210)*(x8212)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x8202)*(x8205)))+(((x8203)*(x8222))));
26564 evalcond[4]=((((IkReal(-1.00000000000000))*(cj5)*(x8204)*(x8221)))+(((IkReal(-1.00000000000000))*(r02)*(x8202)*(x8206)))+(((IkReal(-1.00000000000000))*(r01)*(x8202)*(x8203)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x8202)*(x8205)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r11)*(x8203)*(x8210)))+(((IkReal(-1.00000000000000))*(x8202)*(x8219)*(x8220)))+(((IkReal(-1.00000000000000))*(r10)*(x8204)*(x8205)))+(((x8212)*(x8223)))+(((IkReal(-1.00000000000000))*(x8204)*(x8207)))+(((x8212)*(x8216))));
26565 evalcond[5]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x8202)))+(((IkReal(-1.00000000000000))*(x8211)*(x8225)))+(((IkReal(-0.0100000000000000))*(x8205)*(x8213)))+(((IkReal(-1.00000000000000))*(x8208)*(x8209)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x8221)))+(((IkReal(-1.00000000000000))*(cj0)*(x8215)*(x8221)))+(((IkReal(0.0100000000000000))*(x8205)*(x8211)))+(((IkReal(-1.00000000000000))*(x8209)*(x8217)))+(((sj0)*(x8215)*(x8220)))+(((x8213)*(x8225)))+(((cj0)*(r12)*(x8208)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x8220)))+(((IkReal(0.0100000000000000))*(cj0)*(x8207))));
26566 evalcond[6]=((IkReal(0.0690000000000000))+(((x8208)*(x8218)))+(((IkReal(0.0100000000000000))*(sj0)*(x8207)))+(((r12)*(sj0)*(x8208)))+(((IkReal(-1.00000000000000))*(x8223)*(x8225)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x8221)))+(((IkReal(-1.00000000000000))*(cj0)*(x8215)*(x8220)))+(((IkReal(-1.00000000000000))*(sj0)*(x8215)*(x8221)))+(((IkReal(-1.00000000000000))*(x8216)*(x8225)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x8220)))+(((IkReal(0.0100000000000000))*(x8205)*(x8223)))+(((IkReal(-1.00000000000000))*(px)*(x8202)))+(((x8217)*(x8218)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(0.0100000000000000))*(x8205)*(x8216)))+(((IkReal(-1.00000000000000))*(py)*(x8210))));
26567 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
26568 {
26569 {
26570 IkReal dummyeval[1];
26571 IkReal gconst12;
26572 gconst12=IKsign(sj1);
26573 dummyeval[0]=sj1;
26574 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
26575 {
26576 {
26577 IkReal dummyeval[1];
26578 dummyeval[0]=sj1;
26579 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
26580 {
26581 {
26582 IkReal dummyeval[1];
26583 dummyeval[0]=cj1;
26584 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
26585 {
26586 {
26587 IkReal evalcond[9];
26588 IkReal x8227=((IkReal(1.00000000000000))*(cj0));
26589 IkReal x8228=((cj4)*(sj6));
26590 IkReal x8229=((sj0)*(sj6));
26591 IkReal x8230=((cj5)*(sj4));
26592 IkReal x8231=((IkReal(0.374290000000000))*(sj5));
26593 IkReal x8232=((sj4)*(sj5));
26594 IkReal x8233=((cj0)*(cj6));
26595 IkReal x8234=((IkReal(0.0100000000000000))*(cj5));
26596 IkReal x8235=((cj4)*(sj5));
26597 IkReal x8236=((cj5)*(sj0));
26598 IkReal x8237=((IkReal(0.374290000000000))*(r02));
26599 IkReal x8238=((r20)*(sj6));
26600 IkReal x8239=((cj6)*(r21));
26601 IkReal x8240=((IkReal(1.00000000000000))*(sj0));
26602 IkReal x8241=((cj0)*(sj6));
26603 IkReal x8242=((cj4)*(cj6));
26604 IkReal x8243=((IkReal(0.374290000000000))*(r12));
26605 IkReal x8244=((cj0)*(cj5));
26606 IkReal x8245=((cj6)*(sj5));
26607 IkReal x8246=((cj6)*(r01));
26608 IkReal x8247=((r00)*(sj6));
26609 IkReal x8248=((IkReal(0.0100000000000000))*(sj5));
26610 IkReal x8249=((cj6)*(r11));
26611 IkReal x8250=((IkReal(1.00000000000000))*(r10));
26612 IkReal x8251=((r02)*(sj0));
26613 IkReal x8252=((cj6)*(sj4));
26614 IkReal x8253=((r12)*(x8240));
26615 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
26616 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x8242)))+(((x8230)*(x8239)))+(((x8230)*(x8238)))+(((r21)*(x8228)))+(((r22)*(x8232))));
26617 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(x8234)*(x8238)))+(((IkReal(-1.00000000000000))*(x8234)*(x8239)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x8231)*(x8239)))+(((x8231)*(x8238)))+(((IkReal(-1.00000000000000))*(r22)*(x8248)))+(pz));
26618 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x8240)*(x8245)))+(((IkReal(-1.00000000000000))*(r01)*(x8227)*(x8245)))+(((IkReal(-1.00000000000000))*(sj5)*(x8229)*(x8250)))+(((IkReal(-1.00000000000000))*(sj5)*(x8227)*(x8247)))+(((r02)*(x8244)))+(((r12)*(x8236))));
26619 evalcond[4]=((((sj0)*(x8230)*(x8246)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x8227)*(x8230)))+(((IkReal(-1.00000000000000))*(r00)*(x8240)*(x8242)))+(((r00)*(x8229)*(x8230)))+(((IkReal(-1.00000000000000))*(r11)*(x8227)*(x8228)))+(((x8232)*(x8251)))+(((IkReal(-1.00000000000000))*(r12)*(x8227)*(x8232)))+(((IkReal(-1.00000000000000))*(x8227)*(x8230)*(x8249)))+(((r01)*(sj0)*(x8228)))+(((cj4)*(r10)*(x8233))));
26620 evalcond[5]=((IkReal(-1.00000000000000))+(((cj4)*(r00)*(x8233)))+(((IkReal(-1.00000000000000))*(r11)*(x8228)*(x8240)))+(((IkReal(-1.00000000000000))*(r01)*(x8227)*(x8228)))+(((IkReal(-1.00000000000000))*(r02)*(x8227)*(x8232)))+(((r10)*(sj0)*(x8242)))+(((IkReal(-1.00000000000000))*(x8230)*(x8240)*(x8249)))+(((IkReal(-1.00000000000000))*(x8227)*(x8230)*(x8247)))+(((IkReal(-1.00000000000000))*(x8229)*(x8230)*(x8250)))+(((IkReal(-1.00000000000000))*(x8227)*(x8230)*(x8246)))+(((IkReal(-1.00000000000000))*(x8232)*(x8253))));
26621 evalcond[6]=((IkReal(-0.0690000000000000))+(((r10)*(x8234)*(x8241)))+(((IkReal(-1.00000000000000))*(py)*(x8227)))+(((IkReal(-1.00000000000000))*(r00)*(x8229)*(x8234)))+(((IkReal(-1.00000000000000))*(x8248)*(x8251)))+(((r11)*(x8233)*(x8234)))+(((r00)*(x8229)*(x8231)))+(((IkReal(-1.00000000000000))*(r10)*(x8231)*(x8241)))+(((IkReal(-1.00000000000000))*(r11)*(x8231)*(x8233)))+(((sj0)*(x8231)*(x8246)))+(((IkReal(-1.00000000000000))*(sj0)*(x8234)*(x8246)))+(((x8243)*(x8244)))+(((cj0)*(r12)*(x8248)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x8236)*(x8237))));
26622 evalcond[7]=((((IkReal(-1.00000000000000))*(r02)*(x8227)*(x8235)))+(((IkReal(-1.00000000000000))*(x8228)*(x8236)*(x8250)))+(((IkReal(-1.00000000000000))*(r10)*(x8240)*(x8252)))+(((r01)*(sj4)*(x8241)))+(((IkReal(-1.00000000000000))*(r11)*(x8236)*(x8242)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x8227)*(x8242)))+(((IkReal(-1.00000000000000))*(x8235)*(x8253)))+(((IkReal(-1.00000000000000))*(r00)*(x8227)*(x8252)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8227)*(x8228)))+(((r11)*(sj4)*(x8229))));
26623 evalcond[8]=((IkReal(0.0690000000000000))+(((cj0)*(r02)*(x8248)))+(((IkReal(-1.00000000000000))*(px)*(x8227)))+(((x8237)*(x8244)))+(((sj0)*(x8234)*(x8249)))+(((r12)*(sj0)*(x8248)))+(((IkReal(-1.00000000000000))*(r01)*(x8231)*(x8233)))+(((IkReal(-1.00000000000000))*(r10)*(x8229)*(x8231)))+(((IkReal(-1.00000000000000))*(sj0)*(x8231)*(x8249)))+(((IkReal(-1.00000000000000))*(r00)*(x8231)*(x8241)))+(((r01)*(x8233)*(x8234)))+(((x8236)*(x8243)))+(((r10)*(x8229)*(x8234)))+(((IkReal(-1.00000000000000))*(py)*(x8240)))+(((r00)*(x8234)*(x8241))));
26624 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
26625 {
26626 {
26627 IkReal j3array[1], cj3array[1], sj3array[1];
26628 bool j3valid[1]={false};
26629 _nj3 = 1;
26630 IkReal x8254=((r20)*(sj6));
26631 IkReal x8255=((cj4)*(cj5));
26632 IkReal x8256=((cj6)*(r21));
26633 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8254)*(x8255)))+(((x8255)*(x8256))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x8256)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8254))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8254)*(x8255)))+(((x8255)*(x8256)))))+IKsqr(((((sj5)*(x8256)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8254)))))-1) <= IKFAST_SINCOS_THRESH )
26634     continue;
26635 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8254)*(x8255)))+(((x8255)*(x8256)))), ((((sj5)*(x8256)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8254)))));
26636 sj3array[0]=IKsin(j3array[0]);
26637 cj3array[0]=IKcos(j3array[0]);
26638 if( j3array[0] > IKPI )
26639 {
26640     j3array[0]-=IK2PI;
26641 }
26642 else if( j3array[0] < -IKPI )
26643 {    j3array[0]+=IK2PI;
26644 }
26645 j3valid[0] = true;
26646 for(int ij3 = 0; ij3 < 1; ++ij3)
26647 {
26648 if( !j3valid[ij3] )
26649 {
26650     continue;
26651 }
26652 _ij3[0] = ij3; _ij3[1] = -1;
26653 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26654 {
26655 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26656 {
26657     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26658 }
26659 }
26660 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26661 {
26662 IkReal evalcond[4];
26663 IkReal x8257=IKsin(j3);
26664 IkReal x8258=((sj0)*(sj5));
26665 IkReal x8259=((r00)*(sj6));
26666 IkReal x8260=((cj6)*(r01));
26667 IkReal x8261=((cj5)*(sj0));
26668 IkReal x8262=((cj0)*(cj5));
26669 IkReal x8263=((cj6)*(sj4));
26670 IkReal x8264=((sj4)*(sj6));
26671 IkReal x8265=((cj0)*(r11));
26672 IkReal x8266=((cj4)*(cj6));
26673 IkReal x8267=((cj4)*(sj6));
26674 IkReal x8268=((IkReal(1.00000000000000))*(cj0));
26675 IkReal x8269=((cj4)*(sj5));
26676 IkReal x8270=((sj5)*(sj6));
26677 IkReal x8271=((cj6)*(sj5));
26678 IkReal x8272=((IkReal(1.00000000000000))*(IKcos(j3)));
26679 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x8272)))+(((r20)*(x8270)))+(((r21)*(x8271))));
26680 evalcond[1]=((((cj5)*(r20)*(x8267)))+(((r22)*(x8269)))+(((IkReal(-1.00000000000000))*(r21)*(x8264)))+(((cj5)*(r21)*(x8266)))+(((r20)*(x8263)))+(((IkReal(-1.00000000000000))*(x8257))));
26681 evalcond[2]=((((r12)*(x8262)))+(((IkReal(-1.00000000000000))*(x8265)*(x8271)))+(((x8258)*(x8260)))+(((IkReal(-1.00000000000000))*(r10)*(x8268)*(x8270)))+(((x8258)*(x8259)))+(x8257)+(((IkReal(-1.00000000000000))*(r02)*(x8261))));
26682 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x8262)*(x8267)))+(((cj4)*(x8259)*(x8261)))+(((r00)*(sj0)*(x8263)))+(((x8264)*(x8265)))+(((IkReal(-1.00000000000000))*(x8272)))+(((IkReal(-1.00000000000000))*(r10)*(x8263)*(x8268)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x8264)))+(((IkReal(-1.00000000000000))*(r12)*(x8268)*(x8269)))+(((cj4)*(r02)*(x8258)))+(((cj4)*(x8260)*(x8261)))+(((IkReal(-1.00000000000000))*(r11)*(x8262)*(x8266))));
26683 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
26684 {
26685 continue;
26686 }
26687 }
26688 
26689 {
26690 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26691 vinfos[0].jointtype = 1;
26692 vinfos[0].foffset = j0;
26693 vinfos[0].indices[0] = _ij0[0];
26694 vinfos[0].indices[1] = _ij0[1];
26695 vinfos[0].maxsolutions = _nj0;
26696 vinfos[1].jointtype = 1;
26697 vinfos[1].foffset = j1;
26698 vinfos[1].indices[0] = _ij1[0];
26699 vinfos[1].indices[1] = _ij1[1];
26700 vinfos[1].maxsolutions = _nj1;
26701 vinfos[2].jointtype = 1;
26702 vinfos[2].foffset = j2;
26703 vinfos[2].indices[0] = _ij2[0];
26704 vinfos[2].indices[1] = _ij2[1];
26705 vinfos[2].maxsolutions = _nj2;
26706 vinfos[3].jointtype = 1;
26707 vinfos[3].foffset = j3;
26708 vinfos[3].indices[0] = _ij3[0];
26709 vinfos[3].indices[1] = _ij3[1];
26710 vinfos[3].maxsolutions = _nj3;
26711 vinfos[4].jointtype = 1;
26712 vinfos[4].foffset = j4;
26713 vinfos[4].indices[0] = _ij4[0];
26714 vinfos[4].indices[1] = _ij4[1];
26715 vinfos[4].maxsolutions = _nj4;
26716 vinfos[5].jointtype = 1;
26717 vinfos[5].foffset = j5;
26718 vinfos[5].indices[0] = _ij5[0];
26719 vinfos[5].indices[1] = _ij5[1];
26720 vinfos[5].maxsolutions = _nj5;
26721 vinfos[6].jointtype = 1;
26722 vinfos[6].foffset = j6;
26723 vinfos[6].indices[0] = _ij6[0];
26724 vinfos[6].indices[1] = _ij6[1];
26725 vinfos[6].maxsolutions = _nj6;
26726 std::vector<int> vfree(0);
26727 solutions.AddSolution(vinfos,vfree);
26728 }
26729 }
26730 }
26731 
26732 } else
26733 {
26734 IkReal x8273=((IkReal(1.00000000000000))*(cj0));
26735 IkReal x8274=((cj4)*(sj6));
26736 IkReal x8275=((sj0)*(sj6));
26737 IkReal x8276=((cj5)*(sj4));
26738 IkReal x8277=((IkReal(0.374290000000000))*(sj5));
26739 IkReal x8278=((sj4)*(sj5));
26740 IkReal x8279=((cj0)*(cj6));
26741 IkReal x8280=((IkReal(0.0100000000000000))*(cj5));
26742 IkReal x8281=((cj4)*(sj5));
26743 IkReal x8282=((cj5)*(sj0));
26744 IkReal x8283=((IkReal(0.374290000000000))*(r02));
26745 IkReal x8284=((r20)*(sj6));
26746 IkReal x8285=((cj6)*(r21));
26747 IkReal x8286=((IkReal(1.00000000000000))*(sj0));
26748 IkReal x8287=((cj0)*(sj6));
26749 IkReal x8288=((cj4)*(cj6));
26750 IkReal x8289=((IkReal(0.374290000000000))*(r12));
26751 IkReal x8290=((cj0)*(cj5));
26752 IkReal x8291=((cj6)*(sj5));
26753 IkReal x8292=((cj6)*(r01));
26754 IkReal x8293=((r00)*(sj6));
26755 IkReal x8294=((IkReal(0.0100000000000000))*(sj5));
26756 IkReal x8295=((cj6)*(r11));
26757 IkReal x8296=((IkReal(1.00000000000000))*(r10));
26758 IkReal x8297=((r02)*(sj0));
26759 IkReal x8298=((cj6)*(sj4));
26760 IkReal x8299=((r12)*(x8286));
26761 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
26762 evalcond[1]=((((x8276)*(x8285)))+(((r22)*(x8278)))+(((x8276)*(x8284)))+(((IkReal(-1.00000000000000))*(r20)*(x8288)))+(((r21)*(x8274))));
26763 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(r22)*(x8294)))+(((IkReal(-1.00000000000000))*(x8280)*(x8284)))+(((IkReal(-1.00000000000000))*(x8280)*(x8285)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x8277)*(x8284)))+(((x8277)*(x8285))));
26764 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x8275)*(x8296)))+(((r12)*(x8282)))+(((r02)*(x8290)))+(((IkReal(-1.00000000000000))*(r11)*(x8286)*(x8291)))+(((IkReal(-1.00000000000000))*(r01)*(x8273)*(x8291)))+(((IkReal(-1.00000000000000))*(sj5)*(x8273)*(x8293))));
26765 evalcond[4]=((((x8278)*(x8297)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x8273)*(x8276)))+(((r00)*(x8275)*(x8276)))+(((IkReal(-1.00000000000000))*(r12)*(x8273)*(x8278)))+(((IkReal(-1.00000000000000))*(r11)*(x8273)*(x8274)))+(((r01)*(sj0)*(x8274)))+(((IkReal(-1.00000000000000))*(x8273)*(x8276)*(x8295)))+(((IkReal(-1.00000000000000))*(r00)*(x8286)*(x8288)))+(((cj4)*(r10)*(x8279)))+(((sj0)*(x8276)*(x8292))));
26766 evalcond[5]=((IkReal(1.00000000000000))+(((r10)*(sj0)*(x8288)))+(((cj4)*(r00)*(x8279)))+(((IkReal(-1.00000000000000))*(r01)*(x8273)*(x8274)))+(((IkReal(-1.00000000000000))*(r11)*(x8274)*(x8286)))+(((IkReal(-1.00000000000000))*(x8273)*(x8276)*(x8292)))+(((IkReal(-1.00000000000000))*(x8276)*(x8286)*(x8295)))+(((IkReal(-1.00000000000000))*(r02)*(x8273)*(x8278)))+(((IkReal(-1.00000000000000))*(x8278)*(x8299)))+(((IkReal(-1.00000000000000))*(x8275)*(x8276)*(x8296)))+(((IkReal(-1.00000000000000))*(x8273)*(x8276)*(x8293))));
26767 evalcond[6]=((IkReal(-0.0690000000000000))+(((x8289)*(x8290)))+(((r11)*(x8279)*(x8280)))+(((IkReal(-1.00000000000000))*(r11)*(x8277)*(x8279)))+(((cj0)*(r12)*(x8294)))+(((IkReal(-1.00000000000000))*(r00)*(x8275)*(x8280)))+(((IkReal(-1.00000000000000))*(r10)*(x8277)*(x8287)))+(((IkReal(-1.00000000000000))*(sj0)*(x8280)*(x8292)))+(((IkReal(-1.00000000000000))*(x8282)*(x8283)))+(((IkReal(-1.00000000000000))*(py)*(x8273)))+(((sj0)*(x8277)*(x8292)))+(((px)*(sj0)))+(((r10)*(x8280)*(x8287)))+(((r00)*(x8275)*(x8277)))+(((IkReal(-1.00000000000000))*(x8294)*(x8297))));
26768 evalcond[7]=((((IkReal(-1.00000000000000))*(r10)*(x8286)*(x8298)))+(((IkReal(-1.00000000000000))*(x8281)*(x8299)))+(((IkReal(-1.00000000000000))*(r00)*(x8273)*(x8298)))+(((IkReal(-1.00000000000000))*(r02)*(x8273)*(x8281)))+(((IkReal(-1.00000000000000))*(x8274)*(x8282)*(x8296)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x8273)*(x8288)))+(((r11)*(sj4)*(x8275)))+(((r01)*(sj4)*(x8287)))+(((IkReal(-1.00000000000000))*(r11)*(x8282)*(x8288)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8273)*(x8274))));
26769 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x8273)))+(((IkReal(-1.00000000000000))*(py)*(x8286)))+(((r12)*(sj0)*(x8294)))+(((x8283)*(x8290)))+(((r10)*(x8275)*(x8280)))+(((r01)*(x8279)*(x8280)))+(((IkReal(-1.00000000000000))*(r00)*(x8277)*(x8287)))+(((IkReal(-1.00000000000000))*(sj0)*(x8277)*(x8295)))+(((cj0)*(r02)*(x8294)))+(((sj0)*(x8280)*(x8295)))+(((IkReal(-1.00000000000000))*(r10)*(x8275)*(x8277)))+(((IkReal(-1.00000000000000))*(r01)*(x8277)*(x8279)))+(((x8282)*(x8289)))+(((r00)*(x8280)*(x8287))));
26770 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
26771 {
26772 {
26773 IkReal j3array[1], cj3array[1], sj3array[1];
26774 bool j3valid[1]={false};
26775 _nj3 = 1;
26776 IkReal x8300=((IkReal(1.00000000000000))*(sj5));
26777 IkReal x8301=((cj6)*(r21));
26778 IkReal x8302=((r20)*(sj6));
26779 IkReal x8303=((IkReal(1.00000000000000))*(cj4)*(cj5));
26780 if( IKabs(((((IkReal(-1.00000000000000))*(x8302)*(x8303)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8300)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8301)*(x8303)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x8300)*(x8301)))+(((IkReal(-1.00000000000000))*(x8300)*(x8302)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x8302)*(x8303)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8300)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8301)*(x8303)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x8300)*(x8301)))+(((IkReal(-1.00000000000000))*(x8300)*(x8302)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
26781     continue;
26782 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x8302)*(x8303)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x8300)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8301)*(x8303)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x8300)*(x8301)))+(((IkReal(-1.00000000000000))*(x8300)*(x8302)))+(((cj5)*(r22)))));
26783 sj3array[0]=IKsin(j3array[0]);
26784 cj3array[0]=IKcos(j3array[0]);
26785 if( j3array[0] > IKPI )
26786 {
26787     j3array[0]-=IK2PI;
26788 }
26789 else if( j3array[0] < -IKPI )
26790 {    j3array[0]+=IK2PI;
26791 }
26792 j3valid[0] = true;
26793 for(int ij3 = 0; ij3 < 1; ++ij3)
26794 {
26795 if( !j3valid[ij3] )
26796 {
26797     continue;
26798 }
26799 _ij3[0] = ij3; _ij3[1] = -1;
26800 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26801 {
26802 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26803 {
26804     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26805 }
26806 }
26807 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26808 {
26809 IkReal evalcond[4];
26810 IkReal x8304=IKsin(j3);
26811 IkReal x8305=IKcos(j3);
26812 IkReal x8306=((sj0)*(sj5));
26813 IkReal x8307=((r00)*(sj6));
26814 IkReal x8308=((cj6)*(r01));
26815 IkReal x8309=((cj0)*(cj5));
26816 IkReal x8310=((IkReal(1.00000000000000))*(cj5));
26817 IkReal x8311=((cj4)*(cj5));
26818 IkReal x8312=((cj6)*(sj4));
26819 IkReal x8313=((sj4)*(sj6));
26820 IkReal x8314=((cj0)*(r11));
26821 IkReal x8315=((IkReal(1.00000000000000))*(cj4));
26822 IkReal x8316=((cj6)*(r21));
26823 IkReal x8317=((r20)*(sj6));
26824 IkReal x8318=((cj0)*(sj5));
26825 IkReal x8319=((r10)*(sj6));
26826 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x8310)))+(x8305)+(((sj5)*(x8316)))+(((sj5)*(x8317))));
26827 evalcond[1]=((((x8311)*(x8317)))+(((x8311)*(x8316)))+(((r20)*(x8312)))+(((cj4)*(r22)*(sj5)))+(x8304)+(((IkReal(-1.00000000000000))*(r21)*(x8313))));
26828 evalcond[2]=((((r12)*(x8309)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8310)))+(((x8306)*(x8308)))+(((x8306)*(x8307)))+(((IkReal(-1.00000000000000))*(x8318)*(x8319)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x8314)))+(x8304));
26829 evalcond[3]=((((sj0)*(x8308)*(x8311)))+(((x8313)*(x8314)))+(((IkReal(-1.00000000000000))*(x8309)*(x8315)*(x8319)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x8313)))+(((sj0)*(x8307)*(x8311)))+(((IkReal(-1.00000000000000))*(x8305)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x8312)))+(((IkReal(-1.00000000000000))*(r12)*(x8315)*(x8318)))+(((cj4)*(r02)*(x8306)))+(((r00)*(sj0)*(x8312)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x8309)*(x8315))));
26830 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
26831 {
26832 continue;
26833 }
26834 }
26835 
26836 {
26837 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26838 vinfos[0].jointtype = 1;
26839 vinfos[0].foffset = j0;
26840 vinfos[0].indices[0] = _ij0[0];
26841 vinfos[0].indices[1] = _ij0[1];
26842 vinfos[0].maxsolutions = _nj0;
26843 vinfos[1].jointtype = 1;
26844 vinfos[1].foffset = j1;
26845 vinfos[1].indices[0] = _ij1[0];
26846 vinfos[1].indices[1] = _ij1[1];
26847 vinfos[1].maxsolutions = _nj1;
26848 vinfos[2].jointtype = 1;
26849 vinfos[2].foffset = j2;
26850 vinfos[2].indices[0] = _ij2[0];
26851 vinfos[2].indices[1] = _ij2[1];
26852 vinfos[2].maxsolutions = _nj2;
26853 vinfos[3].jointtype = 1;
26854 vinfos[3].foffset = j3;
26855 vinfos[3].indices[0] = _ij3[0];
26856 vinfos[3].indices[1] = _ij3[1];
26857 vinfos[3].maxsolutions = _nj3;
26858 vinfos[4].jointtype = 1;
26859 vinfos[4].foffset = j4;
26860 vinfos[4].indices[0] = _ij4[0];
26861 vinfos[4].indices[1] = _ij4[1];
26862 vinfos[4].maxsolutions = _nj4;
26863 vinfos[5].jointtype = 1;
26864 vinfos[5].foffset = j5;
26865 vinfos[5].indices[0] = _ij5[0];
26866 vinfos[5].indices[1] = _ij5[1];
26867 vinfos[5].maxsolutions = _nj5;
26868 vinfos[6].jointtype = 1;
26869 vinfos[6].foffset = j6;
26870 vinfos[6].indices[0] = _ij6[0];
26871 vinfos[6].indices[1] = _ij6[1];
26872 vinfos[6].maxsolutions = _nj6;
26873 std::vector<int> vfree(0);
26874 solutions.AddSolution(vinfos,vfree);
26875 }
26876 }
26877 }
26878 
26879 } else
26880 {
26881 if( 1 )
26882 {
26883 continue;
26884 
26885 } else
26886 {
26887 }
26888 }
26889 }
26890 }
26891 
26892 } else
26893 {
26894 {
26895 IkReal j3array[1], cj3array[1], sj3array[1];
26896 bool j3valid[1]={false};
26897 _nj3 = 1;
26898 IkReal x8320=((cj5)*(r02));
26899 IkReal x8321=((cj0)*(sj5));
26900 IkReal x8322=((r10)*(sj6));
26901 IkReal x8323=((IkReal(1.00000000000000))*(cj6));
26902 IkReal x8324=((sj0)*(sj5));
26903 IkReal x8325=((cj5)*(r12));
26904 IkReal x8326=((IkReal(1.00000000000000))*(r00)*(sj6));
26905 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x8325)))+(((x8321)*(x8322)))+(((sj0)*(x8320)))+(((IkReal(-1.00000000000000))*(x8324)*(x8326)))+(((IkReal(-1.00000000000000))*(r01)*(x8323)*(x8324)))+(((cj6)*(r11)*(x8321))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x8325)))+(((IkReal(-1.00000000000000))*(x8322)*(x8324)))+(((IkReal(-1.00000000000000))*(r11)*(x8323)*(x8324)))+(((IkReal(-1.00000000000000))*(r01)*(x8321)*(x8323)))+(((IkReal(-1.00000000000000))*(x8321)*(x8326)))+(((cj0)*(x8320))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x8325)))+(((x8321)*(x8322)))+(((sj0)*(x8320)))+(((IkReal(-1.00000000000000))*(x8324)*(x8326)))+(((IkReal(-1.00000000000000))*(r01)*(x8323)*(x8324)))+(((cj6)*(r11)*(x8321)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x8325)))+(((IkReal(-1.00000000000000))*(x8322)*(x8324)))+(((IkReal(-1.00000000000000))*(r11)*(x8323)*(x8324)))+(((IkReal(-1.00000000000000))*(r01)*(x8321)*(x8323)))+(((IkReal(-1.00000000000000))*(x8321)*(x8326)))+(((cj0)*(x8320)))))))-1) <= IKFAST_SINCOS_THRESH )
26906     continue;
26907 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x8325)))+(((x8321)*(x8322)))+(((sj0)*(x8320)))+(((IkReal(-1.00000000000000))*(x8324)*(x8326)))+(((IkReal(-1.00000000000000))*(r01)*(x8323)*(x8324)))+(((cj6)*(r11)*(x8321)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x8325)))+(((IkReal(-1.00000000000000))*(x8322)*(x8324)))+(((IkReal(-1.00000000000000))*(r11)*(x8323)*(x8324)))+(((IkReal(-1.00000000000000))*(r01)*(x8321)*(x8323)))+(((IkReal(-1.00000000000000))*(x8321)*(x8326)))+(((cj0)*(x8320)))))));
26908 sj3array[0]=IKsin(j3array[0]);
26909 cj3array[0]=IKcos(j3array[0]);
26910 if( j3array[0] > IKPI )
26911 {
26912     j3array[0]-=IK2PI;
26913 }
26914 else if( j3array[0] < -IKPI )
26915 {    j3array[0]+=IK2PI;
26916 }
26917 j3valid[0] = true;
26918 for(int ij3 = 0; ij3 < 1; ++ij3)
26919 {
26920 if( !j3valid[ij3] )
26921 {
26922     continue;
26923 }
26924 _ij3[0] = ij3; _ij3[1] = -1;
26925 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
26926 {
26927 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
26928 {
26929     j3valid[iij3]=false; _ij3[1] = iij3; break; 
26930 }
26931 }
26932 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
26933 {
26934 IkReal evalcond[6];
26935 IkReal x8327=IKsin(j3);
26936 IkReal x8328=IKcos(j3);
26937 IkReal x8329=((sj0)*(sj5));
26938 IkReal x8330=((r00)*(sj6));
26939 IkReal x8331=((IkReal(1.00000000000000))*(cj4));
26940 IkReal x8332=((cj6)*(r01));
26941 IkReal x8333=((cj0)*(cj5));
26942 IkReal x8334=((cj5)*(sj0));
26943 IkReal x8335=((cj6)*(r11));
26944 IkReal x8336=((cj0)*(sj5));
26945 IkReal x8337=((IkReal(1.00000000000000))*(cj1));
26946 IkReal x8338=((cj6)*(sj4));
26947 IkReal x8339=((IkReal(1.00000000000000))*(sj1));
26948 IkReal x8340=((cj4)*(cj5));
26949 IkReal x8341=((cj6)*(r21));
26950 IkReal x8342=((r20)*(sj6));
26951 IkReal x8343=((r10)*(sj6));
26952 IkReal x8344=((IkReal(1.00000000000000))*(cj0));
26953 IkReal x8345=((cj0)*(sj4)*(sj6));
26954 IkReal x8346=((sj0)*(sj4)*(sj6));
26955 evalcond[0]=((((sj5)*(x8342)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x8328)*(x8339)))+(((sj5)*(x8341))));
26956 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8340)*(x8342)))+(((r20)*(x8338)))+(((x8340)*(x8341)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x8327)*(x8339))));
26957 evalcond[2]=((((IkReal(-1.00000000000000))*(x8336)*(x8343)))+(((x8329)*(x8330)))+(((IkReal(-1.00000000000000))*(x8335)*(x8336)))+(x8327)+(((r12)*(x8333)))+(((x8329)*(x8332)))+(((IkReal(-1.00000000000000))*(r02)*(x8334))));
26958 evalcond[3]=((((IkReal(-1.00000000000000))*(x8332)*(x8336)))+(((IkReal(-1.00000000000000))*(x8329)*(x8343)))+(((IkReal(-1.00000000000000))*(x8328)*(x8337)))+(((IkReal(-1.00000000000000))*(x8329)*(x8335)))+(((r02)*(x8333)))+(((IkReal(-1.00000000000000))*(x8330)*(x8336)))+(((r12)*(x8334))));
26959 evalcond[4]=((((cj4)*(r02)*(x8329)))+(((cj4)*(x8332)*(x8334)))+(((IkReal(-1.00000000000000))*(r12)*(x8331)*(x8336)))+(((IkReal(-1.00000000000000))*(r01)*(x8346)))+(((r00)*(sj0)*(x8338)))+(((cj4)*(x8330)*(x8334)))+(((IkReal(-1.00000000000000))*(x8328)))+(((r11)*(x8345)))+(((IkReal(-1.00000000000000))*(r10)*(x8338)*(x8344)))+(((IkReal(-1.00000000000000))*(x8331)*(x8333)*(x8343)))+(((IkReal(-1.00000000000000))*(x8331)*(x8333)*(x8335))));
26960 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x8329)*(x8331)))+(((IkReal(-1.00000000000000))*(x8331)*(x8334)*(x8343)))+(((IkReal(-1.00000000000000))*(x8331)*(x8332)*(x8333)))+(((IkReal(-1.00000000000000))*(x8330)*(x8331)*(x8333)))+(((IkReal(-1.00000000000000))*(x8327)*(x8337)))+(((r01)*(x8345)))+(((IkReal(-1.00000000000000))*(x8331)*(x8334)*(x8335)))+(((IkReal(-1.00000000000000))*(r02)*(x8331)*(x8336)))+(((r11)*(x8346)))+(((IkReal(-1.00000000000000))*(r00)*(x8338)*(x8344)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8338))));
26961 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
26962 {
26963 continue;
26964 }
26965 }
26966 
26967 {
26968 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
26969 vinfos[0].jointtype = 1;
26970 vinfos[0].foffset = j0;
26971 vinfos[0].indices[0] = _ij0[0];
26972 vinfos[0].indices[1] = _ij0[1];
26973 vinfos[0].maxsolutions = _nj0;
26974 vinfos[1].jointtype = 1;
26975 vinfos[1].foffset = j1;
26976 vinfos[1].indices[0] = _ij1[0];
26977 vinfos[1].indices[1] = _ij1[1];
26978 vinfos[1].maxsolutions = _nj1;
26979 vinfos[2].jointtype = 1;
26980 vinfos[2].foffset = j2;
26981 vinfos[2].indices[0] = _ij2[0];
26982 vinfos[2].indices[1] = _ij2[1];
26983 vinfos[2].maxsolutions = _nj2;
26984 vinfos[3].jointtype = 1;
26985 vinfos[3].foffset = j3;
26986 vinfos[3].indices[0] = _ij3[0];
26987 vinfos[3].indices[1] = _ij3[1];
26988 vinfos[3].maxsolutions = _nj3;
26989 vinfos[4].jointtype = 1;
26990 vinfos[4].foffset = j4;
26991 vinfos[4].indices[0] = _ij4[0];
26992 vinfos[4].indices[1] = _ij4[1];
26993 vinfos[4].maxsolutions = _nj4;
26994 vinfos[5].jointtype = 1;
26995 vinfos[5].foffset = j5;
26996 vinfos[5].indices[0] = _ij5[0];
26997 vinfos[5].indices[1] = _ij5[1];
26998 vinfos[5].maxsolutions = _nj5;
26999 vinfos[6].jointtype = 1;
27000 vinfos[6].foffset = j6;
27001 vinfos[6].indices[0] = _ij6[0];
27002 vinfos[6].indices[1] = _ij6[1];
27003 vinfos[6].maxsolutions = _nj6;
27004 std::vector<int> vfree(0);
27005 solutions.AddSolution(vinfos,vfree);
27006 }
27007 }
27008 }
27009 
27010 }
27011 
27012 }
27013 
27014 } else
27015 {
27016 {
27017 IkReal j3array[1], cj3array[1], sj3array[1];
27018 bool j3valid[1]={false};
27019 _nj3 = 1;
27020 IkReal x8347=((sj5)*(sj6));
27021 IkReal x8348=((IkReal(1.00000000000000))*(sj0));
27022 IkReal x8349=((cj6)*(sj5));
27023 IkReal x8350=((IkReal(1.00000000000000))*(cj5));
27024 if( IKabs(((((cj0)*(r10)*(x8347)))+(((IkReal(-1.00000000000000))*(r01)*(x8348)*(x8349)))+(((IkReal(-1.00000000000000))*(r00)*(x8347)*(x8348)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x8349)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x8350))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8347)))+(((IkReal(-1.00000000000000))*(r22)*(x8350)))+(((r21)*(x8349))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r10)*(x8347)))+(((IkReal(-1.00000000000000))*(r01)*(x8348)*(x8349)))+(((IkReal(-1.00000000000000))*(r00)*(x8347)*(x8348)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x8349)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x8350)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8347)))+(((IkReal(-1.00000000000000))*(r22)*(x8350)))+(((r21)*(x8349)))))))-1) <= IKFAST_SINCOS_THRESH )
27025     continue;
27026 j3array[0]=IKatan2(((((cj0)*(r10)*(x8347)))+(((IkReal(-1.00000000000000))*(r01)*(x8348)*(x8349)))+(((IkReal(-1.00000000000000))*(r00)*(x8347)*(x8348)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x8349)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x8350)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x8347)))+(((IkReal(-1.00000000000000))*(r22)*(x8350)))+(((r21)*(x8349)))))));
27027 sj3array[0]=IKsin(j3array[0]);
27028 cj3array[0]=IKcos(j3array[0]);
27029 if( j3array[0] > IKPI )
27030 {
27031     j3array[0]-=IK2PI;
27032 }
27033 else if( j3array[0] < -IKPI )
27034 {    j3array[0]+=IK2PI;
27035 }
27036 j3valid[0] = true;
27037 for(int ij3 = 0; ij3 < 1; ++ij3)
27038 {
27039 if( !j3valid[ij3] )
27040 {
27041     continue;
27042 }
27043 _ij3[0] = ij3; _ij3[1] = -1;
27044 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27045 {
27046 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27047 {
27048     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27049 }
27050 }
27051 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27052 {
27053 IkReal evalcond[6];
27054 IkReal x8351=IKsin(j3);
27055 IkReal x8352=IKcos(j3);
27056 IkReal x8353=((sj0)*(sj5));
27057 IkReal x8354=((r00)*(sj6));
27058 IkReal x8355=((IkReal(1.00000000000000))*(cj4));
27059 IkReal x8356=((cj6)*(r01));
27060 IkReal x8357=((cj0)*(cj5));
27061 IkReal x8358=((cj5)*(sj0));
27062 IkReal x8359=((cj6)*(r11));
27063 IkReal x8360=((cj0)*(sj5));
27064 IkReal x8361=((IkReal(1.00000000000000))*(cj1));
27065 IkReal x8362=((cj6)*(sj4));
27066 IkReal x8363=((IkReal(1.00000000000000))*(sj1));
27067 IkReal x8364=((cj4)*(cj5));
27068 IkReal x8365=((cj6)*(r21));
27069 IkReal x8366=((r20)*(sj6));
27070 IkReal x8367=((r10)*(sj6));
27071 IkReal x8368=((IkReal(1.00000000000000))*(cj0));
27072 IkReal x8369=((cj0)*(sj4)*(sj6));
27073 IkReal x8370=((sj0)*(sj4)*(sj6));
27074 evalcond[0]=((((sj5)*(x8366)))+(((sj5)*(x8365)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x8352)*(x8363))));
27075 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8364)*(x8365)))+(((r20)*(x8362)))+(((IkReal(-1.00000000000000))*(x8351)*(x8363)))+(((cj4)*(r22)*(sj5)))+(((x8364)*(x8366))));
27076 evalcond[2]=((((x8353)*(x8356)))+(((IkReal(-1.00000000000000))*(x8360)*(x8367)))+(x8351)+(((IkReal(-1.00000000000000))*(r02)*(x8358)))+(((x8353)*(x8354)))+(((r12)*(x8357)))+(((IkReal(-1.00000000000000))*(x8359)*(x8360))));
27077 evalcond[3]=((((r12)*(x8358)))+(((IkReal(-1.00000000000000))*(x8353)*(x8359)))+(((IkReal(-1.00000000000000))*(x8353)*(x8367)))+(((IkReal(-1.00000000000000))*(x8356)*(x8360)))+(((IkReal(-1.00000000000000))*(x8352)*(x8361)))+(((IkReal(-1.00000000000000))*(x8354)*(x8360)))+(((r02)*(x8357))));
27078 evalcond[4]=((((cj4)*(x8356)*(x8358)))+(((r11)*(x8369)))+(((IkReal(-1.00000000000000))*(r01)*(x8370)))+(((IkReal(-1.00000000000000))*(x8355)*(x8357)*(x8367)))+(((r00)*(sj0)*(x8362)))+(((IkReal(-1.00000000000000))*(x8355)*(x8357)*(x8359)))+(((cj4)*(x8354)*(x8358)))+(((IkReal(-1.00000000000000))*(x8352)))+(((IkReal(-1.00000000000000))*(r12)*(x8355)*(x8360)))+(((IkReal(-1.00000000000000))*(r10)*(x8362)*(x8368)))+(((cj4)*(r02)*(x8353))));
27079 evalcond[5]=((((IkReal(-1.00000000000000))*(x8354)*(x8355)*(x8357)))+(((IkReal(-1.00000000000000))*(r12)*(x8353)*(x8355)))+(((IkReal(-1.00000000000000))*(x8351)*(x8361)))+(((IkReal(-1.00000000000000))*(x8355)*(x8358)*(x8359)))+(((IkReal(-1.00000000000000))*(r02)*(x8355)*(x8360)))+(((r11)*(x8370)))+(((IkReal(-1.00000000000000))*(x8355)*(x8358)*(x8367)))+(((IkReal(-1.00000000000000))*(r00)*(x8362)*(x8368)))+(((IkReal(-1.00000000000000))*(x8355)*(x8356)*(x8357)))+(((r01)*(x8369)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8362))));
27080 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
27081 {
27082 continue;
27083 }
27084 }
27085 
27086 {
27087 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
27088 vinfos[0].jointtype = 1;
27089 vinfos[0].foffset = j0;
27090 vinfos[0].indices[0] = _ij0[0];
27091 vinfos[0].indices[1] = _ij0[1];
27092 vinfos[0].maxsolutions = _nj0;
27093 vinfos[1].jointtype = 1;
27094 vinfos[1].foffset = j1;
27095 vinfos[1].indices[0] = _ij1[0];
27096 vinfos[1].indices[1] = _ij1[1];
27097 vinfos[1].maxsolutions = _nj1;
27098 vinfos[2].jointtype = 1;
27099 vinfos[2].foffset = j2;
27100 vinfos[2].indices[0] = _ij2[0];
27101 vinfos[2].indices[1] = _ij2[1];
27102 vinfos[2].maxsolutions = _nj2;
27103 vinfos[3].jointtype = 1;
27104 vinfos[3].foffset = j3;
27105 vinfos[3].indices[0] = _ij3[0];
27106 vinfos[3].indices[1] = _ij3[1];
27107 vinfos[3].maxsolutions = _nj3;
27108 vinfos[4].jointtype = 1;
27109 vinfos[4].foffset = j4;
27110 vinfos[4].indices[0] = _ij4[0];
27111 vinfos[4].indices[1] = _ij4[1];
27112 vinfos[4].maxsolutions = _nj4;
27113 vinfos[5].jointtype = 1;
27114 vinfos[5].foffset = j5;
27115 vinfos[5].indices[0] = _ij5[0];
27116 vinfos[5].indices[1] = _ij5[1];
27117 vinfos[5].maxsolutions = _nj5;
27118 vinfos[6].jointtype = 1;
27119 vinfos[6].foffset = j6;
27120 vinfos[6].indices[0] = _ij6[0];
27121 vinfos[6].indices[1] = _ij6[1];
27122 vinfos[6].maxsolutions = _nj6;
27123 std::vector<int> vfree(0);
27124 solutions.AddSolution(vinfos,vfree);
27125 }
27126 }
27127 }
27128 
27129 }
27130 
27131 }
27132 
27133 } else
27134 {
27135 {
27136 IkReal j3array[1], cj3array[1], sj3array[1];
27137 bool j3valid[1]={false};
27138 _nj3 = 1;
27139 IkReal x8371=((r20)*(sj6));
27140 IkReal x8372=((cj4)*(cj5));
27141 IkReal x8373=((cj6)*(r21));
27142 if( IKabs(((gconst12)*(((((x8371)*(x8372)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8372)*(x8373))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((sj5)*(x8371)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8373))))))) < IKFAST_ATAN2_MAGTHRESH )
27143     continue;
27144 j3array[0]=IKatan2(((gconst12)*(((((x8371)*(x8372)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x8372)*(x8373)))))), ((gconst12)*(((((sj5)*(x8371)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8373)))))));
27145 sj3array[0]=IKsin(j3array[0]);
27146 cj3array[0]=IKcos(j3array[0]);
27147 if( j3array[0] > IKPI )
27148 {
27149     j3array[0]-=IK2PI;
27150 }
27151 else if( j3array[0] < -IKPI )
27152 {    j3array[0]+=IK2PI;
27153 }
27154 j3valid[0] = true;
27155 for(int ij3 = 0; ij3 < 1; ++ij3)
27156 {
27157 if( !j3valid[ij3] )
27158 {
27159     continue;
27160 }
27161 _ij3[0] = ij3; _ij3[1] = -1;
27162 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27163 {
27164 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27165 {
27166     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27167 }
27168 }
27169 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27170 {
27171 IkReal evalcond[6];
27172 IkReal x8374=IKsin(j3);
27173 IkReal x8375=IKcos(j3);
27174 IkReal x8376=((sj0)*(sj5));
27175 IkReal x8377=((r00)*(sj6));
27176 IkReal x8378=((IkReal(1.00000000000000))*(cj4));
27177 IkReal x8379=((cj6)*(r01));
27178 IkReal x8380=((cj0)*(cj5));
27179 IkReal x8381=((cj5)*(sj0));
27180 IkReal x8382=((cj6)*(r11));
27181 IkReal x8383=((cj0)*(sj5));
27182 IkReal x8384=((IkReal(1.00000000000000))*(cj1));
27183 IkReal x8385=((cj6)*(sj4));
27184 IkReal x8386=((IkReal(1.00000000000000))*(sj1));
27185 IkReal x8387=((cj4)*(cj5));
27186 IkReal x8388=((cj6)*(r21));
27187 IkReal x8389=((r20)*(sj6));
27188 IkReal x8390=((r10)*(sj6));
27189 IkReal x8391=((IkReal(1.00000000000000))*(cj0));
27190 IkReal x8392=((cj0)*(sj4)*(sj6));
27191 IkReal x8393=((sj0)*(sj4)*(sj6));
27192 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8389)))+(((IkReal(-1.00000000000000))*(x8375)*(x8386)))+(((sj5)*(x8388))));
27193 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x8374)*(x8386)))+(((x8387)*(x8389)))+(((x8387)*(x8388)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x8385))));
27194 evalcond[2]=((((r12)*(x8380)))+(((IkReal(-1.00000000000000))*(r02)*(x8381)))+(x8374)+(((x8376)*(x8377)))+(((IkReal(-1.00000000000000))*(x8382)*(x8383)))+(((x8376)*(x8379)))+(((IkReal(-1.00000000000000))*(x8383)*(x8390))));
27195 evalcond[3]=((((IkReal(-1.00000000000000))*(x8376)*(x8390)))+(((r02)*(x8380)))+(((r12)*(x8381)))+(((IkReal(-1.00000000000000))*(x8377)*(x8383)))+(((IkReal(-1.00000000000000))*(x8375)*(x8384)))+(((IkReal(-1.00000000000000))*(x8376)*(x8382)))+(((IkReal(-1.00000000000000))*(x8379)*(x8383))));
27196 evalcond[4]=((((IkReal(-1.00000000000000))*(x8375)))+(((IkReal(-1.00000000000000))*(r12)*(x8378)*(x8383)))+(((IkReal(-1.00000000000000))*(r10)*(x8385)*(x8391)))+(((cj4)*(r02)*(x8376)))+(((r00)*(sj0)*(x8385)))+(((IkReal(-1.00000000000000))*(x8378)*(x8380)*(x8382)))+(((r11)*(x8392)))+(((IkReal(-1.00000000000000))*(x8378)*(x8380)*(x8390)))+(((IkReal(-1.00000000000000))*(r01)*(x8393)))+(((cj4)*(x8377)*(x8381)))+(((cj4)*(x8379)*(x8381))));
27197 evalcond[5]=((((IkReal(-1.00000000000000))*(x8378)*(x8379)*(x8380)))+(((IkReal(-1.00000000000000))*(r12)*(x8376)*(x8378)))+(((IkReal(-1.00000000000000))*(x8377)*(x8378)*(x8380)))+(((IkReal(-1.00000000000000))*(x8378)*(x8381)*(x8390)))+(((r11)*(x8393)))+(((IkReal(-1.00000000000000))*(r02)*(x8378)*(x8383)))+(((IkReal(-1.00000000000000))*(x8378)*(x8381)*(x8382)))+(((IkReal(-1.00000000000000))*(r00)*(x8385)*(x8391)))+(((r01)*(x8392)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8385)))+(((IkReal(-1.00000000000000))*(x8374)*(x8384))));
27198 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
27199 {
27200 continue;
27201 }
27202 }
27203 
27204 {
27205 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
27206 vinfos[0].jointtype = 1;
27207 vinfos[0].foffset = j0;
27208 vinfos[0].indices[0] = _ij0[0];
27209 vinfos[0].indices[1] = _ij0[1];
27210 vinfos[0].maxsolutions = _nj0;
27211 vinfos[1].jointtype = 1;
27212 vinfos[1].foffset = j1;
27213 vinfos[1].indices[0] = _ij1[0];
27214 vinfos[1].indices[1] = _ij1[1];
27215 vinfos[1].maxsolutions = _nj1;
27216 vinfos[2].jointtype = 1;
27217 vinfos[2].foffset = j2;
27218 vinfos[2].indices[0] = _ij2[0];
27219 vinfos[2].indices[1] = _ij2[1];
27220 vinfos[2].maxsolutions = _nj2;
27221 vinfos[3].jointtype = 1;
27222 vinfos[3].foffset = j3;
27223 vinfos[3].indices[0] = _ij3[0];
27224 vinfos[3].indices[1] = _ij3[1];
27225 vinfos[3].maxsolutions = _nj3;
27226 vinfos[4].jointtype = 1;
27227 vinfos[4].foffset = j4;
27228 vinfos[4].indices[0] = _ij4[0];
27229 vinfos[4].indices[1] = _ij4[1];
27230 vinfos[4].maxsolutions = _nj4;
27231 vinfos[5].jointtype = 1;
27232 vinfos[5].foffset = j5;
27233 vinfos[5].indices[0] = _ij5[0];
27234 vinfos[5].indices[1] = _ij5[1];
27235 vinfos[5].maxsolutions = _nj5;
27236 vinfos[6].jointtype = 1;
27237 vinfos[6].foffset = j6;
27238 vinfos[6].indices[0] = _ij6[0];
27239 vinfos[6].indices[1] = _ij6[1];
27240 vinfos[6].maxsolutions = _nj6;
27241 std::vector<int> vfree(0);
27242 solutions.AddSolution(vinfos,vfree);
27243 }
27244 }
27245 }
27246 
27247 }
27248 
27249 }
27250 
27251 } else
27252 {
27253 if( 1 )
27254 {
27255 continue;
27256 
27257 } else
27258 {
27259 }
27260 }
27261 }
27262 }
27263 }
27264 }
27265 }
27266 }
27267 
27268 } else
27269 {
27270 {
27271 IkReal j3array[1], cj3array[1], sj3array[1];
27272 bool j3valid[1]={false};
27273 _nj3 = 1;
27274 IkReal x8394=((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30);
27275 IkReal x8395=((sj5)*(sj6));
27276 IkReal x8396=((r00)*(sj0));
27277 IkReal x8397=((cj1)*(cj2));
27278 IkReal x8398=((cj0)*(r10));
27279 IkReal x8399=((cj6)*(sj5));
27280 IkReal x8400=((r01)*(sj0));
27281 IkReal x8401=((IkReal(1.00000000000000))*(cj0));
27282 IkReal x8402=((cj5)*(r12));
27283 IkReal x8403=((IkReal(1.00000000000000))*(cj5));
27284 IkReal x8404=((r02)*(sj0));
27285 if( IKabs(((x8394)*(((((IkReal(-1.00000000000000))*(x8395)*(x8398)))+(((x8399)*(x8400)))+(((IkReal(-1.00000000000000))*(r11)*(x8399)*(x8401)))+(((cj0)*(x8402)))+(((x8395)*(x8396)))+(((IkReal(-1.00000000000000))*(x8403)*(x8404))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x8394)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(sj2)*(x8399)))+(((IkReal(-1.00000000000000))*(x8397)*(x8401)*(x8402)))+(((r20)*(sj2)*(x8395)))+(((cj0)*(r11)*(x8397)*(x8399)))+(((IkReal(-1.00000000000000))*(x8395)*(x8396)*(x8397)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x8403)))+(((IkReal(-1.00000000000000))*(x8397)*(x8399)*(x8400)))+(((x8395)*(x8397)*(x8398)))+(((cj5)*(x8397)*(x8404))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x8394)*(((((IkReal(-1.00000000000000))*(x8395)*(x8398)))+(((x8399)*(x8400)))+(((IkReal(-1.00000000000000))*(r11)*(x8399)*(x8401)))+(((cj0)*(x8402)))+(((x8395)*(x8396)))+(((IkReal(-1.00000000000000))*(x8403)*(x8404)))))))+IKsqr(((x8394)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(sj2)*(x8399)))+(((IkReal(-1.00000000000000))*(x8397)*(x8401)*(x8402)))+(((r20)*(sj2)*(x8395)))+(((cj0)*(r11)*(x8397)*(x8399)))+(((IkReal(-1.00000000000000))*(x8395)*(x8396)*(x8397)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x8403)))+(((IkReal(-1.00000000000000))*(x8397)*(x8399)*(x8400)))+(((x8395)*(x8397)*(x8398)))+(((cj5)*(x8397)*(x8404)))))))-1) <= IKFAST_SINCOS_THRESH )
27286     continue;
27287 j3array[0]=IKatan2(((x8394)*(((((IkReal(-1.00000000000000))*(x8395)*(x8398)))+(((x8399)*(x8400)))+(((IkReal(-1.00000000000000))*(r11)*(x8399)*(x8401)))+(((cj0)*(x8402)))+(((x8395)*(x8396)))+(((IkReal(-1.00000000000000))*(x8403)*(x8404)))))), ((x8394)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(sj2)*(x8399)))+(((IkReal(-1.00000000000000))*(x8397)*(x8401)*(x8402)))+(((r20)*(sj2)*(x8395)))+(((cj0)*(r11)*(x8397)*(x8399)))+(((IkReal(-1.00000000000000))*(x8395)*(x8396)*(x8397)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x8403)))+(((IkReal(-1.00000000000000))*(x8397)*(x8399)*(x8400)))+(((x8395)*(x8397)*(x8398)))+(((cj5)*(x8397)*(x8404)))))));
27288 sj3array[0]=IKsin(j3array[0]);
27289 cj3array[0]=IKcos(j3array[0]);
27290 if( j3array[0] > IKPI )
27291 {
27292     j3array[0]-=IK2PI;
27293 }
27294 else if( j3array[0] < -IKPI )
27295 {    j3array[0]+=IK2PI;
27296 }
27297 j3valid[0] = true;
27298 for(int ij3 = 0; ij3 < 1; ++ij3)
27299 {
27300 if( !j3valid[ij3] )
27301 {
27302     continue;
27303 }
27304 _ij3[0] = ij3; _ij3[1] = -1;
27305 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27306 {
27307 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27308 {
27309     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27310 }
27311 }
27312 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27313 {
27314 IkReal evalcond[6];
27315 IkReal x8405=IKcos(j3);
27316 IkReal x8406=IKsin(j3);
27317 IkReal x8407=((sj0)*(sj5));
27318 IkReal x8408=((r00)*(sj6));
27319 IkReal x8409=((IkReal(1.00000000000000))*(cj4));
27320 IkReal x8410=((cj6)*(r01));
27321 IkReal x8411=((cj0)*(cj5));
27322 IkReal x8412=((cj5)*(sj0));
27323 IkReal x8413=((cj6)*(r11));
27324 IkReal x8414=((cj6)*(sj4));
27325 IkReal x8415=((IkReal(1.00000000000000))*(cj1));
27326 IkReal x8416=((cj4)*(cj5));
27327 IkReal x8417=((cj6)*(r21));
27328 IkReal x8418=((r20)*(sj6));
27329 IkReal x8419=((r10)*(sj6));
27330 IkReal x8420=((cj0)*(sj5));
27331 IkReal x8421=((IkReal(1.00000000000000))*(cj0));
27332 IkReal x8422=((IkReal(1.00000000000000))*(x8420));
27333 IkReal x8423=((IkReal(1.00000000000000))*(x8406));
27334 IkReal x8424=((cj0)*(sj4)*(sj6));
27335 IkReal x8425=((cj2)*(x8406));
27336 IkReal x8426=((sj0)*(sj4)*(sj6));
27337 IkReal x8427=((IkReal(1.00000000000000))*(sj1)*(x8405));
27338 evalcond[0]=((((sj5)*(x8418)))+(((IkReal(-1.00000000000000))*(x8415)*(x8425)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x8427)))+(((sj5)*(x8417))));
27339 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8416)*(x8418)))+(((r20)*(x8414)))+(((IkReal(-1.00000000000000))*(sj1)*(x8423)))+(((x8416)*(x8417)))+(((cj4)*(r22)*(sj5)))+(((cj1)*(cj2)*(x8405))));
27340 evalcond[2]=((((IkReal(-1.00000000000000))*(x8413)*(x8422)))+(((IkReal(-1.00000000000000))*(x8419)*(x8422)))+(((x8407)*(x8410)))+(((x8407)*(x8408)))+(((IkReal(-1.00000000000000))*(sj2)*(x8423)))+(((IkReal(-1.00000000000000))*(r02)*(x8412)))+(((r12)*(x8411))));
27341 evalcond[3]=((((IkReal(-1.00000000000000))*(x8410)*(x8422)))+(((sj1)*(x8425)))+(((IkReal(-1.00000000000000))*(x8405)*(x8415)))+(((IkReal(-1.00000000000000))*(x8408)*(x8422)))+(((r12)*(x8412)))+(((IkReal(-1.00000000000000))*(x8407)*(x8413)))+(((IkReal(-1.00000000000000))*(x8407)*(x8419)))+(((r02)*(x8411))));
27342 evalcond[4]=((((cj4)*(x8408)*(x8412)))+(((IkReal(-1.00000000000000))*(r12)*(x8409)*(x8420)))+(((IkReal(-1.00000000000000))*(x8409)*(x8411)*(x8413)))+(((r00)*(sj0)*(x8414)))+(((IkReal(-1.00000000000000))*(r10)*(x8414)*(x8421)))+(((cj4)*(x8410)*(x8412)))+(((r11)*(x8424)))+(((cj4)*(r02)*(x8407)))+(((sj2)*(x8405)))+(((IkReal(-1.00000000000000))*(r01)*(x8426)))+(((IkReal(-1.00000000000000))*(x8409)*(x8411)*(x8419))));
27343 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x8407)*(x8409)))+(((IkReal(-1.00000000000000))*(r00)*(x8414)*(x8421)))+(((IkReal(-1.00000000000000))*(x8409)*(x8412)*(x8413)))+(((IkReal(-1.00000000000000))*(r02)*(x8409)*(x8420)))+(((r11)*(x8426)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8414)))+(((IkReal(-1.00000000000000))*(cj2)*(x8427)))+(((IkReal(-1.00000000000000))*(x8408)*(x8409)*(x8411)))+(((IkReal(-1.00000000000000))*(x8409)*(x8412)*(x8419)))+(((IkReal(-1.00000000000000))*(x8409)*(x8410)*(x8411)))+(((r01)*(x8424)))+(((IkReal(-1.00000000000000))*(x8406)*(x8415))));
27344 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
27345 {
27346 continue;
27347 }
27348 }
27349 
27350 {
27351 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
27352 vinfos[0].jointtype = 1;
27353 vinfos[0].foffset = j0;
27354 vinfos[0].indices[0] = _ij0[0];
27355 vinfos[0].indices[1] = _ij0[1];
27356 vinfos[0].maxsolutions = _nj0;
27357 vinfos[1].jointtype = 1;
27358 vinfos[1].foffset = j1;
27359 vinfos[1].indices[0] = _ij1[0];
27360 vinfos[1].indices[1] = _ij1[1];
27361 vinfos[1].maxsolutions = _nj1;
27362 vinfos[2].jointtype = 1;
27363 vinfos[2].foffset = j2;
27364 vinfos[2].indices[0] = _ij2[0];
27365 vinfos[2].indices[1] = _ij2[1];
27366 vinfos[2].maxsolutions = _nj2;
27367 vinfos[3].jointtype = 1;
27368 vinfos[3].foffset = j3;
27369 vinfos[3].indices[0] = _ij3[0];
27370 vinfos[3].indices[1] = _ij3[1];
27371 vinfos[3].maxsolutions = _nj3;
27372 vinfos[4].jointtype = 1;
27373 vinfos[4].foffset = j4;
27374 vinfos[4].indices[0] = _ij4[0];
27375 vinfos[4].indices[1] = _ij4[1];
27376 vinfos[4].maxsolutions = _nj4;
27377 vinfos[5].jointtype = 1;
27378 vinfos[5].foffset = j5;
27379 vinfos[5].indices[0] = _ij5[0];
27380 vinfos[5].indices[1] = _ij5[1];
27381 vinfos[5].maxsolutions = _nj5;
27382 vinfos[6].jointtype = 1;
27383 vinfos[6].foffset = j6;
27384 vinfos[6].indices[0] = _ij6[0];
27385 vinfos[6].indices[1] = _ij6[1];
27386 vinfos[6].maxsolutions = _nj6;
27387 std::vector<int> vfree(0);
27388 solutions.AddSolution(vinfos,vfree);
27389 }
27390 }
27391 }
27392 
27393 }
27394 
27395 }
27396 
27397 } else
27398 {
27399 {
27400 IkReal j3array[1], cj3array[1], sj3array[1];
27401 bool j3valid[1]={false};
27402 _nj3 = 1;
27403 IkReal x8428=(cj1)*(cj1);
27404 IkReal x8429=(sj1)*(sj1);
27405 IkReal x8430=((r00)*(sj6));
27406 IkReal x8431=((cj6)*(r01));
27407 IkReal x8432=((IkReal(1.00000000000000))*(cj1));
27408 IkReal x8433=((cj5)*(r22));
27409 IkReal x8434=((sj5)*(sj6));
27410 IkReal x8435=((r10)*(sj0));
27411 IkReal x8436=((cj1)*(cj5));
27412 IkReal x8437=((cj0)*(r02));
27413 IkReal x8438=((r12)*(sj0));
27414 IkReal x8439=((IkReal(1.00000000000000))*(sj1));
27415 IkReal x8440=((cj6)*(sj5));
27416 IkReal x8441=((cj0)*(sj5));
27417 IkReal x8442=((r11)*(sj0));
27418 IkReal x8443=((sj1)*(x8441));
27419 if( IKabs(((((IKabs(((((cj2)*(x8428)))+(((cj2)*(x8429))))) != 0)?((IkReal)1/(((((cj2)*(x8428)))+(((cj2)*(x8429)))))):(IkReal)1.0e30))*(((((x8431)*(x8443)))+(((IkReal(-1.00000000000000))*(x8432)*(x8433)))+(((IkReal(-1.00000000000000))*(cj5)*(x8438)*(x8439)))+(((cj1)*(r20)*(x8434)))+(((x8430)*(x8443)))+(((sj1)*(x8440)*(x8442)))+(((cj1)*(r21)*(x8440)))+(((IkReal(-1.00000000000000))*(cj5)*(x8437)*(x8439)))+(((sj1)*(x8434)*(x8435))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x8428)+(x8429))) != 0)?((IkReal)1/(((x8428)+(x8429)))):(IkReal)1.0e30))*(((((r20)*(sj1)*(x8434)))+(((IkReal(-1.00000000000000))*(x8431)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8430)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8432)*(x8434)*(x8435)))+(((x8436)*(x8438)))+(((IkReal(-1.00000000000000))*(x8433)*(x8439)))+(((IkReal(-1.00000000000000))*(x8432)*(x8440)*(x8442)))+(((r21)*(sj1)*(x8440)))+(((x8436)*(x8437))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x8428)))+(((cj2)*(x8429))))) != 0)?((IkReal)1/(((((cj2)*(x8428)))+(((cj2)*(x8429)))))):(IkReal)1.0e30))*(((((x8431)*(x8443)))+(((IkReal(-1.00000000000000))*(x8432)*(x8433)))+(((IkReal(-1.00000000000000))*(cj5)*(x8438)*(x8439)))+(((cj1)*(r20)*(x8434)))+(((x8430)*(x8443)))+(((sj1)*(x8440)*(x8442)))+(((cj1)*(r21)*(x8440)))+(((IkReal(-1.00000000000000))*(cj5)*(x8437)*(x8439)))+(((sj1)*(x8434)*(x8435)))))))+IKsqr(((((IKabs(((x8428)+(x8429))) != 0)?((IkReal)1/(((x8428)+(x8429)))):(IkReal)1.0e30))*(((((r20)*(sj1)*(x8434)))+(((IkReal(-1.00000000000000))*(x8431)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8430)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8432)*(x8434)*(x8435)))+(((x8436)*(x8438)))+(((IkReal(-1.00000000000000))*(x8433)*(x8439)))+(((IkReal(-1.00000000000000))*(x8432)*(x8440)*(x8442)))+(((r21)*(sj1)*(x8440)))+(((x8436)*(x8437)))))))-1) <= IKFAST_SINCOS_THRESH )
27420     continue;
27421 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x8428)))+(((cj2)*(x8429))))) != 0)?((IkReal)1/(((((cj2)*(x8428)))+(((cj2)*(x8429)))))):(IkReal)1.0e30))*(((((x8431)*(x8443)))+(((IkReal(-1.00000000000000))*(x8432)*(x8433)))+(((IkReal(-1.00000000000000))*(cj5)*(x8438)*(x8439)))+(((cj1)*(r20)*(x8434)))+(((x8430)*(x8443)))+(((sj1)*(x8440)*(x8442)))+(((cj1)*(r21)*(x8440)))+(((IkReal(-1.00000000000000))*(cj5)*(x8437)*(x8439)))+(((sj1)*(x8434)*(x8435)))))), ((((IKabs(((x8428)+(x8429))) != 0)?((IkReal)1/(((x8428)+(x8429)))):(IkReal)1.0e30))*(((((r20)*(sj1)*(x8434)))+(((IkReal(-1.00000000000000))*(x8431)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8430)*(x8432)*(x8441)))+(((IkReal(-1.00000000000000))*(x8432)*(x8434)*(x8435)))+(((x8436)*(x8438)))+(((IkReal(-1.00000000000000))*(x8433)*(x8439)))+(((IkReal(-1.00000000000000))*(x8432)*(x8440)*(x8442)))+(((r21)*(sj1)*(x8440)))+(((x8436)*(x8437)))))));
27422 sj3array[0]=IKsin(j3array[0]);
27423 cj3array[0]=IKcos(j3array[0]);
27424 if( j3array[0] > IKPI )
27425 {
27426     j3array[0]-=IK2PI;
27427 }
27428 else if( j3array[0] < -IKPI )
27429 {    j3array[0]+=IK2PI;
27430 }
27431 j3valid[0] = true;
27432 for(int ij3 = 0; ij3 < 1; ++ij3)
27433 {
27434 if( !j3valid[ij3] )
27435 {
27436     continue;
27437 }
27438 _ij3[0] = ij3; _ij3[1] = -1;
27439 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27440 {
27441 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27442 {
27443     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27444 }
27445 }
27446 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27447 {
27448 IkReal evalcond[6];
27449 IkReal x8444=IKcos(j3);
27450 IkReal x8445=IKsin(j3);
27451 IkReal x8446=((sj0)*(sj5));
27452 IkReal x8447=((r00)*(sj6));
27453 IkReal x8448=((IkReal(1.00000000000000))*(cj4));
27454 IkReal x8449=((cj6)*(r01));
27455 IkReal x8450=((cj0)*(cj5));
27456 IkReal x8451=((cj5)*(sj0));
27457 IkReal x8452=((cj6)*(r11));
27458 IkReal x8453=((cj6)*(sj4));
27459 IkReal x8454=((IkReal(1.00000000000000))*(cj1));
27460 IkReal x8455=((cj4)*(cj5));
27461 IkReal x8456=((cj6)*(r21));
27462 IkReal x8457=((r20)*(sj6));
27463 IkReal x8458=((r10)*(sj6));
27464 IkReal x8459=((cj0)*(sj5));
27465 IkReal x8460=((IkReal(1.00000000000000))*(cj0));
27466 IkReal x8461=((IkReal(1.00000000000000))*(x8459));
27467 IkReal x8462=((IkReal(1.00000000000000))*(x8445));
27468 IkReal x8463=((cj0)*(sj4)*(sj6));
27469 IkReal x8464=((cj2)*(x8445));
27470 IkReal x8465=((sj0)*(sj4)*(sj6));
27471 IkReal x8466=((IkReal(1.00000000000000))*(sj1)*(x8444));
27472 evalcond[0]=((((IkReal(-1.00000000000000))*(x8466)))+(((sj5)*(x8456)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x8457)))+(((IkReal(-1.00000000000000))*(x8454)*(x8464))));
27473 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x8455)*(x8457)))+(((IkReal(-1.00000000000000))*(sj1)*(x8462)))+(((cj4)*(r22)*(sj5)))+(((x8455)*(x8456)))+(((r20)*(x8453)))+(((cj1)*(cj2)*(x8444))));
27474 evalcond[2]=((((x8446)*(x8449)))+(((IkReal(-1.00000000000000))*(sj2)*(x8462)))+(((IkReal(-1.00000000000000))*(x8458)*(x8461)))+(((IkReal(-1.00000000000000))*(r02)*(x8451)))+(((IkReal(-1.00000000000000))*(x8452)*(x8461)))+(((x8446)*(x8447)))+(((r12)*(x8450))));
27475 evalcond[3]=((((IkReal(-1.00000000000000))*(x8446)*(x8458)))+(((r12)*(x8451)))+(((IkReal(-1.00000000000000))*(x8449)*(x8461)))+(((r02)*(x8450)))+(((IkReal(-1.00000000000000))*(x8444)*(x8454)))+(((IkReal(-1.00000000000000))*(x8447)*(x8461)))+(((IkReal(-1.00000000000000))*(x8446)*(x8452)))+(((sj1)*(x8464))));
27476 evalcond[4]=((((r11)*(x8463)))+(((IkReal(-1.00000000000000))*(x8448)*(x8450)*(x8452)))+(((IkReal(-1.00000000000000))*(r12)*(x8448)*(x8459)))+(((IkReal(-1.00000000000000))*(r01)*(x8465)))+(((IkReal(-1.00000000000000))*(r10)*(x8453)*(x8460)))+(((IkReal(-1.00000000000000))*(x8448)*(x8450)*(x8458)))+(((cj4)*(x8447)*(x8451)))+(((cj4)*(x8449)*(x8451)))+(((sj2)*(x8444)))+(((r00)*(sj0)*(x8453)))+(((cj4)*(r02)*(x8446))));
27477 evalcond[5]=((((IkReal(-1.00000000000000))*(x8448)*(x8451)*(x8452)))+(((IkReal(-1.00000000000000))*(x8447)*(x8448)*(x8450)))+(((IkReal(-1.00000000000000))*(x8445)*(x8454)))+(((IkReal(-1.00000000000000))*(cj2)*(x8466)))+(((r01)*(x8463)))+(((IkReal(-1.00000000000000))*(r02)*(x8448)*(x8459)))+(((IkReal(-1.00000000000000))*(x8448)*(x8449)*(x8450)))+(((IkReal(-1.00000000000000))*(r12)*(x8446)*(x8448)))+(((r11)*(x8465)))+(((IkReal(-1.00000000000000))*(x8448)*(x8451)*(x8458)))+(((IkReal(-1.00000000000000))*(r00)*(x8453)*(x8460)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8453))));
27478 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
27479 {
27480 continue;
27481 }
27482 }
27483 
27484 {
27485 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
27486 vinfos[0].jointtype = 1;
27487 vinfos[0].foffset = j0;
27488 vinfos[0].indices[0] = _ij0[0];
27489 vinfos[0].indices[1] = _ij0[1];
27490 vinfos[0].maxsolutions = _nj0;
27491 vinfos[1].jointtype = 1;
27492 vinfos[1].foffset = j1;
27493 vinfos[1].indices[0] = _ij1[0];
27494 vinfos[1].indices[1] = _ij1[1];
27495 vinfos[1].maxsolutions = _nj1;
27496 vinfos[2].jointtype = 1;
27497 vinfos[2].foffset = j2;
27498 vinfos[2].indices[0] = _ij2[0];
27499 vinfos[2].indices[1] = _ij2[1];
27500 vinfos[2].maxsolutions = _nj2;
27501 vinfos[3].jointtype = 1;
27502 vinfos[3].foffset = j3;
27503 vinfos[3].indices[0] = _ij3[0];
27504 vinfos[3].indices[1] = _ij3[1];
27505 vinfos[3].maxsolutions = _nj3;
27506 vinfos[4].jointtype = 1;
27507 vinfos[4].foffset = j4;
27508 vinfos[4].indices[0] = _ij4[0];
27509 vinfos[4].indices[1] = _ij4[1];
27510 vinfos[4].maxsolutions = _nj4;
27511 vinfos[5].jointtype = 1;
27512 vinfos[5].foffset = j5;
27513 vinfos[5].indices[0] = _ij5[0];
27514 vinfos[5].indices[1] = _ij5[1];
27515 vinfos[5].maxsolutions = _nj5;
27516 vinfos[6].jointtype = 1;
27517 vinfos[6].foffset = j6;
27518 vinfos[6].indices[0] = _ij6[0];
27519 vinfos[6].indices[1] = _ij6[1];
27520 vinfos[6].maxsolutions = _nj6;
27521 std::vector<int> vfree(0);
27522 solutions.AddSolution(vinfos,vfree);
27523 }
27524 }
27525 }
27526 
27527 }
27528 
27529 }
27530 
27531 } else
27532 {
27533 {
27534 IkReal j3array[1], cj3array[1], sj3array[1];
27535 bool j3valid[1]={false};
27536 _nj3 = 1;
27537 IkReal x8467=((sj1)*(sj6));
27538 IkReal x8468=((r20)*(sj5));
27539 IkReal x8469=((IkReal(1.00000000000000))*(r21));
27540 IkReal x8470=((cj5)*(cj6));
27541 IkReal x8471=((r22)*(sj5));
27542 IkReal x8472=((cj4)*(sj1));
27543 IkReal x8473=((cj1)*(cj2));
27544 IkReal x8474=((cj5)*(r20));
27545 IkReal x8475=((cj4)*(x8473));
27546 IkReal x8476=((IkReal(1.00000000000000))*(cj5)*(r22));
27547 IkReal x8477=((cj6)*(r20)*(sj4));
27548 IkReal x8478=((cj6)*(r21)*(sj5));
27549 if( IKabs(((gconst4)*(((((sj1)*(x8477)))+(((cj4)*(x8467)*(x8474)))+(((x8471)*(x8472)))+(((sj6)*(x8468)*(x8473)))+(((x8473)*(x8478)))+(((IkReal(-1.00000000000000))*(x8473)*(x8476)))+(((IkReal(-1.00000000000000))*(sj4)*(x8467)*(x8469)))+(((r21)*(x8470)*(x8472))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(sj1)*(x8476)))+(((x8467)*(x8468)))+(((r21)*(sj4)*(sj6)*(x8473)))+(((IkReal(-1.00000000000000))*(x8473)*(x8477)))+(((IkReal(-1.00000000000000))*(x8471)*(x8475)))+(((sj1)*(x8478)))+(((IkReal(-1.00000000000000))*(sj6)*(x8474)*(x8475)))+(((IkReal(-1.00000000000000))*(x8469)*(x8470)*(x8475))))))) < IKFAST_ATAN2_MAGTHRESH )
27550     continue;
27551 j3array[0]=IKatan2(((gconst4)*(((((sj1)*(x8477)))+(((cj4)*(x8467)*(x8474)))+(((x8471)*(x8472)))+(((sj6)*(x8468)*(x8473)))+(((x8473)*(x8478)))+(((IkReal(-1.00000000000000))*(x8473)*(x8476)))+(((IkReal(-1.00000000000000))*(sj4)*(x8467)*(x8469)))+(((r21)*(x8470)*(x8472)))))), ((gconst4)*(((((IkReal(-1.00000000000000))*(sj1)*(x8476)))+(((x8467)*(x8468)))+(((r21)*(sj4)*(sj6)*(x8473)))+(((IkReal(-1.00000000000000))*(x8473)*(x8477)))+(((IkReal(-1.00000000000000))*(x8471)*(x8475)))+(((sj1)*(x8478)))+(((IkReal(-1.00000000000000))*(sj6)*(x8474)*(x8475)))+(((IkReal(-1.00000000000000))*(x8469)*(x8470)*(x8475)))))));
27552 sj3array[0]=IKsin(j3array[0]);
27553 cj3array[0]=IKcos(j3array[0]);
27554 if( j3array[0] > IKPI )
27555 {
27556     j3array[0]-=IK2PI;
27557 }
27558 else if( j3array[0] < -IKPI )
27559 {    j3array[0]+=IK2PI;
27560 }
27561 j3valid[0] = true;
27562 for(int ij3 = 0; ij3 < 1; ++ij3)
27563 {
27564 if( !j3valid[ij3] )
27565 {
27566     continue;
27567 }
27568 _ij3[0] = ij3; _ij3[1] = -1;
27569 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27570 {
27571 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27572 {
27573     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27574 }
27575 }
27576 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27577 {
27578 IkReal evalcond[6];
27579 IkReal x8479=IKcos(j3);
27580 IkReal x8480=IKsin(j3);
27581 IkReal x8481=((sj0)*(sj5));
27582 IkReal x8482=((r00)*(sj6));
27583 IkReal x8483=((IkReal(1.00000000000000))*(cj4));
27584 IkReal x8484=((cj6)*(r01));
27585 IkReal x8485=((cj0)*(cj5));
27586 IkReal x8486=((cj5)*(sj0));
27587 IkReal x8487=((cj6)*(r11));
27588 IkReal x8488=((cj6)*(sj4));
27589 IkReal x8489=((IkReal(1.00000000000000))*(cj1));
27590 IkReal x8490=((cj4)*(cj5));
27591 IkReal x8491=((cj6)*(r21));
27592 IkReal x8492=((r20)*(sj6));
27593 IkReal x8493=((r10)*(sj6));
27594 IkReal x8494=((cj0)*(sj5));
27595 IkReal x8495=((IkReal(1.00000000000000))*(cj0));
27596 IkReal x8496=((IkReal(1.00000000000000))*(x8494));
27597 IkReal x8497=((IkReal(1.00000000000000))*(x8480));
27598 IkReal x8498=((cj0)*(sj4)*(sj6));
27599 IkReal x8499=((cj2)*(x8480));
27600 IkReal x8500=((sj0)*(sj4)*(sj6));
27601 IkReal x8501=((IkReal(1.00000000000000))*(sj1)*(x8479));
27602 evalcond[0]=((((sj5)*(x8491)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x8489)*(x8499)))+(((sj5)*(x8492)))+(((IkReal(-1.00000000000000))*(x8501))));
27603 evalcond[1]=((((cj1)*(cj2)*(x8479)))+(((x8490)*(x8492)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x8488)))+(((x8490)*(x8491)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x8497))));
27604 evalcond[2]=((((x8481)*(x8482)))+(((x8481)*(x8484)))+(((IkReal(-1.00000000000000))*(r02)*(x8486)))+(((IkReal(-1.00000000000000))*(x8493)*(x8496)))+(((IkReal(-1.00000000000000))*(sj2)*(x8497)))+(((IkReal(-1.00000000000000))*(x8487)*(x8496)))+(((r12)*(x8485))));
27605 evalcond[3]=((((sj1)*(x8499)))+(((IkReal(-1.00000000000000))*(x8481)*(x8487)))+(((r02)*(x8485)))+(((IkReal(-1.00000000000000))*(x8484)*(x8496)))+(((IkReal(-1.00000000000000))*(x8481)*(x8493)))+(((IkReal(-1.00000000000000))*(x8482)*(x8496)))+(((IkReal(-1.00000000000000))*(x8479)*(x8489)))+(((r12)*(x8486))));
27606 evalcond[4]=((((IkReal(-1.00000000000000))*(x8483)*(x8485)*(x8487)))+(((sj2)*(x8479)))+(((IkReal(-1.00000000000000))*(r12)*(x8483)*(x8494)))+(((IkReal(-1.00000000000000))*(x8483)*(x8485)*(x8493)))+(((IkReal(-1.00000000000000))*(r01)*(x8500)))+(((cj4)*(x8482)*(x8486)))+(((r11)*(x8498)))+(((r00)*(sj0)*(x8488)))+(((IkReal(-1.00000000000000))*(r10)*(x8488)*(x8495)))+(((cj4)*(x8484)*(x8486)))+(((cj4)*(r02)*(x8481))));
27607 evalcond[5]=((((IkReal(-1.00000000000000))*(x8483)*(x8484)*(x8485)))+(((IkReal(-1.00000000000000))*(r12)*(x8481)*(x8483)))+(((r01)*(x8498)))+(((IkReal(-1.00000000000000))*(x8480)*(x8489)))+(((r11)*(x8500)))+(((IkReal(-1.00000000000000))*(x8483)*(x8486)*(x8487)))+(((IkReal(-1.00000000000000))*(cj2)*(x8501)))+(((IkReal(-1.00000000000000))*(r02)*(x8483)*(x8494)))+(((IkReal(-1.00000000000000))*(x8482)*(x8483)*(x8485)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x8488)))+(((IkReal(-1.00000000000000))*(x8483)*(x8486)*(x8493)))+(((IkReal(-1.00000000000000))*(r00)*(x8488)*(x8495))));
27608 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
27609 {
27610 continue;
27611 }
27612 }
27613 
27614 {
27615 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
27616 vinfos[0].jointtype = 1;
27617 vinfos[0].foffset = j0;
27618 vinfos[0].indices[0] = _ij0[0];
27619 vinfos[0].indices[1] = _ij0[1];
27620 vinfos[0].maxsolutions = _nj0;
27621 vinfos[1].jointtype = 1;
27622 vinfos[1].foffset = j1;
27623 vinfos[1].indices[0] = _ij1[0];
27624 vinfos[1].indices[1] = _ij1[1];
27625 vinfos[1].maxsolutions = _nj1;
27626 vinfos[2].jointtype = 1;
27627 vinfos[2].foffset = j2;
27628 vinfos[2].indices[0] = _ij2[0];
27629 vinfos[2].indices[1] = _ij2[1];
27630 vinfos[2].maxsolutions = _nj2;
27631 vinfos[3].jointtype = 1;
27632 vinfos[3].foffset = j3;
27633 vinfos[3].indices[0] = _ij3[0];
27634 vinfos[3].indices[1] = _ij3[1];
27635 vinfos[3].maxsolutions = _nj3;
27636 vinfos[4].jointtype = 1;
27637 vinfos[4].foffset = j4;
27638 vinfos[4].indices[0] = _ij4[0];
27639 vinfos[4].indices[1] = _ij4[1];
27640 vinfos[4].maxsolutions = _nj4;
27641 vinfos[5].jointtype = 1;
27642 vinfos[5].foffset = j5;
27643 vinfos[5].indices[0] = _ij5[0];
27644 vinfos[5].indices[1] = _ij5[1];
27645 vinfos[5].maxsolutions = _nj5;
27646 vinfos[6].jointtype = 1;
27647 vinfos[6].foffset = j6;
27648 vinfos[6].indices[0] = _ij6[0];
27649 vinfos[6].indices[1] = _ij6[1];
27650 vinfos[6].maxsolutions = _nj6;
27651 std::vector<int> vfree(0);
27652 solutions.AddSolution(vinfos,vfree);
27653 }
27654 }
27655 }
27656 
27657 }
27658 
27659 }
27660 }
27661 }
27662 
27663 }
27664 
27665 }
27666 }
27667 }
27668 
27669 }
27670 
27671 }
27672 
27673 } else
27674 {
27675 {
27676 IkReal j2array[1], cj2array[1], sj2array[1];
27677 bool j2valid[1]={false};
27678 _nj2 = 1;
27679 IkReal x8502=((cj6)*(sj5));
27680 IkReal x8503=((r01)*(sj0));
27681 IkReal x8504=((cj5)*(cj6));
27682 IkReal x8505=((sj5)*(sj6));
27683 IkReal x8506=((cj0)*(r10));
27684 IkReal x8507=((IkReal(5.42449275362319))*(sj0));
27685 IkReal x8508=((IkReal(0.144927536231884))*(cj0));
27686 IkReal x8509=((IkReal(5.42449275362319))*(cj0));
27687 IkReal x8510=((IkReal(0.144927536231884))*(cj5)*(sj6));
27688 if( IKabs(((((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x8506)*(x8510)))+(((IkReal(-1.00000000000000))*(r00)*(x8505)*(x8507)))+(((IkReal(-5.42449275362319))*(x8502)*(x8503)))+(((IkReal(0.144927536231884))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r11)*(x8504)*(x8508)))+(((IkReal(-1.00000000000000))*(r12)*(sj5)*(x8508)))+(((cj5)*(r02)*(x8507)))+(((r00)*(sj0)*(x8510)))+(((IkReal(-1.00000000000000))*(cj5)*(r12)*(x8509)))+(((r11)*(x8502)*(x8509)))+(((IkReal(5.42449275362319))*(x8505)*(x8506)))+(((IkReal(0.144927536231884))*(x8503)*(x8504))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(0.0144927536231884))*(((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(374.290000000000))*(cj5)*(r22)))+(((IkReal(10.0000000000000))*(cj5)*(r20)*(sj6)))+(((IkReal(-374.290000000000))*(r20)*(x8505)))+(((IkReal(10.0000000000000))*(r22)*(sj5)))+(((IkReal(10.0000000000000))*(r21)*(x8504)))+(((IkReal(-1000.00000000000))*(pz)))+(((IkReal(-364.420000000000))*(sj1)))+(((IkReal(-374.290000000000))*(r21)*(x8502))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x8506)*(x8510)))+(((IkReal(-1.00000000000000))*(r00)*(x8505)*(x8507)))+(((IkReal(-5.42449275362319))*(x8502)*(x8503)))+(((IkReal(0.144927536231884))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r11)*(x8504)*(x8508)))+(((IkReal(-1.00000000000000))*(r12)*(sj5)*(x8508)))+(((cj5)*(r02)*(x8507)))+(((r00)*(sj0)*(x8510)))+(((IkReal(-1.00000000000000))*(cj5)*(r12)*(x8509)))+(((r11)*(x8502)*(x8509)))+(((IkReal(5.42449275362319))*(x8505)*(x8506)))+(((IkReal(0.144927536231884))*(x8503)*(x8504)))))+IKsqr(((IkReal(0.0144927536231884))*(((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(374.290000000000))*(cj5)*(r22)))+(((IkReal(10.0000000000000))*(cj5)*(r20)*(sj6)))+(((IkReal(-374.290000000000))*(r20)*(x8505)))+(((IkReal(10.0000000000000))*(r22)*(sj5)))+(((IkReal(10.0000000000000))*(r21)*(x8504)))+(((IkReal(-1000.00000000000))*(pz)))+(((IkReal(-364.420000000000))*(sj1)))+(((IkReal(-374.290000000000))*(r21)*(x8502)))))))-1) <= IKFAST_SINCOS_THRESH )
27689     continue;
27690 j2array[0]=IKatan2(((((IkReal(14.4927536231884))*(cj0)*(py)))+(((IkReal(-14.4927536231884))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(x8506)*(x8510)))+(((IkReal(-1.00000000000000))*(r00)*(x8505)*(x8507)))+(((IkReal(-5.42449275362319))*(x8502)*(x8503)))+(((IkReal(0.144927536231884))*(r02)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(r11)*(x8504)*(x8508)))+(((IkReal(-1.00000000000000))*(r12)*(sj5)*(x8508)))+(((cj5)*(r02)*(x8507)))+(((r00)*(sj0)*(x8510)))+(((IkReal(-1.00000000000000))*(cj5)*(r12)*(x8509)))+(((r11)*(x8502)*(x8509)))+(((IkReal(5.42449275362319))*(x8505)*(x8506)))+(((IkReal(0.144927536231884))*(x8503)*(x8504)))), ((IkReal(0.0144927536231884))*(((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(374.290000000000))*(cj5)*(r22)))+(((IkReal(10.0000000000000))*(cj5)*(r20)*(sj6)))+(((IkReal(-374.290000000000))*(r20)*(x8505)))+(((IkReal(10.0000000000000))*(r22)*(sj5)))+(((IkReal(10.0000000000000))*(r21)*(x8504)))+(((IkReal(-1000.00000000000))*(pz)))+(((IkReal(-364.420000000000))*(sj1)))+(((IkReal(-374.290000000000))*(r21)*(x8502)))))));
27691 sj2array[0]=IKsin(j2array[0]);
27692 cj2array[0]=IKcos(j2array[0]);
27693 if( j2array[0] > IKPI )
27694 {
27695     j2array[0]-=IK2PI;
27696 }
27697 else if( j2array[0] < -IKPI )
27698 {    j2array[0]+=IK2PI;
27699 }
27700 j2valid[0] = true;
27701 for(int ij2 = 0; ij2 < 1; ++ij2)
27702 {
27703 if( !j2valid[ij2] )
27704 {
27705     continue;
27706 }
27707 _ij2[0] = ij2; _ij2[1] = -1;
27708 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
27709 {
27710 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
27711 {
27712     j2valid[iij2]=false; _ij2[1] = iij2; break; 
27713 }
27714 }
27715 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
27716 {
27717 IkReal evalcond[3];
27718 IkReal x8511=IKcos(j2);
27719 IkReal x8512=((IkReal(0.374290000000000))*(sj5));
27720 IkReal x8513=((cj0)*(sj6));
27721 IkReal x8514=((IkReal(0.0100000000000000))*(sj5));
27722 IkReal x8515=((cj0)*(r02));
27723 IkReal x8516=((IkReal(0.0100000000000000))*(cj5));
27724 IkReal x8517=((IkReal(1.00000000000000))*(py));
27725 IkReal x8518=((r01)*(sj0));
27726 IkReal x8519=((r20)*(sj6));
27727 IkReal x8520=((r11)*(sj0));
27728 IkReal x8521=((IkReal(0.374290000000000))*(cj5));
27729 IkReal x8522=((cj0)*(r12));
27730 IkReal x8523=((sj0)*(x8521));
27731 IkReal x8524=((cj6)*(x8516));
27732 IkReal x8525=((IkReal(0.0690000000000000))*(x8511));
27733 IkReal x8526=((r10)*(sj0)*(sj6));
27734 IkReal x8527=((r00)*(sj0)*(sj6));
27735 IkReal x8528=((cj0)*(cj6)*(x8512));
27736 evalcond[0]=((((cj1)*(x8525)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x8521)))+(((IkReal(-1.00000000000000))*(x8516)*(x8519)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x8514)))+(((cj6)*(r21)*(x8512)))+(((x8512)*(x8519)))+(((IkReal(-1.00000000000000))*(r21)*(x8524))));
27737 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(x8512)*(x8513)))+(((IkReal(-1.00000000000000))*(r11)*(x8528)))+(((IkReal(-1.00000000000000))*(x8516)*(x8527)))+(((IkReal(-1.00000000000000))*(r02)*(x8523)))+(((x8512)*(x8527)))+(((x8521)*(x8522)))+(((r10)*(x8513)*(x8516)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8514)))+(((IkReal(0.0690000000000000))*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(x8518)*(x8524)))+(((IkReal(-1.00000000000000))*(cj0)*(x8517)))+(((px)*(sj0)))+(((cj6)*(x8512)*(x8518)))+(((cj0)*(r11)*(x8524)))+(((x8514)*(x8522))));
27738 evalcond[2]=((IkReal(0.0690000000000000))+(((x8516)*(x8526)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((r12)*(x8523)))+(((IkReal(-1.00000000000000))*(x8512)*(x8526)))+(((IkReal(-1.00000000000000))*(sj0)*(x8517)))+(((IkReal(-1.00000000000000))*(cj6)*(x8512)*(x8520)))+(((IkReal(-1.00000000000000))*(r01)*(x8528)))+(((r00)*(x8513)*(x8516)))+(((x8515)*(x8521)))+(((IkReal(-1.00000000000000))*(sj1)*(x8525)))+(((IkReal(-1.00000000000000))*(r00)*(x8512)*(x8513)))+(((x8514)*(x8515)))+(((cj0)*(r01)*(x8524)))+(((IkReal(0.364420000000000))*(cj1)))+(((r12)*(sj0)*(x8514)))+(((x8520)*(x8524))));
27739 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
27740 {
27741 continue;
27742 }
27743 }
27744 
27745 {
27746 IkReal dummyeval[1];
27747 IkReal gconst0;
27748 IkReal x8529=(cj6)*(cj6);
27749 IkReal x8530=(sj6)*(sj6);
27750 IkReal x8531=((IkReal(1.00000000000000))*(r01));
27751 IkReal x8532=((sj0)*(sj5));
27752 IkReal x8533=((cj6)*(r22));
27753 IkReal x8534=((r21)*(sj6));
27754 IkReal x8535=((r00)*(r21));
27755 IkReal x8536=((cj0)*(sj5));
27756 IkReal x8537=((cj6)*(r20));
27757 IkReal x8538=((r22)*(sj6));
27758 IkReal x8539=((cj0)*(cj5));
27759 IkReal x8540=((IkReal(1.00000000000000))*(r10));
27760 IkReal x8541=((cj5)*(sj0));
27761 IkReal x8542=((r20)*(x8530));
27762 IkReal x8543=((x8529)*(x8541));
27763 gconst0=IKsign(((((r00)*(x8532)*(x8533)))+(((x8535)*(x8543)))+(((IkReal(-1.00000000000000))*(x8531)*(x8532)*(x8538)))+(((IkReal(-1.00000000000000))*(r02)*(x8532)*(x8537)))+(((IkReal(-1.00000000000000))*(r21)*(x8530)*(x8539)*(x8540)))+(((r12)*(x8536)*(x8537)))+(((IkReal(-1.00000000000000))*(x8531)*(x8541)*(x8542)))+(((IkReal(-1.00000000000000))*(r20)*(x8531)*(x8543)))+(((r11)*(x8536)*(x8538)))+(((x8530)*(x8535)*(x8541)))+(((IkReal(-1.00000000000000))*(x8533)*(x8536)*(x8540)))+(((r11)*(x8539)*(x8542)))+(((r11)*(r20)*(x8529)*(x8539)))+(((IkReal(-1.00000000000000))*(r21)*(x8529)*(x8539)*(x8540)))+(((r02)*(x8532)*(x8534)))+(((IkReal(-1.00000000000000))*(r12)*(x8534)*(x8536)))));
27764 IkReal x8544=(cj6)*(cj6);
27765 IkReal x8545=(sj6)*(sj6);
27766 IkReal x8546=((IkReal(1.00000000000000))*(r01));
27767 IkReal x8547=((sj0)*(sj5));
27768 IkReal x8548=((cj6)*(r22));
27769 IkReal x8549=((r21)*(sj6));
27770 IkReal x8550=((r00)*(r21));
27771 IkReal x8551=((cj0)*(sj5));
27772 IkReal x8552=((cj6)*(r20));
27773 IkReal x8553=((r22)*(sj6));
27774 IkReal x8554=((cj0)*(cj5));
27775 IkReal x8555=((IkReal(1.00000000000000))*(r10));
27776 IkReal x8556=((cj5)*(sj0));
27777 IkReal x8557=((r20)*(x8545));
27778 IkReal x8558=((x8544)*(x8556));
27779 dummyeval[0]=((((x8545)*(x8550)*(x8556)))+(((IkReal(-1.00000000000000))*(r21)*(x8544)*(x8554)*(x8555)))+(((r11)*(x8551)*(x8553)))+(((r11)*(r20)*(x8544)*(x8554)))+(((r02)*(x8547)*(x8549)))+(((IkReal(-1.00000000000000))*(x8546)*(x8547)*(x8553)))+(((r11)*(x8554)*(x8557)))+(((IkReal(-1.00000000000000))*(r20)*(x8546)*(x8558)))+(((IkReal(-1.00000000000000))*(r12)*(x8549)*(x8551)))+(((IkReal(-1.00000000000000))*(x8548)*(x8551)*(x8555)))+(((IkReal(-1.00000000000000))*(r02)*(x8547)*(x8552)))+(((r12)*(x8551)*(x8552)))+(((r00)*(x8547)*(x8548)))+(((x8550)*(x8558)))+(((IkReal(-1.00000000000000))*(x8546)*(x8556)*(x8557)))+(((IkReal(-1.00000000000000))*(r21)*(x8545)*(x8554)*(x8555))));
27780 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
27781 {
27782 {
27783 IkReal dummyeval[1];
27784 IkReal gconst1;
27785 IkReal x8559=(cj6)*(cj6);
27786 IkReal x8560=(sj6)*(sj6);
27787 IkReal x8561=((sj5)*(sj6));
27788 IkReal x8562=((IkReal(1.00000000000000))*(cj0));
27789 IkReal x8563=((cj6)*(sj5));
27790 IkReal x8564=((r20)*(sj0));
27791 IkReal x8565=((cj0)*(r20));
27792 IkReal x8566=((r00)*(r21));
27793 IkReal x8567=((r22)*(sj0));
27794 IkReal x8568=((IkReal(1.00000000000000))*(r21)*(sj0));
27795 IkReal x8569=((cj5)*(x8560));
27796 IkReal x8570=((cj5)*(x8559));
27797 gconst1=IKsign(((((r12)*(x8563)*(x8564)))+(((r11)*(x8564)*(x8570)))+(((IkReal(-1.00000000000000))*(r10)*(x8568)*(x8570)))+(((IkReal(-1.00000000000000))*(r10)*(x8568)*(x8569)))+(((IkReal(-1.00000000000000))*(r10)*(x8563)*(x8567)))+(((IkReal(-1.00000000000000))*(x8562)*(x8566)*(x8569)))+(((r01)*(x8565)*(x8569)))+(((r02)*(x8563)*(x8565)))+(((cj0)*(r01)*(r22)*(x8561)))+(((r01)*(x8565)*(x8570)))+(((IkReal(-1.00000000000000))*(x8562)*(x8566)*(x8570)))+(((r11)*(x8564)*(x8569)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x8562)*(x8563)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x8561)*(x8562)))+(((r11)*(x8561)*(x8567)))+(((IkReal(-1.00000000000000))*(r12)*(x8561)*(x8568)))));
27798 IkReal x8571=(cj6)*(cj6);
27799 IkReal x8572=(sj6)*(sj6);
27800 IkReal x8573=((sj5)*(sj6));
27801 IkReal x8574=((IkReal(1.00000000000000))*(cj0));
27802 IkReal x8575=((cj6)*(sj5));
27803 IkReal x8576=((r20)*(sj0));
27804 IkReal x8577=((cj0)*(r20));
27805 IkReal x8578=((r00)*(r21));
27806 IkReal x8579=((r22)*(sj0));
27807 IkReal x8580=((IkReal(1.00000000000000))*(r21)*(sj0));
27808 IkReal x8581=((cj5)*(x8572));
27809 IkReal x8582=((cj5)*(x8571));
27810 dummyeval[0]=((((IkReal(-1.00000000000000))*(r12)*(x8573)*(x8580)))+(((cj0)*(r01)*(r22)*(x8573)))+(((r12)*(x8575)*(x8576)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x8574)*(x8575)))+(((r01)*(x8577)*(x8581)))+(((IkReal(-1.00000000000000))*(r10)*(x8575)*(x8579)))+(((IkReal(-1.00000000000000))*(x8574)*(x8578)*(x8582)))+(((r11)*(x8576)*(x8582)))+(((r11)*(x8576)*(x8581)))+(((r11)*(x8573)*(x8579)))+(((r01)*(x8577)*(x8582)))+(((IkReal(-1.00000000000000))*(r10)*(x8580)*(x8581)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x8573)*(x8574)))+(((IkReal(-1.00000000000000))*(x8574)*(x8578)*(x8581)))+(((r02)*(x8575)*(x8577)))+(((IkReal(-1.00000000000000))*(r10)*(x8580)*(x8582))));
27811 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
27812 {
27813 {
27814 IkReal dummyeval[2];
27815 IkReal x8583=(cj1)*(cj1);
27816 IkReal x8584=(sj1)*(sj1);
27817 dummyeval[0]=((((cj2)*(x8584)))+(((cj2)*(x8583))));
27818 dummyeval[1]=((x8583)+(x8584));
27819 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
27820 {
27821 {
27822 IkReal evalcond[4];
27823 IkReal x8585=((IkReal(0.374290000000000))*(sj5));
27824 IkReal x8586=((cj0)*(sj6));
27825 IkReal x8587=((IkReal(0.0100000000000000))*(sj5));
27826 IkReal x8588=((cj0)*(r02));
27827 IkReal x8589=((IkReal(0.0100000000000000))*(cj5));
27828 IkReal x8590=((IkReal(1.00000000000000))*(py));
27829 IkReal x8591=((r01)*(sj0));
27830 IkReal x8592=((r20)*(sj6));
27831 IkReal x8593=((r11)*(sj0));
27832 IkReal x8594=((IkReal(0.374290000000000))*(cj5));
27833 IkReal x8595=((cj0)*(r12));
27834 IkReal x8596=((sj0)*(x8594));
27835 IkReal x8597=((cj6)*(x8589));
27836 IkReal x8598=((r10)*(sj0)*(sj6));
27837 IkReal x8599=((r00)*(sj0)*(sj6));
27838 IkReal x8600=((cj0)*(cj6)*(x8585));
27839 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
27840 evalcond[1]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x8594)))+(((IkReal(-1.00000000000000))*(r22)*(x8587)))+(((cj6)*(r21)*(x8585)))+(pz)+(((IkReal(-1.00000000000000))*(x8589)*(x8592)))+(((IkReal(-1.00000000000000))*(r21)*(x8597)))+(((x8585)*(x8592))));
27841 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x8591)*(x8597)))+(((IkReal(-1.00000000000000))*(r10)*(x8585)*(x8586)))+(((IkReal(-1.00000000000000))*(cj0)*(x8590)))+(((IkReal(-1.00000000000000))*(x8589)*(x8599)))+(((cj0)*(r11)*(x8597)))+(((x8587)*(x8595)))+(((x8585)*(x8599)))+(((IkReal(-1.00000000000000))*(r02)*(x8596)))+(((r10)*(x8586)*(x8589)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8587)))+(((px)*(sj0)))+(((cj6)*(x8585)*(x8591)))+(((x8594)*(x8595)))+(((IkReal(-1.00000000000000))*(r11)*(x8600))));
27842 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x8588)*(x8594)))+(((IkReal(-1.00000000000000))*(cj6)*(x8585)*(x8593)))+(((r00)*(x8586)*(x8589)))+(((x8587)*(x8588)))+(((IkReal(-1.00000000000000))*(r01)*(x8600)))+(((r12)*(sj0)*(x8587)))+(((IkReal(-1.00000000000000))*(r00)*(x8585)*(x8586)))+(((x8589)*(x8598)))+(((r12)*(x8596)))+(((cj0)*(r01)*(x8597)))+(((IkReal(-1.00000000000000))*(x8585)*(x8598)))+(((IkReal(-1.00000000000000))*(sj0)*(x8590)))+(((x8593)*(x8597)))+(((IkReal(0.364420000000000))*(cj1))));
27843 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  )
27844 {
27845 {
27846 IkReal dummyeval[1];
27847 IkReal gconst13;
27848 IkReal x8601=(cj6)*(cj6);
27849 IkReal x8602=(sj6)*(sj6);
27850 IkReal x8603=((IkReal(1.00000000000000))*(r21));
27851 IkReal x8604=((cj6)*(r20));
27852 IkReal x8605=((r22)*(sj5));
27853 IkReal x8606=((r01)*(sj0));
27854 IkReal x8607=((r00)*(sj0));
27855 IkReal x8608=((cj0)*(r10));
27856 IkReal x8609=((r02)*(sj0)*(sj5));
27857 IkReal x8610=((cj5)*(x8601));
27858 IkReal x8611=((cj0)*(r12)*(sj5));
27859 IkReal x8612=((IkReal(1.00000000000000))*(cj0)*(r11));
27860 IkReal x8613=((cj5)*(x8602));
27861 IkReal x8614=((r20)*(x8613));
27862 gconst13=IKsign(((((IkReal(-1.00000000000000))*(x8612)*(x8614)))+(((r20)*(x8606)*(x8610)))+(((IkReal(-1.00000000000000))*(x8603)*(x8607)*(x8610)))+(((x8604)*(x8609)))+(((IkReal(-1.00000000000000))*(sj6)*(x8603)*(x8609)))+(((IkReal(-1.00000000000000))*(cj6)*(x8605)*(x8607)))+(((IkReal(-1.00000000000000))*(r20)*(x8610)*(x8612)))+(((IkReal(-1.00000000000000))*(x8603)*(x8607)*(x8613)))+(((IkReal(-1.00000000000000))*(x8604)*(x8611)))+(((x8606)*(x8614)))+(((r21)*(x8608)*(x8610)))+(((sj6)*(x8605)*(x8606)))+(((IkReal(-1.00000000000000))*(sj6)*(x8605)*(x8612)))+(((r21)*(sj6)*(x8611)))+(((cj6)*(x8605)*(x8608)))+(((r21)*(x8608)*(x8613)))));
27863 IkReal x8615=(cj6)*(cj6);
27864 IkReal x8616=(sj6)*(sj6);
27865 IkReal x8617=((IkReal(1.00000000000000))*(r21));
27866 IkReal x8618=((cj6)*(r20));
27867 IkReal x8619=((r22)*(sj5));
27868 IkReal x8620=((r01)*(sj0));
27869 IkReal x8621=((r00)*(sj0));
27870 IkReal x8622=((cj0)*(r10));
27871 IkReal x8623=((r02)*(sj0)*(sj5));
27872 IkReal x8624=((cj5)*(x8615));
27873 IkReal x8625=((cj0)*(r12)*(sj5));
27874 IkReal x8626=((IkReal(1.00000000000000))*(cj0)*(r11));
27875 IkReal x8627=((cj5)*(x8616));
27876 IkReal x8628=((r20)*(x8627));
27877 dummyeval[0]=((((r21)*(sj6)*(x8625)))+(((r20)*(x8620)*(x8624)))+(((IkReal(-1.00000000000000))*(x8626)*(x8628)))+(((IkReal(-1.00000000000000))*(r20)*(x8624)*(x8626)))+(((r21)*(x8622)*(x8624)))+(((IkReal(-1.00000000000000))*(x8618)*(x8625)))+(((IkReal(-1.00000000000000))*(sj6)*(x8617)*(x8623)))+(((IkReal(-1.00000000000000))*(x8617)*(x8621)*(x8624)))+(((x8620)*(x8628)))+(((cj6)*(x8619)*(x8622)))+(((x8618)*(x8623)))+(((r21)*(x8622)*(x8627)))+(((IkReal(-1.00000000000000))*(sj6)*(x8619)*(x8626)))+(((IkReal(-1.00000000000000))*(x8617)*(x8621)*(x8627)))+(((IkReal(-1.00000000000000))*(cj6)*(x8619)*(x8621)))+(((sj6)*(x8619)*(x8620))));
27878 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
27879 {
27880 {
27881 IkReal dummyeval[1];
27882 IkReal gconst14;
27883 IkReal x8629=(cj6)*(cj6);
27884 IkReal x8630=(sj6)*(sj6);
27885 IkReal x8631=((sj5)*(sj6));
27886 IkReal x8632=((IkReal(1.00000000000000))*(cj0));
27887 IkReal x8633=((cj6)*(sj5));
27888 IkReal x8634=((r20)*(sj0));
27889 IkReal x8635=((cj0)*(r20));
27890 IkReal x8636=((r00)*(r21));
27891 IkReal x8637=((r22)*(sj0));
27892 IkReal x8638=((IkReal(1.00000000000000))*(r21)*(sj0));
27893 IkReal x8639=((cj5)*(x8630));
27894 IkReal x8640=((cj5)*(x8629));
27895 gconst14=IKsign(((((IkReal(-1.00000000000000))*(r10)*(x8638)*(x8639)))+(((IkReal(-1.00000000000000))*(r10)*(x8638)*(x8640)))+(((r01)*(x8635)*(x8640)))+(((r11)*(x8634)*(x8639)))+(((r02)*(x8633)*(x8635)))+(((r12)*(x8633)*(x8634)))+(((r11)*(x8634)*(x8640)))+(((IkReal(-1.00000000000000))*(r10)*(x8633)*(x8637)))+(((cj0)*(r01)*(r22)*(x8631)))+(((r01)*(x8635)*(x8639)))+(((IkReal(-1.00000000000000))*(r12)*(x8631)*(x8638)))+(((r11)*(x8631)*(x8637)))+(((IkReal(-1.00000000000000))*(x8632)*(x8636)*(x8639)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x8631)*(x8632)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x8632)*(x8633)))+(((IkReal(-1.00000000000000))*(x8632)*(x8636)*(x8640)))));
27896 IkReal x8641=(cj6)*(cj6);
27897 IkReal x8642=(sj6)*(sj6);
27898 IkReal x8643=((sj5)*(sj6));
27899 IkReal x8644=((IkReal(1.00000000000000))*(cj0));
27900 IkReal x8645=((cj6)*(sj5));
27901 IkReal x8646=((r20)*(sj0));
27902 IkReal x8647=((cj0)*(r20));
27903 IkReal x8648=((r00)*(r21));
27904 IkReal x8649=((r22)*(sj0));
27905 IkReal x8650=((IkReal(1.00000000000000))*(r21)*(sj0));
27906 IkReal x8651=((cj5)*(x8642));
27907 IkReal x8652=((cj5)*(x8641));
27908 dummyeval[0]=((((cj0)*(r01)*(r22)*(x8643)))+(((r01)*(x8647)*(x8652)))+(((r11)*(x8646)*(x8652)))+(((IkReal(-1.00000000000000))*(r10)*(x8650)*(x8652)))+(((IkReal(-1.00000000000000))*(r10)*(x8645)*(x8649)))+(((r02)*(x8645)*(x8647)))+(((r11)*(x8643)*(x8649)))+(((IkReal(-1.00000000000000))*(r12)*(x8643)*(x8650)))+(((IkReal(-1.00000000000000))*(r10)*(x8650)*(x8651)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x8643)*(x8644)))+(((r01)*(x8647)*(x8651)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x8644)*(x8645)))+(((IkReal(-1.00000000000000))*(x8644)*(x8648)*(x8651)))+(((r12)*(x8645)*(x8646)))+(((r11)*(x8646)*(x8651)))+(((IkReal(-1.00000000000000))*(x8644)*(x8648)*(x8652))));
27909 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
27910 {
27911 {
27912 IkReal dummyeval[1];
27913 dummyeval[0]=sj1;
27914 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
27915 {
27916 {
27917 IkReal evalcond[5];
27918 IkReal x8653=((cj5)*(r22));
27919 IkReal x8654=((IkReal(0.374290000000000))*(sj5));
27920 IkReal x8655=((cj0)*(sj6));
27921 IkReal x8656=((cj6)*(r21));
27922 IkReal x8657=((IkReal(0.0100000000000000))*(sj5));
27923 IkReal x8658=((cj0)*(r02));
27924 IkReal x8659=((IkReal(0.0100000000000000))*(cj5));
27925 IkReal x8660=((IkReal(1.00000000000000))*(py));
27926 IkReal x8661=((r01)*(sj0));
27927 IkReal x8662=((r20)*(sj6));
27928 IkReal x8663=((r11)*(sj0));
27929 IkReal x8664=((IkReal(0.374290000000000))*(cj5));
27930 IkReal x8665=((cj0)*(r12));
27931 IkReal x8666=((sj0)*(x8664));
27932 IkReal x8667=((cj6)*(x8659));
27933 IkReal x8668=((r10)*(sj0)*(sj6));
27934 IkReal x8669=((r00)*(sj0)*(sj6));
27935 IkReal x8670=((cj0)*(cj6)*(x8654));
27936 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
27937 evalcond[1]=((((sj5)*(x8656)))+(((sj5)*(x8662)))+(((IkReal(-1.00000000000000))*(x8653))));
27938 evalcond[2]=((((x8654)*(x8656)))+(((IkReal(-0.374290000000000))*(x8653)))+(((IkReal(-1.00000000000000))*(x8659)*(x8662)))+(((IkReal(-1.00000000000000))*(x8656)*(x8659)))+(((x8654)*(x8662)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x8657))));
27939 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x8659)*(x8669)))+(((IkReal(-1.00000000000000))*(r11)*(x8670)))+(((cj6)*(x8654)*(x8661)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8657)))+(((x8657)*(x8665)))+(((IkReal(-1.00000000000000))*(r10)*(x8654)*(x8655)))+(((IkReal(-1.00000000000000))*(x8661)*(x8667)))+(((x8654)*(x8669)))+(((IkReal(-1.00000000000000))*(cj0)*(x8660)))+(((r10)*(x8655)*(x8659)))+(((IkReal(-1.00000000000000))*(r02)*(x8666)))+(((px)*(sj0)))+(((x8664)*(x8665)))+(((cj0)*(r11)*(x8667))));
27940 evalcond[4]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((r00)*(x8655)*(x8659)))+(((r12)*(sj0)*(x8657)))+(((IkReal(-1.00000000000000))*(r00)*(x8654)*(x8655)))+(((IkReal(-1.00000000000000))*(x8654)*(x8668)))+(((x8657)*(x8658)))+(((IkReal(-1.00000000000000))*(r01)*(x8670)))+(((x8659)*(x8668)))+(((r12)*(x8666)))+(((x8658)*(x8664)))+(((x8663)*(x8667)))+(((cj0)*(r01)*(x8667)))+(((IkReal(-1.00000000000000))*(sj0)*(x8660)))+(((IkReal(-1.00000000000000))*(cj6)*(x8654)*(x8663))));
27941 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
27942 {
27943 {
27944 IkReal j3array[1], cj3array[1], sj3array[1];
27945 bool j3valid[1]={false};
27946 _nj3 = 1;
27947 IkReal x8671=((cj0)*(cj5));
27948 IkReal x8672=((IkReal(1.00000000000000))*(cj0));
27949 IkReal x8673=((cj6)*(r11));
27950 IkReal x8674=((r10)*(sj6));
27951 IkReal x8675=((cj5)*(sj0));
27952 IkReal x8676=((r00)*(sj5)*(sj6));
27953 IkReal x8677=((cj6)*(r01)*(sj5));
27954 IkReal x8678=((IkReal(1.00000000000000))*(sj0)*(sj5));
27955 if( IKabs(((((sj0)*(x8677)))+(((r12)*(x8671)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8673)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8674)))+(((sj0)*(x8676)))+(((IkReal(-1.00000000000000))*(r02)*(x8675))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x8672)*(x8677)))+(((r02)*(x8671)))+(((IkReal(-1.00000000000000))*(x8672)*(x8676)))+(((IkReal(-1.00000000000000))*(x8674)*(x8678)))+(((IkReal(-1.00000000000000))*(x8673)*(x8678)))+(((r12)*(x8675))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x8677)))+(((r12)*(x8671)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8673)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8674)))+(((sj0)*(x8676)))+(((IkReal(-1.00000000000000))*(r02)*(x8675)))))+IKsqr(((((IkReal(-1.00000000000000))*(x8672)*(x8677)))+(((r02)*(x8671)))+(((IkReal(-1.00000000000000))*(x8672)*(x8676)))+(((IkReal(-1.00000000000000))*(x8674)*(x8678)))+(((IkReal(-1.00000000000000))*(x8673)*(x8678)))+(((r12)*(x8675)))))-1) <= IKFAST_SINCOS_THRESH )
27956     continue;
27957 j3array[0]=IKatan2(((((sj0)*(x8677)))+(((r12)*(x8671)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8673)))+(((IkReal(-1.00000000000000))*(sj5)*(x8672)*(x8674)))+(((sj0)*(x8676)))+(((IkReal(-1.00000000000000))*(r02)*(x8675)))), ((((IkReal(-1.00000000000000))*(x8672)*(x8677)))+(((r02)*(x8671)))+(((IkReal(-1.00000000000000))*(x8672)*(x8676)))+(((IkReal(-1.00000000000000))*(x8674)*(x8678)))+(((IkReal(-1.00000000000000))*(x8673)*(x8678)))+(((r12)*(x8675)))));
27958 sj3array[0]=IKsin(j3array[0]);
27959 cj3array[0]=IKcos(j3array[0]);
27960 if( j3array[0] > IKPI )
27961 {
27962     j3array[0]-=IK2PI;
27963 }
27964 else if( j3array[0] < -IKPI )
27965 {    j3array[0]+=IK2PI;
27966 }
27967 j3valid[0] = true;
27968 for(int ij3 = 0; ij3 < 1; ++ij3)
27969 {
27970 if( !j3valid[ij3] )
27971 {
27972     continue;
27973 }
27974 _ij3[0] = ij3; _ij3[1] = -1;
27975 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
27976 {
27977 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
27978 {
27979     j3valid[iij3]=false; _ij3[1] = iij3; break; 
27980 }
27981 }
27982 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
27983 {
27984 IkReal evalcond[2];
27985 IkReal x8679=((cj0)*(cj5));
27986 IkReal x8680=((IkReal(1.00000000000000))*(cj0));
27987 IkReal x8681=((cj6)*(r11));
27988 IkReal x8682=((r10)*(sj6));
27989 IkReal x8683=((cj5)*(sj0));
27990 IkReal x8684=((r00)*(sj5)*(sj6));
27991 IkReal x8685=((cj6)*(r01)*(sj5));
27992 IkReal x8686=((IkReal(1.00000000000000))*(sj0)*(sj5));
27993 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x8683)))+(((IkReal(-1.00000000000000))*(sj5)*(x8680)*(x8682)))+(((sj0)*(x8684)))+(((r12)*(x8679)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((IkReal(-1.00000000000000))*(sj5)*(x8680)*(x8681)))+(((sj0)*(x8685))));
27994 evalcond[1]=((((r02)*(x8679)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(x8680)*(x8684)))+(((IkReal(-1.00000000000000))*(x8682)*(x8686)))+(((IkReal(-1.00000000000000))*(x8680)*(x8685)))+(((IkReal(-1.00000000000000))*(x8681)*(x8686)))+(((r12)*(x8683))));
27995 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
27996 {
27997 continue;
27998 }
27999 }
28000 
28001 {
28002 IkReal dummyeval[1];
28003 IkReal gconst20;
28004 IkReal x8687=(cj5)*(cj5);
28005 IkReal x8688=(r20)*(r20);
28006 IkReal x8689=(sj6)*(sj6);
28007 IkReal x8690=(cj6)*(cj6);
28008 IkReal x8691=(r21)*(r21);
28009 IkReal x8692=((cj6)*(r21));
28010 IkReal x8693=((IkReal(2.00000000000000))*(r20)*(sj6));
28011 IkReal x8694=((cj5)*(r22)*(sj5));
28012 gconst20=IKsign(((((x8687)*(x8690)*(x8691)))+(((IkReal(-1.00000000000000))*(x8692)*(x8693)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x8687)*(x8688)*(x8689)))+(((x8689)*(x8691)))+(((x8687)*(x8692)*(x8693)))+(((x8688)*(x8690)))+(((x8693)*(x8694)))+(((IkReal(2.00000000000000))*(x8692)*(x8694)))));
28013 IkReal x8695=(cj5)*(cj5);
28014 IkReal x8696=(r20)*(r20);
28015 IkReal x8697=(sj6)*(sj6);
28016 IkReal x8698=(cj6)*(cj6);
28017 IkReal x8699=(r21)*(r21);
28018 IkReal x8700=((cj6)*(r21));
28019 IkReal x8701=((IkReal(2.00000000000000))*(r20)*(sj6));
28020 IkReal x8702=((cj5)*(r22)*(sj5));
28021 dummyeval[0]=((((IkReal(2.00000000000000))*(x8700)*(x8702)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x8695)*(x8700)*(x8701)))+(((x8696)*(x8698)))+(((x8697)*(x8699)))+(((x8695)*(x8698)*(x8699)))+(((IkReal(-1.00000000000000))*(x8700)*(x8701)))+(((x8701)*(x8702)))+(((x8695)*(x8696)*(x8697))));
28022 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28023 {
28024 {
28025 IkReal dummyeval[1];
28026 IkReal gconst21;
28027 IkReal x8703=(cj6)*(cj6);
28028 IkReal x8704=(sj6)*(sj6);
28029 IkReal x8705=((IkReal(1.00000000000000))*(r21));
28030 IkReal x8706=((cj6)*(r20));
28031 IkReal x8707=((r22)*(sj5));
28032 IkReal x8708=((r01)*(sj0));
28033 IkReal x8709=((r00)*(sj0));
28034 IkReal x8710=((cj0)*(r10));
28035 IkReal x8711=((r02)*(sj0)*(sj5));
28036 IkReal x8712=((cj5)*(x8703));
28037 IkReal x8713=((cj0)*(r12)*(sj5));
28038 IkReal x8714=((IkReal(1.00000000000000))*(cj0)*(r11));
28039 IkReal x8715=((cj5)*(x8704));
28040 IkReal x8716=((r20)*(x8715));
28041 gconst21=IKsign(((((r21)*(x8710)*(x8715)))+(((sj6)*(x8707)*(x8708)))+(((cj6)*(x8707)*(x8710)))+(((IkReal(-1.00000000000000))*(r20)*(x8712)*(x8714)))+(((IkReal(-1.00000000000000))*(cj6)*(x8707)*(x8709)))+(((x8706)*(x8711)))+(((x8708)*(x8716)))+(((IkReal(-1.00000000000000))*(x8706)*(x8713)))+(((r20)*(x8708)*(x8712)))+(((IkReal(-1.00000000000000))*(sj6)*(x8707)*(x8714)))+(((IkReal(-1.00000000000000))*(x8705)*(x8709)*(x8712)))+(((r21)*(sj6)*(x8713)))+(((IkReal(-1.00000000000000))*(x8705)*(x8709)*(x8715)))+(((IkReal(-1.00000000000000))*(sj6)*(x8705)*(x8711)))+(((r21)*(x8710)*(x8712)))+(((IkReal(-1.00000000000000))*(x8714)*(x8716)))));
28042 IkReal x8717=(cj6)*(cj6);
28043 IkReal x8718=(sj6)*(sj6);
28044 IkReal x8719=((IkReal(1.00000000000000))*(r21));
28045 IkReal x8720=((cj6)*(r20));
28046 IkReal x8721=((r22)*(sj5));
28047 IkReal x8722=((r01)*(sj0));
28048 IkReal x8723=((r00)*(sj0));
28049 IkReal x8724=((cj0)*(r10));
28050 IkReal x8725=((r02)*(sj0)*(sj5));
28051 IkReal x8726=((cj5)*(x8717));
28052 IkReal x8727=((cj0)*(r12)*(sj5));
28053 IkReal x8728=((IkReal(1.00000000000000))*(cj0)*(r11));
28054 IkReal x8729=((cj5)*(x8718));
28055 IkReal x8730=((r20)*(x8729));
28056 dummyeval[0]=((((x8722)*(x8730)))+(((r21)*(sj6)*(x8727)))+(((IkReal(-1.00000000000000))*(x8728)*(x8730)))+(((r21)*(x8724)*(x8729)))+(((sj6)*(x8721)*(x8722)))+(((x8720)*(x8725)))+(((r21)*(x8724)*(x8726)))+(((IkReal(-1.00000000000000))*(cj6)*(x8721)*(x8723)))+(((IkReal(-1.00000000000000))*(x8719)*(x8723)*(x8726)))+(((IkReal(-1.00000000000000))*(r20)*(x8726)*(x8728)))+(((r20)*(x8722)*(x8726)))+(((IkReal(-1.00000000000000))*(x8720)*(x8727)))+(((cj6)*(x8721)*(x8724)))+(((IkReal(-1.00000000000000))*(x8719)*(x8723)*(x8729)))+(((IkReal(-1.00000000000000))*(sj6)*(x8721)*(x8728)))+(((IkReal(-1.00000000000000))*(sj6)*(x8719)*(x8725))));
28057 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28058 {
28059 continue;
28060 
28061 } else
28062 {
28063 {
28064 IkReal j4array[1], cj4array[1], sj4array[1];
28065 bool j4valid[1]={false};
28066 _nj4 = 1;
28067 IkReal x8731=((sj0)*(sj6));
28068 IkReal x8732=((cj0)*(cj6));
28069 IkReal x8733=((IkReal(1.00000000000000))*(cj5));
28070 IkReal x8734=((cj6)*(sj0));
28071 IkReal x8735=((cj0)*(sj6));
28072 if( IKabs(((gconst21)*(((((r01)*(x8731)))+(((IkReal(-1.00000000000000))*(r11)*(x8735)))+(((r10)*(x8732)))+(((IkReal(-1.00000000000000))*(r00)*(x8734))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(r00)*(x8731)*(x8733)))+(((IkReal(-1.00000000000000))*(r01)*(x8733)*(x8734)))+(((cj0)*(r12)*(sj5)))+(((cj5)*(r11)*(x8732)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(r10)*(x8735))))))) < IKFAST_ATAN2_MAGTHRESH )
28073     continue;
28074 j4array[0]=IKatan2(((gconst21)*(((((r01)*(x8731)))+(((IkReal(-1.00000000000000))*(r11)*(x8735)))+(((r10)*(x8732)))+(((IkReal(-1.00000000000000))*(r00)*(x8734)))))), ((gconst21)*(((((IkReal(-1.00000000000000))*(r00)*(x8731)*(x8733)))+(((IkReal(-1.00000000000000))*(r01)*(x8733)*(x8734)))+(((cj0)*(r12)*(sj5)))+(((cj5)*(r11)*(x8732)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(r10)*(x8735)))))));
28075 sj4array[0]=IKsin(j4array[0]);
28076 cj4array[0]=IKcos(j4array[0]);
28077 if( j4array[0] > IKPI )
28078 {
28079     j4array[0]-=IK2PI;
28080 }
28081 else if( j4array[0] < -IKPI )
28082 {    j4array[0]+=IK2PI;
28083 }
28084 j4valid[0] = true;
28085 for(int ij4 = 0; ij4 < 1; ++ij4)
28086 {
28087 if( !j4valid[ij4] )
28088 {
28089     continue;
28090 }
28091 _ij4[0] = ij4; _ij4[1] = -1;
28092 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
28093 {
28094 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
28095 {
28096     j4valid[iij4]=false; _ij4[1] = iij4; break; 
28097 }
28098 }
28099 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
28100 {
28101 IkReal evalcond[6];
28102 IkReal x8736=IKsin(j4);
28103 IkReal x8737=IKcos(j4);
28104 IkReal x8738=((r22)*(sj5));
28105 IkReal x8739=((IkReal(1.00000000000000))*(cj6));
28106 IkReal x8740=((IkReal(1.00000000000000))*(cj0));
28107 IkReal x8741=((cj5)*(r11));
28108 IkReal x8742=((cj5)*(cj6));
28109 IkReal x8743=((r11)*(sj6));
28110 IkReal x8744=((IkReal(1.00000000000000))*(sj6));
28111 IkReal x8745=((cj6)*(r00));
28112 IkReal x8746=((r12)*(sj5));
28113 IkReal x8747=((r02)*(sj5));
28114 IkReal x8748=((cj6)*(r10));
28115 IkReal x8749=((cj5)*(sj6));
28116 IkReal x8750=((cj5)*(r01));
28117 IkReal x8751=((sj0)*(x8736));
28118 IkReal x8752=((r00)*(x8749));
28119 IkReal x8753=((cj0)*(x8736));
28120 IkReal x8754=((sj0)*(x8737));
28121 IkReal x8755=((r20)*(x8737));
28122 IkReal x8756=((cj0)*(x8737));
28123 IkReal x8757=((r21)*(x8736));
28124 IkReal x8758=((r21)*(x8737));
28125 IkReal x8759=((r20)*(x8736));
28126 IkReal x8760=((x8737)*(x8746));
28127 IkReal x8761=((r01)*(sj6)*(x8737));
28128 IkReal x8762=((cj5)*(r10)*(x8744));
28129 evalcond[0]=((IkReal(-1.00000000000000))+(((x8736)*(x8738)))+(((IkReal(-1.00000000000000))*(x8739)*(x8755)))+(((x8749)*(x8759)))+(((x8742)*(x8757)))+(((sj6)*(x8758))));
28130 evalcond[1]=((((x8749)*(x8755)))+(((x8742)*(x8758)))+(((IkReal(-1.00000000000000))*(x8744)*(x8757)))+(((cj6)*(x8759)))+(((x8737)*(x8738))));
28131 evalcond[2]=((((IkReal(-1.00000000000000))*(x8739)*(x8741)*(x8753)))+(((IkReal(-1.00000000000000))*(x8737)*(x8740)*(x8743)))+(((x8748)*(x8756)))+(((IkReal(-1.00000000000000))*(r10)*(x8736)*(x8740)*(x8749)))+(((IkReal(-1.00000000000000))*(x8736)*(x8740)*(x8746)))+(((x8747)*(x8751)))+(((r01)*(x8742)*(x8751)))+(((x8751)*(x8752)))+(((r01)*(sj6)*(x8754)))+(((IkReal(-1.00000000000000))*(r00)*(x8739)*(x8754))));
28132 evalcond[3]=((((x8747)*(x8754)))+(((r01)*(x8742)*(x8754)))+(((IkReal(-1.00000000000000))*(r10)*(x8739)*(x8753)))+(((IkReal(-1.00000000000000))*(x8740)*(x8760)))+(((x8752)*(x8754)))+(((IkReal(-1.00000000000000))*(r10)*(x8737)*(x8740)*(x8749)))+(cj3)+(((x8743)*(x8753)))+(((IkReal(-1.00000000000000))*(x8739)*(x8741)*(x8756)))+(((x8745)*(x8751)))+(((IkReal(-1.00000000000000))*(r01)*(x8744)*(x8751))));
28133 evalcond[4]=((((IkReal(-1.00000000000000))*(x8743)*(x8754)))+(((IkReal(-1.00000000000000))*(x8739)*(x8750)*(x8753)))+(((IkReal(-1.00000000000000))*(x8736)*(x8740)*(x8752)))+(((IkReal(-1.00000000000000))*(x8736)*(x8740)*(x8747)))+(((x8748)*(x8754)))+(((IkReal(-1.00000000000000))*(x8746)*(x8751)))+(((IkReal(-1.00000000000000))*(x8739)*(x8741)*(x8751)))+(((x8745)*(x8756)))+(((IkReal(-1.00000000000000))*(x8751)*(x8762)))+(((IkReal(-1.00000000000000))*(x8740)*(x8761))));
28134 evalcond[5]=((((IkReal(-1.00000000000000))*(x8737)*(x8740)*(x8747)))+(((r01)*(sj6)*(x8753)))+(((IkReal(-1.00000000000000))*(x8746)*(x8754)))+(((x8743)*(x8751)))+(((IkReal(-1.00000000000000))*(x8739)*(x8750)*(x8756)))+(((IkReal(-1.00000000000000))*(r00)*(x8739)*(x8753)))+(((IkReal(-1.00000000000000))*(x8737)*(x8740)*(x8752)))+(((IkReal(-1.00000000000000))*(x8739)*(x8741)*(x8754)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r10)*(x8739)*(x8751)))+(((IkReal(-1.00000000000000))*(x8754)*(x8762))));
28135 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
28136 {
28137 continue;
28138 }
28139 }
28140 
28141 {
28142 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
28143 vinfos[0].jointtype = 1;
28144 vinfos[0].foffset = j0;
28145 vinfos[0].indices[0] = _ij0[0];
28146 vinfos[0].indices[1] = _ij0[1];
28147 vinfos[0].maxsolutions = _nj0;
28148 vinfos[1].jointtype = 1;
28149 vinfos[1].foffset = j1;
28150 vinfos[1].indices[0] = _ij1[0];
28151 vinfos[1].indices[1] = _ij1[1];
28152 vinfos[1].maxsolutions = _nj1;
28153 vinfos[2].jointtype = 1;
28154 vinfos[2].foffset = j2;
28155 vinfos[2].indices[0] = _ij2[0];
28156 vinfos[2].indices[1] = _ij2[1];
28157 vinfos[2].maxsolutions = _nj2;
28158 vinfos[3].jointtype = 1;
28159 vinfos[3].foffset = j3;
28160 vinfos[3].indices[0] = _ij3[0];
28161 vinfos[3].indices[1] = _ij3[1];
28162 vinfos[3].maxsolutions = _nj3;
28163 vinfos[4].jointtype = 1;
28164 vinfos[4].foffset = j4;
28165 vinfos[4].indices[0] = _ij4[0];
28166 vinfos[4].indices[1] = _ij4[1];
28167 vinfos[4].maxsolutions = _nj4;
28168 vinfos[5].jointtype = 1;
28169 vinfos[5].foffset = j5;
28170 vinfos[5].indices[0] = _ij5[0];
28171 vinfos[5].indices[1] = _ij5[1];
28172 vinfos[5].maxsolutions = _nj5;
28173 vinfos[6].jointtype = 1;
28174 vinfos[6].foffset = j6;
28175 vinfos[6].indices[0] = _ij6[0];
28176 vinfos[6].indices[1] = _ij6[1];
28177 vinfos[6].maxsolutions = _nj6;
28178 std::vector<int> vfree(0);
28179 solutions.AddSolution(vinfos,vfree);
28180 }
28181 }
28182 }
28183 
28184 }
28185 
28186 }
28187 
28188 } else
28189 {
28190 {
28191 IkReal j4array[1], cj4array[1], sj4array[1];
28192 bool j4valid[1]={false};
28193 _nj4 = 1;
28194 if( IKabs(((gconst20)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst20)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
28195     continue;
28196 j4array[0]=IKatan2(((gconst20)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst20)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
28197 sj4array[0]=IKsin(j4array[0]);
28198 cj4array[0]=IKcos(j4array[0]);
28199 if( j4array[0] > IKPI )
28200 {
28201     j4array[0]-=IK2PI;
28202 }
28203 else if( j4array[0] < -IKPI )
28204 {    j4array[0]+=IK2PI;
28205 }
28206 j4valid[0] = true;
28207 for(int ij4 = 0; ij4 < 1; ++ij4)
28208 {
28209 if( !j4valid[ij4] )
28210 {
28211     continue;
28212 }
28213 _ij4[0] = ij4; _ij4[1] = -1;
28214 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
28215 {
28216 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
28217 {
28218     j4valid[iij4]=false; _ij4[1] = iij4; break; 
28219 }
28220 }
28221 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
28222 {
28223 IkReal evalcond[6];
28224 IkReal x8763=IKsin(j4);
28225 IkReal x8764=IKcos(j4);
28226 IkReal x8765=((r22)*(sj5));
28227 IkReal x8766=((IkReal(1.00000000000000))*(cj6));
28228 IkReal x8767=((IkReal(1.00000000000000))*(cj0));
28229 IkReal x8768=((cj5)*(r11));
28230 IkReal x8769=((cj5)*(cj6));
28231 IkReal x8770=((r11)*(sj6));
28232 IkReal x8771=((IkReal(1.00000000000000))*(sj6));
28233 IkReal x8772=((cj6)*(r00));
28234 IkReal x8773=((r12)*(sj5));
28235 IkReal x8774=((r02)*(sj5));
28236 IkReal x8775=((cj6)*(r10));
28237 IkReal x8776=((cj5)*(sj6));
28238 IkReal x8777=((cj5)*(r01));
28239 IkReal x8778=((sj0)*(x8763));
28240 IkReal x8779=((r00)*(x8776));
28241 IkReal x8780=((cj0)*(x8763));
28242 IkReal x8781=((sj0)*(x8764));
28243 IkReal x8782=((r20)*(x8764));
28244 IkReal x8783=((cj0)*(x8764));
28245 IkReal x8784=((r21)*(x8763));
28246 IkReal x8785=((r21)*(x8764));
28247 IkReal x8786=((r20)*(x8763));
28248 IkReal x8787=((x8764)*(x8773));
28249 IkReal x8788=((r01)*(sj6)*(x8764));
28250 IkReal x8789=((cj5)*(r10)*(x8771));
28251 evalcond[0]=((IkReal(-1.00000000000000))+(((x8763)*(x8765)))+(((x8769)*(x8784)))+(((IkReal(-1.00000000000000))*(x8766)*(x8782)))+(((sj6)*(x8785)))+(((x8776)*(x8786))));
28252 evalcond[1]=((((x8769)*(x8785)))+(((IkReal(-1.00000000000000))*(x8771)*(x8784)))+(((cj6)*(x8786)))+(((x8764)*(x8765)))+(((x8776)*(x8782))));
28253 evalcond[2]=((((r01)*(sj6)*(x8781)))+(((IkReal(-1.00000000000000))*(r00)*(x8766)*(x8781)))+(((r01)*(x8769)*(x8778)))+(((IkReal(-1.00000000000000))*(r10)*(x8763)*(x8767)*(x8776)))+(((IkReal(-1.00000000000000))*(x8764)*(x8767)*(x8770)))+(((x8774)*(x8778)))+(((IkReal(-1.00000000000000))*(x8766)*(x8768)*(x8780)))+(((IkReal(-1.00000000000000))*(x8763)*(x8767)*(x8773)))+(((x8775)*(x8783)))+(((x8778)*(x8779))));
28254 evalcond[3]=((((r01)*(x8769)*(x8781)))+(((x8770)*(x8780)))+(((x8779)*(x8781)))+(((IkReal(-1.00000000000000))*(r10)*(x8764)*(x8767)*(x8776)))+(((IkReal(-1.00000000000000))*(x8766)*(x8768)*(x8783)))+(((IkReal(-1.00000000000000))*(r01)*(x8771)*(x8778)))+(((IkReal(-1.00000000000000))*(r10)*(x8766)*(x8780)))+(cj3)+(((IkReal(-1.00000000000000))*(x8767)*(x8787)))+(((x8772)*(x8778)))+(((x8774)*(x8781))));
28255 evalcond[4]=((((x8775)*(x8781)))+(((IkReal(-1.00000000000000))*(x8763)*(x8767)*(x8774)))+(((x8772)*(x8783)))+(((IkReal(-1.00000000000000))*(x8773)*(x8778)))+(((IkReal(-1.00000000000000))*(x8763)*(x8767)*(x8779)))+(((IkReal(-1.00000000000000))*(x8767)*(x8788)))+(((IkReal(-1.00000000000000))*(x8766)*(x8768)*(x8778)))+(((IkReal(-1.00000000000000))*(x8778)*(x8789)))+(((IkReal(-1.00000000000000))*(x8770)*(x8781)))+(((IkReal(-1.00000000000000))*(x8766)*(x8777)*(x8780))));
28256 evalcond[5]=((((IkReal(-1.00000000000000))*(x8764)*(x8767)*(x8779)))+(((IkReal(-1.00000000000000))*(r00)*(x8766)*(x8780)))+(((IkReal(-1.00000000000000))*(x8764)*(x8767)*(x8774)))+(((IkReal(-1.00000000000000))*(r10)*(x8766)*(x8778)))+(((IkReal(-1.00000000000000))*(x8766)*(x8768)*(x8781)))+(((r01)*(sj6)*(x8780)))+(((IkReal(-1.00000000000000))*(x8766)*(x8777)*(x8783)))+(((IkReal(-1.00000000000000))*(x8773)*(x8781)))+(((IkReal(-1.00000000000000))*(sj3)))+(((x8770)*(x8778)))+(((IkReal(-1.00000000000000))*(x8781)*(x8789))));
28257 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
28258 {
28259 continue;
28260 }
28261 }
28262 
28263 {
28264 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
28265 vinfos[0].jointtype = 1;
28266 vinfos[0].foffset = j0;
28267 vinfos[0].indices[0] = _ij0[0];
28268 vinfos[0].indices[1] = _ij0[1];
28269 vinfos[0].maxsolutions = _nj0;
28270 vinfos[1].jointtype = 1;
28271 vinfos[1].foffset = j1;
28272 vinfos[1].indices[0] = _ij1[0];
28273 vinfos[1].indices[1] = _ij1[1];
28274 vinfos[1].maxsolutions = _nj1;
28275 vinfos[2].jointtype = 1;
28276 vinfos[2].foffset = j2;
28277 vinfos[2].indices[0] = _ij2[0];
28278 vinfos[2].indices[1] = _ij2[1];
28279 vinfos[2].maxsolutions = _nj2;
28280 vinfos[3].jointtype = 1;
28281 vinfos[3].foffset = j3;
28282 vinfos[3].indices[0] = _ij3[0];
28283 vinfos[3].indices[1] = _ij3[1];
28284 vinfos[3].maxsolutions = _nj3;
28285 vinfos[4].jointtype = 1;
28286 vinfos[4].foffset = j4;
28287 vinfos[4].indices[0] = _ij4[0];
28288 vinfos[4].indices[1] = _ij4[1];
28289 vinfos[4].maxsolutions = _nj4;
28290 vinfos[5].jointtype = 1;
28291 vinfos[5].foffset = j5;
28292 vinfos[5].indices[0] = _ij5[0];
28293 vinfos[5].indices[1] = _ij5[1];
28294 vinfos[5].maxsolutions = _nj5;
28295 vinfos[6].jointtype = 1;
28296 vinfos[6].foffset = j6;
28297 vinfos[6].indices[0] = _ij6[0];
28298 vinfos[6].indices[1] = _ij6[1];
28299 vinfos[6].maxsolutions = _nj6;
28300 std::vector<int> vfree(0);
28301 solutions.AddSolution(vinfos,vfree);
28302 }
28303 }
28304 }
28305 
28306 }
28307 
28308 }
28309 }
28310 }
28311 
28312 } else
28313 {
28314 IkReal x8790=((cj5)*(r22));
28315 IkReal x8791=((IkReal(0.374290000000000))*(sj5));
28316 IkReal x8792=((cj0)*(sj6));
28317 IkReal x8793=((cj6)*(r21));
28318 IkReal x8794=((IkReal(0.0100000000000000))*(sj5));
28319 IkReal x8795=((cj0)*(r02));
28320 IkReal x8796=((IkReal(0.0100000000000000))*(cj5));
28321 IkReal x8797=((IkReal(1.00000000000000))*(py));
28322 IkReal x8798=((r01)*(sj0));
28323 IkReal x8799=((r20)*(sj6));
28324 IkReal x8800=((r11)*(sj0));
28325 IkReal x8801=((IkReal(0.374290000000000))*(cj5));
28326 IkReal x8802=((cj0)*(r12));
28327 IkReal x8803=((sj0)*(x8801));
28328 IkReal x8804=((cj6)*(x8796));
28329 IkReal x8805=((r10)*(sj0)*(sj6));
28330 IkReal x8806=((r00)*(sj0)*(sj6));
28331 IkReal x8807=((cj0)*(cj6)*(x8791));
28332 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
28333 evalcond[1]=((((sj5)*(x8793)))+(((sj5)*(x8799)))+(((IkReal(-1.00000000000000))*(x8790))));
28334 evalcond[2]=((((IkReal(-1.00000000000000))*(x8793)*(x8796)))+(((x8791)*(x8799)))+(((x8791)*(x8793)))+(((IkReal(-1.00000000000000))*(x8796)*(x8799)))+(((IkReal(-0.374290000000000))*(x8790)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x8794))));
28335 evalcond[3]=((IkReal(0.0690000000000000))+(((x8794)*(x8802)))+(((cj6)*(x8791)*(x8798)))+(((IkReal(-1.00000000000000))*(x8796)*(x8806)))+(((x8791)*(x8806)))+(((cj0)*(r11)*(x8804)))+(((IkReal(-1.00000000000000))*(r10)*(x8791)*(x8792)))+(((IkReal(-1.00000000000000))*(r11)*(x8807)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8794)))+(((IkReal(-1.00000000000000))*(r02)*(x8803)))+(((px)*(sj0)))+(((x8801)*(x8802)))+(((IkReal(-1.00000000000000))*(x8798)*(x8804)))+(((IkReal(-1.00000000000000))*(cj0)*(x8797)))+(((r10)*(x8792)*(x8796))));
28336 evalcond[4]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x8800)*(x8804)))+(((x8796)*(x8805)))+(((r00)*(x8792)*(x8796)))+(((r12)*(sj0)*(x8794)))+(((IkReal(-1.00000000000000))*(x8791)*(x8805)))+(((x8794)*(x8795)))+(((IkReal(-1.00000000000000))*(cj6)*(x8791)*(x8800)))+(((IkReal(-1.00000000000000))*(r00)*(x8791)*(x8792)))+(((r12)*(x8803)))+(((cj0)*(r01)*(x8804)))+(((IkReal(-1.00000000000000))*(r01)*(x8807)))+(((x8795)*(x8801)))+(((IkReal(-1.00000000000000))*(sj0)*(x8797))));
28337 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
28338 {
28339 {
28340 IkReal j3array[1], cj3array[1], sj3array[1];
28341 bool j3valid[1]={false};
28342 _nj3 = 1;
28343 IkReal x8808=((sj0)*(sj5));
28344 IkReal x8809=((r00)*(sj6));
28345 IkReal x8810=((IkReal(1.00000000000000))*(cj5));
28346 IkReal x8811=((cj6)*(r11));
28347 IkReal x8812=((cj6)*(r01));
28348 IkReal x8813=((r10)*(sj6));
28349 IkReal x8814=((cj0)*(sj5));
28350 if( IKabs(((((x8808)*(x8812)))+(((IkReal(-1.00000000000000))*(x8813)*(x8814)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8810)))+(((x8808)*(x8809)))+(((IkReal(-1.00000000000000))*(x8811)*(x8814))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x8808)*(x8811)))+(((x8808)*(x8813)))+(((x8809)*(x8814)))+(((x8812)*(x8814)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x8810)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x8810))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x8808)*(x8812)))+(((IkReal(-1.00000000000000))*(x8813)*(x8814)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8810)))+(((x8808)*(x8809)))+(((IkReal(-1.00000000000000))*(x8811)*(x8814)))))+IKsqr(((((x8808)*(x8811)))+(((x8808)*(x8813)))+(((x8809)*(x8814)))+(((x8812)*(x8814)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x8810)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x8810)))))-1) <= IKFAST_SINCOS_THRESH )
28351     continue;
28352 j3array[0]=IKatan2(((((x8808)*(x8812)))+(((IkReal(-1.00000000000000))*(x8813)*(x8814)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8810)))+(((x8808)*(x8809)))+(((IkReal(-1.00000000000000))*(x8811)*(x8814)))), ((((x8808)*(x8811)))+(((x8808)*(x8813)))+(((x8809)*(x8814)))+(((x8812)*(x8814)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x8810)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x8810)))));
28353 sj3array[0]=IKsin(j3array[0]);
28354 cj3array[0]=IKcos(j3array[0]);
28355 if( j3array[0] > IKPI )
28356 {
28357     j3array[0]-=IK2PI;
28358 }
28359 else if( j3array[0] < -IKPI )
28360 {    j3array[0]+=IK2PI;
28361 }
28362 j3valid[0] = true;
28363 for(int ij3 = 0; ij3 < 1; ++ij3)
28364 {
28365 if( !j3valid[ij3] )
28366 {
28367     continue;
28368 }
28369 _ij3[0] = ij3; _ij3[1] = -1;
28370 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
28371 {
28372 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
28373 {
28374     j3valid[iij3]=false; _ij3[1] = iij3; break; 
28375 }
28376 }
28377 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
28378 {
28379 IkReal evalcond[2];
28380 IkReal x8815=((cj0)*(cj5));
28381 IkReal x8816=((IkReal(1.00000000000000))*(cj0));
28382 IkReal x8817=((cj6)*(r11));
28383 IkReal x8818=((r10)*(sj6));
28384 IkReal x8819=((cj5)*(sj0));
28385 IkReal x8820=((r00)*(sj5)*(sj6));
28386 IkReal x8821=((cj6)*(r01)*(sj5));
28387 IkReal x8822=((IkReal(1.00000000000000))*(sj0)*(sj5));
28388 evalcond[0]=((((sj0)*(x8821)))+(((r12)*(x8815)))+(((IkReal(-1.00000000000000))*(r02)*(x8819)))+(((sj0)*(x8820)))+(((IkReal(-1.00000000000000))*(sj5)*(x8816)*(x8817)))+(((IkReal(-1.00000000000000))*(sj5)*(x8816)*(x8818)))+(((IkReal(-1.00000000000000))*(IKsin(j3)))));
28389 evalcond[1]=((((IkReal(-1.00000000000000))*(x8817)*(x8822)))+(((r12)*(x8819)))+(((IkReal(-1.00000000000000))*(x8816)*(x8820)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x8818)*(x8822)))+(((r02)*(x8815)))+(((IkReal(-1.00000000000000))*(x8816)*(x8821))));
28390 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
28391 {
28392 continue;
28393 }
28394 }
28395 
28396 {
28397 IkReal dummyeval[1];
28398 IkReal gconst24;
28399 IkReal x8823=(r21)*(r21);
28400 IkReal x8824=(cj5)*(cj5);
28401 IkReal x8825=(sj6)*(sj6);
28402 IkReal x8826=(cj6)*(cj6);
28403 IkReal x8827=(r20)*(r20);
28404 IkReal x8828=((cj6)*(r21));
28405 IkReal x8829=((IkReal(2.00000000000000))*(r20)*(sj6));
28406 IkReal x8830=((cj5)*(r22)*(sj5));
28407 IkReal x8831=((IkReal(1.00000000000000))*(x8825));
28408 IkReal x8832=((IkReal(1.00000000000000))*(x8826));
28409 gconst24=IKsign(((((IkReal(-1.00000000000000))*(x8823)*(x8824)*(x8832)))+(((IkReal(-2.00000000000000))*(x8828)*(x8830)))+(((IkReal(-1.00000000000000))*(x8823)*(x8831)))+(((IkReal(-1.00000000000000))*(x8824)*(x8828)*(x8829)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x8829)*(x8830)))+(((IkReal(-1.00000000000000))*(x8824)*(x8827)*(x8831)))+(((x8828)*(x8829)))+(((IkReal(-1.00000000000000))*(x8827)*(x8832)))));
28410 IkReal x8833=(r21)*(r21);
28411 IkReal x8834=(cj5)*(cj5);
28412 IkReal x8835=(sj6)*(sj6);
28413 IkReal x8836=(cj6)*(cj6);
28414 IkReal x8837=(r20)*(r20);
28415 IkReal x8838=((cj6)*(r21));
28416 IkReal x8839=((IkReal(2.00000000000000))*(r20)*(sj6));
28417 IkReal x8840=((cj5)*(r22)*(sj5));
28418 IkReal x8841=((IkReal(1.00000000000000))*(x8835));
28419 IkReal x8842=((IkReal(1.00000000000000))*(x8836));
28420 dummyeval[0]=((((IkReal(-1.00000000000000))*(x8833)*(x8834)*(x8842)))+(((IkReal(-1.00000000000000))*(x8834)*(x8837)*(x8841)))+(((x8838)*(x8839)))+(((IkReal(-2.00000000000000))*(x8838)*(x8840)))+(((IkReal(-1.00000000000000))*(x8833)*(x8841)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x8837)*(x8842)))+(((IkReal(-1.00000000000000))*(x8834)*(x8838)*(x8839)))+(((IkReal(-1.00000000000000))*(x8839)*(x8840))));
28421 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28422 {
28423 {
28424 IkReal dummyeval[1];
28425 IkReal gconst25;
28426 IkReal x8843=(cj6)*(cj6);
28427 IkReal x8844=(sj6)*(sj6);
28428 IkReal x8845=((IkReal(1.00000000000000))*(r01));
28429 IkReal x8846=((sj0)*(sj5));
28430 IkReal x8847=((cj6)*(r22));
28431 IkReal x8848=((r21)*(sj6));
28432 IkReal x8849=((r00)*(r21));
28433 IkReal x8850=((cj0)*(sj5));
28434 IkReal x8851=((cj6)*(r20));
28435 IkReal x8852=((r22)*(sj6));
28436 IkReal x8853=((cj0)*(cj5));
28437 IkReal x8854=((IkReal(1.00000000000000))*(r10));
28438 IkReal x8855=((cj5)*(sj0));
28439 IkReal x8856=((r20)*(x8844));
28440 IkReal x8857=((x8843)*(x8855));
28441 gconst25=IKsign(((((IkReal(-1.00000000000000))*(x8845)*(x8855)*(x8856)))+(((IkReal(-1.00000000000000))*(r12)*(x8848)*(x8850)))+(((r02)*(x8846)*(x8848)))+(((IkReal(-1.00000000000000))*(r21)*(x8843)*(x8853)*(x8854)))+(((r11)*(x8853)*(x8856)))+(((x8849)*(x8857)))+(((IkReal(-1.00000000000000))*(r02)*(x8846)*(x8851)))+(((r11)*(r20)*(x8843)*(x8853)))+(((x8844)*(x8849)*(x8855)))+(((r12)*(x8850)*(x8851)))+(((IkReal(-1.00000000000000))*(r20)*(x8845)*(x8857)))+(((IkReal(-1.00000000000000))*(x8845)*(x8846)*(x8852)))+(((r00)*(x8846)*(x8847)))+(((IkReal(-1.00000000000000))*(r21)*(x8844)*(x8853)*(x8854)))+(((r11)*(x8850)*(x8852)))+(((IkReal(-1.00000000000000))*(x8847)*(x8850)*(x8854)))));
28442 IkReal x8858=(cj6)*(cj6);
28443 IkReal x8859=(sj6)*(sj6);
28444 IkReal x8860=((IkReal(1.00000000000000))*(r01));
28445 IkReal x8861=((sj0)*(sj5));
28446 IkReal x8862=((cj6)*(r22));
28447 IkReal x8863=((r21)*(sj6));
28448 IkReal x8864=((r00)*(r21));
28449 IkReal x8865=((cj0)*(sj5));
28450 IkReal x8866=((cj6)*(r20));
28451 IkReal x8867=((r22)*(sj6));
28452 IkReal x8868=((cj0)*(cj5));
28453 IkReal x8869=((IkReal(1.00000000000000))*(r10));
28454 IkReal x8870=((cj5)*(sj0));
28455 IkReal x8871=((r20)*(x8859));
28456 IkReal x8872=((x8858)*(x8870));
28457 dummyeval[0]=((((IkReal(-1.00000000000000))*(x8860)*(x8870)*(x8871)))+(((IkReal(-1.00000000000000))*(r21)*(x8858)*(x8868)*(x8869)))+(((IkReal(-1.00000000000000))*(x8860)*(x8861)*(x8867)))+(((IkReal(-1.00000000000000))*(x8862)*(x8865)*(x8869)))+(((x8864)*(x8872)))+(((r02)*(x8861)*(x8863)))+(((IkReal(-1.00000000000000))*(r21)*(x8859)*(x8868)*(x8869)))+(((IkReal(-1.00000000000000))*(r02)*(x8861)*(x8866)))+(((r11)*(x8865)*(x8867)))+(((r12)*(x8865)*(x8866)))+(((r00)*(x8861)*(x8862)))+(((r11)*(x8868)*(x8871)))+(((x8859)*(x8864)*(x8870)))+(((r11)*(r20)*(x8858)*(x8868)))+(((IkReal(-1.00000000000000))*(r20)*(x8860)*(x8872)))+(((IkReal(-1.00000000000000))*(r12)*(x8863)*(x8865))));
28458 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28459 {
28460 continue;
28461 
28462 } else
28463 {
28464 {
28465 IkReal j4array[1], cj4array[1], sj4array[1];
28466 bool j4valid[1]={false};
28467 _nj4 = 1;
28468 IkReal x8873=((r01)*(sj0));
28469 IkReal x8874=((IkReal(1.00000000000000))*(cj5));
28470 IkReal x8875=((cj0)*(r10));
28471 IkReal x8876=((r00)*(sj0));
28472 IkReal x8877=((cj0)*(r11));
28473 if( IKabs(((gconst25)*(((((cj6)*(x8875)))+(((sj6)*(x8873)))+(((IkReal(-1.00000000000000))*(sj6)*(x8877)))+(((IkReal(-1.00000000000000))*(cj6)*(x8876))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((IkReal(-1.00000000000000))*(sj6)*(x8874)*(x8876)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x8877)))+(((IkReal(-1.00000000000000))*(cj6)*(x8873)*(x8874)))+(((cj5)*(sj6)*(x8875))))))) < IKFAST_ATAN2_MAGTHRESH )
28474     continue;
28475 j4array[0]=IKatan2(((gconst25)*(((((cj6)*(x8875)))+(((sj6)*(x8873)))+(((IkReal(-1.00000000000000))*(sj6)*(x8877)))+(((IkReal(-1.00000000000000))*(cj6)*(x8876)))))), ((gconst25)*(((((IkReal(-1.00000000000000))*(sj6)*(x8874)*(x8876)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x8877)))+(((IkReal(-1.00000000000000))*(cj6)*(x8873)*(x8874)))+(((cj5)*(sj6)*(x8875)))))));
28476 sj4array[0]=IKsin(j4array[0]);
28477 cj4array[0]=IKcos(j4array[0]);
28478 if( j4array[0] > IKPI )
28479 {
28480     j4array[0]-=IK2PI;
28481 }
28482 else if( j4array[0] < -IKPI )
28483 {    j4array[0]+=IK2PI;
28484 }
28485 j4valid[0] = true;
28486 for(int ij4 = 0; ij4 < 1; ++ij4)
28487 {
28488 if( !j4valid[ij4] )
28489 {
28490     continue;
28491 }
28492 _ij4[0] = ij4; _ij4[1] = -1;
28493 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
28494 {
28495 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
28496 {
28497     j4valid[iij4]=false; _ij4[1] = iij4; break; 
28498 }
28499 }
28500 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
28501 {
28502 IkReal evalcond[6];
28503 IkReal x8878=IKsin(j4);
28504 IkReal x8879=IKcos(j4);
28505 IkReal x8880=((r22)*(sj5));
28506 IkReal x8881=((IkReal(1.00000000000000))*(cj6));
28507 IkReal x8882=((IkReal(1.00000000000000))*(cj0));
28508 IkReal x8883=((cj5)*(r11));
28509 IkReal x8884=((cj5)*(cj6));
28510 IkReal x8885=((r11)*(sj6));
28511 IkReal x8886=((IkReal(1.00000000000000))*(sj6));
28512 IkReal x8887=((cj6)*(r00));
28513 IkReal x8888=((r12)*(sj5));
28514 IkReal x8889=((r02)*(sj5));
28515 IkReal x8890=((cj6)*(r10));
28516 IkReal x8891=((cj5)*(sj6));
28517 IkReal x8892=((cj5)*(r01));
28518 IkReal x8893=((sj0)*(x8878));
28519 IkReal x8894=((r00)*(x8891));
28520 IkReal x8895=((cj0)*(x8878));
28521 IkReal x8896=((sj0)*(x8879));
28522 IkReal x8897=((r20)*(x8879));
28523 IkReal x8898=((cj0)*(x8879));
28524 IkReal x8899=((r21)*(x8878));
28525 IkReal x8900=((r21)*(x8879));
28526 IkReal x8901=((r20)*(x8878));
28527 IkReal x8902=((x8879)*(x8888));
28528 IkReal x8903=((r01)*(sj6)*(x8879));
28529 IkReal x8904=((cj5)*(r10)*(x8886));
28530 evalcond[0]=((IkReal(1.00000000000000))+(((x8884)*(x8899)))+(((sj6)*(x8900)))+(((x8878)*(x8880)))+(((x8891)*(x8901)))+(((IkReal(-1.00000000000000))*(x8881)*(x8897))));
28531 evalcond[1]=((((x8879)*(x8880)))+(((x8891)*(x8897)))+(((cj6)*(x8901)))+(((IkReal(-1.00000000000000))*(x8886)*(x8899)))+(((x8884)*(x8900))));
28532 evalcond[2]=((((r01)*(x8884)*(x8893)))+(((r01)*(sj6)*(x8896)))+(((IkReal(-1.00000000000000))*(x8879)*(x8882)*(x8885)))+(((x8890)*(x8898)))+(((x8889)*(x8893)))+(((IkReal(-1.00000000000000))*(r10)*(x8878)*(x8882)*(x8891)))+(((IkReal(-1.00000000000000))*(x8878)*(x8882)*(x8888)))+(((IkReal(-1.00000000000000))*(x8881)*(x8883)*(x8895)))+(((x8893)*(x8894)))+(((IkReal(-1.00000000000000))*(r00)*(x8881)*(x8896))));
28533 evalcond[3]=((((r01)*(x8884)*(x8896)))+(((IkReal(-1.00000000000000))*(r10)*(x8881)*(x8895)))+(((IkReal(-1.00000000000000))*(x8881)*(x8883)*(x8898)))+(((IkReal(-1.00000000000000))*(x8882)*(x8902)))+(((IkReal(-1.00000000000000))*(r01)*(x8886)*(x8893)))+(cj3)+(((x8885)*(x8895)))+(((x8887)*(x8893)))+(((IkReal(-1.00000000000000))*(r10)*(x8879)*(x8882)*(x8891)))+(((x8889)*(x8896)))+(((x8894)*(x8896))));
28534 evalcond[4]=((((IkReal(-1.00000000000000))*(x8881)*(x8892)*(x8895)))+(((IkReal(-1.00000000000000))*(x8878)*(x8882)*(x8894)))+(((IkReal(-1.00000000000000))*(x8878)*(x8882)*(x8889)))+(((x8890)*(x8896)))+(((IkReal(-1.00000000000000))*(x8888)*(x8893)))+(((IkReal(-1.00000000000000))*(x8893)*(x8904)))+(((IkReal(-1.00000000000000))*(x8881)*(x8883)*(x8893)))+(((IkReal(-1.00000000000000))*(x8885)*(x8896)))+(((x8887)*(x8898)))+(((IkReal(-1.00000000000000))*(x8882)*(x8903))));
28535 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x8881)*(x8895)))+(sj3)+(((IkReal(-1.00000000000000))*(x8879)*(x8882)*(x8889)))+(((IkReal(-1.00000000000000))*(x8881)*(x8883)*(x8896)))+(((IkReal(-1.00000000000000))*(x8888)*(x8896)))+(((IkReal(-1.00000000000000))*(x8896)*(x8904)))+(((IkReal(-1.00000000000000))*(x8879)*(x8882)*(x8894)))+(((IkReal(-1.00000000000000))*(r10)*(x8881)*(x8893)))+(((r01)*(sj6)*(x8895)))+(((IkReal(-1.00000000000000))*(x8881)*(x8892)*(x8898)))+(((x8885)*(x8893))));
28536 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
28537 {
28538 continue;
28539 }
28540 }
28541 
28542 {
28543 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
28544 vinfos[0].jointtype = 1;
28545 vinfos[0].foffset = j0;
28546 vinfos[0].indices[0] = _ij0[0];
28547 vinfos[0].indices[1] = _ij0[1];
28548 vinfos[0].maxsolutions = _nj0;
28549 vinfos[1].jointtype = 1;
28550 vinfos[1].foffset = j1;
28551 vinfos[1].indices[0] = _ij1[0];
28552 vinfos[1].indices[1] = _ij1[1];
28553 vinfos[1].maxsolutions = _nj1;
28554 vinfos[2].jointtype = 1;
28555 vinfos[2].foffset = j2;
28556 vinfos[2].indices[0] = _ij2[0];
28557 vinfos[2].indices[1] = _ij2[1];
28558 vinfos[2].maxsolutions = _nj2;
28559 vinfos[3].jointtype = 1;
28560 vinfos[3].foffset = j3;
28561 vinfos[3].indices[0] = _ij3[0];
28562 vinfos[3].indices[1] = _ij3[1];
28563 vinfos[3].maxsolutions = _nj3;
28564 vinfos[4].jointtype = 1;
28565 vinfos[4].foffset = j4;
28566 vinfos[4].indices[0] = _ij4[0];
28567 vinfos[4].indices[1] = _ij4[1];
28568 vinfos[4].maxsolutions = _nj4;
28569 vinfos[5].jointtype = 1;
28570 vinfos[5].foffset = j5;
28571 vinfos[5].indices[0] = _ij5[0];
28572 vinfos[5].indices[1] = _ij5[1];
28573 vinfos[5].maxsolutions = _nj5;
28574 vinfos[6].jointtype = 1;
28575 vinfos[6].foffset = j6;
28576 vinfos[6].indices[0] = _ij6[0];
28577 vinfos[6].indices[1] = _ij6[1];
28578 vinfos[6].maxsolutions = _nj6;
28579 std::vector<int> vfree(0);
28580 solutions.AddSolution(vinfos,vfree);
28581 }
28582 }
28583 }
28584 
28585 }
28586 
28587 }
28588 
28589 } else
28590 {
28591 {
28592 IkReal j4array[1], cj4array[1], sj4array[1];
28593 bool j4valid[1]={false};
28594 _nj4 = 1;
28595 if( IKabs(((gconst24)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst24)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
28596     continue;
28597 j4array[0]=IKatan2(((gconst24)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst24)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
28598 sj4array[0]=IKsin(j4array[0]);
28599 cj4array[0]=IKcos(j4array[0]);
28600 if( j4array[0] > IKPI )
28601 {
28602     j4array[0]-=IK2PI;
28603 }
28604 else if( j4array[0] < -IKPI )
28605 {    j4array[0]+=IK2PI;
28606 }
28607 j4valid[0] = true;
28608 for(int ij4 = 0; ij4 < 1; ++ij4)
28609 {
28610 if( !j4valid[ij4] )
28611 {
28612     continue;
28613 }
28614 _ij4[0] = ij4; _ij4[1] = -1;
28615 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
28616 {
28617 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
28618 {
28619     j4valid[iij4]=false; _ij4[1] = iij4; break; 
28620 }
28621 }
28622 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
28623 {
28624 IkReal evalcond[6];
28625 IkReal x8905=IKsin(j4);
28626 IkReal x8906=IKcos(j4);
28627 IkReal x8907=((r22)*(sj5));
28628 IkReal x8908=((IkReal(1.00000000000000))*(cj6));
28629 IkReal x8909=((IkReal(1.00000000000000))*(cj0));
28630 IkReal x8910=((cj5)*(r11));
28631 IkReal x8911=((cj5)*(cj6));
28632 IkReal x8912=((r11)*(sj6));
28633 IkReal x8913=((IkReal(1.00000000000000))*(sj6));
28634 IkReal x8914=((cj6)*(r00));
28635 IkReal x8915=((r12)*(sj5));
28636 IkReal x8916=((r02)*(sj5));
28637 IkReal x8917=((cj6)*(r10));
28638 IkReal x8918=((cj5)*(sj6));
28639 IkReal x8919=((cj5)*(r01));
28640 IkReal x8920=((sj0)*(x8905));
28641 IkReal x8921=((r00)*(x8918));
28642 IkReal x8922=((cj0)*(x8905));
28643 IkReal x8923=((sj0)*(x8906));
28644 IkReal x8924=((r20)*(x8906));
28645 IkReal x8925=((cj0)*(x8906));
28646 IkReal x8926=((r21)*(x8905));
28647 IkReal x8927=((r21)*(x8906));
28648 IkReal x8928=((r20)*(x8905));
28649 IkReal x8929=((x8906)*(x8915));
28650 IkReal x8930=((r01)*(sj6)*(x8906));
28651 IkReal x8931=((cj5)*(r10)*(x8913));
28652 evalcond[0]=((IkReal(1.00000000000000))+(((x8905)*(x8907)))+(((IkReal(-1.00000000000000))*(x8908)*(x8924)))+(((x8918)*(x8928)))+(((sj6)*(x8927)))+(((x8911)*(x8926))));
28653 evalcond[1]=((((x8906)*(x8907)))+(((cj6)*(x8928)))+(((x8918)*(x8924)))+(((x8911)*(x8927)))+(((IkReal(-1.00000000000000))*(x8913)*(x8926))));
28654 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x8905)*(x8909)*(x8918)))+(((IkReal(-1.00000000000000))*(x8908)*(x8910)*(x8922)))+(((x8920)*(x8921)))+(((r01)*(x8911)*(x8920)))+(((IkReal(-1.00000000000000))*(x8905)*(x8909)*(x8915)))+(((x8917)*(x8925)))+(((IkReal(-1.00000000000000))*(x8906)*(x8909)*(x8912)))+(((IkReal(-1.00000000000000))*(r00)*(x8908)*(x8923)))+(((r01)*(sj6)*(x8923)))+(((x8916)*(x8920))));
28655 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x8906)*(x8909)*(x8918)))+(((x8914)*(x8920)))+(((IkReal(-1.00000000000000))*(x8909)*(x8929)))+(((r01)*(x8911)*(x8923)))+(((IkReal(-1.00000000000000))*(r10)*(x8908)*(x8922)))+(((x8921)*(x8923)))+(((IkReal(-1.00000000000000))*(x8908)*(x8910)*(x8925)))+(((x8916)*(x8923)))+(cj3)+(((IkReal(-1.00000000000000))*(r01)*(x8913)*(x8920)))+(((x8912)*(x8922))));
28656 evalcond[4]=((((x8917)*(x8923)))+(((IkReal(-1.00000000000000))*(x8908)*(x8910)*(x8920)))+(((x8914)*(x8925)))+(((IkReal(-1.00000000000000))*(x8920)*(x8931)))+(((IkReal(-1.00000000000000))*(x8909)*(x8930)))+(((IkReal(-1.00000000000000))*(x8905)*(x8909)*(x8916)))+(((IkReal(-1.00000000000000))*(x8915)*(x8920)))+(((IkReal(-1.00000000000000))*(x8908)*(x8919)*(x8922)))+(((IkReal(-1.00000000000000))*(x8912)*(x8923)))+(((IkReal(-1.00000000000000))*(x8905)*(x8909)*(x8921))));
28657 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x8908)*(x8920)))+(((IkReal(-1.00000000000000))*(x8906)*(x8909)*(x8921)))+(sj3)+(((IkReal(-1.00000000000000))*(r00)*(x8908)*(x8922)))+(((IkReal(-1.00000000000000))*(x8923)*(x8931)))+(((IkReal(-1.00000000000000))*(x8908)*(x8910)*(x8923)))+(((r01)*(sj6)*(x8922)))+(((IkReal(-1.00000000000000))*(x8906)*(x8909)*(x8916)))+(((IkReal(-1.00000000000000))*(x8908)*(x8919)*(x8925)))+(((IkReal(-1.00000000000000))*(x8915)*(x8923)))+(((x8912)*(x8920))));
28658 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
28659 {
28660 continue;
28661 }
28662 }
28663 
28664 {
28665 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
28666 vinfos[0].jointtype = 1;
28667 vinfos[0].foffset = j0;
28668 vinfos[0].indices[0] = _ij0[0];
28669 vinfos[0].indices[1] = _ij0[1];
28670 vinfos[0].maxsolutions = _nj0;
28671 vinfos[1].jointtype = 1;
28672 vinfos[1].foffset = j1;
28673 vinfos[1].indices[0] = _ij1[0];
28674 vinfos[1].indices[1] = _ij1[1];
28675 vinfos[1].maxsolutions = _nj1;
28676 vinfos[2].jointtype = 1;
28677 vinfos[2].foffset = j2;
28678 vinfos[2].indices[0] = _ij2[0];
28679 vinfos[2].indices[1] = _ij2[1];
28680 vinfos[2].maxsolutions = _nj2;
28681 vinfos[3].jointtype = 1;
28682 vinfos[3].foffset = j3;
28683 vinfos[3].indices[0] = _ij3[0];
28684 vinfos[3].indices[1] = _ij3[1];
28685 vinfos[3].maxsolutions = _nj3;
28686 vinfos[4].jointtype = 1;
28687 vinfos[4].foffset = j4;
28688 vinfos[4].indices[0] = _ij4[0];
28689 vinfos[4].indices[1] = _ij4[1];
28690 vinfos[4].maxsolutions = _nj4;
28691 vinfos[5].jointtype = 1;
28692 vinfos[5].foffset = j5;
28693 vinfos[5].indices[0] = _ij5[0];
28694 vinfos[5].indices[1] = _ij5[1];
28695 vinfos[5].maxsolutions = _nj5;
28696 vinfos[6].jointtype = 1;
28697 vinfos[6].foffset = j6;
28698 vinfos[6].indices[0] = _ij6[0];
28699 vinfos[6].indices[1] = _ij6[1];
28700 vinfos[6].maxsolutions = _nj6;
28701 std::vector<int> vfree(0);
28702 solutions.AddSolution(vinfos,vfree);
28703 }
28704 }
28705 }
28706 
28707 }
28708 
28709 }
28710 }
28711 }
28712 
28713 } else
28714 {
28715 if( 1 )
28716 {
28717 continue;
28718 
28719 } else
28720 {
28721 }
28722 }
28723 }
28724 }
28725 
28726 } else
28727 {
28728 {
28729 IkReal j3array[1], cj3array[1], sj3array[1];
28730 bool j3valid[1]={false};
28731 _nj3 = 1;
28732 IkReal x8932=((sj5)*(sj6));
28733 IkReal x8933=((cj6)*(sj5));
28734 IkReal x8934=((IkReal(1.00000000000000))*(cj0));
28735 IkReal x8935=((IkReal(1.00000000000000))*(cj5));
28736 if( IKabs(((((IkReal(-1.00000000000000))*(r11)*(x8933)*(x8934)))+(((r01)*(sj0)*(x8933)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x8932)))+(((IkReal(-1.00000000000000))*(r10)*(x8932)*(x8934)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8935))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x8933)))+(((IkReal(-1.00000000000000))*(r22)*(x8935)))+(((r20)*(x8932))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r11)*(x8933)*(x8934)))+(((r01)*(sj0)*(x8933)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x8932)))+(((IkReal(-1.00000000000000))*(r10)*(x8932)*(x8934)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8935)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x8933)))+(((IkReal(-1.00000000000000))*(r22)*(x8935)))+(((r20)*(x8932)))))))-1) <= IKFAST_SINCOS_THRESH )
28737     continue;
28738 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r11)*(x8933)*(x8934)))+(((r01)*(sj0)*(x8933)))+(((cj0)*(cj5)*(r12)))+(((r00)*(sj0)*(x8932)))+(((IkReal(-1.00000000000000))*(r10)*(x8932)*(x8934)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x8935)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x8933)))+(((IkReal(-1.00000000000000))*(r22)*(x8935)))+(((r20)*(x8932)))))));
28739 sj3array[0]=IKsin(j3array[0]);
28740 cj3array[0]=IKcos(j3array[0]);
28741 if( j3array[0] > IKPI )
28742 {
28743     j3array[0]-=IK2PI;
28744 }
28745 else if( j3array[0] < -IKPI )
28746 {    j3array[0]+=IK2PI;
28747 }
28748 j3valid[0] = true;
28749 for(int ij3 = 0; ij3 < 1; ++ij3)
28750 {
28751 if( !j3valid[ij3] )
28752 {
28753     continue;
28754 }
28755 _ij3[0] = ij3; _ij3[1] = -1;
28756 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
28757 {
28758 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
28759 {
28760     j3valid[iij3]=false; _ij3[1] = iij3; break; 
28761 }
28762 }
28763 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
28764 {
28765 IkReal evalcond[3];
28766 IkReal x8936=IKcos(j3);
28767 IkReal x8937=((sj5)*(sj6));
28768 IkReal x8938=((cj0)*(cj5));
28769 IkReal x8939=((IkReal(1.00000000000000))*(cj0));
28770 IkReal x8940=((IkReal(1.00000000000000))*(sj0));
28771 IkReal x8941=((IkReal(1.00000000000000))*(x8936));
28772 IkReal x8942=((cj6)*(r01)*(sj5));
28773 IkReal x8943=((cj6)*(r11)*(sj5));
28774 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x8941)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x8937))));
28775 evalcond[1]=((((r00)*(sj0)*(x8937)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x8940)))+(((IkReal(-1.00000000000000))*(r10)*(x8937)*(x8939)))+(((IkReal(-1.00000000000000))*(IKsin(j3))))+(((IkReal(-1.00000000000000))*(x8939)*(x8943)))+(((sj0)*(x8942)))+(((r12)*(x8938))));
28776 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x8937)*(x8940)))+(((IkReal(-1.00000000000000))*(cj1)*(x8941)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x8937)*(x8939)))+(((IkReal(-1.00000000000000))*(x8940)*(x8943)))+(((IkReal(-1.00000000000000))*(x8939)*(x8942)))+(((r02)*(x8938))));
28777 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
28778 {
28779 continue;
28780 }
28781 }
28782 
28783 {
28784 IkReal dummyeval[1];
28785 IkReal gconst15;
28786 IkReal x8944=(r21)*(r21);
28787 IkReal x8945=(cj5)*(cj5);
28788 IkReal x8946=(sj6)*(sj6);
28789 IkReal x8947=(cj6)*(cj6);
28790 IkReal x8948=(r20)*(r20);
28791 IkReal x8949=((cj6)*(r21));
28792 IkReal x8950=((IkReal(2.00000000000000))*(r20)*(sj6));
28793 IkReal x8951=((cj5)*(r22)*(sj5));
28794 IkReal x8952=((IkReal(1.00000000000000))*(x8946));
28795 IkReal x8953=((IkReal(1.00000000000000))*(x8947));
28796 gconst15=IKsign(((((IkReal(-1.00000000000000))*(x8945)*(x8948)*(x8952)))+(((IkReal(-1.00000000000000))*(x8944)*(x8952)))+(((x8949)*(x8950)))+(((IkReal(-1.00000000000000))*(x8944)*(x8945)*(x8953)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x8948)*(x8953)))+(((IkReal(-1.00000000000000))*(x8945)*(x8949)*(x8950)))+(((IkReal(-2.00000000000000))*(x8949)*(x8951)))+(((IkReal(-1.00000000000000))*(x8950)*(x8951)))));
28797 IkReal x8954=(r21)*(r21);
28798 IkReal x8955=(cj5)*(cj5);
28799 IkReal x8956=(sj6)*(sj6);
28800 IkReal x8957=(cj6)*(cj6);
28801 IkReal x8958=(r20)*(r20);
28802 IkReal x8959=((cj6)*(r21));
28803 IkReal x8960=((IkReal(2.00000000000000))*(r20)*(sj6));
28804 IkReal x8961=((cj5)*(r22)*(sj5));
28805 IkReal x8962=((IkReal(1.00000000000000))*(x8956));
28806 IkReal x8963=((IkReal(1.00000000000000))*(x8957));
28807 dummyeval[0]=((((IkReal(-1.00000000000000))*(x8955)*(x8958)*(x8962)))+(((IkReal(-1.00000000000000))*(x8958)*(x8963)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x8960)*(x8961)))+(((IkReal(-1.00000000000000))*(x8954)*(x8962)))+(((IkReal(-1.00000000000000))*(x8955)*(x8959)*(x8960)))+(((IkReal(-2.00000000000000))*(x8959)*(x8961)))+(((x8959)*(x8960)))+(((IkReal(-1.00000000000000))*(x8954)*(x8955)*(x8963))));
28808 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28809 {
28810 {
28811 IkReal dummyeval[1];
28812 IkReal gconst16;
28813 IkReal x8964=(cj6)*(cj6);
28814 IkReal x8965=(sj6)*(sj6);
28815 IkReal x8966=((IkReal(1.00000000000000))*(r21));
28816 IkReal x8967=((cj6)*(r20));
28817 IkReal x8968=((r22)*(sj5));
28818 IkReal x8969=((r01)*(sj0));
28819 IkReal x8970=((r00)*(sj0));
28820 IkReal x8971=((cj0)*(r10));
28821 IkReal x8972=((r02)*(sj0)*(sj5));
28822 IkReal x8973=((cj5)*(x8964));
28823 IkReal x8974=((cj0)*(r12)*(sj5));
28824 IkReal x8975=((IkReal(1.00000000000000))*(cj0)*(r11));
28825 IkReal x8976=((cj5)*(x8965));
28826 IkReal x8977=((r20)*(x8976));
28827 gconst16=IKsign(((((IkReal(-1.00000000000000))*(sj6)*(x8966)*(x8972)))+(((sj6)*(x8968)*(x8969)))+(((r20)*(x8969)*(x8973)))+(((IkReal(-1.00000000000000))*(x8966)*(x8970)*(x8976)))+(((IkReal(-1.00000000000000))*(r20)*(x8973)*(x8975)))+(((r21)*(sj6)*(x8974)))+(((r21)*(x8971)*(x8976)))+(((IkReal(-1.00000000000000))*(cj6)*(x8968)*(x8970)))+(((IkReal(-1.00000000000000))*(x8975)*(x8977)))+(((IkReal(-1.00000000000000))*(x8966)*(x8970)*(x8973)))+(((cj6)*(x8968)*(x8971)))+(((x8969)*(x8977)))+(((IkReal(-1.00000000000000))*(sj6)*(x8968)*(x8975)))+(((IkReal(-1.00000000000000))*(x8967)*(x8974)))+(((r21)*(x8971)*(x8973)))+(((x8967)*(x8972)))));
28828 IkReal x8978=(cj6)*(cj6);
28829 IkReal x8979=(sj6)*(sj6);
28830 IkReal x8980=((IkReal(1.00000000000000))*(r21));
28831 IkReal x8981=((cj6)*(r20));
28832 IkReal x8982=((r22)*(sj5));
28833 IkReal x8983=((r01)*(sj0));
28834 IkReal x8984=((r00)*(sj0));
28835 IkReal x8985=((cj0)*(r10));
28836 IkReal x8986=((r02)*(sj0)*(sj5));
28837 IkReal x8987=((cj5)*(x8978));
28838 IkReal x8988=((cj0)*(r12)*(sj5));
28839 IkReal x8989=((IkReal(1.00000000000000))*(cj0)*(r11));
28840 IkReal x8990=((cj5)*(x8979));
28841 IkReal x8991=((r20)*(x8990));
28842 dummyeval[0]=((((IkReal(-1.00000000000000))*(x8989)*(x8991)))+(((r21)*(x8985)*(x8987)))+(((IkReal(-1.00000000000000))*(sj6)*(x8980)*(x8986)))+(((x8983)*(x8991)))+(((r21)*(x8985)*(x8990)))+(((IkReal(-1.00000000000000))*(x8981)*(x8988)))+(((cj6)*(x8982)*(x8985)))+(((r20)*(x8983)*(x8987)))+(((sj6)*(x8982)*(x8983)))+(((IkReal(-1.00000000000000))*(x8980)*(x8984)*(x8987)))+(((IkReal(-1.00000000000000))*(sj6)*(x8982)*(x8989)))+(((IkReal(-1.00000000000000))*(x8980)*(x8984)*(x8990)))+(((IkReal(-1.00000000000000))*(r20)*(x8987)*(x8989)))+(((r21)*(sj6)*(x8988)))+(((x8981)*(x8986)))+(((IkReal(-1.00000000000000))*(cj6)*(x8982)*(x8984))));
28843 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
28844 {
28845 continue;
28846 
28847 } else
28848 {
28849 {
28850 IkReal j4array[1], cj4array[1], sj4array[1];
28851 bool j4valid[1]={false};
28852 _nj4 = 1;
28853 IkReal x8992=((cj1)*(sj6));
28854 IkReal x8993=((r01)*(sj0));
28855 IkReal x8994=((cj0)*(r11));
28856 IkReal x8995=((cj1)*(cj6));
28857 IkReal x8996=((cj0)*(r10));
28858 IkReal x8997=((IkReal(1.00000000000000))*(sj0));
28859 IkReal x8998=((cj1)*(sj5));
28860 if( IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(x8992)*(x8994)))+(((IkReal(-1.00000000000000))*(r00)*(x8995)*(x8997)))+(((x8992)*(x8993)))+(((x8995)*(x8996))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((cj0)*(r12)*(x8998)))+(((IkReal(-1.00000000000000))*(r02)*(x8997)*(x8998)))+(((IkReal(-1.00000000000000))*(cj5)*(x8993)*(x8995)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8992)*(x8997)))+(((cj5)*(x8992)*(x8996)))+(((cj5)*(x8994)*(x8995))))))) < IKFAST_ATAN2_MAGTHRESH )
28861     continue;
28862 j4array[0]=IKatan2(((gconst16)*(((((IkReal(-1.00000000000000))*(x8992)*(x8994)))+(((IkReal(-1.00000000000000))*(r00)*(x8995)*(x8997)))+(((x8992)*(x8993)))+(((x8995)*(x8996)))))), ((gconst16)*(((((cj0)*(r12)*(x8998)))+(((IkReal(-1.00000000000000))*(r02)*(x8997)*(x8998)))+(((IkReal(-1.00000000000000))*(cj5)*(x8993)*(x8995)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x8992)*(x8997)))+(((cj5)*(x8992)*(x8996)))+(((cj5)*(x8994)*(x8995)))))));
28863 sj4array[0]=IKsin(j4array[0]);
28864 cj4array[0]=IKcos(j4array[0]);
28865 if( j4array[0] > IKPI )
28866 {
28867     j4array[0]-=IK2PI;
28868 }
28869 else if( j4array[0] < -IKPI )
28870 {    j4array[0]+=IK2PI;
28871 }
28872 j4valid[0] = true;
28873 for(int ij4 = 0; ij4 < 1; ++ij4)
28874 {
28875 if( !j4valid[ij4] )
28876 {
28877     continue;
28878 }
28879 _ij4[0] = ij4; _ij4[1] = -1;
28880 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
28881 {
28882 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
28883 {
28884     j4valid[iij4]=false; _ij4[1] = iij4; break; 
28885 }
28886 }
28887 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
28888 {
28889 IkReal evalcond[6];
28890 IkReal x8999=IKsin(j4);
28891 IkReal x9000=IKcos(j4);
28892 IkReal x9001=((r22)*(sj5));
28893 IkReal x9002=((IkReal(1.00000000000000))*(cj6));
28894 IkReal x9003=((IkReal(1.00000000000000))*(cj0));
28895 IkReal x9004=((cj5)*(r11));
28896 IkReal x9005=((cj5)*(cj6));
28897 IkReal x9006=((IkReal(1.00000000000000))*(sj3));
28898 IkReal x9007=((r11)*(sj6));
28899 IkReal x9008=((IkReal(1.00000000000000))*(sj6));
28900 IkReal x9009=((cj6)*(r00));
28901 IkReal x9010=((r12)*(sj5));
28902 IkReal x9011=((r02)*(sj5));
28903 IkReal x9012=((cj6)*(r10));
28904 IkReal x9013=((cj5)*(sj6));
28905 IkReal x9014=((cj5)*(r01));
28906 IkReal x9015=((sj0)*(x8999));
28907 IkReal x9016=((r00)*(x9013));
28908 IkReal x9017=((cj0)*(x8999));
28909 IkReal x9018=((sj0)*(x9000));
28910 IkReal x9019=((r20)*(x9000));
28911 IkReal x9020=((cj0)*(x9000));
28912 IkReal x9021=((r21)*(x8999));
28913 IkReal x9022=((r21)*(x9000));
28914 IkReal x9023=((r20)*(x8999));
28915 IkReal x9024=((x9000)*(x9010));
28916 IkReal x9025=((r01)*(sj6)*(x9000));
28917 IkReal x9026=((cj5)*(r10)*(x9008));
28918 evalcond[0]=((((IkReal(-1.00000000000000))*(x9002)*(x9019)))+(((IkReal(-1.00000000000000))*(cj1)))+(((x9005)*(x9021)))+(((x8999)*(x9001)))+(((x9013)*(x9023)))+(((sj6)*(x9022))));
28919 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(x9006)))+(((x9000)*(x9001)))+(((x9005)*(x9022)))+(((IkReal(-1.00000000000000))*(x9008)*(x9021)))+(((x9013)*(x9019)))+(((cj6)*(x9023))));
28920 evalcond[2]=((((x9012)*(x9020)))+(((IkReal(-1.00000000000000))*(r10)*(x8999)*(x9003)*(x9013)))+(((x9011)*(x9015)))+(((IkReal(-1.00000000000000))*(r00)*(x9002)*(x9018)))+(((IkReal(-1.00000000000000))*(x9002)*(x9004)*(x9017)))+(((IkReal(-1.00000000000000))*(x8999)*(x9003)*(x9010)))+(((r01)*(sj6)*(x9018)))+(((r01)*(x9005)*(x9015)))+(((IkReal(-1.00000000000000))*(x9000)*(x9003)*(x9007)))+(((x9015)*(x9016))));
28921 evalcond[3]=((((IkReal(-1.00000000000000))*(x9003)*(x9024)))+(((IkReal(-1.00000000000000))*(r10)*(x9002)*(x9017)))+(((x9011)*(x9018)))+(((x9007)*(x9017)))+(cj3)+(((r01)*(x9005)*(x9018)))+(((IkReal(-1.00000000000000))*(x9002)*(x9004)*(x9020)))+(((IkReal(-1.00000000000000))*(r01)*(x9008)*(x9015)))+(((x9009)*(x9015)))+(((x9016)*(x9018)))+(((IkReal(-1.00000000000000))*(r10)*(x9000)*(x9003)*(x9013))));
28922 evalcond[4]=((((IkReal(-1.00000000000000))*(x8999)*(x9003)*(x9011)))+(((IkReal(-1.00000000000000))*(x9010)*(x9015)))+(((x9012)*(x9018)))+(((x9009)*(x9020)))+(sj1)+(((IkReal(-1.00000000000000))*(x9015)*(x9026)))+(((IkReal(-1.00000000000000))*(x9007)*(x9018)))+(((IkReal(-1.00000000000000))*(x9002)*(x9014)*(x9017)))+(((IkReal(-1.00000000000000))*(x8999)*(x9003)*(x9016)))+(((IkReal(-1.00000000000000))*(x9002)*(x9004)*(x9015)))+(((IkReal(-1.00000000000000))*(x9003)*(x9025))));
28923 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x9002)*(x9017)))+(((IkReal(-1.00000000000000))*(x9002)*(x9014)*(x9020)))+(((IkReal(-1.00000000000000))*(x9000)*(x9003)*(x9011)))+(((IkReal(-1.00000000000000))*(x9010)*(x9018)))+(((IkReal(-1.00000000000000))*(r10)*(x9002)*(x9015)))+(((IkReal(-1.00000000000000))*(x9002)*(x9004)*(x9018)))+(((IkReal(-1.00000000000000))*(x9000)*(x9003)*(x9016)))+(((IkReal(-1.00000000000000))*(cj1)*(x9006)))+(((x9007)*(x9015)))+(((r01)*(sj6)*(x9017)))+(((IkReal(-1.00000000000000))*(x9018)*(x9026))));
28924 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
28925 {
28926 continue;
28927 }
28928 }
28929 
28930 {
28931 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
28932 vinfos[0].jointtype = 1;
28933 vinfos[0].foffset = j0;
28934 vinfos[0].indices[0] = _ij0[0];
28935 vinfos[0].indices[1] = _ij0[1];
28936 vinfos[0].maxsolutions = _nj0;
28937 vinfos[1].jointtype = 1;
28938 vinfos[1].foffset = j1;
28939 vinfos[1].indices[0] = _ij1[0];
28940 vinfos[1].indices[1] = _ij1[1];
28941 vinfos[1].maxsolutions = _nj1;
28942 vinfos[2].jointtype = 1;
28943 vinfos[2].foffset = j2;
28944 vinfos[2].indices[0] = _ij2[0];
28945 vinfos[2].indices[1] = _ij2[1];
28946 vinfos[2].maxsolutions = _nj2;
28947 vinfos[3].jointtype = 1;
28948 vinfos[3].foffset = j3;
28949 vinfos[3].indices[0] = _ij3[0];
28950 vinfos[3].indices[1] = _ij3[1];
28951 vinfos[3].maxsolutions = _nj3;
28952 vinfos[4].jointtype = 1;
28953 vinfos[4].foffset = j4;
28954 vinfos[4].indices[0] = _ij4[0];
28955 vinfos[4].indices[1] = _ij4[1];
28956 vinfos[4].maxsolutions = _nj4;
28957 vinfos[5].jointtype = 1;
28958 vinfos[5].foffset = j5;
28959 vinfos[5].indices[0] = _ij5[0];
28960 vinfos[5].indices[1] = _ij5[1];
28961 vinfos[5].maxsolutions = _nj5;
28962 vinfos[6].jointtype = 1;
28963 vinfos[6].foffset = j6;
28964 vinfos[6].indices[0] = _ij6[0];
28965 vinfos[6].indices[1] = _ij6[1];
28966 vinfos[6].maxsolutions = _nj6;
28967 std::vector<int> vfree(0);
28968 solutions.AddSolution(vinfos,vfree);
28969 }
28970 }
28971 }
28972 
28973 }
28974 
28975 }
28976 
28977 } else
28978 {
28979 {
28980 IkReal j4array[1], cj4array[1], sj4array[1];
28981 bool j4valid[1]={false};
28982 _nj4 = 1;
28983 IkReal x9027=((IkReal(1.00000000000000))*(cj1));
28984 IkReal x9028=((sj1)*(sj3));
28985 IkReal x9029=((r21)*(sj6));
28986 IkReal x9030=((r22)*(sj5));
28987 IkReal x9031=((cj6)*(r20));
28988 IkReal x9032=((cj5)*(r20)*(sj6));
28989 IkReal x9033=((cj5)*(cj6)*(r21));
28990 if( IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x9027)*(x9032)))+(((x9028)*(x9029)))+(((IkReal(-1.00000000000000))*(x9027)*(x9030)))+(((IkReal(-1.00000000000000))*(x9028)*(x9031)))+(((IkReal(-1.00000000000000))*(x9027)*(x9033))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x9028)*(x9030)))+(((IkReal(-1.00000000000000))*(x9028)*(x9032)))+(((IkReal(-1.00000000000000))*(x9027)*(x9029)))+(((cj1)*(x9031)))+(((IkReal(-1.00000000000000))*(x9028)*(x9033))))))) < IKFAST_ATAN2_MAGTHRESH )
28991     continue;
28992 j4array[0]=IKatan2(((gconst15)*(((((IkReal(-1.00000000000000))*(x9027)*(x9032)))+(((x9028)*(x9029)))+(((IkReal(-1.00000000000000))*(x9027)*(x9030)))+(((IkReal(-1.00000000000000))*(x9028)*(x9031)))+(((IkReal(-1.00000000000000))*(x9027)*(x9033)))))), ((gconst15)*(((((IkReal(-1.00000000000000))*(x9028)*(x9030)))+(((IkReal(-1.00000000000000))*(x9028)*(x9032)))+(((IkReal(-1.00000000000000))*(x9027)*(x9029)))+(((cj1)*(x9031)))+(((IkReal(-1.00000000000000))*(x9028)*(x9033)))))));
28993 sj4array[0]=IKsin(j4array[0]);
28994 cj4array[0]=IKcos(j4array[0]);
28995 if( j4array[0] > IKPI )
28996 {
28997     j4array[0]-=IK2PI;
28998 }
28999 else if( j4array[0] < -IKPI )
29000 {    j4array[0]+=IK2PI;
29001 }
29002 j4valid[0] = true;
29003 for(int ij4 = 0; ij4 < 1; ++ij4)
29004 {
29005 if( !j4valid[ij4] )
29006 {
29007     continue;
29008 }
29009 _ij4[0] = ij4; _ij4[1] = -1;
29010 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
29011 {
29012 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
29013 {
29014     j4valid[iij4]=false; _ij4[1] = iij4; break; 
29015 }
29016 }
29017 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
29018 {
29019 IkReal evalcond[6];
29020 IkReal x9034=IKsin(j4);
29021 IkReal x9035=IKcos(j4);
29022 IkReal x9036=((r22)*(sj5));
29023 IkReal x9037=((IkReal(1.00000000000000))*(cj6));
29024 IkReal x9038=((IkReal(1.00000000000000))*(cj0));
29025 IkReal x9039=((cj5)*(r11));
29026 IkReal x9040=((cj5)*(cj6));
29027 IkReal x9041=((IkReal(1.00000000000000))*(sj3));
29028 IkReal x9042=((r11)*(sj6));
29029 IkReal x9043=((IkReal(1.00000000000000))*(sj6));
29030 IkReal x9044=((cj6)*(r00));
29031 IkReal x9045=((r12)*(sj5));
29032 IkReal x9046=((r02)*(sj5));
29033 IkReal x9047=((cj6)*(r10));
29034 IkReal x9048=((cj5)*(sj6));
29035 IkReal x9049=((cj5)*(r01));
29036 IkReal x9050=((sj0)*(x9034));
29037 IkReal x9051=((r00)*(x9048));
29038 IkReal x9052=((cj0)*(x9034));
29039 IkReal x9053=((sj0)*(x9035));
29040 IkReal x9054=((r20)*(x9035));
29041 IkReal x9055=((cj0)*(x9035));
29042 IkReal x9056=((r21)*(x9034));
29043 IkReal x9057=((r21)*(x9035));
29044 IkReal x9058=((r20)*(x9034));
29045 IkReal x9059=((x9035)*(x9045));
29046 IkReal x9060=((r01)*(sj6)*(x9035));
29047 IkReal x9061=((cj5)*(r10)*(x9043));
29048 evalcond[0]=((((IkReal(-1.00000000000000))*(x9037)*(x9054)))+(((sj6)*(x9057)))+(((x9048)*(x9058)))+(((IkReal(-1.00000000000000))*(cj1)))+(((x9040)*(x9056)))+(((x9034)*(x9036))));
29049 evalcond[1]=((((x9035)*(x9036)))+(((IkReal(-1.00000000000000))*(sj1)*(x9041)))+(((IkReal(-1.00000000000000))*(x9043)*(x9056)))+(((x9048)*(x9054)))+(((x9040)*(x9057)))+(((cj6)*(x9058))));
29050 evalcond[2]=((((r01)*(x9040)*(x9050)))+(((IkReal(-1.00000000000000))*(x9037)*(x9039)*(x9052)))+(((x9046)*(x9050)))+(((r01)*(sj6)*(x9053)))+(((x9050)*(x9051)))+(((IkReal(-1.00000000000000))*(x9034)*(x9038)*(x9045)))+(((IkReal(-1.00000000000000))*(x9035)*(x9038)*(x9042)))+(((IkReal(-1.00000000000000))*(r10)*(x9034)*(x9038)*(x9048)))+(((IkReal(-1.00000000000000))*(r00)*(x9037)*(x9053)))+(((x9047)*(x9055))));
29051 evalcond[3]=((((x9051)*(x9053)))+(((IkReal(-1.00000000000000))*(x9038)*(x9059)))+(((IkReal(-1.00000000000000))*(r10)*(x9035)*(x9038)*(x9048)))+(((IkReal(-1.00000000000000))*(x9037)*(x9039)*(x9055)))+(((x9044)*(x9050)))+(((x9046)*(x9053)))+(cj3)+(((r01)*(x9040)*(x9053)))+(((IkReal(-1.00000000000000))*(r01)*(x9043)*(x9050)))+(((x9042)*(x9052)))+(((IkReal(-1.00000000000000))*(r10)*(x9037)*(x9052))));
29052 evalcond[4]=((((IkReal(-1.00000000000000))*(x9050)*(x9061)))+(((x9044)*(x9055)))+(((x9047)*(x9053)))+(((IkReal(-1.00000000000000))*(x9034)*(x9038)*(x9051)))+(sj1)+(((IkReal(-1.00000000000000))*(x9034)*(x9038)*(x9046)))+(((IkReal(-1.00000000000000))*(x9037)*(x9049)*(x9052)))+(((IkReal(-1.00000000000000))*(x9045)*(x9050)))+(((IkReal(-1.00000000000000))*(x9042)*(x9053)))+(((IkReal(-1.00000000000000))*(x9037)*(x9039)*(x9050)))+(((IkReal(-1.00000000000000))*(x9038)*(x9060))));
29053 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x9037)*(x9050)))+(((IkReal(-1.00000000000000))*(x9035)*(x9038)*(x9046)))+(((IkReal(-1.00000000000000))*(x9037)*(x9039)*(x9053)))+(((IkReal(-1.00000000000000))*(cj1)*(x9041)))+(((IkReal(-1.00000000000000))*(r00)*(x9037)*(x9052)))+(((x9042)*(x9050)))+(((IkReal(-1.00000000000000))*(x9035)*(x9038)*(x9051)))+(((IkReal(-1.00000000000000))*(x9053)*(x9061)))+(((r01)*(sj6)*(x9052)))+(((IkReal(-1.00000000000000))*(x9045)*(x9053)))+(((IkReal(-1.00000000000000))*(x9037)*(x9049)*(x9055))));
29054 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
29055 {
29056 continue;
29057 }
29058 }
29059 
29060 {
29061 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29062 vinfos[0].jointtype = 1;
29063 vinfos[0].foffset = j0;
29064 vinfos[0].indices[0] = _ij0[0];
29065 vinfos[0].indices[1] = _ij0[1];
29066 vinfos[0].maxsolutions = _nj0;
29067 vinfos[1].jointtype = 1;
29068 vinfos[1].foffset = j1;
29069 vinfos[1].indices[0] = _ij1[0];
29070 vinfos[1].indices[1] = _ij1[1];
29071 vinfos[1].maxsolutions = _nj1;
29072 vinfos[2].jointtype = 1;
29073 vinfos[2].foffset = j2;
29074 vinfos[2].indices[0] = _ij2[0];
29075 vinfos[2].indices[1] = _ij2[1];
29076 vinfos[2].maxsolutions = _nj2;
29077 vinfos[3].jointtype = 1;
29078 vinfos[3].foffset = j3;
29079 vinfos[3].indices[0] = _ij3[0];
29080 vinfos[3].indices[1] = _ij3[1];
29081 vinfos[3].maxsolutions = _nj3;
29082 vinfos[4].jointtype = 1;
29083 vinfos[4].foffset = j4;
29084 vinfos[4].indices[0] = _ij4[0];
29085 vinfos[4].indices[1] = _ij4[1];
29086 vinfos[4].maxsolutions = _nj4;
29087 vinfos[5].jointtype = 1;
29088 vinfos[5].foffset = j5;
29089 vinfos[5].indices[0] = _ij5[0];
29090 vinfos[5].indices[1] = _ij5[1];
29091 vinfos[5].maxsolutions = _nj5;
29092 vinfos[6].jointtype = 1;
29093 vinfos[6].foffset = j6;
29094 vinfos[6].indices[0] = _ij6[0];
29095 vinfos[6].indices[1] = _ij6[1];
29096 vinfos[6].maxsolutions = _nj6;
29097 std::vector<int> vfree(0);
29098 solutions.AddSolution(vinfos,vfree);
29099 }
29100 }
29101 }
29102 
29103 }
29104 
29105 }
29106 }
29107 }
29108 
29109 }
29110 
29111 }
29112 
29113 } else
29114 {
29115 {
29116 IkReal j4array[1], cj4array[1], sj4array[1];
29117 bool j4valid[1]={false};
29118 _nj4 = 1;
29119 IkReal x9062=((sj0)*(sj6));
29120 IkReal x9063=((cj0)*(cj6));
29121 IkReal x9064=((cj0)*(sj6));
29122 IkReal x9065=((IkReal(1.00000000000000))*(cj1));
29123 IkReal x9066=((r20)*(sj1));
29124 IkReal x9067=((cj6)*(sj0));
29125 IkReal x9068=((r21)*(sj1));
29126 IkReal x9069=((cj5)*(x9065));
29127 if( IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(r00)*(x9063)*(x9065)))+(((cj6)*(x9066)))+(((cj1)*(r11)*(x9062)))+(((IkReal(-1.00000000000000))*(sj6)*(x9068)))+(((IkReal(-1.00000000000000))*(r10)*(x9065)*(x9067)))+(((cj1)*(r01)*(x9064))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x9065)))+(((IkReal(-1.00000000000000))*(r11)*(x9067)*(x9069)))+(((cj5)*(sj6)*(x9066)))+(((IkReal(-1.00000000000000))*(r00)*(x9064)*(x9069)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(sj5)*(x9065)))+(((IkReal(-1.00000000000000))*(r10)*(x9062)*(x9069)))+(((cj5)*(cj6)*(x9068)))+(((r22)*(sj1)*(sj5)))+(((IkReal(-1.00000000000000))*(r01)*(x9063)*(x9069))))))) < IKFAST_ATAN2_MAGTHRESH )
29128     continue;
29129 j4array[0]=IKatan2(((gconst14)*(((((IkReal(-1.00000000000000))*(r00)*(x9063)*(x9065)))+(((cj6)*(x9066)))+(((cj1)*(r11)*(x9062)))+(((IkReal(-1.00000000000000))*(sj6)*(x9068)))+(((IkReal(-1.00000000000000))*(r10)*(x9065)*(x9067)))+(((cj1)*(r01)*(x9064)))))), ((gconst14)*(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x9065)))+(((IkReal(-1.00000000000000))*(r11)*(x9067)*(x9069)))+(((cj5)*(sj6)*(x9066)))+(((IkReal(-1.00000000000000))*(r00)*(x9064)*(x9069)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(sj5)*(x9065)))+(((IkReal(-1.00000000000000))*(r10)*(x9062)*(x9069)))+(((cj5)*(cj6)*(x9068)))+(((r22)*(sj1)*(sj5)))+(((IkReal(-1.00000000000000))*(r01)*(x9063)*(x9069)))))));
29130 sj4array[0]=IKsin(j4array[0]);
29131 cj4array[0]=IKcos(j4array[0]);
29132 if( j4array[0] > IKPI )
29133 {
29134     j4array[0]-=IK2PI;
29135 }
29136 else if( j4array[0] < -IKPI )
29137 {    j4array[0]+=IK2PI;
29138 }
29139 j4valid[0] = true;
29140 for(int ij4 = 0; ij4 < 1; ++ij4)
29141 {
29142 if( !j4valid[ij4] )
29143 {
29144     continue;
29145 }
29146 _ij4[0] = ij4; _ij4[1] = -1;
29147 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
29148 {
29149 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
29150 {
29151     j4valid[iij4]=false; _ij4[1] = iij4; break; 
29152 }
29153 }
29154 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
29155 {
29156 IkReal evalcond[3];
29157 IkReal x9070=IKsin(j4);
29158 IkReal x9071=IKcos(j4);
29159 IkReal x9072=((r00)*(sj6));
29160 IkReal x9073=((cj6)*(r01));
29161 IkReal x9074=((IkReal(1.00000000000000))*(cj0));
29162 IkReal x9075=((IkReal(1.00000000000000))*(sj0));
29163 IkReal x9076=((r10)*(sj6));
29164 IkReal x9077=((sj5)*(x9070));
29165 IkReal x9078=((IkReal(1.00000000000000))*(cj6)*(r11));
29166 IkReal x9079=((cj5)*(x9070));
29167 IkReal x9080=((cj6)*(x9071));
29168 IkReal x9081=((sj0)*(x9079));
29169 IkReal x9082=((r01)*(sj6)*(x9071));
29170 IkReal x9083=((r11)*(sj6)*(x9071));
29171 evalcond[0]=((((IkReal(-1.00000000000000))*(r20)*(x9080)))+(((r20)*(sj6)*(x9079)))+(((r21)*(sj6)*(x9071)))+(((cj6)*(r21)*(x9079)))+(((IkReal(-1.00000000000000))*(cj1)))+(((r22)*(x9077))));
29172 evalcond[1]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x9074)*(x9079)))+(((IkReal(-1.00000000000000))*(r12)*(x9074)*(x9077)))+(((r02)*(sj0)*(x9077)))+(((IkReal(-1.00000000000000))*(x9074)*(x9076)*(x9079)))+(((sj0)*(x9082)))+(((IkReal(-1.00000000000000))*(x9074)*(x9083)))+(((x9073)*(x9081)))+(((IkReal(-1.00000000000000))*(r00)*(x9075)*(x9080)))+(((x9072)*(x9081)))+(((cj0)*(r10)*(x9080))));
29173 evalcond[2]=((((IkReal(-1.00000000000000))*(x9074)*(x9082)))+(((r10)*(sj0)*(x9080)))+(((IkReal(-1.00000000000000))*(x9072)*(x9074)*(x9079)))+(((IkReal(-1.00000000000000))*(x9073)*(x9074)*(x9079)))+(((IkReal(-1.00000000000000))*(r12)*(x9075)*(x9077)))+(sj1)+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x9075)*(x9079)))+(((IkReal(-1.00000000000000))*(x9075)*(x9076)*(x9079)))+(((IkReal(-1.00000000000000))*(r02)*(x9074)*(x9077)))+(((cj0)*(r00)*(x9080)))+(((IkReal(-1.00000000000000))*(x9075)*(x9083))));
29174 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
29175 {
29176 continue;
29177 }
29178 }
29179 
29180 {
29181 IkReal dummyeval[1];
29182 IkReal gconst17;
29183 gconst17=IKsign(sj1);
29184 dummyeval[0]=sj1;
29185 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
29186 {
29187 {
29188 IkReal dummyeval[1];
29189 dummyeval[0]=sj1;
29190 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
29191 {
29192 {
29193 IkReal dummyeval[1];
29194 dummyeval[0]=cj1;
29195 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
29196 {
29197 {
29198 IkReal evalcond[9];
29199 IkReal x9084=((IkReal(1.00000000000000))*(cj0));
29200 IkReal x9085=((cj4)*(sj6));
29201 IkReal x9086=((sj0)*(sj6));
29202 IkReal x9087=((cj5)*(sj4));
29203 IkReal x9088=((IkReal(0.374290000000000))*(sj5));
29204 IkReal x9089=((sj4)*(sj5));
29205 IkReal x9090=((cj0)*(cj6));
29206 IkReal x9091=((IkReal(0.0100000000000000))*(cj5));
29207 IkReal x9092=((cj4)*(sj5));
29208 IkReal x9093=((cj5)*(sj0));
29209 IkReal x9094=((IkReal(0.374290000000000))*(r02));
29210 IkReal x9095=((r20)*(sj6));
29211 IkReal x9096=((cj6)*(r21));
29212 IkReal x9097=((IkReal(1.00000000000000))*(sj0));
29213 IkReal x9098=((cj0)*(sj6));
29214 IkReal x9099=((cj4)*(cj6));
29215 IkReal x9100=((IkReal(0.374290000000000))*(r12));
29216 IkReal x9101=((cj0)*(cj5));
29217 IkReal x9102=((cj6)*(sj5));
29218 IkReal x9103=((cj6)*(r01));
29219 IkReal x9104=((r00)*(sj6));
29220 IkReal x9105=((IkReal(0.0100000000000000))*(sj5));
29221 IkReal x9106=((cj6)*(r11));
29222 IkReal x9107=((IkReal(1.00000000000000))*(r10));
29223 IkReal x9108=((r02)*(sj0));
29224 IkReal x9109=((cj6)*(sj4));
29225 IkReal x9110=((r12)*(x9097));
29226 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
29227 evalcond[1]=((((x9087)*(x9096)))+(((r21)*(x9085)))+(((IkReal(-1.00000000000000))*(r20)*(x9099)))+(((r22)*(x9089)))+(((x9087)*(x9095))));
29228 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(x9091)*(x9096)))+(((IkReal(-1.00000000000000))*(r22)*(x9105)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x9088)*(x9095)))+(((IkReal(-1.00000000000000))*(x9091)*(x9095)))+(pz)+(((x9088)*(x9096))));
29229 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x9086)*(x9107)))+(((r12)*(x9093)))+(((r02)*(x9101)))+(((IkReal(-1.00000000000000))*(r01)*(x9084)*(x9102)))+(((IkReal(-1.00000000000000))*(sj5)*(x9084)*(x9104)))+(((IkReal(-1.00000000000000))*(r11)*(x9097)*(x9102))));
29230 evalcond[4]=((((sj0)*(x9087)*(x9103)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x9084)*(x9087)))+(((IkReal(-1.00000000000000))*(r11)*(x9084)*(x9085)))+(((x9089)*(x9108)))+(((r01)*(sj0)*(x9085)))+(((IkReal(-1.00000000000000))*(x9084)*(x9087)*(x9106)))+(((r00)*(x9086)*(x9087)))+(((IkReal(-1.00000000000000))*(r12)*(x9084)*(x9089)))+(((IkReal(-1.00000000000000))*(r00)*(x9097)*(x9099)))+(((cj4)*(r10)*(x9090))));
29231 evalcond[5]=((IkReal(1.00000000000000))+(((r10)*(sj0)*(x9099)))+(((IkReal(-1.00000000000000))*(x9084)*(x9087)*(x9103)))+(((IkReal(-1.00000000000000))*(x9087)*(x9097)*(x9106)))+(((IkReal(-1.00000000000000))*(x9089)*(x9110)))+(((IkReal(-1.00000000000000))*(r01)*(x9084)*(x9085)))+(((IkReal(-1.00000000000000))*(x9084)*(x9087)*(x9104)))+(((IkReal(-1.00000000000000))*(x9086)*(x9087)*(x9107)))+(((IkReal(-1.00000000000000))*(r02)*(x9084)*(x9089)))+(((IkReal(-1.00000000000000))*(r11)*(x9085)*(x9097)))+(((cj4)*(r00)*(x9090))));
29232 evalcond[6]=((IkReal(0.0690000000000000))+(((r10)*(x9091)*(x9098)))+(((x9100)*(x9101)))+(((IkReal(-1.00000000000000))*(py)*(x9084)))+(((IkReal(-1.00000000000000))*(x9093)*(x9094)))+(((cj0)*(r12)*(x9105)))+(((sj0)*(x9088)*(x9103)))+(((r00)*(x9086)*(x9088)))+(((IkReal(-1.00000000000000))*(x9105)*(x9108)))+(((IkReal(-1.00000000000000))*(r00)*(x9086)*(x9091)))+(((IkReal(-1.00000000000000))*(r10)*(x9088)*(x9098)))+(((r11)*(x9090)*(x9091)))+(((IkReal(-1.00000000000000))*(r11)*(x9088)*(x9090)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x9091)*(x9103))));
29233 evalcond[7]=((((IkReal(-1.00000000000000))*(x9085)*(x9093)*(x9107)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9084)*(x9085)))+(((IkReal(-1.00000000000000))*(r11)*(x9093)*(x9099)))+(((IkReal(-1.00000000000000))*(r00)*(x9084)*(x9109)))+(((IkReal(-1.00000000000000))*(r10)*(x9097)*(x9109)))+(((r01)*(sj4)*(x9098)))+(((r11)*(sj4)*(x9086)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x9084)*(x9099)))+(((IkReal(-1.00000000000000))*(x9092)*(x9110)))+(((IkReal(-1.00000000000000))*(r02)*(x9084)*(x9092))));
29234 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x9088)*(x9098)))+(((IkReal(-1.00000000000000))*(sj0)*(x9088)*(x9106)))+(((IkReal(-1.00000000000000))*(px)*(x9084)))+(((r10)*(x9086)*(x9091)))+(((cj0)*(r02)*(x9105)))+(((IkReal(-1.00000000000000))*(r10)*(x9086)*(x9088)))+(((r00)*(x9091)*(x9098)))+(((x9093)*(x9100)))+(((r12)*(sj0)*(x9105)))+(((r01)*(x9090)*(x9091)))+(((IkReal(-1.00000000000000))*(r01)*(x9088)*(x9090)))+(((x9094)*(x9101)))+(((sj0)*(x9091)*(x9106)))+(((IkReal(-1.00000000000000))*(py)*(x9097))));
29235 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
29236 {
29237 {
29238 IkReal j3array[1], cj3array[1], sj3array[1];
29239 bool j3valid[1]={false};
29240 _nj3 = 1;
29241 IkReal x9111=((r20)*(sj6));
29242 IkReal x9112=((cj4)*(cj5));
29243 IkReal x9113=((cj6)*(r21));
29244 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x9112)*(x9113)))+(((x9111)*(x9112))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9113)))+(((sj5)*(x9111))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x9112)*(x9113)))+(((x9111)*(x9112)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9113)))+(((sj5)*(x9111)))))-1) <= IKFAST_SINCOS_THRESH )
29245     continue;
29246 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x9112)*(x9113)))+(((x9111)*(x9112)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9113)))+(((sj5)*(x9111)))));
29247 sj3array[0]=IKsin(j3array[0]);
29248 cj3array[0]=IKcos(j3array[0]);
29249 if( j3array[0] > IKPI )
29250 {
29251     j3array[0]-=IK2PI;
29252 }
29253 else if( j3array[0] < -IKPI )
29254 {    j3array[0]+=IK2PI;
29255 }
29256 j3valid[0] = true;
29257 for(int ij3 = 0; ij3 < 1; ++ij3)
29258 {
29259 if( !j3valid[ij3] )
29260 {
29261     continue;
29262 }
29263 _ij3[0] = ij3; _ij3[1] = -1;
29264 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29265 {
29266 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29267 {
29268     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29269 }
29270 }
29271 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29272 {
29273 IkReal evalcond[4];
29274 IkReal x9114=IKcos(j3);
29275 IkReal x9115=((sj0)*(sj5));
29276 IkReal x9116=((r00)*(sj6));
29277 IkReal x9117=((cj6)*(r01));
29278 IkReal x9118=((cj5)*(sj0));
29279 IkReal x9119=((cj0)*(cj5));
29280 IkReal x9120=((cj6)*(sj4));
29281 IkReal x9121=((sj4)*(sj6));
29282 IkReal x9122=((cj0)*(r11));
29283 IkReal x9123=((cj4)*(cj6));
29284 IkReal x9124=((cj4)*(sj6));
29285 IkReal x9125=((IkReal(1.00000000000000))*(cj0));
29286 IkReal x9126=((cj4)*(sj5));
29287 IkReal x9127=((sj5)*(sj6));
29288 IkReal x9128=((cj6)*(sj5));
29289 IkReal x9129=((IkReal(1.00000000000000))*(IKsin(j3)));
29290 evalcond[0]=((((r21)*(x9128)))+(((r20)*(x9127)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x9114))));
29291 evalcond[1]=((((cj5)*(r20)*(x9124)))+(((cj5)*(r21)*(x9123)))+(((IkReal(-1.00000000000000))*(x9129)))+(((r22)*(x9126)))+(((IkReal(-1.00000000000000))*(r21)*(x9121)))+(((r20)*(x9120))));
29292 evalcond[2]=((((IkReal(-1.00000000000000))*(x9122)*(x9128)))+(((IkReal(-1.00000000000000))*(x9129)))+(((r12)*(x9119)))+(((IkReal(-1.00000000000000))*(r02)*(x9118)))+(((x9115)*(x9116)))+(((x9115)*(x9117)))+(((IkReal(-1.00000000000000))*(r10)*(x9125)*(x9127))));
29293 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x9120)*(x9125)))+(((IkReal(-1.00000000000000))*(r11)*(x9119)*(x9123)))+(((cj4)*(r02)*(x9115)))+(((r00)*(sj0)*(x9120)))+(((cj4)*(x9117)*(x9118)))+(x9114)+(((cj4)*(x9116)*(x9118)))+(((x9121)*(x9122)))+(((IkReal(-1.00000000000000))*(r12)*(x9125)*(x9126)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x9121)))+(((IkReal(-1.00000000000000))*(r10)*(x9119)*(x9124))));
29294 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
29295 {
29296 continue;
29297 }
29298 }
29299 
29300 {
29301 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29302 vinfos[0].jointtype = 1;
29303 vinfos[0].foffset = j0;
29304 vinfos[0].indices[0] = _ij0[0];
29305 vinfos[0].indices[1] = _ij0[1];
29306 vinfos[0].maxsolutions = _nj0;
29307 vinfos[1].jointtype = 1;
29308 vinfos[1].foffset = j1;
29309 vinfos[1].indices[0] = _ij1[0];
29310 vinfos[1].indices[1] = _ij1[1];
29311 vinfos[1].maxsolutions = _nj1;
29312 vinfos[2].jointtype = 1;
29313 vinfos[2].foffset = j2;
29314 vinfos[2].indices[0] = _ij2[0];
29315 vinfos[2].indices[1] = _ij2[1];
29316 vinfos[2].maxsolutions = _nj2;
29317 vinfos[3].jointtype = 1;
29318 vinfos[3].foffset = j3;
29319 vinfos[3].indices[0] = _ij3[0];
29320 vinfos[3].indices[1] = _ij3[1];
29321 vinfos[3].maxsolutions = _nj3;
29322 vinfos[4].jointtype = 1;
29323 vinfos[4].foffset = j4;
29324 vinfos[4].indices[0] = _ij4[0];
29325 vinfos[4].indices[1] = _ij4[1];
29326 vinfos[4].maxsolutions = _nj4;
29327 vinfos[5].jointtype = 1;
29328 vinfos[5].foffset = j5;
29329 vinfos[5].indices[0] = _ij5[0];
29330 vinfos[5].indices[1] = _ij5[1];
29331 vinfos[5].maxsolutions = _nj5;
29332 vinfos[6].jointtype = 1;
29333 vinfos[6].foffset = j6;
29334 vinfos[6].indices[0] = _ij6[0];
29335 vinfos[6].indices[1] = _ij6[1];
29336 vinfos[6].maxsolutions = _nj6;
29337 std::vector<int> vfree(0);
29338 solutions.AddSolution(vinfos,vfree);
29339 }
29340 }
29341 }
29342 
29343 } else
29344 {
29345 IkReal x9130=((IkReal(1.00000000000000))*(cj0));
29346 IkReal x9131=((cj4)*(sj6));
29347 IkReal x9132=((sj0)*(sj6));
29348 IkReal x9133=((cj5)*(sj4));
29349 IkReal x9134=((IkReal(0.374290000000000))*(sj5));
29350 IkReal x9135=((sj4)*(sj5));
29351 IkReal x9136=((cj0)*(cj6));
29352 IkReal x9137=((IkReal(0.0100000000000000))*(cj5));
29353 IkReal x9138=((cj4)*(sj5));
29354 IkReal x9139=((cj5)*(sj0));
29355 IkReal x9140=((IkReal(0.374290000000000))*(r02));
29356 IkReal x9141=((r20)*(sj6));
29357 IkReal x9142=((cj6)*(r21));
29358 IkReal x9143=((IkReal(1.00000000000000))*(sj0));
29359 IkReal x9144=((cj0)*(sj6));
29360 IkReal x9145=((cj4)*(cj6));
29361 IkReal x9146=((IkReal(0.374290000000000))*(r12));
29362 IkReal x9147=((cj0)*(cj5));
29363 IkReal x9148=((cj6)*(sj5));
29364 IkReal x9149=((cj6)*(r01));
29365 IkReal x9150=((r00)*(sj6));
29366 IkReal x9151=((IkReal(0.0100000000000000))*(sj5));
29367 IkReal x9152=((cj6)*(r11));
29368 IkReal x9153=((IkReal(1.00000000000000))*(r10));
29369 IkReal x9154=((r02)*(sj0));
29370 IkReal x9155=((cj6)*(sj4));
29371 IkReal x9156=((r12)*(x9143));
29372 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
29373 evalcond[1]=((((x9133)*(x9142)))+(((x9133)*(x9141)))+(((r22)*(x9135)))+(((r21)*(x9131)))+(((IkReal(-1.00000000000000))*(r20)*(x9145))));
29374 evalcond[2]=((IkReal(-0.364420000000000))+(((x9134)*(x9142)))+(((x9134)*(x9141)))+(((IkReal(-1.00000000000000))*(r22)*(x9151)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x9137)*(x9141)))+(((IkReal(-1.00000000000000))*(x9137)*(x9142))));
29375 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x9132)*(x9153)))+(((r12)*(x9139)))+(((r02)*(x9147)))+(((IkReal(-1.00000000000000))*(sj5)*(x9130)*(x9150)))+(((IkReal(-1.00000000000000))*(r01)*(x9130)*(x9148)))+(((IkReal(-1.00000000000000))*(r11)*(x9143)*(x9148))));
29376 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(sj6)*(x9130)*(x9133)))+(((x9135)*(x9154)))+(((sj0)*(x9133)*(x9149)))+(((IkReal(-1.00000000000000))*(r12)*(x9130)*(x9135)))+(((IkReal(-1.00000000000000))*(r11)*(x9130)*(x9131)))+(((cj4)*(r10)*(x9136)))+(((r01)*(sj0)*(x9131)))+(((IkReal(-1.00000000000000))*(x9130)*(x9133)*(x9152)))+(((r00)*(x9132)*(x9133)))+(((IkReal(-1.00000000000000))*(r00)*(x9143)*(x9145))));
29377 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x9130)*(x9133)*(x9150)))+(((cj4)*(r00)*(x9136)))+(((IkReal(-1.00000000000000))*(r01)*(x9130)*(x9131)))+(((IkReal(-1.00000000000000))*(x9133)*(x9143)*(x9152)))+(((IkReal(-1.00000000000000))*(r11)*(x9131)*(x9143)))+(((IkReal(-1.00000000000000))*(x9130)*(x9133)*(x9149)))+(((IkReal(-1.00000000000000))*(x9132)*(x9133)*(x9153)))+(((IkReal(-1.00000000000000))*(x9135)*(x9156)))+(((IkReal(-1.00000000000000))*(r02)*(x9130)*(x9135)))+(((r10)*(sj0)*(x9145))));
29378 evalcond[6]=((IkReal(0.0690000000000000))+(((x9146)*(x9147)))+(((cj0)*(r12)*(x9151)))+(((IkReal(-1.00000000000000))*(r11)*(x9134)*(x9136)))+(((sj0)*(x9134)*(x9149)))+(((IkReal(-1.00000000000000))*(sj0)*(x9137)*(x9149)))+(((r00)*(x9132)*(x9134)))+(((IkReal(-1.00000000000000))*(x9151)*(x9154)))+(((IkReal(-1.00000000000000))*(r00)*(x9132)*(x9137)))+(((IkReal(-1.00000000000000))*(x9139)*(x9140)))+(((IkReal(-1.00000000000000))*(r10)*(x9134)*(x9144)))+(((IkReal(-1.00000000000000))*(py)*(x9130)))+(((r11)*(x9136)*(x9137)))+(((px)*(sj0)))+(((r10)*(x9137)*(x9144))));
29379 evalcond[7]=((((r01)*(sj4)*(x9144)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x9130)*(x9145)))+(((IkReal(-1.00000000000000))*(r11)*(x9139)*(x9145)))+(((IkReal(-1.00000000000000))*(r10)*(x9143)*(x9155)))+(((IkReal(-1.00000000000000))*(r00)*(x9130)*(x9155)))+(((IkReal(-1.00000000000000))*(r02)*(x9130)*(x9138)))+(((IkReal(-1.00000000000000))*(x9131)*(x9139)*(x9153)))+(((r11)*(sj4)*(x9132)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9130)*(x9131)))+(((IkReal(-1.00000000000000))*(x9138)*(x9156))));
29380 evalcond[8]=((IkReal(0.0690000000000000))+(((r10)*(x9132)*(x9137)))+(((IkReal(-1.00000000000000))*(px)*(x9130)))+(((r00)*(x9137)*(x9144)))+(((x9139)*(x9146)))+(((r01)*(x9136)*(x9137)))+(((IkReal(-1.00000000000000))*(r10)*(x9132)*(x9134)))+(((IkReal(-1.00000000000000))*(r00)*(x9134)*(x9144)))+(((sj0)*(x9137)*(x9152)))+(((x9140)*(x9147)))+(((IkReal(-1.00000000000000))*(sj0)*(x9134)*(x9152)))+(((IkReal(-1.00000000000000))*(py)*(x9143)))+(((cj0)*(r02)*(x9151)))+(((r12)*(sj0)*(x9151)))+(((IkReal(-1.00000000000000))*(r01)*(x9134)*(x9136))));
29381 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
29382 {
29383 {
29384 IkReal j3array[1], cj3array[1], sj3array[1];
29385 bool j3valid[1]={false};
29386 _nj3 = 1;
29387 IkReal x9157=((IkReal(1.00000000000000))*(sj5));
29388 IkReal x9158=((cj6)*(r21));
29389 IkReal x9159=((r20)*(sj6));
29390 IkReal x9160=((IkReal(1.00000000000000))*(cj4)*(cj5));
29391 if( IKabs(((((IkReal(-1.00000000000000))*(x9158)*(x9160)))+(((IkReal(-1.00000000000000))*(x9159)*(x9160)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9157)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x9157)*(x9159)))+(((IkReal(-1.00000000000000))*(x9157)*(x9158)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x9158)*(x9160)))+(((IkReal(-1.00000000000000))*(x9159)*(x9160)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9157)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x9157)*(x9159)))+(((IkReal(-1.00000000000000))*(x9157)*(x9158)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
29392     continue;
29393 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x9158)*(x9160)))+(((IkReal(-1.00000000000000))*(x9159)*(x9160)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9157)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x9157)*(x9159)))+(((IkReal(-1.00000000000000))*(x9157)*(x9158)))+(((cj5)*(r22)))));
29394 sj3array[0]=IKsin(j3array[0]);
29395 cj3array[0]=IKcos(j3array[0]);
29396 if( j3array[0] > IKPI )
29397 {
29398     j3array[0]-=IK2PI;
29399 }
29400 else if( j3array[0] < -IKPI )
29401 {    j3array[0]+=IK2PI;
29402 }
29403 j3valid[0] = true;
29404 for(int ij3 = 0; ij3 < 1; ++ij3)
29405 {
29406 if( !j3valid[ij3] )
29407 {
29408     continue;
29409 }
29410 _ij3[0] = ij3; _ij3[1] = -1;
29411 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29412 {
29413 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29414 {
29415     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29416 }
29417 }
29418 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29419 {
29420 IkReal evalcond[4];
29421 IkReal x9161=IKsin(j3);
29422 IkReal x9162=IKcos(j3);
29423 IkReal x9163=((sj0)*(sj5));
29424 IkReal x9164=((r00)*(sj6));
29425 IkReal x9165=((cj6)*(r01));
29426 IkReal x9166=((cj5)*(sj0));
29427 IkReal x9167=((cj0)*(cj5));
29428 IkReal x9168=((cj6)*(sj4));
29429 IkReal x9169=((sj4)*(sj6));
29430 IkReal x9170=((cj0)*(r11));
29431 IkReal x9171=((cj4)*(cj6));
29432 IkReal x9172=((cj4)*(sj6));
29433 IkReal x9173=((IkReal(1.00000000000000))*(cj0));
29434 IkReal x9174=((cj4)*(sj5));
29435 IkReal x9175=((sj5)*(sj6));
29436 IkReal x9176=((cj6)*(sj5));
29437 evalcond[0]=((((r20)*(x9175)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r21)*(x9176)))+(x9162));
29438 evalcond[1]=((((cj5)*(r21)*(x9171)))+(((r22)*(x9174)))+(((r20)*(x9168)))+(x9161)+(((cj5)*(r20)*(x9172)))+(((IkReal(-1.00000000000000))*(r21)*(x9169))));
29439 evalcond[2]=((((x9163)*(x9164)))+(((x9163)*(x9165)))+(((IkReal(-1.00000000000000))*(r10)*(x9173)*(x9175)))+(((r12)*(x9167)))+(((IkReal(-1.00000000000000))*(x9161)))+(((IkReal(-1.00000000000000))*(r02)*(x9166)))+(((IkReal(-1.00000000000000))*(x9170)*(x9176))));
29440 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x9169)))+(((IkReal(-1.00000000000000))*(r11)*(x9167)*(x9171)))+(((IkReal(-1.00000000000000))*(r10)*(x9168)*(x9173)))+(((x9169)*(x9170)))+(((cj4)*(x9164)*(x9166)))+(((cj4)*(r02)*(x9163)))+(((r00)*(sj0)*(x9168)))+(((IkReal(-1.00000000000000))*(r12)*(x9173)*(x9174)))+(((IkReal(-1.00000000000000))*(r10)*(x9167)*(x9172)))+(((cj4)*(x9165)*(x9166)))+(x9162));
29441 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
29442 {
29443 continue;
29444 }
29445 }
29446 
29447 {
29448 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29449 vinfos[0].jointtype = 1;
29450 vinfos[0].foffset = j0;
29451 vinfos[0].indices[0] = _ij0[0];
29452 vinfos[0].indices[1] = _ij0[1];
29453 vinfos[0].maxsolutions = _nj0;
29454 vinfos[1].jointtype = 1;
29455 vinfos[1].foffset = j1;
29456 vinfos[1].indices[0] = _ij1[0];
29457 vinfos[1].indices[1] = _ij1[1];
29458 vinfos[1].maxsolutions = _nj1;
29459 vinfos[2].jointtype = 1;
29460 vinfos[2].foffset = j2;
29461 vinfos[2].indices[0] = _ij2[0];
29462 vinfos[2].indices[1] = _ij2[1];
29463 vinfos[2].maxsolutions = _nj2;
29464 vinfos[3].jointtype = 1;
29465 vinfos[3].foffset = j3;
29466 vinfos[3].indices[0] = _ij3[0];
29467 vinfos[3].indices[1] = _ij3[1];
29468 vinfos[3].maxsolutions = _nj3;
29469 vinfos[4].jointtype = 1;
29470 vinfos[4].foffset = j4;
29471 vinfos[4].indices[0] = _ij4[0];
29472 vinfos[4].indices[1] = _ij4[1];
29473 vinfos[4].maxsolutions = _nj4;
29474 vinfos[5].jointtype = 1;
29475 vinfos[5].foffset = j5;
29476 vinfos[5].indices[0] = _ij5[0];
29477 vinfos[5].indices[1] = _ij5[1];
29478 vinfos[5].maxsolutions = _nj5;
29479 vinfos[6].jointtype = 1;
29480 vinfos[6].foffset = j6;
29481 vinfos[6].indices[0] = _ij6[0];
29482 vinfos[6].indices[1] = _ij6[1];
29483 vinfos[6].maxsolutions = _nj6;
29484 std::vector<int> vfree(0);
29485 solutions.AddSolution(vinfos,vfree);
29486 }
29487 }
29488 }
29489 
29490 } else
29491 {
29492 IkReal x9177=((IkReal(1.00000000000000))*(cj0));
29493 IkReal x9178=((cj4)*(sj6));
29494 IkReal x9179=((sj0)*(sj4));
29495 IkReal x9180=((cj5)*(sj6));
29496 IkReal x9181=((sj4)*(sj5));
29497 IkReal x9182=((r12)*(sj5));
29498 IkReal x9183=((IkReal(0.374290000000000))*(cj5));
29499 IkReal x9184=((r02)*(sj0));
29500 IkReal x9185=((r20)*(sj4));
29501 IkReal x9186=((IkReal(1.00000000000000))*(sj0));
29502 IkReal x9187=((IkReal(1.00000000000000))*(cj5));
29503 IkReal x9188=((cj0)*(r10));
29504 IkReal x9189=((cj4)*(cj6));
29505 IkReal x9190=((r00)*(sj0));
29506 IkReal x9191=((cj6)*(r21));
29507 IkReal x9192=((IkReal(0.374290000000000))*(sj5));
29508 IkReal x9193=((cj0)*(r00));
29509 IkReal x9194=((IkReal(0.0100000000000000))*(sj5));
29510 IkReal x9195=((cj0)*(r02));
29511 IkReal x9196=((cj5)*(sj4));
29512 IkReal x9197=((cj6)*(r01));
29513 IkReal x9198=((cj6)*(r11));
29514 IkReal x9199=((r01)*(sj0));
29515 IkReal x9200=((r10)*(sj0));
29516 IkReal x9201=((IkReal(0.0100000000000000))*(cj5)*(cj6));
29517 IkReal x9202=((sj6)*(x9192));
29518 IkReal x9203=((cj0)*(cj6)*(x9192));
29519 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
29520 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x9187)))+(((r20)*(sj5)*(sj6)))+(((sj5)*(x9191))));
29521 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x9181)))+(((r21)*(x9178)))+(((IkReal(-1.00000000000000))*(r20)*(x9189)))+(((x9180)*(x9185)))+(((x9191)*(x9196))));
29522 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x9183)))+(((IkReal(-0.0100000000000000))*(cj5)*(x9191)))+(((IkReal(-1.00000000000000))*(r22)*(x9194)))+(((IkReal(-0.0100000000000000))*(r20)*(x9180)))+(pz)+(((x9191)*(x9192)))+(((r20)*(x9202))));
29523 evalcond[4]=((((cj5)*(r21)*(x9189)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x9178)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x9185))));
29524 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(x9177)*(x9178)))+(((IkReal(-1.00000000000000))*(r12)*(x9177)*(x9181)))+(((r02)*(sj5)*(x9179)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x9177)*(x9180)))+(((cj5)*(x9179)*(x9197)))+(((x9178)*(x9199)))+(((r00)*(x9179)*(x9180)))+(((x9188)*(x9189)))+(((IkReal(-1.00000000000000))*(x9177)*(x9196)*(x9198)))+(((IkReal(-1.00000000000000))*(r00)*(x9186)*(x9189))));
29525 evalcond[6]=((((IkReal(-1.00000000000000))*(x9179)*(x9182)))+(((IkReal(-1.00000000000000))*(r01)*(x9177)*(x9178)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x9177)*(x9180)))+(((IkReal(-1.00000000000000))*(r10)*(x9179)*(x9180)))+(((IkReal(-1.00000000000000))*(r02)*(x9177)*(x9181)))+(((IkReal(-1.00000000000000))*(x9177)*(x9196)*(x9197)))+(((IkReal(-1.00000000000000))*(x9179)*(x9187)*(x9198)))+(((x9189)*(x9200)))+(((x9189)*(x9193)))+(((IkReal(-1.00000000000000))*(r11)*(x9178)*(x9186))));
29526 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(x9182)))+(((cj0)*(r12)*(x9183)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9198)))+(((IkReal(-1.00000000000000))*(x9183)*(x9184)))+(((IkReal(-1.00000000000000))*(x9188)*(x9202)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x9197)))+(((IkReal(-1.00000000000000))*(py)*(x9177)))+(((IkReal(-1.00000000000000))*(cj0)*(x9192)*(x9198)))+(((x9190)*(x9202)))+(((IkReal(0.0100000000000000))*(x9180)*(x9188)))+(((sj0)*(x9192)*(x9197)))+(((IkReal(-0.0100000000000000))*(x9180)*(x9190)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x9184)*(x9194))));
29527 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(x9193)*(x9202)))+(((IkReal(0.0100000000000000))*(x9180)*(x9193)))+(((r12)*(sj0)*(x9183)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x9198)))+(((IkReal(-1.00000000000000))*(cj0)*(x9192)*(x9197)))+(((x9194)*(x9195)))+(((IkReal(-1.00000000000000))*(sj0)*(x9192)*(x9198)))+(((IkReal(-1.00000000000000))*(px)*(x9177)))+(((IkReal(0.0100000000000000))*(sj0)*(x9182)))+(((IkReal(-1.00000000000000))*(x9200)*(x9202)))+(((IkReal(0.0100000000000000))*(x9180)*(x9200)))+(((x9183)*(x9195)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9197)))+(((IkReal(-1.00000000000000))*(py)*(x9186))));
29528 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
29529 {
29530 {
29531 IkReal j3array[1], cj3array[1], sj3array[1];
29532 bool j3valid[1]={false};
29533 _nj3 = 1;
29534 IkReal x9204=((cj0)*(cj5));
29535 IkReal x9205=((IkReal(1.00000000000000))*(cj0));
29536 IkReal x9206=((cj6)*(r11));
29537 IkReal x9207=((r10)*(sj6));
29538 IkReal x9208=((cj5)*(sj0));
29539 IkReal x9209=((r00)*(sj5)*(sj6));
29540 IkReal x9210=((cj6)*(r01)*(sj5));
29541 IkReal x9211=((IkReal(1.00000000000000))*(sj0)*(sj5));
29542 if( IKabs(((((r12)*(x9204)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9206)))+(((IkReal(-1.00000000000000))*(r02)*(x9208)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9207)))+(((sj0)*(x9209)))+(((sj0)*(x9210))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r02)*(x9204)))+(((IkReal(-1.00000000000000))*(x9205)*(x9209)))+(((IkReal(-1.00000000000000))*(x9207)*(x9211)))+(((IkReal(-1.00000000000000))*(x9205)*(x9210)))+(((r12)*(x9208)))+(((IkReal(-1.00000000000000))*(x9206)*(x9211))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r12)*(x9204)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9206)))+(((IkReal(-1.00000000000000))*(r02)*(x9208)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9207)))+(((sj0)*(x9209)))+(((sj0)*(x9210)))))+IKsqr(((((r02)*(x9204)))+(((IkReal(-1.00000000000000))*(x9205)*(x9209)))+(((IkReal(-1.00000000000000))*(x9207)*(x9211)))+(((IkReal(-1.00000000000000))*(x9205)*(x9210)))+(((r12)*(x9208)))+(((IkReal(-1.00000000000000))*(x9206)*(x9211)))))-1) <= IKFAST_SINCOS_THRESH )
29543     continue;
29544 j3array[0]=IKatan2(((((r12)*(x9204)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9206)))+(((IkReal(-1.00000000000000))*(r02)*(x9208)))+(((IkReal(-1.00000000000000))*(sj5)*(x9205)*(x9207)))+(((sj0)*(x9209)))+(((sj0)*(x9210)))), ((((r02)*(x9204)))+(((IkReal(-1.00000000000000))*(x9205)*(x9209)))+(((IkReal(-1.00000000000000))*(x9207)*(x9211)))+(((IkReal(-1.00000000000000))*(x9205)*(x9210)))+(((r12)*(x9208)))+(((IkReal(-1.00000000000000))*(x9206)*(x9211)))));
29545 sj3array[0]=IKsin(j3array[0]);
29546 cj3array[0]=IKcos(j3array[0]);
29547 if( j3array[0] > IKPI )
29548 {
29549     j3array[0]-=IK2PI;
29550 }
29551 else if( j3array[0] < -IKPI )
29552 {    j3array[0]+=IK2PI;
29553 }
29554 j3valid[0] = true;
29555 for(int ij3 = 0; ij3 < 1; ++ij3)
29556 {
29557 if( !j3valid[ij3] )
29558 {
29559     continue;
29560 }
29561 _ij3[0] = ij3; _ij3[1] = -1;
29562 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29563 {
29564 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29565 {
29566     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29567 }
29568 }
29569 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29570 {
29571 IkReal evalcond[4];
29572 IkReal x9212=IKcos(j3);
29573 IkReal x9213=((sj0)*(sj5));
29574 IkReal x9214=((r00)*(sj6));
29575 IkReal x9215=((cj6)*(sj0));
29576 IkReal x9216=((IkReal(1.00000000000000))*(cj4));
29577 IkReal x9217=((r00)*(sj4));
29578 IkReal x9218=((cj0)*(cj5));
29579 IkReal x9219=((cj5)*(sj0));
29580 IkReal x9220=((cj6)*(r11));
29581 IkReal x9221=((r10)*(sj6));
29582 IkReal x9222=((cj0)*(sj5));
29583 IkReal x9223=((r10)*(sj4));
29584 IkReal x9224=((IkReal(1.00000000000000))*(IKsin(j3)));
29585 IkReal x9225=((cj4)*(cj5)*(r01));
29586 IkReal x9226=((IkReal(1.00000000000000))*(cj0)*(cj6));
29587 IkReal x9227=((cj0)*(sj4)*(sj6));
29588 IkReal x9228=((sj0)*(sj4)*(sj6));
29589 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x9219)))+(((IkReal(-1.00000000000000))*(x9221)*(x9222)))+(((x9213)*(x9214)))+(((IkReal(-1.00000000000000))*(x9220)*(x9222)))+(((cj6)*(r01)*(x9213)))+(((r12)*(x9218)))+(((IkReal(-1.00000000000000))*(x9224))));
29590 evalcond[1]=((((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9222)))+(((IkReal(-1.00000000000000))*(x9213)*(x9221)))+(((IkReal(-1.00000000000000))*(x9213)*(x9220)))+(((r12)*(x9219)))+(((IkReal(-1.00000000000000))*(x9214)*(x9222)))+(((IkReal(-1.00000000000000))*(x9212)))+(((r02)*(x9218))));
29591 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x9216)*(x9222)))+(x9212)+(((cj4)*(r02)*(x9213)))+(((IkReal(-1.00000000000000))*(x9223)*(x9226)))+(((x9215)*(x9217)))+(((x9215)*(x9225)))+(((IkReal(-1.00000000000000))*(x9216)*(x9218)*(x9221)))+(((r11)*(x9227)))+(((IkReal(-1.00000000000000))*(r01)*(x9228)))+(((cj4)*(x9214)*(x9219)))+(((IkReal(-1.00000000000000))*(x9216)*(x9218)*(x9220))));
29592 evalcond[3]=((((IkReal(-1.00000000000000))*(x9216)*(x9219)*(x9221)))+(((r01)*(x9227)))+(((r11)*(x9228)))+(((IkReal(-1.00000000000000))*(r02)*(x9216)*(x9222)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x9215)*(x9216)))+(((IkReal(-1.00000000000000))*(x9217)*(x9226)))+(((IkReal(-1.00000000000000))*(x9214)*(x9216)*(x9218)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9216)*(x9218)))+(((IkReal(-1.00000000000000))*(r12)*(x9213)*(x9216)))+(((IkReal(-1.00000000000000))*(x9224)))+(((IkReal(-1.00000000000000))*(x9215)*(x9223))));
29593 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
29594 {
29595 continue;
29596 }
29597 }
29598 
29599 {
29600 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29601 vinfos[0].jointtype = 1;
29602 vinfos[0].foffset = j0;
29603 vinfos[0].indices[0] = _ij0[0];
29604 vinfos[0].indices[1] = _ij0[1];
29605 vinfos[0].maxsolutions = _nj0;
29606 vinfos[1].jointtype = 1;
29607 vinfos[1].foffset = j1;
29608 vinfos[1].indices[0] = _ij1[0];
29609 vinfos[1].indices[1] = _ij1[1];
29610 vinfos[1].maxsolutions = _nj1;
29611 vinfos[2].jointtype = 1;
29612 vinfos[2].foffset = j2;
29613 vinfos[2].indices[0] = _ij2[0];
29614 vinfos[2].indices[1] = _ij2[1];
29615 vinfos[2].maxsolutions = _nj2;
29616 vinfos[3].jointtype = 1;
29617 vinfos[3].foffset = j3;
29618 vinfos[3].indices[0] = _ij3[0];
29619 vinfos[3].indices[1] = _ij3[1];
29620 vinfos[3].maxsolutions = _nj3;
29621 vinfos[4].jointtype = 1;
29622 vinfos[4].foffset = j4;
29623 vinfos[4].indices[0] = _ij4[0];
29624 vinfos[4].indices[1] = _ij4[1];
29625 vinfos[4].maxsolutions = _nj4;
29626 vinfos[5].jointtype = 1;
29627 vinfos[5].foffset = j5;
29628 vinfos[5].indices[0] = _ij5[0];
29629 vinfos[5].indices[1] = _ij5[1];
29630 vinfos[5].maxsolutions = _nj5;
29631 vinfos[6].jointtype = 1;
29632 vinfos[6].foffset = j6;
29633 vinfos[6].indices[0] = _ij6[0];
29634 vinfos[6].indices[1] = _ij6[1];
29635 vinfos[6].maxsolutions = _nj6;
29636 std::vector<int> vfree(0);
29637 solutions.AddSolution(vinfos,vfree);
29638 }
29639 }
29640 }
29641 
29642 } else
29643 {
29644 IkReal x9229=((IkReal(1.00000000000000))*(cj0));
29645 IkReal x9230=((cj4)*(sj6));
29646 IkReal x9231=((sj0)*(sj4));
29647 IkReal x9232=((cj5)*(sj6));
29648 IkReal x9233=((sj4)*(sj5));
29649 IkReal x9234=((r12)*(sj5));
29650 IkReal x9235=((IkReal(0.374290000000000))*(cj5));
29651 IkReal x9236=((r02)*(sj0));
29652 IkReal x9237=((r20)*(sj4));
29653 IkReal x9238=((IkReal(1.00000000000000))*(sj0));
29654 IkReal x9239=((IkReal(1.00000000000000))*(cj5));
29655 IkReal x9240=((cj0)*(r10));
29656 IkReal x9241=((cj4)*(cj6));
29657 IkReal x9242=((r00)*(sj0));
29658 IkReal x9243=((cj6)*(r21));
29659 IkReal x9244=((IkReal(0.374290000000000))*(sj5));
29660 IkReal x9245=((cj0)*(r00));
29661 IkReal x9246=((IkReal(0.0100000000000000))*(sj5));
29662 IkReal x9247=((cj0)*(r02));
29663 IkReal x9248=((cj5)*(sj4));
29664 IkReal x9249=((cj6)*(r01));
29665 IkReal x9250=((cj6)*(r11));
29666 IkReal x9251=((r01)*(sj0));
29667 IkReal x9252=((r10)*(sj0));
29668 IkReal x9253=((IkReal(0.0100000000000000))*(cj5)*(cj6));
29669 IkReal x9254=((sj6)*(x9244));
29670 IkReal x9255=((cj0)*(cj6)*(x9244));
29671 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
29672 evalcond[1]=((((sj5)*(x9243)))+(((IkReal(-1.00000000000000))*(r22)*(x9239)))+(((r20)*(sj5)*(sj6))));
29673 evalcond[2]=((IkReal(1.00000000000000))+(((r21)*(x9230)))+(((IkReal(-1.00000000000000))*(r20)*(x9241)))+(((x9232)*(x9237)))+(((r22)*(x9233)))+(((x9243)*(x9248))));
29674 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x9246)))+(((IkReal(-1.00000000000000))*(r22)*(x9235)))+(((IkReal(-0.0100000000000000))*(cj5)*(x9243)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x9232)))+(((r20)*(x9254)))+(((x9243)*(x9244))));
29675 evalcond[4]=((((cj6)*(x9237)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x9230)))+(((cj5)*(r21)*(x9241))));
29676 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x9229)*(x9233)))+(((x9230)*(x9251)))+(((cj5)*(x9231)*(x9249)))+(((x9240)*(x9241)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x9229)*(x9232)))+(((IkReal(-1.00000000000000))*(x9229)*(x9248)*(x9250)))+(((r02)*(sj5)*(x9231)))+(((IkReal(-1.00000000000000))*(r00)*(x9238)*(x9241)))+(((r00)*(x9231)*(x9232)))+(((IkReal(-1.00000000000000))*(r11)*(x9229)*(x9230))));
29677 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(sj4)*(x9229)*(x9232)))+(((IkReal(-1.00000000000000))*(x9231)*(x9234)))+(((IkReal(-1.00000000000000))*(r10)*(x9231)*(x9232)))+(((x9241)*(x9252)))+(((x9241)*(x9245)))+(((IkReal(-1.00000000000000))*(x9231)*(x9239)*(x9250)))+(((IkReal(-1.00000000000000))*(r01)*(x9229)*(x9230)))+(((IkReal(-1.00000000000000))*(r02)*(x9229)*(x9233)))+(((IkReal(-1.00000000000000))*(r11)*(x9230)*(x9238)))+(((IkReal(-1.00000000000000))*(x9229)*(x9248)*(x9249))));
29678 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(x9234)))+(((sj0)*(x9244)*(x9249)))+(((cj0)*(r12)*(x9235)))+(((IkReal(-1.00000000000000))*(x9236)*(x9246)))+(((IkReal(-1.00000000000000))*(x9235)*(x9236)))+(((IkReal(0.0100000000000000))*(x9232)*(x9240)))+(((x9242)*(x9254)))+(((IkReal(-0.0100000000000000))*(x9232)*(x9242)))+(((IkReal(-1.00000000000000))*(py)*(x9229)))+(((IkReal(-1.00000000000000))*(cj0)*(x9244)*(x9250)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9250)))+(((IkReal(-1.00000000000000))*(x9240)*(x9254)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x9249))));
29679 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x9244)*(x9249)))+(((IkReal(0.0100000000000000))*(x9232)*(x9245)))+(((x9235)*(x9247)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x9250)))+(((IkReal(-1.00000000000000))*(px)*(x9229)))+(((IkReal(-1.00000000000000))*(py)*(x9238)))+(((IkReal(-1.00000000000000))*(x9245)*(x9254)))+(((IkReal(-1.00000000000000))*(sj0)*(x9244)*(x9250)))+(((x9246)*(x9247)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9249)))+(((r12)*(sj0)*(x9235)))+(((IkReal(0.0100000000000000))*(x9232)*(x9252)))+(((IkReal(-1.00000000000000))*(x9252)*(x9254)))+(((IkReal(0.0100000000000000))*(sj0)*(x9234))));
29680 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
29681 {
29682 {
29683 IkReal j3array[1], cj3array[1], sj3array[1];
29684 bool j3valid[1]={false};
29685 _nj3 = 1;
29686 IkReal x9256=((sj0)*(sj5));
29687 IkReal x9257=((r00)*(sj6));
29688 IkReal x9258=((IkReal(1.00000000000000))*(cj5));
29689 IkReal x9259=((cj6)*(r11));
29690 IkReal x9260=((cj6)*(r01));
29691 IkReal x9261=((r10)*(sj6));
29692 IkReal x9262=((cj0)*(sj5));
29693 if( IKabs(((((IkReal(-1.00000000000000))*(x9259)*(x9262)))+(((IkReal(-1.00000000000000))*(x9261)*(x9262)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9258)))+(((x9256)*(x9257)))+(((x9256)*(x9260))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9258)))+(((x9256)*(x9259)))+(((x9257)*(x9262)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9258)))+(((x9256)*(x9261)))+(((x9260)*(x9262))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x9259)*(x9262)))+(((IkReal(-1.00000000000000))*(x9261)*(x9262)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9258)))+(((x9256)*(x9257)))+(((x9256)*(x9260)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9258)))+(((x9256)*(x9259)))+(((x9257)*(x9262)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9258)))+(((x9256)*(x9261)))+(((x9260)*(x9262)))))-1) <= IKFAST_SINCOS_THRESH )
29694     continue;
29695 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x9259)*(x9262)))+(((IkReal(-1.00000000000000))*(x9261)*(x9262)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9258)))+(((x9256)*(x9257)))+(((x9256)*(x9260)))), ((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9258)))+(((x9256)*(x9259)))+(((x9257)*(x9262)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9258)))+(((x9256)*(x9261)))+(((x9260)*(x9262)))));
29696 sj3array[0]=IKsin(j3array[0]);
29697 cj3array[0]=IKcos(j3array[0]);
29698 if( j3array[0] > IKPI )
29699 {
29700     j3array[0]-=IK2PI;
29701 }
29702 else if( j3array[0] < -IKPI )
29703 {    j3array[0]+=IK2PI;
29704 }
29705 j3valid[0] = true;
29706 for(int ij3 = 0; ij3 < 1; ++ij3)
29707 {
29708 if( !j3valid[ij3] )
29709 {
29710     continue;
29711 }
29712 _ij3[0] = ij3; _ij3[1] = -1;
29713 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29714 {
29715 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29716 {
29717     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29718 }
29719 }
29720 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29721 {
29722 IkReal evalcond[4];
29723 IkReal x9263=IKcos(j3);
29724 IkReal x9264=IKsin(j3);
29725 IkReal x9265=((sj0)*(sj5));
29726 IkReal x9266=((r00)*(sj6));
29727 IkReal x9267=((cj6)*(sj0));
29728 IkReal x9268=((IkReal(1.00000000000000))*(cj4));
29729 IkReal x9269=((r00)*(sj4));
29730 IkReal x9270=((cj0)*(cj5));
29731 IkReal x9271=((cj5)*(sj0));
29732 IkReal x9272=((cj6)*(r11));
29733 IkReal x9273=((r10)*(sj6));
29734 IkReal x9274=((cj0)*(sj5));
29735 IkReal x9275=((r10)*(sj4));
29736 IkReal x9276=((cj4)*(cj5)*(r01));
29737 IkReal x9277=((IkReal(1.00000000000000))*(cj0)*(cj6));
29738 IkReal x9278=((cj0)*(sj4)*(sj6));
29739 IkReal x9279=((sj0)*(sj4)*(sj6));
29740 evalcond[0]=((((IkReal(-1.00000000000000))*(x9273)*(x9274)))+(((cj6)*(r01)*(x9265)))+(((IkReal(-1.00000000000000))*(r02)*(x9271)))+(((IkReal(-1.00000000000000))*(x9264)))+(((IkReal(-1.00000000000000))*(x9272)*(x9274)))+(((x9265)*(x9266)))+(((r12)*(x9270))));
29741 evalcond[1]=((((r02)*(x9270)))+(((IkReal(-1.00000000000000))*(x9265)*(x9272)))+(x9263)+(((r12)*(x9271)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9274)))+(((IkReal(-1.00000000000000))*(x9266)*(x9274)))+(((IkReal(-1.00000000000000))*(x9265)*(x9273))));
29742 evalcond[2]=((((cj4)*(r02)*(x9265)))+(((x9267)*(x9269)))+(x9263)+(((r11)*(x9278)))+(((IkReal(-1.00000000000000))*(x9268)*(x9270)*(x9273)))+(((x9267)*(x9276)))+(((IkReal(-1.00000000000000))*(x9268)*(x9270)*(x9272)))+(((IkReal(-1.00000000000000))*(x9275)*(x9277)))+(((cj4)*(x9266)*(x9271)))+(((IkReal(-1.00000000000000))*(r12)*(x9268)*(x9274)))+(((IkReal(-1.00000000000000))*(r01)*(x9279))));
29743 evalcond[3]=((((r11)*(x9279)))+(((IkReal(-1.00000000000000))*(x9267)*(x9275)))+(x9264)+(((IkReal(-1.00000000000000))*(x9268)*(x9271)*(x9273)))+(((r01)*(x9278)))+(((IkReal(-1.00000000000000))*(x9266)*(x9268)*(x9270)))+(((IkReal(-1.00000000000000))*(x9269)*(x9277)))+(((IkReal(-1.00000000000000))*(r12)*(x9265)*(x9268)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x9267)*(x9268)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9268)*(x9270)))+(((IkReal(-1.00000000000000))*(r02)*(x9268)*(x9274))));
29744 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
29745 {
29746 continue;
29747 }
29748 }
29749 
29750 {
29751 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29752 vinfos[0].jointtype = 1;
29753 vinfos[0].foffset = j0;
29754 vinfos[0].indices[0] = _ij0[0];
29755 vinfos[0].indices[1] = _ij0[1];
29756 vinfos[0].maxsolutions = _nj0;
29757 vinfos[1].jointtype = 1;
29758 vinfos[1].foffset = j1;
29759 vinfos[1].indices[0] = _ij1[0];
29760 vinfos[1].indices[1] = _ij1[1];
29761 vinfos[1].maxsolutions = _nj1;
29762 vinfos[2].jointtype = 1;
29763 vinfos[2].foffset = j2;
29764 vinfos[2].indices[0] = _ij2[0];
29765 vinfos[2].indices[1] = _ij2[1];
29766 vinfos[2].maxsolutions = _nj2;
29767 vinfos[3].jointtype = 1;
29768 vinfos[3].foffset = j3;
29769 vinfos[3].indices[0] = _ij3[0];
29770 vinfos[3].indices[1] = _ij3[1];
29771 vinfos[3].maxsolutions = _nj3;
29772 vinfos[4].jointtype = 1;
29773 vinfos[4].foffset = j4;
29774 vinfos[4].indices[0] = _ij4[0];
29775 vinfos[4].indices[1] = _ij4[1];
29776 vinfos[4].maxsolutions = _nj4;
29777 vinfos[5].jointtype = 1;
29778 vinfos[5].foffset = j5;
29779 vinfos[5].indices[0] = _ij5[0];
29780 vinfos[5].indices[1] = _ij5[1];
29781 vinfos[5].maxsolutions = _nj5;
29782 vinfos[6].jointtype = 1;
29783 vinfos[6].foffset = j6;
29784 vinfos[6].indices[0] = _ij6[0];
29785 vinfos[6].indices[1] = _ij6[1];
29786 vinfos[6].maxsolutions = _nj6;
29787 std::vector<int> vfree(0);
29788 solutions.AddSolution(vinfos,vfree);
29789 }
29790 }
29791 }
29792 
29793 } else
29794 {
29795 if( 1 )
29796 {
29797 continue;
29798 
29799 } else
29800 {
29801 }
29802 }
29803 }
29804 }
29805 }
29806 }
29807 
29808 } else
29809 {
29810 {
29811 IkReal j3array[1], cj3array[1], sj3array[1];
29812 bool j3valid[1]={false};
29813 _nj3 = 1;
29814 IkReal x9280=((cj0)*(cj5));
29815 IkReal x9281=((IkReal(1.00000000000000))*(cj0));
29816 IkReal x9282=((cj6)*(r11));
29817 IkReal x9283=((r10)*(sj6));
29818 IkReal x9284=((cj5)*(sj0));
29819 IkReal x9285=((r00)*(sj5)*(sj6));
29820 IkReal x9286=((cj6)*(r01)*(sj5));
29821 IkReal x9287=((IkReal(1.00000000000000))*(sj0)*(sj5));
29822 if( IKabs(((((sj0)*(x9286)))+(((r12)*(x9280)))+(((IkReal(-1.00000000000000))*(r02)*(x9284)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9283)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9282)))+(((sj0)*(x9285))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x9280)))+(((IkReal(-1.00000000000000))*(x9283)*(x9287)))+(((r12)*(x9284)))+(((IkReal(-1.00000000000000))*(x9281)*(x9286)))+(((IkReal(-1.00000000000000))*(x9281)*(x9285)))+(((IkReal(-1.00000000000000))*(x9282)*(x9287))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x9286)))+(((r12)*(x9280)))+(((IkReal(-1.00000000000000))*(r02)*(x9284)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9283)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9282)))+(((sj0)*(x9285)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x9280)))+(((IkReal(-1.00000000000000))*(x9283)*(x9287)))+(((r12)*(x9284)))+(((IkReal(-1.00000000000000))*(x9281)*(x9286)))+(((IkReal(-1.00000000000000))*(x9281)*(x9285)))+(((IkReal(-1.00000000000000))*(x9282)*(x9287)))))))-1) <= IKFAST_SINCOS_THRESH )
29823     continue;
29824 j3array[0]=IKatan2(((((sj0)*(x9286)))+(((r12)*(x9280)))+(((IkReal(-1.00000000000000))*(r02)*(x9284)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9283)))+(((IkReal(-1.00000000000000))*(sj5)*(x9281)*(x9282)))+(((sj0)*(x9285)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x9280)))+(((IkReal(-1.00000000000000))*(x9283)*(x9287)))+(((r12)*(x9284)))+(((IkReal(-1.00000000000000))*(x9281)*(x9286)))+(((IkReal(-1.00000000000000))*(x9281)*(x9285)))+(((IkReal(-1.00000000000000))*(x9282)*(x9287)))))));
29825 sj3array[0]=IKsin(j3array[0]);
29826 cj3array[0]=IKcos(j3array[0]);
29827 if( j3array[0] > IKPI )
29828 {
29829     j3array[0]-=IK2PI;
29830 }
29831 else if( j3array[0] < -IKPI )
29832 {    j3array[0]+=IK2PI;
29833 }
29834 j3valid[0] = true;
29835 for(int ij3 = 0; ij3 < 1; ++ij3)
29836 {
29837 if( !j3valid[ij3] )
29838 {
29839     continue;
29840 }
29841 _ij3[0] = ij3; _ij3[1] = -1;
29842 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29843 {
29844 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29845 {
29846     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29847 }
29848 }
29849 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29850 {
29851 IkReal evalcond[6];
29852 IkReal x9288=IKsin(j3);
29853 IkReal x9289=IKcos(j3);
29854 IkReal x9290=((sj0)*(sj5));
29855 IkReal x9291=((r00)*(sj6));
29856 IkReal x9292=((cj6)*(r01));
29857 IkReal x9293=((cj4)*(cj5));
29858 IkReal x9294=((IkReal(1.00000000000000))*(cj0));
29859 IkReal x9295=((cj5)*(r12));
29860 IkReal x9296=((IkReal(1.00000000000000))*(sj0));
29861 IkReal x9297=((cj6)*(r11));
29862 IkReal x9298=((cj5)*(r02));
29863 IkReal x9299=((IkReal(1.00000000000000))*(cj1));
29864 IkReal x9300=((cj6)*(sj4));
29865 IkReal x9301=((cj6)*(r21));
29866 IkReal x9302=((r20)*(sj6));
29867 IkReal x9303=((r10)*(sj6));
29868 IkReal x9304=((sj4)*(sj6));
29869 IkReal x9305=((cj4)*(r02));
29870 IkReal x9306=((IkReal(1.00000000000000))*(cj4)*(r12));
29871 IkReal x9307=((IkReal(1.00000000000000))*(x9288));
29872 IkReal x9308=((cj0)*(x9304));
29873 evalcond[0]=((((sj5)*(x9301)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x9289)))+(((sj5)*(x9302))));
29874 evalcond[1]=((((x9293)*(x9301)))+(((IkReal(-1.00000000000000))*(sj1)*(x9307)))+(((r20)*(x9300)))+(((x9293)*(x9302)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x9304))));
29875 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x9294)*(x9297)))+(((IkReal(-1.00000000000000))*(x9296)*(x9298)))+(((cj0)*(x9295)))+(((x9290)*(x9291)))+(((IkReal(-1.00000000000000))*(sj5)*(x9294)*(x9303)))+(((x9290)*(x9292)))+(((IkReal(-1.00000000000000))*(x9307))));
29876 evalcond[3]=((((IkReal(-1.00000000000000))*(x9289)*(x9299)))+(((cj0)*(x9298)))+(((sj0)*(x9295)))+(((IkReal(-1.00000000000000))*(sj5)*(x9292)*(x9294)))+(((IkReal(-1.00000000000000))*(x9290)*(x9303)))+(((IkReal(-1.00000000000000))*(x9290)*(x9297)))+(((IkReal(-1.00000000000000))*(sj5)*(x9291)*(x9294))));
29877 evalcond[4]=((((sj0)*(x9291)*(x9293)))+(((IkReal(-1.00000000000000))*(x9293)*(x9294)*(x9297)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9294)))+(((r00)*(sj0)*(x9300)))+(((sj0)*(x9292)*(x9293)))+(((IkReal(-1.00000000000000))*(r10)*(x9294)*(x9300)))+(((x9290)*(x9305)))+(((r11)*(x9308)))+(((IkReal(-1.00000000000000))*(x9293)*(x9294)*(x9303)))+(x9289)+(((IkReal(-1.00000000000000))*(r01)*(x9296)*(x9304))));
29878 evalcond[5]=((((IkReal(-1.00000000000000))*(x9291)*(x9293)*(x9294)))+(((r11)*(sj0)*(x9304)))+(((IkReal(-1.00000000000000))*(x9288)*(x9299)))+(((IkReal(-1.00000000000000))*(x9293)*(x9296)*(x9303)))+(((IkReal(-1.00000000000000))*(x9293)*(x9296)*(x9297)))+(((IkReal(-1.00000000000000))*(x9290)*(x9306)))+(((IkReal(-1.00000000000000))*(sj5)*(x9294)*(x9305)))+(((IkReal(-1.00000000000000))*(x9292)*(x9293)*(x9294)))+(((IkReal(-1.00000000000000))*(r00)*(x9294)*(x9300)))+(((IkReal(-1.00000000000000))*(r10)*(x9296)*(x9300)))+(((r01)*(x9308))));
29879 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
29880 {
29881 continue;
29882 }
29883 }
29884 
29885 {
29886 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
29887 vinfos[0].jointtype = 1;
29888 vinfos[0].foffset = j0;
29889 vinfos[0].indices[0] = _ij0[0];
29890 vinfos[0].indices[1] = _ij0[1];
29891 vinfos[0].maxsolutions = _nj0;
29892 vinfos[1].jointtype = 1;
29893 vinfos[1].foffset = j1;
29894 vinfos[1].indices[0] = _ij1[0];
29895 vinfos[1].indices[1] = _ij1[1];
29896 vinfos[1].maxsolutions = _nj1;
29897 vinfos[2].jointtype = 1;
29898 vinfos[2].foffset = j2;
29899 vinfos[2].indices[0] = _ij2[0];
29900 vinfos[2].indices[1] = _ij2[1];
29901 vinfos[2].maxsolutions = _nj2;
29902 vinfos[3].jointtype = 1;
29903 vinfos[3].foffset = j3;
29904 vinfos[3].indices[0] = _ij3[0];
29905 vinfos[3].indices[1] = _ij3[1];
29906 vinfos[3].maxsolutions = _nj3;
29907 vinfos[4].jointtype = 1;
29908 vinfos[4].foffset = j4;
29909 vinfos[4].indices[0] = _ij4[0];
29910 vinfos[4].indices[1] = _ij4[1];
29911 vinfos[4].maxsolutions = _nj4;
29912 vinfos[5].jointtype = 1;
29913 vinfos[5].foffset = j5;
29914 vinfos[5].indices[0] = _ij5[0];
29915 vinfos[5].indices[1] = _ij5[1];
29916 vinfos[5].maxsolutions = _nj5;
29917 vinfos[6].jointtype = 1;
29918 vinfos[6].foffset = j6;
29919 vinfos[6].indices[0] = _ij6[0];
29920 vinfos[6].indices[1] = _ij6[1];
29921 vinfos[6].maxsolutions = _nj6;
29922 std::vector<int> vfree(0);
29923 solutions.AddSolution(vinfos,vfree);
29924 }
29925 }
29926 }
29927 
29928 }
29929 
29930 }
29931 
29932 } else
29933 {
29934 {
29935 IkReal j3array[1], cj3array[1], sj3array[1];
29936 bool j3valid[1]={false};
29937 _nj3 = 1;
29938 IkReal x9309=((sj5)*(sj6));
29939 IkReal x9310=((cj6)*(sj5));
29940 IkReal x9311=((IkReal(1.00000000000000))*(cj0));
29941 IkReal x9312=((IkReal(1.00000000000000))*(cj5));
29942 if( IKabs(((((r01)*(sj0)*(x9310)))+(((IkReal(-1.00000000000000))*(r11)*(x9310)*(x9311)))+(((r00)*(sj0)*(x9309)))+(((IkReal(-1.00000000000000))*(r10)*(x9309)*(x9311)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9312))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x9310)))+(((IkReal(-1.00000000000000))*(r22)*(x9312)))+(((r20)*(x9309))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r01)*(sj0)*(x9310)))+(((IkReal(-1.00000000000000))*(r11)*(x9310)*(x9311)))+(((r00)*(sj0)*(x9309)))+(((IkReal(-1.00000000000000))*(r10)*(x9309)*(x9311)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9312)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x9310)))+(((IkReal(-1.00000000000000))*(r22)*(x9312)))+(((r20)*(x9309)))))))-1) <= IKFAST_SINCOS_THRESH )
29943     continue;
29944 j3array[0]=IKatan2(((((r01)*(sj0)*(x9310)))+(((IkReal(-1.00000000000000))*(r11)*(x9310)*(x9311)))+(((r00)*(sj0)*(x9309)))+(((IkReal(-1.00000000000000))*(r10)*(x9309)*(x9311)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9312)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x9310)))+(((IkReal(-1.00000000000000))*(r22)*(x9312)))+(((r20)*(x9309)))))));
29945 sj3array[0]=IKsin(j3array[0]);
29946 cj3array[0]=IKcos(j3array[0]);
29947 if( j3array[0] > IKPI )
29948 {
29949     j3array[0]-=IK2PI;
29950 }
29951 else if( j3array[0] < -IKPI )
29952 {    j3array[0]+=IK2PI;
29953 }
29954 j3valid[0] = true;
29955 for(int ij3 = 0; ij3 < 1; ++ij3)
29956 {
29957 if( !j3valid[ij3] )
29958 {
29959     continue;
29960 }
29961 _ij3[0] = ij3; _ij3[1] = -1;
29962 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
29963 {
29964 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
29965 {
29966     j3valid[iij3]=false; _ij3[1] = iij3; break; 
29967 }
29968 }
29969 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
29970 {
29971 IkReal evalcond[6];
29972 IkReal x9313=IKsin(j3);
29973 IkReal x9314=IKcos(j3);
29974 IkReal x9315=((sj0)*(sj5));
29975 IkReal x9316=((r00)*(sj6));
29976 IkReal x9317=((cj6)*(r01));
29977 IkReal x9318=((cj4)*(cj5));
29978 IkReal x9319=((IkReal(1.00000000000000))*(cj0));
29979 IkReal x9320=((cj5)*(r12));
29980 IkReal x9321=((IkReal(1.00000000000000))*(sj0));
29981 IkReal x9322=((cj6)*(r11));
29982 IkReal x9323=((cj5)*(r02));
29983 IkReal x9324=((IkReal(1.00000000000000))*(cj1));
29984 IkReal x9325=((cj6)*(sj4));
29985 IkReal x9326=((cj6)*(r21));
29986 IkReal x9327=((r20)*(sj6));
29987 IkReal x9328=((r10)*(sj6));
29988 IkReal x9329=((sj4)*(sj6));
29989 IkReal x9330=((cj4)*(r02));
29990 IkReal x9331=((IkReal(1.00000000000000))*(cj4)*(r12));
29991 IkReal x9332=((IkReal(1.00000000000000))*(x9313));
29992 IkReal x9333=((cj0)*(x9329));
29993 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x9314)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9326)))+(((sj5)*(x9327))));
29994 evalcond[1]=((((x9318)*(x9327)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x9329)))+(((r20)*(x9325)))+(((x9318)*(x9326)))+(((IkReal(-1.00000000000000))*(sj1)*(x9332))));
29995 evalcond[2]=((((IkReal(-1.00000000000000))*(x9332)))+(((x9315)*(x9317)))+(((IkReal(-1.00000000000000))*(sj5)*(x9319)*(x9322)))+(((x9315)*(x9316)))+(((IkReal(-1.00000000000000))*(sj5)*(x9319)*(x9328)))+(((IkReal(-1.00000000000000))*(x9321)*(x9323)))+(((cj0)*(x9320))));
29996 evalcond[3]=((((IkReal(-1.00000000000000))*(x9314)*(x9324)))+(((IkReal(-1.00000000000000))*(sj5)*(x9316)*(x9319)))+(((IkReal(-1.00000000000000))*(x9315)*(x9322)))+(((IkReal(-1.00000000000000))*(x9315)*(x9328)))+(((sj0)*(x9320)))+(((IkReal(-1.00000000000000))*(sj5)*(x9317)*(x9319)))+(((cj0)*(x9323))));
29997 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x9321)*(x9329)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9319)))+(((r11)*(x9333)))+(((sj0)*(x9316)*(x9318)))+(((IkReal(-1.00000000000000))*(x9318)*(x9319)*(x9322)))+(((IkReal(-1.00000000000000))*(x9318)*(x9319)*(x9328)))+(((IkReal(-1.00000000000000))*(r10)*(x9319)*(x9325)))+(((sj0)*(x9317)*(x9318)))+(((r00)*(sj0)*(x9325)))+(((x9315)*(x9330)))+(x9314));
29998 evalcond[5]=((((r11)*(sj0)*(x9329)))+(((IkReal(-1.00000000000000))*(x9318)*(x9321)*(x9322)))+(((IkReal(-1.00000000000000))*(r10)*(x9321)*(x9325)))+(((IkReal(-1.00000000000000))*(x9317)*(x9318)*(x9319)))+(((IkReal(-1.00000000000000))*(sj5)*(x9319)*(x9330)))+(((IkReal(-1.00000000000000))*(x9315)*(x9331)))+(((IkReal(-1.00000000000000))*(r00)*(x9319)*(x9325)))+(((IkReal(-1.00000000000000))*(x9313)*(x9324)))+(((IkReal(-1.00000000000000))*(x9316)*(x9318)*(x9319)))+(((r01)*(x9333)))+(((IkReal(-1.00000000000000))*(x9318)*(x9321)*(x9328))));
29999 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
30000 {
30001 continue;
30002 }
30003 }
30004 
30005 {
30006 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30007 vinfos[0].jointtype = 1;
30008 vinfos[0].foffset = j0;
30009 vinfos[0].indices[0] = _ij0[0];
30010 vinfos[0].indices[1] = _ij0[1];
30011 vinfos[0].maxsolutions = _nj0;
30012 vinfos[1].jointtype = 1;
30013 vinfos[1].foffset = j1;
30014 vinfos[1].indices[0] = _ij1[0];
30015 vinfos[1].indices[1] = _ij1[1];
30016 vinfos[1].maxsolutions = _nj1;
30017 vinfos[2].jointtype = 1;
30018 vinfos[2].foffset = j2;
30019 vinfos[2].indices[0] = _ij2[0];
30020 vinfos[2].indices[1] = _ij2[1];
30021 vinfos[2].maxsolutions = _nj2;
30022 vinfos[3].jointtype = 1;
30023 vinfos[3].foffset = j3;
30024 vinfos[3].indices[0] = _ij3[0];
30025 vinfos[3].indices[1] = _ij3[1];
30026 vinfos[3].maxsolutions = _nj3;
30027 vinfos[4].jointtype = 1;
30028 vinfos[4].foffset = j4;
30029 vinfos[4].indices[0] = _ij4[0];
30030 vinfos[4].indices[1] = _ij4[1];
30031 vinfos[4].maxsolutions = _nj4;
30032 vinfos[5].jointtype = 1;
30033 vinfos[5].foffset = j5;
30034 vinfos[5].indices[0] = _ij5[0];
30035 vinfos[5].indices[1] = _ij5[1];
30036 vinfos[5].maxsolutions = _nj5;
30037 vinfos[6].jointtype = 1;
30038 vinfos[6].foffset = j6;
30039 vinfos[6].indices[0] = _ij6[0];
30040 vinfos[6].indices[1] = _ij6[1];
30041 vinfos[6].maxsolutions = _nj6;
30042 std::vector<int> vfree(0);
30043 solutions.AddSolution(vinfos,vfree);
30044 }
30045 }
30046 }
30047 
30048 }
30049 
30050 }
30051 
30052 } else
30053 {
30054 {
30055 IkReal j3array[1], cj3array[1], sj3array[1];
30056 bool j3valid[1]={false};
30057 _nj3 = 1;
30058 IkReal x9334=((r20)*(sj6));
30059 IkReal x9335=((cj4)*(cj5));
30060 IkReal x9336=((cj6)*(r21));
30061 if( IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x9334)*(x9335)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x9335)*(x9336))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((sj5)*(x9336)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9334))))))) < IKFAST_ATAN2_MAGTHRESH )
30062     continue;
30063 j3array[0]=IKatan2(((gconst17)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x9334)*(x9335)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x9335)*(x9336)))))), ((gconst17)*(((((sj5)*(x9336)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9334)))))));
30064 sj3array[0]=IKsin(j3array[0]);
30065 cj3array[0]=IKcos(j3array[0]);
30066 if( j3array[0] > IKPI )
30067 {
30068     j3array[0]-=IK2PI;
30069 }
30070 else if( j3array[0] < -IKPI )
30071 {    j3array[0]+=IK2PI;
30072 }
30073 j3valid[0] = true;
30074 for(int ij3 = 0; ij3 < 1; ++ij3)
30075 {
30076 if( !j3valid[ij3] )
30077 {
30078     continue;
30079 }
30080 _ij3[0] = ij3; _ij3[1] = -1;
30081 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30082 {
30083 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30084 {
30085     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30086 }
30087 }
30088 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30089 {
30090 IkReal evalcond[6];
30091 IkReal x9337=IKsin(j3);
30092 IkReal x9338=IKcos(j3);
30093 IkReal x9339=((sj0)*(sj5));
30094 IkReal x9340=((r00)*(sj6));
30095 IkReal x9341=((cj6)*(r01));
30096 IkReal x9342=((cj4)*(cj5));
30097 IkReal x9343=((IkReal(1.00000000000000))*(cj0));
30098 IkReal x9344=((cj5)*(r12));
30099 IkReal x9345=((IkReal(1.00000000000000))*(sj0));
30100 IkReal x9346=((cj6)*(r11));
30101 IkReal x9347=((cj5)*(r02));
30102 IkReal x9348=((IkReal(1.00000000000000))*(cj1));
30103 IkReal x9349=((cj6)*(sj4));
30104 IkReal x9350=((cj6)*(r21));
30105 IkReal x9351=((r20)*(sj6));
30106 IkReal x9352=((r10)*(sj6));
30107 IkReal x9353=((sj4)*(sj6));
30108 IkReal x9354=((cj4)*(r02));
30109 IkReal x9355=((IkReal(1.00000000000000))*(cj4)*(r12));
30110 IkReal x9356=((IkReal(1.00000000000000))*(x9337));
30111 IkReal x9357=((cj0)*(x9353));
30112 evalcond[0]=((((sj5)*(x9350)))+(((sj5)*(x9351)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x9338))));
30113 evalcond[1]=((((x9342)*(x9350)))+(((r20)*(x9349)))+(((cj4)*(r22)*(sj5)))+(((x9342)*(x9351)))+(((IkReal(-1.00000000000000))*(sj1)*(x9356)))+(((IkReal(-1.00000000000000))*(r21)*(x9353))));
30114 evalcond[2]=((((x9339)*(x9341)))+(((IkReal(-1.00000000000000))*(x9345)*(x9347)))+(((IkReal(-1.00000000000000))*(sj5)*(x9343)*(x9352)))+(((IkReal(-1.00000000000000))*(sj5)*(x9343)*(x9346)))+(((IkReal(-1.00000000000000))*(x9356)))+(((cj0)*(x9344)))+(((x9339)*(x9340))));
30115 evalcond[3]=((((IkReal(-1.00000000000000))*(x9339)*(x9352)))+(((sj0)*(x9344)))+(((IkReal(-1.00000000000000))*(x9339)*(x9346)))+(((IkReal(-1.00000000000000))*(sj5)*(x9340)*(x9343)))+(((cj0)*(x9347)))+(((IkReal(-1.00000000000000))*(sj5)*(x9341)*(x9343)))+(((IkReal(-1.00000000000000))*(x9338)*(x9348))));
30116 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9343)))+(x9338)+(((IkReal(-1.00000000000000))*(x9342)*(x9343)*(x9346)))+(((sj0)*(x9341)*(x9342)))+(((IkReal(-1.00000000000000))*(r01)*(x9345)*(x9353)))+(((r00)*(sj0)*(x9349)))+(((IkReal(-1.00000000000000))*(x9342)*(x9343)*(x9352)))+(((sj0)*(x9340)*(x9342)))+(((x9339)*(x9354)))+(((r11)*(x9357)))+(((IkReal(-1.00000000000000))*(r10)*(x9343)*(x9349))));
30117 evalcond[5]=((((IkReal(-1.00000000000000))*(x9342)*(x9345)*(x9352)))+(((IkReal(-1.00000000000000))*(x9341)*(x9342)*(x9343)))+(((IkReal(-1.00000000000000))*(r00)*(x9343)*(x9349)))+(((IkReal(-1.00000000000000))*(x9342)*(x9345)*(x9346)))+(((IkReal(-1.00000000000000))*(x9337)*(x9348)))+(((r11)*(sj0)*(x9353)))+(((r01)*(x9357)))+(((IkReal(-1.00000000000000))*(r10)*(x9345)*(x9349)))+(((IkReal(-1.00000000000000))*(x9339)*(x9355)))+(((IkReal(-1.00000000000000))*(x9340)*(x9342)*(x9343)))+(((IkReal(-1.00000000000000))*(sj5)*(x9343)*(x9354))));
30118 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
30119 {
30120 continue;
30121 }
30122 }
30123 
30124 {
30125 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30126 vinfos[0].jointtype = 1;
30127 vinfos[0].foffset = j0;
30128 vinfos[0].indices[0] = _ij0[0];
30129 vinfos[0].indices[1] = _ij0[1];
30130 vinfos[0].maxsolutions = _nj0;
30131 vinfos[1].jointtype = 1;
30132 vinfos[1].foffset = j1;
30133 vinfos[1].indices[0] = _ij1[0];
30134 vinfos[1].indices[1] = _ij1[1];
30135 vinfos[1].maxsolutions = _nj1;
30136 vinfos[2].jointtype = 1;
30137 vinfos[2].foffset = j2;
30138 vinfos[2].indices[0] = _ij2[0];
30139 vinfos[2].indices[1] = _ij2[1];
30140 vinfos[2].maxsolutions = _nj2;
30141 vinfos[3].jointtype = 1;
30142 vinfos[3].foffset = j3;
30143 vinfos[3].indices[0] = _ij3[0];
30144 vinfos[3].indices[1] = _ij3[1];
30145 vinfos[3].maxsolutions = _nj3;
30146 vinfos[4].jointtype = 1;
30147 vinfos[4].foffset = j4;
30148 vinfos[4].indices[0] = _ij4[0];
30149 vinfos[4].indices[1] = _ij4[1];
30150 vinfos[4].maxsolutions = _nj4;
30151 vinfos[5].jointtype = 1;
30152 vinfos[5].foffset = j5;
30153 vinfos[5].indices[0] = _ij5[0];
30154 vinfos[5].indices[1] = _ij5[1];
30155 vinfos[5].maxsolutions = _nj5;
30156 vinfos[6].jointtype = 1;
30157 vinfos[6].foffset = j6;
30158 vinfos[6].indices[0] = _ij6[0];
30159 vinfos[6].indices[1] = _ij6[1];
30160 vinfos[6].maxsolutions = _nj6;
30161 std::vector<int> vfree(0);
30162 solutions.AddSolution(vinfos,vfree);
30163 }
30164 }
30165 }
30166 
30167 }
30168 
30169 }
30170 }
30171 }
30172 
30173 }
30174 
30175 }
30176 
30177 } else
30178 {
30179 {
30180 IkReal j4array[1], cj4array[1], sj4array[1];
30181 bool j4valid[1]={false};
30182 _nj4 = 1;
30183 IkReal x9358=((cj1)*(sj6));
30184 IkReal x9359=((r01)*(sj0));
30185 IkReal x9360=((cj0)*(r11));
30186 IkReal x9361=((cj1)*(cj6));
30187 IkReal x9362=((cj0)*(r10));
30188 IkReal x9363=((IkReal(1.00000000000000))*(sj0));
30189 IkReal x9364=((cj1)*(sj5));
30190 if( IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(r00)*(x9361)*(x9363)))+(((x9361)*(x9362)))+(((x9358)*(x9359)))+(((IkReal(-1.00000000000000))*(x9358)*(x9360))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(cj5)*(x9359)*(x9361)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9358)*(x9363)))+(((cj5)*(x9358)*(x9362)))+(((cj5)*(x9360)*(x9361)))+(((cj0)*(r12)*(x9364)))+(((IkReal(-1.00000000000000))*(r02)*(x9363)*(x9364))))))) < IKFAST_ATAN2_MAGTHRESH )
30191     continue;
30192 j4array[0]=IKatan2(((gconst13)*(((((IkReal(-1.00000000000000))*(r00)*(x9361)*(x9363)))+(((x9361)*(x9362)))+(((x9358)*(x9359)))+(((IkReal(-1.00000000000000))*(x9358)*(x9360)))))), ((gconst13)*(((((IkReal(-1.00000000000000))*(cj5)*(x9359)*(x9361)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9358)*(x9363)))+(((cj5)*(x9358)*(x9362)))+(((cj5)*(x9360)*(x9361)))+(((cj0)*(r12)*(x9364)))+(((IkReal(-1.00000000000000))*(r02)*(x9363)*(x9364)))))));
30193 sj4array[0]=IKsin(j4array[0]);
30194 cj4array[0]=IKcos(j4array[0]);
30195 if( j4array[0] > IKPI )
30196 {
30197     j4array[0]-=IK2PI;
30198 }
30199 else if( j4array[0] < -IKPI )
30200 {    j4array[0]+=IK2PI;
30201 }
30202 j4valid[0] = true;
30203 for(int ij4 = 0; ij4 < 1; ++ij4)
30204 {
30205 if( !j4valid[ij4] )
30206 {
30207     continue;
30208 }
30209 _ij4[0] = ij4; _ij4[1] = -1;
30210 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
30211 {
30212 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
30213 {
30214     j4valid[iij4]=false; _ij4[1] = iij4; break; 
30215 }
30216 }
30217 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
30218 {
30219 IkReal evalcond[3];
30220 IkReal x9365=IKsin(j4);
30221 IkReal x9366=IKcos(j4);
30222 IkReal x9367=((r00)*(sj6));
30223 IkReal x9368=((cj6)*(r01));
30224 IkReal x9369=((IkReal(1.00000000000000))*(cj0));
30225 IkReal x9370=((IkReal(1.00000000000000))*(sj0));
30226 IkReal x9371=((r10)*(sj6));
30227 IkReal x9372=((sj5)*(x9365));
30228 IkReal x9373=((IkReal(1.00000000000000))*(cj6)*(r11));
30229 IkReal x9374=((cj5)*(x9365));
30230 IkReal x9375=((cj6)*(x9366));
30231 IkReal x9376=((sj0)*(x9374));
30232 IkReal x9377=((r01)*(sj6)*(x9366));
30233 IkReal x9378=((r11)*(sj6)*(x9366));
30234 evalcond[0]=((((r20)*(sj6)*(x9374)))+(((IkReal(-1.00000000000000))*(r20)*(x9375)))+(((IkReal(-1.00000000000000))*(cj1)))+(((cj6)*(r21)*(x9374)))+(((r21)*(sj6)*(x9366)))+(((r22)*(x9372))));
30235 evalcond[1]=((((IkReal(-1.00000000000000))*(x9369)*(x9371)*(x9374)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x9369)*(x9374)))+(((IkReal(-1.00000000000000))*(x9369)*(x9378)))+(((x9367)*(x9376)))+(((cj0)*(r10)*(x9375)))+(((IkReal(-1.00000000000000))*(r00)*(x9370)*(x9375)))+(((r02)*(sj0)*(x9372)))+(((sj0)*(x9377)))+(((IkReal(-1.00000000000000))*(r12)*(x9369)*(x9372)))+(((x9368)*(x9376))));
30236 evalcond[2]=((((r10)*(sj0)*(x9375)))+(sj1)+(((IkReal(-1.00000000000000))*(x9369)*(x9377)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x9370)*(x9374)))+(((IkReal(-1.00000000000000))*(x9370)*(x9371)*(x9374)))+(((IkReal(-1.00000000000000))*(r12)*(x9370)*(x9372)))+(((IkReal(-1.00000000000000))*(r02)*(x9369)*(x9372)))+(((IkReal(-1.00000000000000))*(x9367)*(x9369)*(x9374)))+(((cj0)*(r00)*(x9375)))+(((IkReal(-1.00000000000000))*(x9368)*(x9369)*(x9374)))+(((IkReal(-1.00000000000000))*(x9370)*(x9378))));
30237 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
30238 {
30239 continue;
30240 }
30241 }
30242 
30243 {
30244 IkReal dummyeval[1];
30245 IkReal gconst17;
30246 gconst17=IKsign(sj1);
30247 dummyeval[0]=sj1;
30248 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
30249 {
30250 {
30251 IkReal dummyeval[1];
30252 dummyeval[0]=sj1;
30253 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
30254 {
30255 {
30256 IkReal dummyeval[1];
30257 dummyeval[0]=cj1;
30258 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
30259 {
30260 {
30261 IkReal evalcond[9];
30262 IkReal x9379=((IkReal(1.00000000000000))*(cj0));
30263 IkReal x9380=((cj4)*(sj6));
30264 IkReal x9381=((sj0)*(sj6));
30265 IkReal x9382=((cj5)*(sj4));
30266 IkReal x9383=((IkReal(0.374290000000000))*(sj5));
30267 IkReal x9384=((sj4)*(sj5));
30268 IkReal x9385=((cj0)*(cj6));
30269 IkReal x9386=((IkReal(0.0100000000000000))*(cj5));
30270 IkReal x9387=((cj4)*(sj5));
30271 IkReal x9388=((cj5)*(sj0));
30272 IkReal x9389=((IkReal(0.374290000000000))*(r02));
30273 IkReal x9390=((r20)*(sj6));
30274 IkReal x9391=((cj6)*(r21));
30275 IkReal x9392=((IkReal(1.00000000000000))*(sj0));
30276 IkReal x9393=((cj0)*(sj6));
30277 IkReal x9394=((cj4)*(cj6));
30278 IkReal x9395=((IkReal(0.374290000000000))*(r12));
30279 IkReal x9396=((cj0)*(cj5));
30280 IkReal x9397=((cj6)*(sj5));
30281 IkReal x9398=((cj6)*(r01));
30282 IkReal x9399=((r00)*(sj6));
30283 IkReal x9400=((IkReal(0.0100000000000000))*(sj5));
30284 IkReal x9401=((cj6)*(r11));
30285 IkReal x9402=((IkReal(1.00000000000000))*(r10));
30286 IkReal x9403=((r02)*(sj0));
30287 IkReal x9404=((cj6)*(sj4));
30288 IkReal x9405=((r12)*(x9392));
30289 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
30290 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x9394)))+(((x9382)*(x9390)))+(((r22)*(x9384)))+(((x9382)*(x9391)))+(((r21)*(x9380))));
30291 evalcond[2]=((IkReal(0.364420000000000))+(((x9383)*(x9391)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x9400)))+(((IkReal(-1.00000000000000))*(x9386)*(x9391)))+(pz)+(((x9383)*(x9390)))+(((IkReal(-1.00000000000000))*(x9386)*(x9390))));
30292 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x9392)*(x9397)))+(((IkReal(-1.00000000000000))*(sj5)*(x9381)*(x9402)))+(((IkReal(-1.00000000000000))*(sj5)*(x9379)*(x9399)))+(((r12)*(x9388)))+(((IkReal(-1.00000000000000))*(r01)*(x9379)*(x9397)))+(((r02)*(x9396))));
30293 evalcond[4]=((((r01)*(sj0)*(x9380)))+(((x9384)*(x9403)))+(((cj4)*(r10)*(x9385)))+(((r00)*(x9381)*(x9382)))+(((IkReal(-1.00000000000000))*(x9379)*(x9382)*(x9401)))+(((sj0)*(x9382)*(x9398)))+(((IkReal(-1.00000000000000))*(r00)*(x9392)*(x9394)))+(((IkReal(-1.00000000000000))*(r11)*(x9379)*(x9380)))+(((IkReal(-1.00000000000000))*(r12)*(x9379)*(x9384)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x9379)*(x9382))));
30294 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x9379)*(x9382)*(x9399)))+(((IkReal(-1.00000000000000))*(x9381)*(x9382)*(x9402)))+(((IkReal(-1.00000000000000))*(r11)*(x9380)*(x9392)))+(((r10)*(sj0)*(x9394)))+(((IkReal(-1.00000000000000))*(r02)*(x9379)*(x9384)))+(((cj4)*(r00)*(x9385)))+(((IkReal(-1.00000000000000))*(x9382)*(x9392)*(x9401)))+(((IkReal(-1.00000000000000))*(x9384)*(x9405)))+(((IkReal(-1.00000000000000))*(r01)*(x9379)*(x9380)))+(((IkReal(-1.00000000000000))*(x9379)*(x9382)*(x9398))));
30295 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x9386)*(x9398)))+(((IkReal(-1.00000000000000))*(r10)*(x9383)*(x9393)))+(((IkReal(-1.00000000000000))*(r11)*(x9383)*(x9385)))+(((cj0)*(r12)*(x9400)))+(((sj0)*(x9383)*(x9398)))+(((r10)*(x9386)*(x9393)))+(((r00)*(x9381)*(x9383)))+(((IkReal(-1.00000000000000))*(x9400)*(x9403)))+(((IkReal(-1.00000000000000))*(py)*(x9379)))+(((IkReal(-1.00000000000000))*(r00)*(x9381)*(x9386)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x9388)*(x9389)))+(((x9395)*(x9396)))+(((r11)*(x9385)*(x9386))));
30296 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x9379)*(x9404)))+(((IkReal(-1.00000000000000))*(r10)*(x9392)*(x9404)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x9379)*(x9394)))+(((IkReal(-1.00000000000000))*(x9387)*(x9405)))+(((IkReal(-1.00000000000000))*(r02)*(x9379)*(x9387)))+(((r01)*(sj4)*(x9393)))+(((IkReal(-1.00000000000000))*(r11)*(x9388)*(x9394)))+(((IkReal(-1.00000000000000))*(x9380)*(x9388)*(x9402)))+(((r11)*(sj4)*(x9381)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9379)*(x9380))));
30297 evalcond[8]=((IkReal(0.0690000000000000))+(((x9389)*(x9396)))+(((IkReal(-1.00000000000000))*(r00)*(x9383)*(x9393)))+(((r12)*(sj0)*(x9400)))+(((IkReal(-1.00000000000000))*(r10)*(x9381)*(x9383)))+(((r10)*(x9381)*(x9386)))+(((IkReal(-1.00000000000000))*(r01)*(x9383)*(x9385)))+(((IkReal(-1.00000000000000))*(sj0)*(x9383)*(x9401)))+(((r00)*(x9386)*(x9393)))+(((sj0)*(x9386)*(x9401)))+(((r01)*(x9385)*(x9386)))+(((IkReal(-1.00000000000000))*(px)*(x9379)))+(((x9388)*(x9395)))+(((cj0)*(r02)*(x9400)))+(((IkReal(-1.00000000000000))*(py)*(x9392))));
30298 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
30299 {
30300 {
30301 IkReal j3array[1], cj3array[1], sj3array[1];
30302 bool j3valid[1]={false};
30303 _nj3 = 1;
30304 IkReal x9406=((r20)*(sj6));
30305 IkReal x9407=((cj4)*(cj5));
30306 IkReal x9408=((cj6)*(r21));
30307 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x9406)*(x9407)))+(((cj4)*(r22)*(sj5)))+(((x9407)*(x9408))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9406)))+(((sj5)*(x9408))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x9406)*(x9407)))+(((cj4)*(r22)*(sj5)))+(((x9407)*(x9408)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9406)))+(((sj5)*(x9408)))))-1) <= IKFAST_SINCOS_THRESH )
30308     continue;
30309 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((x9406)*(x9407)))+(((cj4)*(r22)*(sj5)))+(((x9407)*(x9408)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9406)))+(((sj5)*(x9408)))));
30310 sj3array[0]=IKsin(j3array[0]);
30311 cj3array[0]=IKcos(j3array[0]);
30312 if( j3array[0] > IKPI )
30313 {
30314     j3array[0]-=IK2PI;
30315 }
30316 else if( j3array[0] < -IKPI )
30317 {    j3array[0]+=IK2PI;
30318 }
30319 j3valid[0] = true;
30320 for(int ij3 = 0; ij3 < 1; ++ij3)
30321 {
30322 if( !j3valid[ij3] )
30323 {
30324     continue;
30325 }
30326 _ij3[0] = ij3; _ij3[1] = -1;
30327 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30328 {
30329 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30330 {
30331     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30332 }
30333 }
30334 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30335 {
30336 IkReal evalcond[4];
30337 IkReal x9409=IKcos(j3);
30338 IkReal x9410=((sj0)*(sj5));
30339 IkReal x9411=((r00)*(sj6));
30340 IkReal x9412=((cj6)*(r01));
30341 IkReal x9413=((cj5)*(sj0));
30342 IkReal x9414=((cj0)*(cj5));
30343 IkReal x9415=((cj6)*(sj4));
30344 IkReal x9416=((sj4)*(sj6));
30345 IkReal x9417=((cj0)*(r11));
30346 IkReal x9418=((cj4)*(cj6));
30347 IkReal x9419=((cj4)*(sj6));
30348 IkReal x9420=((IkReal(1.00000000000000))*(cj0));
30349 IkReal x9421=((cj4)*(sj5));
30350 IkReal x9422=((sj5)*(sj6));
30351 IkReal x9423=((cj6)*(sj5));
30352 IkReal x9424=((IkReal(1.00000000000000))*(IKsin(j3)));
30353 evalcond[0]=((((r20)*(x9422)))+(((r21)*(x9423)))+(((IkReal(-1.00000000000000))*(x9409)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
30354 evalcond[1]=((((cj5)*(r20)*(x9419)))+(((r22)*(x9421)))+(((IkReal(-1.00000000000000))*(r21)*(x9416)))+(((IkReal(-1.00000000000000))*(x9424)))+(((cj5)*(r21)*(x9418)))+(((r20)*(x9415))));
30355 evalcond[2]=((((r12)*(x9414)))+(((x9410)*(x9411)))+(((IkReal(-1.00000000000000))*(x9417)*(x9423)))+(((IkReal(-1.00000000000000))*(r10)*(x9420)*(x9422)))+(((IkReal(-1.00000000000000))*(x9424)))+(((x9410)*(x9412)))+(((IkReal(-1.00000000000000))*(r02)*(x9413))));
30356 evalcond[3]=((x9409)+(((cj4)*(x9412)*(x9413)))+(((IkReal(-1.00000000000000))*(r11)*(x9414)*(x9418)))+(((cj4)*(r02)*(x9410)))+(((x9416)*(x9417)))+(((IkReal(-1.00000000000000))*(r10)*(x9415)*(x9420)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x9416)))+(((cj4)*(x9411)*(x9413)))+(((r00)*(sj0)*(x9415)))+(((IkReal(-1.00000000000000))*(r12)*(x9420)*(x9421)))+(((IkReal(-1.00000000000000))*(r10)*(x9414)*(x9419))));
30357 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
30358 {
30359 continue;
30360 }
30361 }
30362 
30363 {
30364 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30365 vinfos[0].jointtype = 1;
30366 vinfos[0].foffset = j0;
30367 vinfos[0].indices[0] = _ij0[0];
30368 vinfos[0].indices[1] = _ij0[1];
30369 vinfos[0].maxsolutions = _nj0;
30370 vinfos[1].jointtype = 1;
30371 vinfos[1].foffset = j1;
30372 vinfos[1].indices[0] = _ij1[0];
30373 vinfos[1].indices[1] = _ij1[1];
30374 vinfos[1].maxsolutions = _nj1;
30375 vinfos[2].jointtype = 1;
30376 vinfos[2].foffset = j2;
30377 vinfos[2].indices[0] = _ij2[0];
30378 vinfos[2].indices[1] = _ij2[1];
30379 vinfos[2].maxsolutions = _nj2;
30380 vinfos[3].jointtype = 1;
30381 vinfos[3].foffset = j3;
30382 vinfos[3].indices[0] = _ij3[0];
30383 vinfos[3].indices[1] = _ij3[1];
30384 vinfos[3].maxsolutions = _nj3;
30385 vinfos[4].jointtype = 1;
30386 vinfos[4].foffset = j4;
30387 vinfos[4].indices[0] = _ij4[0];
30388 vinfos[4].indices[1] = _ij4[1];
30389 vinfos[4].maxsolutions = _nj4;
30390 vinfos[5].jointtype = 1;
30391 vinfos[5].foffset = j5;
30392 vinfos[5].indices[0] = _ij5[0];
30393 vinfos[5].indices[1] = _ij5[1];
30394 vinfos[5].maxsolutions = _nj5;
30395 vinfos[6].jointtype = 1;
30396 vinfos[6].foffset = j6;
30397 vinfos[6].indices[0] = _ij6[0];
30398 vinfos[6].indices[1] = _ij6[1];
30399 vinfos[6].maxsolutions = _nj6;
30400 std::vector<int> vfree(0);
30401 solutions.AddSolution(vinfos,vfree);
30402 }
30403 }
30404 }
30405 
30406 } else
30407 {
30408 IkReal x9425=((IkReal(1.00000000000000))*(cj0));
30409 IkReal x9426=((cj4)*(sj6));
30410 IkReal x9427=((sj0)*(sj6));
30411 IkReal x9428=((cj5)*(sj4));
30412 IkReal x9429=((IkReal(0.374290000000000))*(sj5));
30413 IkReal x9430=((sj4)*(sj5));
30414 IkReal x9431=((cj0)*(cj6));
30415 IkReal x9432=((IkReal(0.0100000000000000))*(cj5));
30416 IkReal x9433=((cj4)*(sj5));
30417 IkReal x9434=((cj5)*(sj0));
30418 IkReal x9435=((IkReal(0.374290000000000))*(r02));
30419 IkReal x9436=((r20)*(sj6));
30420 IkReal x9437=((cj6)*(r21));
30421 IkReal x9438=((IkReal(1.00000000000000))*(sj0));
30422 IkReal x9439=((cj0)*(sj6));
30423 IkReal x9440=((cj4)*(cj6));
30424 IkReal x9441=((IkReal(0.374290000000000))*(r12));
30425 IkReal x9442=((cj0)*(cj5));
30426 IkReal x9443=((cj6)*(sj5));
30427 IkReal x9444=((cj6)*(r01));
30428 IkReal x9445=((r00)*(sj6));
30429 IkReal x9446=((IkReal(0.0100000000000000))*(sj5));
30430 IkReal x9447=((cj6)*(r11));
30431 IkReal x9448=((IkReal(1.00000000000000))*(r10));
30432 IkReal x9449=((r02)*(sj0));
30433 IkReal x9450=((cj6)*(sj4));
30434 IkReal x9451=((r12)*(x9438));
30435 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
30436 evalcond[1]=((((x9428)*(x9437)))+(((IkReal(-1.00000000000000))*(r20)*(x9440)))+(((x9428)*(x9436)))+(((r21)*(x9426)))+(((r22)*(x9430))));
30437 evalcond[2]=((IkReal(-0.364420000000000))+(((x9429)*(x9437)))+(((IkReal(-1.00000000000000))*(r22)*(x9446)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x9432)*(x9437)))+(pz)+(((IkReal(-1.00000000000000))*(x9432)*(x9436)))+(((x9429)*(x9436))));
30438 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x9438)*(x9443)))+(((r12)*(x9434)))+(((IkReal(-1.00000000000000))*(r01)*(x9425)*(x9443)))+(((r02)*(x9442)))+(((IkReal(-1.00000000000000))*(sj5)*(x9427)*(x9448)))+(((IkReal(-1.00000000000000))*(sj5)*(x9425)*(x9445))));
30439 evalcond[4]=((((IkReal(-1.00000000000000))*(x9425)*(x9428)*(x9447)))+(((r00)*(x9427)*(x9428)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x9425)*(x9428)))+(((x9430)*(x9449)))+(((IkReal(-1.00000000000000))*(r12)*(x9425)*(x9430)))+(((sj0)*(x9428)*(x9444)))+(((IkReal(-1.00000000000000))*(r11)*(x9425)*(x9426)))+(((IkReal(-1.00000000000000))*(r00)*(x9438)*(x9440)))+(((r01)*(sj0)*(x9426)))+(((cj4)*(r10)*(x9431))));
30440 evalcond[5]=((IkReal(-1.00000000000000))+(((cj4)*(r00)*(x9431)))+(((IkReal(-1.00000000000000))*(r11)*(x9426)*(x9438)))+(((IkReal(-1.00000000000000))*(x9425)*(x9428)*(x9445)))+(((IkReal(-1.00000000000000))*(x9427)*(x9428)*(x9448)))+(((IkReal(-1.00000000000000))*(r01)*(x9425)*(x9426)))+(((r10)*(sj0)*(x9440)))+(((IkReal(-1.00000000000000))*(x9428)*(x9438)*(x9447)))+(((IkReal(-1.00000000000000))*(r02)*(x9425)*(x9430)))+(((IkReal(-1.00000000000000))*(x9430)*(x9451)))+(((IkReal(-1.00000000000000))*(x9425)*(x9428)*(x9444))));
30441 evalcond[6]=((IkReal(0.0690000000000000))+(((cj0)*(r12)*(x9446)))+(((IkReal(-1.00000000000000))*(r00)*(x9427)*(x9432)))+(((r10)*(x9432)*(x9439)))+(((x9441)*(x9442)))+(((IkReal(-1.00000000000000))*(sj0)*(x9432)*(x9444)))+(((IkReal(-1.00000000000000))*(r10)*(x9429)*(x9439)))+(((IkReal(-1.00000000000000))*(x9434)*(x9435)))+(((r00)*(x9427)*(x9429)))+(((IkReal(-1.00000000000000))*(r11)*(x9429)*(x9431)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x9446)*(x9449)))+(((sj0)*(x9429)*(x9444)))+(((IkReal(-1.00000000000000))*(py)*(x9425)))+(((r11)*(x9431)*(x9432))));
30442 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x9434)*(x9440)))+(((IkReal(-1.00000000000000))*(r00)*(x9425)*(x9450)))+(((r11)*(sj4)*(x9427)))+(((IkReal(-1.00000000000000))*(x9426)*(x9434)*(x9448)))+(((IkReal(-1.00000000000000))*(r10)*(x9438)*(x9450)))+(((IkReal(-1.00000000000000))*(x9433)*(x9451)))+(((IkReal(-1.00000000000000))*(r02)*(x9425)*(x9433)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x9425)*(x9426)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x9425)*(x9440)))+(((r01)*(sj4)*(x9439))));
30443 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x9429)*(x9439)))+(((r00)*(x9432)*(x9439)))+(((r12)*(sj0)*(x9446)))+(((IkReal(-1.00000000000000))*(r01)*(x9429)*(x9431)))+(((IkReal(-1.00000000000000))*(r10)*(x9427)*(x9429)))+(((x9435)*(x9442)))+(((cj0)*(r02)*(x9446)))+(((r10)*(x9427)*(x9432)))+(((IkReal(-1.00000000000000))*(px)*(x9425)))+(((r01)*(x9431)*(x9432)))+(((x9434)*(x9441)))+(((IkReal(-1.00000000000000))*(sj0)*(x9429)*(x9447)))+(((IkReal(-1.00000000000000))*(py)*(x9438)))+(((sj0)*(x9432)*(x9447))));
30444 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
30445 {
30446 {
30447 IkReal j3array[1], cj3array[1], sj3array[1];
30448 bool j3valid[1]={false};
30449 _nj3 = 1;
30450 IkReal x9452=((IkReal(1.00000000000000))*(sj5));
30451 IkReal x9453=((cj6)*(r21));
30452 IkReal x9454=((r20)*(sj6));
30453 IkReal x9455=((IkReal(1.00000000000000))*(cj4)*(cj5));
30454 if( IKabs(((((IkReal(-1.00000000000000))*(x9454)*(x9455)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9452)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x9453)*(x9455)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x9452)*(x9453)))+(((IkReal(-1.00000000000000))*(x9452)*(x9454)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x9454)*(x9455)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9452)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x9453)*(x9455)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x9452)*(x9453)))+(((IkReal(-1.00000000000000))*(x9452)*(x9454)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
30455     continue;
30456 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x9454)*(x9455)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x9452)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x9453)*(x9455)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x9452)*(x9453)))+(((IkReal(-1.00000000000000))*(x9452)*(x9454)))+(((cj5)*(r22)))));
30457 sj3array[0]=IKsin(j3array[0]);
30458 cj3array[0]=IKcos(j3array[0]);
30459 if( j3array[0] > IKPI )
30460 {
30461     j3array[0]-=IK2PI;
30462 }
30463 else if( j3array[0] < -IKPI )
30464 {    j3array[0]+=IK2PI;
30465 }
30466 j3valid[0] = true;
30467 for(int ij3 = 0; ij3 < 1; ++ij3)
30468 {
30469 if( !j3valid[ij3] )
30470 {
30471     continue;
30472 }
30473 _ij3[0] = ij3; _ij3[1] = -1;
30474 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30475 {
30476 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30477 {
30478     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30479 }
30480 }
30481 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30482 {
30483 IkReal evalcond[4];
30484 IkReal x9456=IKsin(j3);
30485 IkReal x9457=IKcos(j3);
30486 IkReal x9458=((sj0)*(sj5));
30487 IkReal x9459=((r00)*(sj6));
30488 IkReal x9460=((cj6)*(r01));
30489 IkReal x9461=((cj5)*(sj0));
30490 IkReal x9462=((cj0)*(cj5));
30491 IkReal x9463=((cj6)*(sj4));
30492 IkReal x9464=((sj4)*(sj6));
30493 IkReal x9465=((cj0)*(r11));
30494 IkReal x9466=((cj4)*(cj6));
30495 IkReal x9467=((cj4)*(sj6));
30496 IkReal x9468=((IkReal(1.00000000000000))*(cj0));
30497 IkReal x9469=((cj4)*(sj5));
30498 IkReal x9470=((sj5)*(sj6));
30499 IkReal x9471=((cj6)*(sj5));
30500 evalcond[0]=((((r20)*(x9470)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r21)*(x9471)))+(x9457));
30501 evalcond[1]=((((r22)*(x9469)))+(((cj5)*(r21)*(x9466)))+(x9456)+(((cj5)*(r20)*(x9467)))+(((r20)*(x9463)))+(((IkReal(-1.00000000000000))*(r21)*(x9464))));
30502 evalcond[2]=((((x9458)*(x9459)))+(((x9458)*(x9460)))+(((IkReal(-1.00000000000000))*(x9465)*(x9471)))+(((r12)*(x9462)))+(((IkReal(-1.00000000000000))*(x9456)))+(((IkReal(-1.00000000000000))*(r10)*(x9468)*(x9470)))+(((IkReal(-1.00000000000000))*(r02)*(x9461))));
30503 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x9462)*(x9466)))+(((cj4)*(r02)*(x9458)))+(((x9464)*(x9465)))+(((cj4)*(x9460)*(x9461)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x9464)))+(((IkReal(-1.00000000000000))*(r10)*(x9463)*(x9468)))+(((IkReal(-1.00000000000000))*(r10)*(x9462)*(x9467)))+(((IkReal(-1.00000000000000))*(r12)*(x9468)*(x9469)))+(((r00)*(sj0)*(x9463)))+(x9457)+(((cj4)*(x9459)*(x9461))));
30504 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
30505 {
30506 continue;
30507 }
30508 }
30509 
30510 {
30511 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30512 vinfos[0].jointtype = 1;
30513 vinfos[0].foffset = j0;
30514 vinfos[0].indices[0] = _ij0[0];
30515 vinfos[0].indices[1] = _ij0[1];
30516 vinfos[0].maxsolutions = _nj0;
30517 vinfos[1].jointtype = 1;
30518 vinfos[1].foffset = j1;
30519 vinfos[1].indices[0] = _ij1[0];
30520 vinfos[1].indices[1] = _ij1[1];
30521 vinfos[1].maxsolutions = _nj1;
30522 vinfos[2].jointtype = 1;
30523 vinfos[2].foffset = j2;
30524 vinfos[2].indices[0] = _ij2[0];
30525 vinfos[2].indices[1] = _ij2[1];
30526 vinfos[2].maxsolutions = _nj2;
30527 vinfos[3].jointtype = 1;
30528 vinfos[3].foffset = j3;
30529 vinfos[3].indices[0] = _ij3[0];
30530 vinfos[3].indices[1] = _ij3[1];
30531 vinfos[3].maxsolutions = _nj3;
30532 vinfos[4].jointtype = 1;
30533 vinfos[4].foffset = j4;
30534 vinfos[4].indices[0] = _ij4[0];
30535 vinfos[4].indices[1] = _ij4[1];
30536 vinfos[4].maxsolutions = _nj4;
30537 vinfos[5].jointtype = 1;
30538 vinfos[5].foffset = j5;
30539 vinfos[5].indices[0] = _ij5[0];
30540 vinfos[5].indices[1] = _ij5[1];
30541 vinfos[5].maxsolutions = _nj5;
30542 vinfos[6].jointtype = 1;
30543 vinfos[6].foffset = j6;
30544 vinfos[6].indices[0] = _ij6[0];
30545 vinfos[6].indices[1] = _ij6[1];
30546 vinfos[6].maxsolutions = _nj6;
30547 std::vector<int> vfree(0);
30548 solutions.AddSolution(vinfos,vfree);
30549 }
30550 }
30551 }
30552 
30553 } else
30554 {
30555 IkReal x9472=((IkReal(1.00000000000000))*(cj0));
30556 IkReal x9473=((cj4)*(sj6));
30557 IkReal x9474=((sj0)*(sj4));
30558 IkReal x9475=((cj5)*(sj6));
30559 IkReal x9476=((sj4)*(sj5));
30560 IkReal x9477=((r12)*(sj5));
30561 IkReal x9478=((IkReal(0.374290000000000))*(cj5));
30562 IkReal x9479=((r02)*(sj0));
30563 IkReal x9480=((r20)*(sj4));
30564 IkReal x9481=((IkReal(1.00000000000000))*(sj0));
30565 IkReal x9482=((IkReal(1.00000000000000))*(cj5));
30566 IkReal x9483=((cj0)*(r10));
30567 IkReal x9484=((cj4)*(cj6));
30568 IkReal x9485=((r00)*(sj0));
30569 IkReal x9486=((cj6)*(r21));
30570 IkReal x9487=((IkReal(0.374290000000000))*(sj5));
30571 IkReal x9488=((cj0)*(r00));
30572 IkReal x9489=((IkReal(0.0100000000000000))*(sj5));
30573 IkReal x9490=((cj0)*(r02));
30574 IkReal x9491=((cj5)*(sj4));
30575 IkReal x9492=((cj6)*(r01));
30576 IkReal x9493=((cj6)*(r11));
30577 IkReal x9494=((r01)*(sj0));
30578 IkReal x9495=((r10)*(sj0));
30579 IkReal x9496=((IkReal(0.0100000000000000))*(cj5)*(cj6));
30580 IkReal x9497=((sj6)*(x9487));
30581 IkReal x9498=((cj0)*(cj6)*(x9487));
30582 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
30583 evalcond[1]=((((sj5)*(x9486)))+(((r20)*(sj5)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(x9482))));
30584 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x9484)))+(((r22)*(x9476)))+(((r21)*(x9473)))+(((x9486)*(x9491)))+(((x9475)*(x9480))));
30585 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x9489)))+(((IkReal(-0.0100000000000000))*(cj5)*(x9486)))+(((r20)*(x9497)))+(((IkReal(-1.00000000000000))*(r22)*(x9478)))+(((x9486)*(x9487)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x9475))));
30586 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x9480)))+(((cj5)*(r20)*(x9473)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x9484))));
30587 evalcond[5]=((((x9483)*(x9484)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x9472)*(x9475)))+(((r02)*(sj5)*(x9474)))+(((IkReal(-1.00000000000000))*(r00)*(x9481)*(x9484)))+(((r00)*(x9474)*(x9475)))+(((IkReal(-1.00000000000000))*(r11)*(x9472)*(x9473)))+(((x9473)*(x9494)))+(((cj5)*(x9474)*(x9492)))+(((IkReal(-1.00000000000000))*(x9472)*(x9491)*(x9493)))+(((IkReal(-1.00000000000000))*(r12)*(x9472)*(x9476))));
30588 evalcond[6]=((((IkReal(-1.00000000000000))*(x9472)*(x9491)*(x9492)))+(((IkReal(-1.00000000000000))*(x9474)*(x9482)*(x9493)))+(((x9484)*(x9495)))+(((IkReal(-1.00000000000000))*(r01)*(x9472)*(x9473)))+(((IkReal(-1.00000000000000))*(r11)*(x9473)*(x9481)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x9472)*(x9475)))+(((IkReal(-1.00000000000000))*(r02)*(x9472)*(x9476)))+(((IkReal(-1.00000000000000))*(r10)*(x9474)*(x9475)))+(((IkReal(-1.00000000000000))*(x9474)*(x9477)))+(((x9484)*(x9488))));
30589 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9493)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x9492)))+(((IkReal(0.0100000000000000))*(x9475)*(x9483)))+(((IkReal(-1.00000000000000))*(x9478)*(x9479)))+(((IkReal(-1.00000000000000))*(cj0)*(x9487)*(x9493)))+(((IkReal(-1.00000000000000))*(py)*(x9472)))+(((IkReal(-1.00000000000000))*(x9479)*(x9489)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(x9475)*(x9485)))+(((IkReal(-1.00000000000000))*(x9483)*(x9497)))+(((x9485)*(x9497)))+(((IkReal(0.0100000000000000))*(cj0)*(x9477)))+(((sj0)*(x9487)*(x9492)))+(((cj0)*(r12)*(x9478))));
30590 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(py)*(x9481)))+(((IkReal(-1.00000000000000))*(sj0)*(x9487)*(x9493)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x9493)))+(((IkReal(-1.00000000000000))*(x9488)*(x9497)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9492)))+(((IkReal(0.0100000000000000))*(sj0)*(x9477)))+(((IkReal(0.0100000000000000))*(x9475)*(x9495)))+(((IkReal(0.0100000000000000))*(x9475)*(x9488)))+(((x9489)*(x9490)))+(((r12)*(sj0)*(x9478)))+(((IkReal(-1.00000000000000))*(x9495)*(x9497)))+(((IkReal(-1.00000000000000))*(px)*(x9472)))+(((x9478)*(x9490)))+(((IkReal(-1.00000000000000))*(cj0)*(x9487)*(x9492))));
30591 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
30592 {
30593 {
30594 IkReal j3array[1], cj3array[1], sj3array[1];
30595 bool j3valid[1]={false};
30596 _nj3 = 1;
30597 IkReal x9499=((cj0)*(cj5));
30598 IkReal x9500=((IkReal(1.00000000000000))*(cj0));
30599 IkReal x9501=((cj6)*(r11));
30600 IkReal x9502=((r10)*(sj6));
30601 IkReal x9503=((cj5)*(sj0));
30602 IkReal x9504=((r00)*(sj5)*(sj6));
30603 IkReal x9505=((cj6)*(r01)*(sj5));
30604 IkReal x9506=((IkReal(1.00000000000000))*(sj0)*(sj5));
30605 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(x9503)))+(((r12)*(x9499)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9501)))+(((sj0)*(x9504)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9502)))+(((sj0)*(x9505))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r02)*(x9499)))+(((r12)*(x9503)))+(((IkReal(-1.00000000000000))*(x9500)*(x9505)))+(((IkReal(-1.00000000000000))*(x9500)*(x9504)))+(((IkReal(-1.00000000000000))*(x9501)*(x9506)))+(((IkReal(-1.00000000000000))*(x9502)*(x9506))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(x9503)))+(((r12)*(x9499)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9501)))+(((sj0)*(x9504)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9502)))+(((sj0)*(x9505)))))+IKsqr(((((r02)*(x9499)))+(((r12)*(x9503)))+(((IkReal(-1.00000000000000))*(x9500)*(x9505)))+(((IkReal(-1.00000000000000))*(x9500)*(x9504)))+(((IkReal(-1.00000000000000))*(x9501)*(x9506)))+(((IkReal(-1.00000000000000))*(x9502)*(x9506)))))-1) <= IKFAST_SINCOS_THRESH )
30606     continue;
30607 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(x9503)))+(((r12)*(x9499)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9501)))+(((sj0)*(x9504)))+(((IkReal(-1.00000000000000))*(sj5)*(x9500)*(x9502)))+(((sj0)*(x9505)))), ((((r02)*(x9499)))+(((r12)*(x9503)))+(((IkReal(-1.00000000000000))*(x9500)*(x9505)))+(((IkReal(-1.00000000000000))*(x9500)*(x9504)))+(((IkReal(-1.00000000000000))*(x9501)*(x9506)))+(((IkReal(-1.00000000000000))*(x9502)*(x9506)))));
30608 sj3array[0]=IKsin(j3array[0]);
30609 cj3array[0]=IKcos(j3array[0]);
30610 if( j3array[0] > IKPI )
30611 {
30612     j3array[0]-=IK2PI;
30613 }
30614 else if( j3array[0] < -IKPI )
30615 {    j3array[0]+=IK2PI;
30616 }
30617 j3valid[0] = true;
30618 for(int ij3 = 0; ij3 < 1; ++ij3)
30619 {
30620 if( !j3valid[ij3] )
30621 {
30622     continue;
30623 }
30624 _ij3[0] = ij3; _ij3[1] = -1;
30625 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30626 {
30627 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30628 {
30629     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30630 }
30631 }
30632 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30633 {
30634 IkReal evalcond[4];
30635 IkReal x9507=IKcos(j3);
30636 IkReal x9508=((sj0)*(sj5));
30637 IkReal x9509=((r00)*(sj6));
30638 IkReal x9510=((cj6)*(sj0));
30639 IkReal x9511=((IkReal(1.00000000000000))*(cj4));
30640 IkReal x9512=((r00)*(sj4));
30641 IkReal x9513=((cj0)*(cj5));
30642 IkReal x9514=((cj5)*(sj0));
30643 IkReal x9515=((cj6)*(r11));
30644 IkReal x9516=((r10)*(sj6));
30645 IkReal x9517=((cj0)*(sj5));
30646 IkReal x9518=((r10)*(sj4));
30647 IkReal x9519=((IkReal(1.00000000000000))*(IKsin(j3)));
30648 IkReal x9520=((cj4)*(cj5)*(r01));
30649 IkReal x9521=((IkReal(1.00000000000000))*(cj0)*(cj6));
30650 IkReal x9522=((cj0)*(sj4)*(sj6));
30651 IkReal x9523=((sj0)*(sj4)*(sj6));
30652 evalcond[0]=((((IkReal(-1.00000000000000))*(x9515)*(x9517)))+(((IkReal(-1.00000000000000))*(x9516)*(x9517)))+(((cj6)*(r01)*(x9508)))+(((IkReal(-1.00000000000000))*(r02)*(x9514)))+(((r12)*(x9513)))+(((x9508)*(x9509)))+(((IkReal(-1.00000000000000))*(x9519))));
30653 evalcond[1]=((((IkReal(-1.00000000000000))*(x9508)*(x9515)))+(((IkReal(-1.00000000000000))*(x9507)))+(((r02)*(x9513)))+(((IkReal(-1.00000000000000))*(x9509)*(x9517)))+(((r12)*(x9514)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9517)))+(((IkReal(-1.00000000000000))*(x9508)*(x9516))));
30654 evalcond[2]=((((IkReal(-1.00000000000000))*(x9511)*(x9513)*(x9515)))+(((cj4)*(r02)*(x9508)))+(((r11)*(x9522)))+(((IkReal(-1.00000000000000))*(x9518)*(x9521)))+(((x9510)*(x9520)))+(((cj4)*(x9509)*(x9514)))+(((IkReal(-1.00000000000000))*(r01)*(x9523)))+(((IkReal(-1.00000000000000))*(r12)*(x9511)*(x9517)))+(((IkReal(-1.00000000000000))*(x9511)*(x9513)*(x9516)))+(x9507)+(((x9510)*(x9512))));
30655 evalcond[3]=((((r01)*(x9522)))+(((IkReal(-1.00000000000000))*(x9510)*(x9518)))+(((IkReal(-1.00000000000000))*(x9509)*(x9511)*(x9513)))+(((IkReal(-1.00000000000000))*(x9512)*(x9521)))+(((IkReal(-1.00000000000000))*(r02)*(x9511)*(x9517)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9511)*(x9513)))+(((r11)*(x9523)))+(((IkReal(-1.00000000000000))*(x9511)*(x9514)*(x9516)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x9510)*(x9511)))+(((IkReal(-1.00000000000000))*(x9519)))+(((IkReal(-1.00000000000000))*(r12)*(x9508)*(x9511))));
30656 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
30657 {
30658 continue;
30659 }
30660 }
30661 
30662 {
30663 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30664 vinfos[0].jointtype = 1;
30665 vinfos[0].foffset = j0;
30666 vinfos[0].indices[0] = _ij0[0];
30667 vinfos[0].indices[1] = _ij0[1];
30668 vinfos[0].maxsolutions = _nj0;
30669 vinfos[1].jointtype = 1;
30670 vinfos[1].foffset = j1;
30671 vinfos[1].indices[0] = _ij1[0];
30672 vinfos[1].indices[1] = _ij1[1];
30673 vinfos[1].maxsolutions = _nj1;
30674 vinfos[2].jointtype = 1;
30675 vinfos[2].foffset = j2;
30676 vinfos[2].indices[0] = _ij2[0];
30677 vinfos[2].indices[1] = _ij2[1];
30678 vinfos[2].maxsolutions = _nj2;
30679 vinfos[3].jointtype = 1;
30680 vinfos[3].foffset = j3;
30681 vinfos[3].indices[0] = _ij3[0];
30682 vinfos[3].indices[1] = _ij3[1];
30683 vinfos[3].maxsolutions = _nj3;
30684 vinfos[4].jointtype = 1;
30685 vinfos[4].foffset = j4;
30686 vinfos[4].indices[0] = _ij4[0];
30687 vinfos[4].indices[1] = _ij4[1];
30688 vinfos[4].maxsolutions = _nj4;
30689 vinfos[5].jointtype = 1;
30690 vinfos[5].foffset = j5;
30691 vinfos[5].indices[0] = _ij5[0];
30692 vinfos[5].indices[1] = _ij5[1];
30693 vinfos[5].maxsolutions = _nj5;
30694 vinfos[6].jointtype = 1;
30695 vinfos[6].foffset = j6;
30696 vinfos[6].indices[0] = _ij6[0];
30697 vinfos[6].indices[1] = _ij6[1];
30698 vinfos[6].maxsolutions = _nj6;
30699 std::vector<int> vfree(0);
30700 solutions.AddSolution(vinfos,vfree);
30701 }
30702 }
30703 }
30704 
30705 } else
30706 {
30707 IkReal x9524=((IkReal(1.00000000000000))*(cj0));
30708 IkReal x9525=((cj4)*(sj6));
30709 IkReal x9526=((sj0)*(sj4));
30710 IkReal x9527=((cj5)*(sj6));
30711 IkReal x9528=((sj4)*(sj5));
30712 IkReal x9529=((r12)*(sj5));
30713 IkReal x9530=((IkReal(0.374290000000000))*(cj5));
30714 IkReal x9531=((r02)*(sj0));
30715 IkReal x9532=((r20)*(sj4));
30716 IkReal x9533=((IkReal(1.00000000000000))*(sj0));
30717 IkReal x9534=((IkReal(1.00000000000000))*(cj5));
30718 IkReal x9535=((cj0)*(r10));
30719 IkReal x9536=((cj4)*(cj6));
30720 IkReal x9537=((r00)*(sj0));
30721 IkReal x9538=((cj6)*(r21));
30722 IkReal x9539=((IkReal(0.374290000000000))*(sj5));
30723 IkReal x9540=((cj0)*(r00));
30724 IkReal x9541=((IkReal(0.0100000000000000))*(sj5));
30725 IkReal x9542=((cj0)*(r02));
30726 IkReal x9543=((cj5)*(sj4));
30727 IkReal x9544=((cj6)*(r01));
30728 IkReal x9545=((cj6)*(r11));
30729 IkReal x9546=((r01)*(sj0));
30730 IkReal x9547=((r10)*(sj0));
30731 IkReal x9548=((IkReal(0.0100000000000000))*(cj5)*(cj6));
30732 IkReal x9549=((sj6)*(x9539));
30733 IkReal x9550=((cj0)*(cj6)*(x9539));
30734 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
30735 evalcond[1]=((((sj5)*(x9538)))+(((IkReal(-1.00000000000000))*(r22)*(x9534)))+(((r20)*(sj5)*(sj6))));
30736 evalcond[2]=((IkReal(1.00000000000000))+(((r22)*(x9528)))+(((r21)*(x9525)))+(((x9527)*(x9532)))+(((x9538)*(x9543)))+(((IkReal(-1.00000000000000))*(r20)*(x9536))));
30737 evalcond[3]=((((r20)*(x9549)))+(((IkReal(-0.0100000000000000))*(cj5)*(x9538)))+(((IkReal(-0.0100000000000000))*(r20)*(x9527)))+(((x9538)*(x9539)))+(((IkReal(-1.00000000000000))*(r22)*(x9541)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x9530))));
30738 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x9536)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x9525)))+(((cj6)*(x9532))));
30739 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x9533)*(x9536)))+(((x9525)*(x9546)))+(((x9535)*(x9536)))+(((IkReal(-1.00000000000000))*(r11)*(x9524)*(x9525)))+(((r00)*(x9526)*(x9527)))+(((cj5)*(x9526)*(x9544)))+(((r02)*(sj5)*(x9526)))+(((IkReal(-1.00000000000000))*(r12)*(x9524)*(x9528)))+(((IkReal(-1.00000000000000))*(x9524)*(x9543)*(x9545)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x9524)*(x9527))));
30740 evalcond[6]=((((IkReal(-1.00000000000000))*(x9526)*(x9534)*(x9545)))+(((IkReal(-1.00000000000000))*(x9524)*(x9543)*(x9544)))+(((IkReal(-1.00000000000000))*(x9526)*(x9529)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x9524)*(x9527)))+(((IkReal(-1.00000000000000))*(r11)*(x9525)*(x9533)))+(((IkReal(-1.00000000000000))*(r01)*(x9524)*(x9525)))+(((x9536)*(x9540)))+(((x9536)*(x9547)))+(((IkReal(-1.00000000000000))*(r10)*(x9526)*(x9527)))+(((IkReal(-1.00000000000000))*(r02)*(x9524)*(x9528))));
30741 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x9535)*(x9549)))+(((sj0)*(x9539)*(x9544)))+(((IkReal(-0.0100000000000000))*(x9527)*(x9537)))+(((x9537)*(x9549)))+(((IkReal(-1.00000000000000))*(cj0)*(x9539)*(x9545)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9545)))+(((IkReal(-1.00000000000000))*(x9531)*(x9541)))+(((IkReal(0.0100000000000000))*(cj0)*(x9529)))+(((IkReal(-1.00000000000000))*(x9530)*(x9531)))+(((IkReal(0.0100000000000000))*(x9527)*(x9535)))+(((cj0)*(r12)*(x9530)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x9544)))+(((IkReal(-1.00000000000000))*(py)*(x9524))));
30742 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x9539)*(x9544)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x9545)))+(((x9541)*(x9542)))+(((IkReal(0.0100000000000000))*(x9527)*(x9540)))+(((IkReal(-1.00000000000000))*(px)*(x9524)))+(((IkReal(0.0100000000000000))*(sj0)*(x9529)))+(((IkReal(-1.00000000000000))*(x9540)*(x9549)))+(((r12)*(sj0)*(x9530)))+(((IkReal(-1.00000000000000))*(x9547)*(x9549)))+(((IkReal(-1.00000000000000))*(py)*(x9533)))+(((x9530)*(x9542)))+(((IkReal(0.0100000000000000))*(x9527)*(x9547)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x9544)))+(((IkReal(-1.00000000000000))*(sj0)*(x9539)*(x9545))));
30743 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
30744 {
30745 {
30746 IkReal j3array[1], cj3array[1], sj3array[1];
30747 bool j3valid[1]={false};
30748 _nj3 = 1;
30749 IkReal x9551=((sj0)*(sj5));
30750 IkReal x9552=((r00)*(sj6));
30751 IkReal x9553=((IkReal(1.00000000000000))*(cj5));
30752 IkReal x9554=((cj6)*(r11));
30753 IkReal x9555=((cj6)*(r01));
30754 IkReal x9556=((r10)*(sj6));
30755 IkReal x9557=((cj0)*(sj5));
30756 if( IKabs(((((x9551)*(x9555)))+(((IkReal(-1.00000000000000))*(x9556)*(x9557)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9553)))+(((x9551)*(x9552)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x9554)*(x9557))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x9552)*(x9557)))+(((x9555)*(x9557)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9553)))+(((x9551)*(x9554)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9553)))+(((x9551)*(x9556))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x9551)*(x9555)))+(((IkReal(-1.00000000000000))*(x9556)*(x9557)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9553)))+(((x9551)*(x9552)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x9554)*(x9557)))))+IKsqr(((((x9552)*(x9557)))+(((x9555)*(x9557)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9553)))+(((x9551)*(x9554)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9553)))+(((x9551)*(x9556)))))-1) <= IKFAST_SINCOS_THRESH )
30757     continue;
30758 j3array[0]=IKatan2(((((x9551)*(x9555)))+(((IkReal(-1.00000000000000))*(x9556)*(x9557)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9553)))+(((x9551)*(x9552)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(x9554)*(x9557)))), ((((x9552)*(x9557)))+(((x9555)*(x9557)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9553)))+(((x9551)*(x9554)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9553)))+(((x9551)*(x9556)))));
30759 sj3array[0]=IKsin(j3array[0]);
30760 cj3array[0]=IKcos(j3array[0]);
30761 if( j3array[0] > IKPI )
30762 {
30763     j3array[0]-=IK2PI;
30764 }
30765 else if( j3array[0] < -IKPI )
30766 {    j3array[0]+=IK2PI;
30767 }
30768 j3valid[0] = true;
30769 for(int ij3 = 0; ij3 < 1; ++ij3)
30770 {
30771 if( !j3valid[ij3] )
30772 {
30773     continue;
30774 }
30775 _ij3[0] = ij3; _ij3[1] = -1;
30776 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30777 {
30778 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30779 {
30780     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30781 }
30782 }
30783 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30784 {
30785 IkReal evalcond[4];
30786 IkReal x9558=IKcos(j3);
30787 IkReal x9559=IKsin(j3);
30788 IkReal x9560=((sj0)*(sj5));
30789 IkReal x9561=((r00)*(sj6));
30790 IkReal x9562=((cj6)*(sj0));
30791 IkReal x9563=((IkReal(1.00000000000000))*(cj4));
30792 IkReal x9564=((r00)*(sj4));
30793 IkReal x9565=((cj0)*(cj5));
30794 IkReal x9566=((cj5)*(sj0));
30795 IkReal x9567=((cj6)*(r11));
30796 IkReal x9568=((r10)*(sj6));
30797 IkReal x9569=((cj0)*(sj5));
30798 IkReal x9570=((r10)*(sj4));
30799 IkReal x9571=((cj4)*(cj5)*(r01));
30800 IkReal x9572=((IkReal(1.00000000000000))*(cj0)*(cj6));
30801 IkReal x9573=((cj0)*(sj4)*(sj6));
30802 IkReal x9574=((sj0)*(sj4)*(sj6));
30803 evalcond[0]=((((r12)*(x9565)))+(((IkReal(-1.00000000000000))*(x9559)))+(((IkReal(-1.00000000000000))*(x9568)*(x9569)))+(((x9560)*(x9561)))+(((IkReal(-1.00000000000000))*(r02)*(x9566)))+(((IkReal(-1.00000000000000))*(x9567)*(x9569)))+(((cj6)*(r01)*(x9560))));
30804 evalcond[1]=((((IkReal(-1.00000000000000))*(x9560)*(x9567)))+(((r12)*(x9566)))+(((r02)*(x9565)))+(((IkReal(-1.00000000000000))*(x9561)*(x9569)))+(x9558)+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9569)))+(((IkReal(-1.00000000000000))*(x9560)*(x9568))));
30805 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x9574)))+(((IkReal(-1.00000000000000))*(x9570)*(x9572)))+(((IkReal(-1.00000000000000))*(x9563)*(x9565)*(x9568)))+(x9558)+(((cj4)*(x9561)*(x9566)))+(((x9562)*(x9571)))+(((r11)*(x9573)))+(((cj4)*(r02)*(x9560)))+(((IkReal(-1.00000000000000))*(x9563)*(x9565)*(x9567)))+(((x9562)*(x9564)))+(((IkReal(-1.00000000000000))*(r12)*(x9563)*(x9569))));
30806 evalcond[3]=((((r01)*(x9573)))+(((IkReal(-1.00000000000000))*(x9564)*(x9572)))+(((IkReal(-1.00000000000000))*(x9563)*(x9566)*(x9568)))+(((r11)*(x9574)))+(((IkReal(-1.00000000000000))*(r02)*(x9563)*(x9569)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x9562)*(x9563)))+(x9559)+(((IkReal(-1.00000000000000))*(x9562)*(x9570)))+(((IkReal(-1.00000000000000))*(r12)*(x9560)*(x9563)))+(((IkReal(-1.00000000000000))*(x9561)*(x9563)*(x9565)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x9563)*(x9565))));
30807 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
30808 {
30809 continue;
30810 }
30811 }
30812 
30813 {
30814 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30815 vinfos[0].jointtype = 1;
30816 vinfos[0].foffset = j0;
30817 vinfos[0].indices[0] = _ij0[0];
30818 vinfos[0].indices[1] = _ij0[1];
30819 vinfos[0].maxsolutions = _nj0;
30820 vinfos[1].jointtype = 1;
30821 vinfos[1].foffset = j1;
30822 vinfos[1].indices[0] = _ij1[0];
30823 vinfos[1].indices[1] = _ij1[1];
30824 vinfos[1].maxsolutions = _nj1;
30825 vinfos[2].jointtype = 1;
30826 vinfos[2].foffset = j2;
30827 vinfos[2].indices[0] = _ij2[0];
30828 vinfos[2].indices[1] = _ij2[1];
30829 vinfos[2].maxsolutions = _nj2;
30830 vinfos[3].jointtype = 1;
30831 vinfos[3].foffset = j3;
30832 vinfos[3].indices[0] = _ij3[0];
30833 vinfos[3].indices[1] = _ij3[1];
30834 vinfos[3].maxsolutions = _nj3;
30835 vinfos[4].jointtype = 1;
30836 vinfos[4].foffset = j4;
30837 vinfos[4].indices[0] = _ij4[0];
30838 vinfos[4].indices[1] = _ij4[1];
30839 vinfos[4].maxsolutions = _nj4;
30840 vinfos[5].jointtype = 1;
30841 vinfos[5].foffset = j5;
30842 vinfos[5].indices[0] = _ij5[0];
30843 vinfos[5].indices[1] = _ij5[1];
30844 vinfos[5].maxsolutions = _nj5;
30845 vinfos[6].jointtype = 1;
30846 vinfos[6].foffset = j6;
30847 vinfos[6].indices[0] = _ij6[0];
30848 vinfos[6].indices[1] = _ij6[1];
30849 vinfos[6].maxsolutions = _nj6;
30850 std::vector<int> vfree(0);
30851 solutions.AddSolution(vinfos,vfree);
30852 }
30853 }
30854 }
30855 
30856 } else
30857 {
30858 if( 1 )
30859 {
30860 continue;
30861 
30862 } else
30863 {
30864 }
30865 }
30866 }
30867 }
30868 }
30869 }
30870 
30871 } else
30872 {
30873 {
30874 IkReal j3array[1], cj3array[1], sj3array[1];
30875 bool j3valid[1]={false};
30876 _nj3 = 1;
30877 IkReal x9575=((cj0)*(cj5));
30878 IkReal x9576=((IkReal(1.00000000000000))*(cj0));
30879 IkReal x9577=((cj6)*(r11));
30880 IkReal x9578=((r10)*(sj6));
30881 IkReal x9579=((cj5)*(sj0));
30882 IkReal x9580=((r00)*(sj5)*(sj6));
30883 IkReal x9581=((cj6)*(r01)*(sj5));
30884 IkReal x9582=((IkReal(1.00000000000000))*(sj0)*(sj5));
30885 if( IKabs(((((IkReal(-1.00000000000000))*(r02)*(x9579)))+(((sj0)*(x9581)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9577)))+(((r12)*(x9575)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9578)))+(((sj0)*(x9580))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x9576)*(x9580)))+(((IkReal(-1.00000000000000))*(x9576)*(x9581)))+(((IkReal(-1.00000000000000))*(x9577)*(x9582)))+(((r02)*(x9575)))+(((IkReal(-1.00000000000000))*(x9578)*(x9582)))+(((r12)*(x9579))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r02)*(x9579)))+(((sj0)*(x9581)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9577)))+(((r12)*(x9575)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9578)))+(((sj0)*(x9580)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x9576)*(x9580)))+(((IkReal(-1.00000000000000))*(x9576)*(x9581)))+(((IkReal(-1.00000000000000))*(x9577)*(x9582)))+(((r02)*(x9575)))+(((IkReal(-1.00000000000000))*(x9578)*(x9582)))+(((r12)*(x9579)))))))-1) <= IKFAST_SINCOS_THRESH )
30886     continue;
30887 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r02)*(x9579)))+(((sj0)*(x9581)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9577)))+(((r12)*(x9575)))+(((IkReal(-1.00000000000000))*(sj5)*(x9576)*(x9578)))+(((sj0)*(x9580)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x9576)*(x9580)))+(((IkReal(-1.00000000000000))*(x9576)*(x9581)))+(((IkReal(-1.00000000000000))*(x9577)*(x9582)))+(((r02)*(x9575)))+(((IkReal(-1.00000000000000))*(x9578)*(x9582)))+(((r12)*(x9579)))))));
30888 sj3array[0]=IKsin(j3array[0]);
30889 cj3array[0]=IKcos(j3array[0]);
30890 if( j3array[0] > IKPI )
30891 {
30892     j3array[0]-=IK2PI;
30893 }
30894 else if( j3array[0] < -IKPI )
30895 {    j3array[0]+=IK2PI;
30896 }
30897 j3valid[0] = true;
30898 for(int ij3 = 0; ij3 < 1; ++ij3)
30899 {
30900 if( !j3valid[ij3] )
30901 {
30902     continue;
30903 }
30904 _ij3[0] = ij3; _ij3[1] = -1;
30905 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
30906 {
30907 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
30908 {
30909     j3valid[iij3]=false; _ij3[1] = iij3; break; 
30910 }
30911 }
30912 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
30913 {
30914 IkReal evalcond[6];
30915 IkReal x9583=IKsin(j3);
30916 IkReal x9584=IKcos(j3);
30917 IkReal x9585=((sj0)*(sj5));
30918 IkReal x9586=((r00)*(sj6));
30919 IkReal x9587=((cj6)*(r01));
30920 IkReal x9588=((cj4)*(cj5));
30921 IkReal x9589=((IkReal(1.00000000000000))*(cj0));
30922 IkReal x9590=((cj5)*(r12));
30923 IkReal x9591=((IkReal(1.00000000000000))*(sj0));
30924 IkReal x9592=((cj6)*(r11));
30925 IkReal x9593=((cj5)*(r02));
30926 IkReal x9594=((IkReal(1.00000000000000))*(cj1));
30927 IkReal x9595=((cj6)*(sj4));
30928 IkReal x9596=((cj6)*(r21));
30929 IkReal x9597=((r20)*(sj6));
30930 IkReal x9598=((r10)*(sj6));
30931 IkReal x9599=((sj4)*(sj6));
30932 IkReal x9600=((cj4)*(r02));
30933 IkReal x9601=((IkReal(1.00000000000000))*(cj4)*(r12));
30934 IkReal x9602=((IkReal(1.00000000000000))*(x9583));
30935 IkReal x9603=((cj0)*(x9599));
30936 evalcond[0]=((((sj5)*(x9596)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x9584)))+(((sj5)*(x9597))));
30937 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x9599)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x9595)))+(((IkReal(-1.00000000000000))*(sj1)*(x9602)))+(((x9588)*(x9597)))+(((x9588)*(x9596))));
30938 evalcond[2]=((((x9585)*(x9586)))+(((IkReal(-1.00000000000000))*(x9602)))+(((IkReal(-1.00000000000000))*(sj5)*(x9589)*(x9592)))+(((IkReal(-1.00000000000000))*(sj5)*(x9589)*(x9598)))+(((cj0)*(x9590)))+(((IkReal(-1.00000000000000))*(x9591)*(x9593)))+(((x9585)*(x9587))));
30939 evalcond[3]=((((IkReal(-1.00000000000000))*(x9585)*(x9592)))+(((IkReal(-1.00000000000000))*(x9584)*(x9594)))+(((IkReal(-1.00000000000000))*(sj5)*(x9587)*(x9589)))+(((IkReal(-1.00000000000000))*(sj5)*(x9586)*(x9589)))+(((IkReal(-1.00000000000000))*(x9585)*(x9598)))+(((sj0)*(x9590)))+(((cj0)*(x9593))));
30940 evalcond[4]=((((r00)*(sj0)*(x9595)))+(((IkReal(-1.00000000000000))*(x9588)*(x9589)*(x9592)))+(((IkReal(-1.00000000000000))*(r01)*(x9591)*(x9599)))+(((r11)*(x9603)))+(x9584)+(((IkReal(-1.00000000000000))*(x9588)*(x9589)*(x9598)))+(((sj0)*(x9586)*(x9588)))+(((IkReal(-1.00000000000000))*(r10)*(x9589)*(x9595)))+(((sj0)*(x9587)*(x9588)))+(((x9585)*(x9600)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9589))));
30941 evalcond[5]=((((IkReal(-1.00000000000000))*(x9585)*(x9601)))+(((IkReal(-1.00000000000000))*(x9587)*(x9588)*(x9589)))+(((IkReal(-1.00000000000000))*(r00)*(x9589)*(x9595)))+(((IkReal(-1.00000000000000))*(x9583)*(x9594)))+(((r11)*(sj0)*(x9599)))+(((r01)*(x9603)))+(((IkReal(-1.00000000000000))*(r10)*(x9591)*(x9595)))+(((IkReal(-1.00000000000000))*(x9586)*(x9588)*(x9589)))+(((IkReal(-1.00000000000000))*(x9588)*(x9591)*(x9592)))+(((IkReal(-1.00000000000000))*(sj5)*(x9589)*(x9600)))+(((IkReal(-1.00000000000000))*(x9588)*(x9591)*(x9598))));
30942 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
30943 {
30944 continue;
30945 }
30946 }
30947 
30948 {
30949 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
30950 vinfos[0].jointtype = 1;
30951 vinfos[0].foffset = j0;
30952 vinfos[0].indices[0] = _ij0[0];
30953 vinfos[0].indices[1] = _ij0[1];
30954 vinfos[0].maxsolutions = _nj0;
30955 vinfos[1].jointtype = 1;
30956 vinfos[1].foffset = j1;
30957 vinfos[1].indices[0] = _ij1[0];
30958 vinfos[1].indices[1] = _ij1[1];
30959 vinfos[1].maxsolutions = _nj1;
30960 vinfos[2].jointtype = 1;
30961 vinfos[2].foffset = j2;
30962 vinfos[2].indices[0] = _ij2[0];
30963 vinfos[2].indices[1] = _ij2[1];
30964 vinfos[2].maxsolutions = _nj2;
30965 vinfos[3].jointtype = 1;
30966 vinfos[3].foffset = j3;
30967 vinfos[3].indices[0] = _ij3[0];
30968 vinfos[3].indices[1] = _ij3[1];
30969 vinfos[3].maxsolutions = _nj3;
30970 vinfos[4].jointtype = 1;
30971 vinfos[4].foffset = j4;
30972 vinfos[4].indices[0] = _ij4[0];
30973 vinfos[4].indices[1] = _ij4[1];
30974 vinfos[4].maxsolutions = _nj4;
30975 vinfos[5].jointtype = 1;
30976 vinfos[5].foffset = j5;
30977 vinfos[5].indices[0] = _ij5[0];
30978 vinfos[5].indices[1] = _ij5[1];
30979 vinfos[5].maxsolutions = _nj5;
30980 vinfos[6].jointtype = 1;
30981 vinfos[6].foffset = j6;
30982 vinfos[6].indices[0] = _ij6[0];
30983 vinfos[6].indices[1] = _ij6[1];
30984 vinfos[6].maxsolutions = _nj6;
30985 std::vector<int> vfree(0);
30986 solutions.AddSolution(vinfos,vfree);
30987 }
30988 }
30989 }
30990 
30991 }
30992 
30993 }
30994 
30995 } else
30996 {
30997 {
30998 IkReal j3array[1], cj3array[1], sj3array[1];
30999 bool j3valid[1]={false};
31000 _nj3 = 1;
31001 IkReal x9604=((sj5)*(sj6));
31002 IkReal x9605=((cj6)*(sj5));
31003 IkReal x9606=((IkReal(1.00000000000000))*(cj0));
31004 IkReal x9607=((IkReal(1.00000000000000))*(cj5));
31005 if( IKabs(((((r01)*(sj0)*(x9605)))+(((r00)*(sj0)*(x9604)))+(((IkReal(-1.00000000000000))*(r10)*(x9604)*(x9606)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9607)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x9605)*(x9606))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x9607)))+(((r21)*(x9605)))+(((r20)*(x9604))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r01)*(sj0)*(x9605)))+(((r00)*(sj0)*(x9604)))+(((IkReal(-1.00000000000000))*(r10)*(x9604)*(x9606)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9607)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x9605)*(x9606)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x9607)))+(((r21)*(x9605)))+(((r20)*(x9604)))))))-1) <= IKFAST_SINCOS_THRESH )
31006     continue;
31007 j3array[0]=IKatan2(((((r01)*(sj0)*(x9605)))+(((r00)*(sj0)*(x9604)))+(((IkReal(-1.00000000000000))*(r10)*(x9604)*(x9606)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9607)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x9605)*(x9606)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x9607)))+(((r21)*(x9605)))+(((r20)*(x9604)))))));
31008 sj3array[0]=IKsin(j3array[0]);
31009 cj3array[0]=IKcos(j3array[0]);
31010 if( j3array[0] > IKPI )
31011 {
31012     j3array[0]-=IK2PI;
31013 }
31014 else if( j3array[0] < -IKPI )
31015 {    j3array[0]+=IK2PI;
31016 }
31017 j3valid[0] = true;
31018 for(int ij3 = 0; ij3 < 1; ++ij3)
31019 {
31020 if( !j3valid[ij3] )
31021 {
31022     continue;
31023 }
31024 _ij3[0] = ij3; _ij3[1] = -1;
31025 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
31026 {
31027 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
31028 {
31029     j3valid[iij3]=false; _ij3[1] = iij3; break; 
31030 }
31031 }
31032 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
31033 {
31034 IkReal evalcond[6];
31035 IkReal x9608=IKsin(j3);
31036 IkReal x9609=IKcos(j3);
31037 IkReal x9610=((sj0)*(sj5));
31038 IkReal x9611=((r00)*(sj6));
31039 IkReal x9612=((cj6)*(r01));
31040 IkReal x9613=((cj4)*(cj5));
31041 IkReal x9614=((IkReal(1.00000000000000))*(cj0));
31042 IkReal x9615=((cj5)*(r12));
31043 IkReal x9616=((IkReal(1.00000000000000))*(sj0));
31044 IkReal x9617=((cj6)*(r11));
31045 IkReal x9618=((cj5)*(r02));
31046 IkReal x9619=((IkReal(1.00000000000000))*(cj1));
31047 IkReal x9620=((cj6)*(sj4));
31048 IkReal x9621=((cj6)*(r21));
31049 IkReal x9622=((r20)*(sj6));
31050 IkReal x9623=((r10)*(sj6));
31051 IkReal x9624=((sj4)*(sj6));
31052 IkReal x9625=((cj4)*(r02));
31053 IkReal x9626=((IkReal(1.00000000000000))*(cj4)*(r12));
31054 IkReal x9627=((IkReal(1.00000000000000))*(x9608));
31055 IkReal x9628=((cj0)*(x9624));
31056 evalcond[0]=((((sj5)*(x9621)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9622)))+(((IkReal(-1.00000000000000))*(sj1)*(x9609))));
31057 evalcond[1]=((((x9613)*(x9621)))+(((r20)*(x9620)))+(((cj4)*(r22)*(sj5)))+(((x9613)*(x9622)))+(((IkReal(-1.00000000000000))*(sj1)*(x9627)))+(((IkReal(-1.00000000000000))*(r21)*(x9624))));
31058 evalcond[2]=((((IkReal(-1.00000000000000))*(x9616)*(x9618)))+(((x9610)*(x9611)))+(((IkReal(-1.00000000000000))*(sj5)*(x9614)*(x9617)))+(((cj0)*(x9615)))+(((IkReal(-1.00000000000000))*(sj5)*(x9614)*(x9623)))+(((x9610)*(x9612)))+(((IkReal(-1.00000000000000))*(x9627))));
31059 evalcond[3]=((((IkReal(-1.00000000000000))*(x9609)*(x9619)))+(((cj0)*(x9618)))+(((IkReal(-1.00000000000000))*(sj5)*(x9611)*(x9614)))+(((IkReal(-1.00000000000000))*(sj5)*(x9612)*(x9614)))+(((IkReal(-1.00000000000000))*(x9610)*(x9623)))+(((sj0)*(x9615)))+(((IkReal(-1.00000000000000))*(x9610)*(x9617))));
31060 evalcond[4]=((((x9610)*(x9625)))+(((sj0)*(x9611)*(x9613)))+(((r11)*(x9628)))+(((r00)*(sj0)*(x9620)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9614)))+(((IkReal(-1.00000000000000))*(r01)*(x9616)*(x9624)))+(((IkReal(-1.00000000000000))*(x9613)*(x9614)*(x9617)))+(((IkReal(-1.00000000000000))*(r10)*(x9614)*(x9620)))+(((IkReal(-1.00000000000000))*(x9613)*(x9614)*(x9623)))+(((sj0)*(x9612)*(x9613)))+(x9609));
31061 evalcond[5]=((((r11)*(sj0)*(x9624)))+(((IkReal(-1.00000000000000))*(r00)*(x9614)*(x9620)))+(((IkReal(-1.00000000000000))*(x9613)*(x9616)*(x9617)))+(((IkReal(-1.00000000000000))*(x9611)*(x9613)*(x9614)))+(((IkReal(-1.00000000000000))*(x9610)*(x9626)))+(((IkReal(-1.00000000000000))*(r10)*(x9616)*(x9620)))+(((IkReal(-1.00000000000000))*(x9613)*(x9616)*(x9623)))+(((r01)*(x9628)))+(((IkReal(-1.00000000000000))*(sj5)*(x9614)*(x9625)))+(((IkReal(-1.00000000000000))*(x9612)*(x9613)*(x9614)))+(((IkReal(-1.00000000000000))*(x9608)*(x9619))));
31062 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
31063 {
31064 continue;
31065 }
31066 }
31067 
31068 {
31069 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
31070 vinfos[0].jointtype = 1;
31071 vinfos[0].foffset = j0;
31072 vinfos[0].indices[0] = _ij0[0];
31073 vinfos[0].indices[1] = _ij0[1];
31074 vinfos[0].maxsolutions = _nj0;
31075 vinfos[1].jointtype = 1;
31076 vinfos[1].foffset = j1;
31077 vinfos[1].indices[0] = _ij1[0];
31078 vinfos[1].indices[1] = _ij1[1];
31079 vinfos[1].maxsolutions = _nj1;
31080 vinfos[2].jointtype = 1;
31081 vinfos[2].foffset = j2;
31082 vinfos[2].indices[0] = _ij2[0];
31083 vinfos[2].indices[1] = _ij2[1];
31084 vinfos[2].maxsolutions = _nj2;
31085 vinfos[3].jointtype = 1;
31086 vinfos[3].foffset = j3;
31087 vinfos[3].indices[0] = _ij3[0];
31088 vinfos[3].indices[1] = _ij3[1];
31089 vinfos[3].maxsolutions = _nj3;
31090 vinfos[4].jointtype = 1;
31091 vinfos[4].foffset = j4;
31092 vinfos[4].indices[0] = _ij4[0];
31093 vinfos[4].indices[1] = _ij4[1];
31094 vinfos[4].maxsolutions = _nj4;
31095 vinfos[5].jointtype = 1;
31096 vinfos[5].foffset = j5;
31097 vinfos[5].indices[0] = _ij5[0];
31098 vinfos[5].indices[1] = _ij5[1];
31099 vinfos[5].maxsolutions = _nj5;
31100 vinfos[6].jointtype = 1;
31101 vinfos[6].foffset = j6;
31102 vinfos[6].indices[0] = _ij6[0];
31103 vinfos[6].indices[1] = _ij6[1];
31104 vinfos[6].maxsolutions = _nj6;
31105 std::vector<int> vfree(0);
31106 solutions.AddSolution(vinfos,vfree);
31107 }
31108 }
31109 }
31110 
31111 }
31112 
31113 }
31114 
31115 } else
31116 {
31117 {
31118 IkReal j3array[1], cj3array[1], sj3array[1];
31119 bool j3valid[1]={false};
31120 _nj3 = 1;
31121 IkReal x9629=((r20)*(sj6));
31122 IkReal x9630=((cj4)*(cj5));
31123 IkReal x9631=((cj6)*(r21));
31124 if( IKabs(((gconst17)*(((((x9629)*(x9630)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x9630)*(x9631)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9629)))+(((sj5)*(x9631))))))) < IKFAST_ATAN2_MAGTHRESH )
31125     continue;
31126 j3array[0]=IKatan2(((gconst17)*(((((x9629)*(x9630)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x9630)*(x9631)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))), ((gconst17)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x9629)))+(((sj5)*(x9631)))))));
31127 sj3array[0]=IKsin(j3array[0]);
31128 cj3array[0]=IKcos(j3array[0]);
31129 if( j3array[0] > IKPI )
31130 {
31131     j3array[0]-=IK2PI;
31132 }
31133 else if( j3array[0] < -IKPI )
31134 {    j3array[0]+=IK2PI;
31135 }
31136 j3valid[0] = true;
31137 for(int ij3 = 0; ij3 < 1; ++ij3)
31138 {
31139 if( !j3valid[ij3] )
31140 {
31141     continue;
31142 }
31143 _ij3[0] = ij3; _ij3[1] = -1;
31144 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
31145 {
31146 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
31147 {
31148     j3valid[iij3]=false; _ij3[1] = iij3; break; 
31149 }
31150 }
31151 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
31152 {
31153 IkReal evalcond[6];
31154 IkReal x9632=IKsin(j3);
31155 IkReal x9633=IKcos(j3);
31156 IkReal x9634=((sj0)*(sj5));
31157 IkReal x9635=((r00)*(sj6));
31158 IkReal x9636=((cj6)*(r01));
31159 IkReal x9637=((cj4)*(cj5));
31160 IkReal x9638=((IkReal(1.00000000000000))*(cj0));
31161 IkReal x9639=((cj5)*(r12));
31162 IkReal x9640=((IkReal(1.00000000000000))*(sj0));
31163 IkReal x9641=((cj6)*(r11));
31164 IkReal x9642=((cj5)*(r02));
31165 IkReal x9643=((IkReal(1.00000000000000))*(cj1));
31166 IkReal x9644=((cj6)*(sj4));
31167 IkReal x9645=((cj6)*(r21));
31168 IkReal x9646=((r20)*(sj6));
31169 IkReal x9647=((r10)*(sj6));
31170 IkReal x9648=((sj4)*(sj6));
31171 IkReal x9649=((cj4)*(r02));
31172 IkReal x9650=((IkReal(1.00000000000000))*(cj4)*(r12));
31173 IkReal x9651=((IkReal(1.00000000000000))*(x9632));
31174 IkReal x9652=((cj0)*(x9648));
31175 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x9633)))+(((sj5)*(x9646)))+(((sj5)*(x9645)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
31176 evalcond[1]=((((r20)*(x9644)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x9648)))+(((x9637)*(x9645)))+(((IkReal(-1.00000000000000))*(sj1)*(x9651)))+(((x9637)*(x9646))));
31177 evalcond[2]=((((x9634)*(x9636)))+(((IkReal(-1.00000000000000))*(x9640)*(x9642)))+(((IkReal(-1.00000000000000))*(x9651)))+(((x9634)*(x9635)))+(((IkReal(-1.00000000000000))*(sj5)*(x9638)*(x9641)))+(((cj0)*(x9639)))+(((IkReal(-1.00000000000000))*(sj5)*(x9638)*(x9647))));
31178 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x9636)*(x9638)))+(((sj0)*(x9639)))+(((IkReal(-1.00000000000000))*(sj5)*(x9635)*(x9638)))+(((IkReal(-1.00000000000000))*(x9634)*(x9647)))+(((IkReal(-1.00000000000000))*(x9633)*(x9643)))+(((IkReal(-1.00000000000000))*(x9634)*(x9641)))+(((cj0)*(x9642))));
31179 evalcond[4]=((((IkReal(-1.00000000000000))*(x9637)*(x9638)*(x9641)))+(((IkReal(-1.00000000000000))*(x9637)*(x9638)*(x9647)))+(((IkReal(-1.00000000000000))*(r10)*(x9638)*(x9644)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x9638)))+(x9633)+(((sj0)*(x9636)*(x9637)))+(((x9634)*(x9649)))+(((r00)*(sj0)*(x9644)))+(((sj0)*(x9635)*(x9637)))+(((r11)*(x9652)))+(((IkReal(-1.00000000000000))*(r01)*(x9640)*(x9648))));
31180 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x9638)*(x9649)))+(((IkReal(-1.00000000000000))*(x9636)*(x9637)*(x9638)))+(((r01)*(x9652)))+(((IkReal(-1.00000000000000))*(x9637)*(x9640)*(x9641)))+(((IkReal(-1.00000000000000))*(x9634)*(x9650)))+(((IkReal(-1.00000000000000))*(x9637)*(x9640)*(x9647)))+(((IkReal(-1.00000000000000))*(x9635)*(x9637)*(x9638)))+(((IkReal(-1.00000000000000))*(x9632)*(x9643)))+(((IkReal(-1.00000000000000))*(r10)*(x9640)*(x9644)))+(((IkReal(-1.00000000000000))*(r00)*(x9638)*(x9644)))+(((r11)*(sj0)*(x9648))));
31181 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
31182 {
31183 continue;
31184 }
31185 }
31186 
31187 {
31188 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
31189 vinfos[0].jointtype = 1;
31190 vinfos[0].foffset = j0;
31191 vinfos[0].indices[0] = _ij0[0];
31192 vinfos[0].indices[1] = _ij0[1];
31193 vinfos[0].maxsolutions = _nj0;
31194 vinfos[1].jointtype = 1;
31195 vinfos[1].foffset = j1;
31196 vinfos[1].indices[0] = _ij1[0];
31197 vinfos[1].indices[1] = _ij1[1];
31198 vinfos[1].maxsolutions = _nj1;
31199 vinfos[2].jointtype = 1;
31200 vinfos[2].foffset = j2;
31201 vinfos[2].indices[0] = _ij2[0];
31202 vinfos[2].indices[1] = _ij2[1];
31203 vinfos[2].maxsolutions = _nj2;
31204 vinfos[3].jointtype = 1;
31205 vinfos[3].foffset = j3;
31206 vinfos[3].indices[0] = _ij3[0];
31207 vinfos[3].indices[1] = _ij3[1];
31208 vinfos[3].maxsolutions = _nj3;
31209 vinfos[4].jointtype = 1;
31210 vinfos[4].foffset = j4;
31211 vinfos[4].indices[0] = _ij4[0];
31212 vinfos[4].indices[1] = _ij4[1];
31213 vinfos[4].maxsolutions = _nj4;
31214 vinfos[5].jointtype = 1;
31215 vinfos[5].foffset = j5;
31216 vinfos[5].indices[0] = _ij5[0];
31217 vinfos[5].indices[1] = _ij5[1];
31218 vinfos[5].maxsolutions = _nj5;
31219 vinfos[6].jointtype = 1;
31220 vinfos[6].foffset = j6;
31221 vinfos[6].indices[0] = _ij6[0];
31222 vinfos[6].indices[1] = _ij6[1];
31223 vinfos[6].maxsolutions = _nj6;
31224 std::vector<int> vfree(0);
31225 solutions.AddSolution(vinfos,vfree);
31226 }
31227 }
31228 }
31229 
31230 }
31231 
31232 }
31233 }
31234 }
31235 
31236 }
31237 
31238 }
31239 
31240 } else
31241 {
31242 IkReal x9653=((IkReal(0.374290000000000))*(sj5));
31243 IkReal x9654=((cj0)*(sj6));
31244 IkReal x9655=((IkReal(0.0100000000000000))*(sj5));
31245 IkReal x9656=((cj0)*(r02));
31246 IkReal x9657=((IkReal(0.0100000000000000))*(cj5));
31247 IkReal x9658=((IkReal(1.00000000000000))*(py));
31248 IkReal x9659=((r01)*(sj0));
31249 IkReal x9660=((r20)*(sj6));
31250 IkReal x9661=((r11)*(sj0));
31251 IkReal x9662=((IkReal(0.374290000000000))*(cj5));
31252 IkReal x9663=((cj0)*(r12));
31253 IkReal x9664=((sj0)*(x9662));
31254 IkReal x9665=((cj6)*(x9657));
31255 IkReal x9666=((r10)*(sj0)*(sj6));
31256 IkReal x9667=((r00)*(sj0)*(sj6));
31257 IkReal x9668=((cj0)*(cj6)*(x9653));
31258 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
31259 evalcond[1]=((((IkReal(-1.00000000000000))*(x9657)*(x9660)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x9655)))+(((IkReal(-1.00000000000000))*(r22)*(x9662)))+(pz)+(((IkReal(-1.00000000000000))*(r21)*(x9665)))+(((x9653)*(x9660)))+(((cj6)*(r21)*(x9653))));
31260 evalcond[2]=((IkReal(-0.0690000000000000))+(((r10)*(x9654)*(x9657)))+(((cj0)*(r11)*(x9665)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9655)))+(((IkReal(-1.00000000000000))*(cj0)*(x9658)))+(((IkReal(-1.00000000000000))*(x9657)*(x9667)))+(((IkReal(-1.00000000000000))*(r02)*(x9664)))+(((x9662)*(x9663)))+(((cj6)*(x9653)*(x9659)))+(((x9653)*(x9667)))+(((x9655)*(x9663)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(x9668)))+(((IkReal(-1.00000000000000))*(x9659)*(x9665)))+(((IkReal(-1.00000000000000))*(r10)*(x9653)*(x9654))));
31261 evalcond[3]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x9653)*(x9654)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x9655)*(x9656)))+(((IkReal(-1.00000000000000))*(x9653)*(x9666)))+(((x9656)*(x9662)))+(((cj0)*(r01)*(x9665)))+(((IkReal(-1.00000000000000))*(cj6)*(x9653)*(x9661)))+(((IkReal(-1.00000000000000))*(sj0)*(x9658)))+(((x9661)*(x9665)))+(((r12)*(sj0)*(x9655)))+(((x9657)*(x9666)))+(((IkReal(-1.00000000000000))*(r01)*(x9668)))+(((IkReal(0.364420000000000))*(cj1)))+(((r00)*(x9654)*(x9657)))+(((r12)*(x9664))));
31262 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  )
31263 {
31264 {
31265 IkReal dummyeval[1];
31266 IkReal gconst26;
31267 IkReal x9669=(cj6)*(cj6);
31268 IkReal x9670=(sj6)*(sj6);
31269 IkReal x9671=((IkReal(1.00000000000000))*(r01));
31270 IkReal x9672=((sj0)*(sj5));
31271 IkReal x9673=((cj6)*(r22));
31272 IkReal x9674=((r21)*(sj6));
31273 IkReal x9675=((r00)*(r21));
31274 IkReal x9676=((cj0)*(sj5));
31275 IkReal x9677=((cj6)*(r20));
31276 IkReal x9678=((r22)*(sj6));
31277 IkReal x9679=((cj0)*(cj5));
31278 IkReal x9680=((IkReal(1.00000000000000))*(r10));
31279 IkReal x9681=((cj5)*(sj0));
31280 IkReal x9682=((r20)*(x9670));
31281 IkReal x9683=((x9669)*(x9681));
31282 gconst26=IKsign(((((x9675)*(x9683)))+(((IkReal(-1.00000000000000))*(r02)*(x9672)*(x9677)))+(((IkReal(-1.00000000000000))*(r21)*(x9670)*(x9679)*(x9680)))+(((r02)*(x9672)*(x9674)))+(((IkReal(-1.00000000000000))*(x9671)*(x9672)*(x9678)))+(((r00)*(x9672)*(x9673)))+(((x9670)*(x9675)*(x9681)))+(((r11)*(r20)*(x9669)*(x9679)))+(((IkReal(-1.00000000000000))*(r12)*(x9674)*(x9676)))+(((IkReal(-1.00000000000000))*(r20)*(x9671)*(x9683)))+(((IkReal(-1.00000000000000))*(x9671)*(x9681)*(x9682)))+(((r12)*(x9676)*(x9677)))+(((r11)*(x9679)*(x9682)))+(((IkReal(-1.00000000000000))*(r21)*(x9669)*(x9679)*(x9680)))+(((r11)*(x9676)*(x9678)))+(((IkReal(-1.00000000000000))*(x9673)*(x9676)*(x9680)))));
31283 IkReal x9684=(cj6)*(cj6);
31284 IkReal x9685=(sj6)*(sj6);
31285 IkReal x9686=((IkReal(1.00000000000000))*(r01));
31286 IkReal x9687=((sj0)*(sj5));
31287 IkReal x9688=((cj6)*(r22));
31288 IkReal x9689=((r21)*(sj6));
31289 IkReal x9690=((r00)*(r21));
31290 IkReal x9691=((cj0)*(sj5));
31291 IkReal x9692=((cj6)*(r20));
31292 IkReal x9693=((r22)*(sj6));
31293 IkReal x9694=((cj0)*(cj5));
31294 IkReal x9695=((IkReal(1.00000000000000))*(r10));
31295 IkReal x9696=((cj5)*(sj0));
31296 IkReal x9697=((r20)*(x9685));
31297 IkReal x9698=((x9684)*(x9696));
31298 dummyeval[0]=((((r00)*(x9687)*(x9688)))+(((IkReal(-1.00000000000000))*(x9686)*(x9687)*(x9693)))+(((r11)*(x9694)*(x9697)))+(((IkReal(-1.00000000000000))*(r12)*(x9689)*(x9691)))+(((IkReal(-1.00000000000000))*(r20)*(x9686)*(x9698)))+(((IkReal(-1.00000000000000))*(x9686)*(x9696)*(x9697)))+(((r11)*(r20)*(x9684)*(x9694)))+(((IkReal(-1.00000000000000))*(r21)*(x9684)*(x9694)*(x9695)))+(((IkReal(-1.00000000000000))*(x9688)*(x9691)*(x9695)))+(((IkReal(-1.00000000000000))*(r21)*(x9685)*(x9694)*(x9695)))+(((x9690)*(x9698)))+(((r02)*(x9687)*(x9689)))+(((r11)*(x9691)*(x9693)))+(((r12)*(x9691)*(x9692)))+(((x9685)*(x9690)*(x9696)))+(((IkReal(-1.00000000000000))*(r02)*(x9687)*(x9692))));
31299 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31300 {
31301 {
31302 IkReal dummyeval[1];
31303 IkReal gconst27;
31304 IkReal x9699=(cj6)*(cj6);
31305 IkReal x9700=(sj6)*(sj6);
31306 IkReal x9701=((sj5)*(sj6));
31307 IkReal x9702=((IkReal(1.00000000000000))*(cj0));
31308 IkReal x9703=((cj6)*(sj5));
31309 IkReal x9704=((r20)*(sj0));
31310 IkReal x9705=((cj0)*(r20));
31311 IkReal x9706=((r00)*(r21));
31312 IkReal x9707=((r22)*(sj0));
31313 IkReal x9708=((IkReal(1.00000000000000))*(r21)*(sj0));
31314 IkReal x9709=((cj5)*(x9700));
31315 IkReal x9710=((cj5)*(x9699));
31316 gconst27=IKsign(((((IkReal(-1.00000000000000))*(r10)*(x9708)*(x9710)))+(((IkReal(-1.00000000000000))*(x9702)*(x9706)*(x9709)))+(((r02)*(x9703)*(x9705)))+(((IkReal(-1.00000000000000))*(r12)*(x9701)*(x9708)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x9701)*(x9702)))+(((r01)*(x9705)*(x9709)))+(((r11)*(x9701)*(x9707)))+(((r12)*(x9703)*(x9704)))+(((r11)*(x9704)*(x9710)))+(((IkReal(-1.00000000000000))*(r10)*(x9703)*(x9707)))+(((IkReal(-1.00000000000000))*(x9702)*(x9706)*(x9710)))+(((IkReal(-1.00000000000000))*(r00)*(r22)*(x9702)*(x9703)))+(((r01)*(x9705)*(x9710)))+(((r11)*(x9704)*(x9709)))+(((IkReal(-1.00000000000000))*(r10)*(x9708)*(x9709)))+(((cj0)*(r01)*(r22)*(x9701)))));
31317 IkReal x9711=(cj6)*(cj6);
31318 IkReal x9712=(sj6)*(sj6);
31319 IkReal x9713=((sj5)*(sj6));
31320 IkReal x9714=((IkReal(1.00000000000000))*(cj0));
31321 IkReal x9715=((cj6)*(sj5));
31322 IkReal x9716=((r20)*(sj0));
31323 IkReal x9717=((cj0)*(r20));
31324 IkReal x9718=((r00)*(r21));
31325 IkReal x9719=((r22)*(sj0));
31326 IkReal x9720=((IkReal(1.00000000000000))*(r21)*(sj0));
31327 IkReal x9721=((cj5)*(x9712));
31328 IkReal x9722=((cj5)*(x9711));
31329 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(r22)*(x9714)*(x9715)))+(((r02)*(x9715)*(x9717)))+(((IkReal(-1.00000000000000))*(r12)*(x9713)*(x9720)))+(((IkReal(-1.00000000000000))*(r10)*(x9715)*(x9719)))+(((r11)*(x9716)*(x9721)))+(((r11)*(x9716)*(x9722)))+(((r01)*(x9717)*(x9722)))+(((cj0)*(r01)*(r22)*(x9713)))+(((r11)*(x9713)*(x9719)))+(((r12)*(x9715)*(x9716)))+(((r01)*(x9717)*(x9721)))+(((IkReal(-1.00000000000000))*(x9714)*(x9718)*(x9721)))+(((IkReal(-1.00000000000000))*(r02)*(r21)*(x9713)*(x9714)))+(((IkReal(-1.00000000000000))*(r10)*(x9720)*(x9722)))+(((IkReal(-1.00000000000000))*(x9714)*(x9718)*(x9722)))+(((IkReal(-1.00000000000000))*(r10)*(x9720)*(x9721))));
31330 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31331 {
31332 {
31333 IkReal dummyeval[1];
31334 dummyeval[0]=sj1;
31335 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31336 {
31337 {
31338 IkReal evalcond[5];
31339 IkReal x9723=((cj5)*(r22));
31340 IkReal x9724=((IkReal(0.374290000000000))*(sj5));
31341 IkReal x9725=((cj0)*(sj6));
31342 IkReal x9726=((cj6)*(r21));
31343 IkReal x9727=((IkReal(0.0100000000000000))*(sj5));
31344 IkReal x9728=((cj0)*(r02));
31345 IkReal x9729=((IkReal(0.0100000000000000))*(cj5));
31346 IkReal x9730=((IkReal(1.00000000000000))*(py));
31347 IkReal x9731=((r01)*(sj0));
31348 IkReal x9732=((r20)*(sj6));
31349 IkReal x9733=((r11)*(sj0));
31350 IkReal x9734=((IkReal(0.374290000000000))*(cj5));
31351 IkReal x9735=((cj0)*(r12));
31352 IkReal x9736=((sj0)*(x9734));
31353 IkReal x9737=((cj6)*(x9729));
31354 IkReal x9738=((r10)*(sj0)*(sj6));
31355 IkReal x9739=((r00)*(sj0)*(sj6));
31356 IkReal x9740=((cj0)*(cj6)*(x9724));
31357 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
31358 evalcond[1]=((((sj5)*(x9732)))+(((sj5)*(x9726)))+(((IkReal(-1.00000000000000))*(x9723))));
31359 evalcond[2]=((((x9724)*(x9732)))+(((IkReal(-1.00000000000000))*(x9726)*(x9729)))+(((IkReal(-0.374290000000000))*(x9723)))+(((IkReal(-1.00000000000000))*(r22)*(x9727)))+(pz)+(((IkReal(-1.00000000000000))*(x9729)*(x9732)))+(((x9724)*(x9726))));
31360 evalcond[3]=((IkReal(-0.0690000000000000))+(((cj0)*(r11)*(x9737)))+(((IkReal(-1.00000000000000))*(x9729)*(x9739)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9727)))+(((x9734)*(x9735)))+(((x9724)*(x9739)))+(((x9727)*(x9735)))+(((IkReal(-1.00000000000000))*(r11)*(x9740)))+(((IkReal(-1.00000000000000))*(r02)*(x9736)))+(((IkReal(-1.00000000000000))*(r10)*(x9724)*(x9725)))+(((r10)*(x9725)*(x9729)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x9731)*(x9737)))+(((IkReal(-1.00000000000000))*(cj0)*(x9730)))+(((cj6)*(x9724)*(x9731))));
31361 evalcond[4]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x9727)*(x9728)))+(((IkReal(-1.00000000000000))*(x9724)*(x9738)))+(((IkReal(-1.00000000000000))*(cj6)*(x9724)*(x9733)))+(((x9729)*(x9738)))+(((IkReal(-1.00000000000000))*(r01)*(x9740)))+(((r12)*(x9736)))+(((x9728)*(x9734)))+(((r12)*(sj0)*(x9727)))+(((IkReal(-1.00000000000000))*(r00)*(x9724)*(x9725)))+(((cj0)*(r01)*(x9737)))+(((x9733)*(x9737)))+(((IkReal(-1.00000000000000))*(sj0)*(x9730)))+(((r00)*(x9725)*(x9729))));
31362 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
31363 {
31364 {
31365 IkReal j3array[1], cj3array[1], sj3array[1];
31366 bool j3valid[1]={false};
31367 _nj3 = 1;
31368 IkReal x9741=((cj5)*(r02));
31369 IkReal x9742=((cj0)*(sj5));
31370 IkReal x9743=((r10)*(sj6));
31371 IkReal x9744=((IkReal(1.00000000000000))*(cj6));
31372 IkReal x9745=((sj0)*(sj5));
31373 IkReal x9746=((cj5)*(r12));
31374 IkReal x9747=((IkReal(1.00000000000000))*(r00)*(sj6));
31375 if( IKabs(((((IkReal(-1.00000000000000))*(x9745)*(x9747)))+(((IkReal(-1.00000000000000))*(cj0)*(x9746)))+(((cj6)*(r11)*(x9742)))+(((x9742)*(x9743)))+(((IkReal(-1.00000000000000))*(r01)*(x9744)*(x9745)))+(((sj0)*(x9741))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x9742)*(x9747)))+(((cj0)*(x9741)))+(((sj0)*(x9746)))+(((IkReal(-1.00000000000000))*(r11)*(x9744)*(x9745)))+(((IkReal(-1.00000000000000))*(x9743)*(x9745)))+(((IkReal(-1.00000000000000))*(r01)*(x9742)*(x9744))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x9745)*(x9747)))+(((IkReal(-1.00000000000000))*(cj0)*(x9746)))+(((cj6)*(r11)*(x9742)))+(((x9742)*(x9743)))+(((IkReal(-1.00000000000000))*(r01)*(x9744)*(x9745)))+(((sj0)*(x9741)))))+IKsqr(((((IkReal(-1.00000000000000))*(x9742)*(x9747)))+(((cj0)*(x9741)))+(((sj0)*(x9746)))+(((IkReal(-1.00000000000000))*(r11)*(x9744)*(x9745)))+(((IkReal(-1.00000000000000))*(x9743)*(x9745)))+(((IkReal(-1.00000000000000))*(r01)*(x9742)*(x9744)))))-1) <= IKFAST_SINCOS_THRESH )
31376     continue;
31377 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x9745)*(x9747)))+(((IkReal(-1.00000000000000))*(cj0)*(x9746)))+(((cj6)*(r11)*(x9742)))+(((x9742)*(x9743)))+(((IkReal(-1.00000000000000))*(r01)*(x9744)*(x9745)))+(((sj0)*(x9741)))), ((((IkReal(-1.00000000000000))*(x9742)*(x9747)))+(((cj0)*(x9741)))+(((sj0)*(x9746)))+(((IkReal(-1.00000000000000))*(r11)*(x9744)*(x9745)))+(((IkReal(-1.00000000000000))*(x9743)*(x9745)))+(((IkReal(-1.00000000000000))*(r01)*(x9742)*(x9744)))));
31378 sj3array[0]=IKsin(j3array[0]);
31379 cj3array[0]=IKcos(j3array[0]);
31380 if( j3array[0] > IKPI )
31381 {
31382     j3array[0]-=IK2PI;
31383 }
31384 else if( j3array[0] < -IKPI )
31385 {    j3array[0]+=IK2PI;
31386 }
31387 j3valid[0] = true;
31388 for(int ij3 = 0; ij3 < 1; ++ij3)
31389 {
31390 if( !j3valid[ij3] )
31391 {
31392     continue;
31393 }
31394 _ij3[0] = ij3; _ij3[1] = -1;
31395 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
31396 {
31397 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
31398 {
31399     j3valid[iij3]=false; _ij3[1] = iij3; break; 
31400 }
31401 }
31402 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
31403 {
31404 IkReal evalcond[2];
31405 IkReal x9748=((cj0)*(cj5));
31406 IkReal x9749=((IkReal(1.00000000000000))*(cj0));
31407 IkReal x9750=((cj6)*(r11));
31408 IkReal x9751=((r10)*(sj6));
31409 IkReal x9752=((cj5)*(sj0));
31410 IkReal x9753=((r00)*(sj5)*(sj6));
31411 IkReal x9754=((cj6)*(r01)*(sj5));
31412 IkReal x9755=((IkReal(1.00000000000000))*(sj0)*(sj5));
31413 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x9752)))+(((sj0)*(x9753)))+(((sj0)*(x9754)))+(((IkReal(-1.00000000000000))*(sj5)*(x9749)*(x9751)))+(((IkReal(-1.00000000000000))*(sj5)*(x9749)*(x9750)))+(IKsin(j3))+(((r12)*(x9748))));
31414 evalcond[1]=((((IkReal(-1.00000000000000))*(x9751)*(x9755)))+(((IkReal(-1.00000000000000))*(x9750)*(x9755)))+(((r12)*(x9752)))+(((IkReal(-1.00000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(x9749)*(x9753)))+(((r02)*(x9748)))+(((IkReal(-1.00000000000000))*(x9749)*(x9754))));
31415 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
31416 {
31417 continue;
31418 }
31419 }
31420 
31421 {
31422 IkReal dummyeval[1];
31423 IkReal gconst33;
31424 IkReal x9756=(r21)*(r21);
31425 IkReal x9757=(cj5)*(cj5);
31426 IkReal x9758=(sj6)*(sj6);
31427 IkReal x9759=(cj6)*(cj6);
31428 IkReal x9760=(r20)*(r20);
31429 IkReal x9761=((cj6)*(r21));
31430 IkReal x9762=((IkReal(2.00000000000000))*(r20)*(sj6));
31431 IkReal x9763=((cj5)*(r22)*(sj5));
31432 IkReal x9764=((IkReal(1.00000000000000))*(x9758));
31433 IkReal x9765=((IkReal(1.00000000000000))*(x9759));
31434 gconst33=IKsign(((((IkReal(-2.00000000000000))*(x9761)*(x9763)))+(((IkReal(-1.00000000000000))*(x9757)*(x9760)*(x9764)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((x9761)*(x9762)))+(((IkReal(-1.00000000000000))*(x9760)*(x9765)))+(((IkReal(-1.00000000000000))*(x9756)*(x9757)*(x9765)))+(((IkReal(-1.00000000000000))*(x9757)*(x9761)*(x9762)))+(((IkReal(-1.00000000000000))*(x9756)*(x9764)))+(((IkReal(-1.00000000000000))*(x9762)*(x9763)))));
31435 IkReal x9766=(r21)*(r21);
31436 IkReal x9767=(cj5)*(cj5);
31437 IkReal x9768=(sj6)*(sj6);
31438 IkReal x9769=(cj6)*(cj6);
31439 IkReal x9770=(r20)*(r20);
31440 IkReal x9771=((cj6)*(r21));
31441 IkReal x9772=((IkReal(2.00000000000000))*(r20)*(sj6));
31442 IkReal x9773=((cj5)*(r22)*(sj5));
31443 IkReal x9774=((IkReal(1.00000000000000))*(x9768));
31444 IkReal x9775=((IkReal(1.00000000000000))*(x9769));
31445 dummyeval[0]=((((IkReal(-1.00000000000000))*(x9772)*(x9773)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x9766)*(x9767)*(x9775)))+(((IkReal(-1.00000000000000))*(x9770)*(x9775)))+(((IkReal(-1.00000000000000))*(x9766)*(x9774)))+(((IkReal(-1.00000000000000))*(x9767)*(x9770)*(x9774)))+(((IkReal(-2.00000000000000))*(x9771)*(x9773)))+(((IkReal(-1.00000000000000))*(x9767)*(x9771)*(x9772)))+(((x9771)*(x9772))));
31446 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31447 {
31448 {
31449 IkReal dummyeval[1];
31450 IkReal gconst34;
31451 IkReal x9776=(cj6)*(cj6);
31452 IkReal x9777=(sj6)*(sj6);
31453 IkReal x9778=((IkReal(1.00000000000000))*(r01));
31454 IkReal x9779=((sj0)*(sj5));
31455 IkReal x9780=((cj6)*(r22));
31456 IkReal x9781=((r21)*(sj6));
31457 IkReal x9782=((r00)*(r21));
31458 IkReal x9783=((cj0)*(sj5));
31459 IkReal x9784=((cj6)*(r20));
31460 IkReal x9785=((r22)*(sj6));
31461 IkReal x9786=((cj0)*(cj5));
31462 IkReal x9787=((IkReal(1.00000000000000))*(r10));
31463 IkReal x9788=((cj5)*(sj0));
31464 IkReal x9789=((r20)*(x9777));
31465 IkReal x9790=((x9776)*(x9788));
31466 gconst34=IKsign(((((r00)*(x9779)*(x9780)))+(((r11)*(r20)*(x9776)*(x9786)))+(((r12)*(x9783)*(x9784)))+(((IkReal(-1.00000000000000))*(r21)*(x9777)*(x9786)*(x9787)))+(((IkReal(-1.00000000000000))*(x9780)*(x9783)*(x9787)))+(((IkReal(-1.00000000000000))*(x9778)*(x9788)*(x9789)))+(((r02)*(x9779)*(x9781)))+(((IkReal(-1.00000000000000))*(r20)*(x9778)*(x9790)))+(((r11)*(x9786)*(x9789)))+(((IkReal(-1.00000000000000))*(r12)*(x9781)*(x9783)))+(((IkReal(-1.00000000000000))*(x9778)*(x9779)*(x9785)))+(((x9777)*(x9782)*(x9788)))+(((r11)*(x9783)*(x9785)))+(((IkReal(-1.00000000000000))*(r21)*(x9776)*(x9786)*(x9787)))+(((x9782)*(x9790)))+(((IkReal(-1.00000000000000))*(r02)*(x9779)*(x9784)))));
31467 IkReal x9791=(cj6)*(cj6);
31468 IkReal x9792=(sj6)*(sj6);
31469 IkReal x9793=((IkReal(1.00000000000000))*(r01));
31470 IkReal x9794=((sj0)*(sj5));
31471 IkReal x9795=((cj6)*(r22));
31472 IkReal x9796=((r21)*(sj6));
31473 IkReal x9797=((r00)*(r21));
31474 IkReal x9798=((cj0)*(sj5));
31475 IkReal x9799=((cj6)*(r20));
31476 IkReal x9800=((r22)*(sj6));
31477 IkReal x9801=((cj0)*(cj5));
31478 IkReal x9802=((IkReal(1.00000000000000))*(r10));
31479 IkReal x9803=((cj5)*(sj0));
31480 IkReal x9804=((r20)*(x9792));
31481 IkReal x9805=((x9791)*(x9803));
31482 dummyeval[0]=((((r12)*(x9798)*(x9799)))+(((r00)*(x9794)*(x9795)))+(((r11)*(x9801)*(x9804)))+(((IkReal(-1.00000000000000))*(r21)*(x9791)*(x9801)*(x9802)))+(((IkReal(-1.00000000000000))*(r20)*(x9793)*(x9805)))+(((r11)*(x9798)*(x9800)))+(((IkReal(-1.00000000000000))*(x9793)*(x9794)*(x9800)))+(((x9797)*(x9805)))+(((IkReal(-1.00000000000000))*(r12)*(x9796)*(x9798)))+(((r11)*(r20)*(x9791)*(x9801)))+(((IkReal(-1.00000000000000))*(r21)*(x9792)*(x9801)*(x9802)))+(((IkReal(-1.00000000000000))*(x9795)*(x9798)*(x9802)))+(((x9792)*(x9797)*(x9803)))+(((r02)*(x9794)*(x9796)))+(((IkReal(-1.00000000000000))*(x9793)*(x9803)*(x9804)))+(((IkReal(-1.00000000000000))*(r02)*(x9794)*(x9799))));
31483 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31484 {
31485 continue;
31486 
31487 } else
31488 {
31489 {
31490 IkReal j4array[1], cj4array[1], sj4array[1];
31491 bool j4valid[1]={false};
31492 _nj4 = 1;
31493 IkReal x9806=((sj0)*(sj6));
31494 IkReal x9807=((cj0)*(r10));
31495 IkReal x9808=((IkReal(1.00000000000000))*(cj5));
31496 IkReal x9809=((cj6)*(sj0));
31497 IkReal x9810=((cj0)*(r11));
31498 if( IKabs(((gconst34)*(((((cj6)*(x9807)))+(((IkReal(-1.00000000000000))*(sj6)*(x9810)))+(((IkReal(-1.00000000000000))*(r00)*(x9809)))+(((r01)*(x9806))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((((IkReal(-1.00000000000000))*(r00)*(x9806)*(x9808)))+(((cj5)*(sj6)*(x9807)))+(((IkReal(-1.00000000000000))*(r01)*(x9808)*(x9809)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x9810))))))) < IKFAST_ATAN2_MAGTHRESH )
31499     continue;
31500 j4array[0]=IKatan2(((gconst34)*(((((cj6)*(x9807)))+(((IkReal(-1.00000000000000))*(sj6)*(x9810)))+(((IkReal(-1.00000000000000))*(r00)*(x9809)))+(((r01)*(x9806)))))), ((gconst34)*(((((IkReal(-1.00000000000000))*(r00)*(x9806)*(x9808)))+(((cj5)*(sj6)*(x9807)))+(((IkReal(-1.00000000000000))*(r01)*(x9808)*(x9809)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(cj6)*(x9810)))))));
31501 sj4array[0]=IKsin(j4array[0]);
31502 cj4array[0]=IKcos(j4array[0]);
31503 if( j4array[0] > IKPI )
31504 {
31505     j4array[0]-=IK2PI;
31506 }
31507 else if( j4array[0] < -IKPI )
31508 {    j4array[0]+=IK2PI;
31509 }
31510 j4valid[0] = true;
31511 for(int ij4 = 0; ij4 < 1; ++ij4)
31512 {
31513 if( !j4valid[ij4] )
31514 {
31515     continue;
31516 }
31517 _ij4[0] = ij4; _ij4[1] = -1;
31518 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
31519 {
31520 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
31521 {
31522     j4valid[iij4]=false; _ij4[1] = iij4; break; 
31523 }
31524 }
31525 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
31526 {
31527 IkReal evalcond[6];
31528 IkReal x9811=IKsin(j4);
31529 IkReal x9812=IKcos(j4);
31530 IkReal x9813=((r22)*(sj5));
31531 IkReal x9814=((IkReal(1.00000000000000))*(cj6));
31532 IkReal x9815=((IkReal(1.00000000000000))*(cj0));
31533 IkReal x9816=((cj5)*(r11));
31534 IkReal x9817=((cj5)*(cj6));
31535 IkReal x9818=((r11)*(sj6));
31536 IkReal x9819=((IkReal(1.00000000000000))*(sj6));
31537 IkReal x9820=((cj6)*(r00));
31538 IkReal x9821=((r12)*(sj5));
31539 IkReal x9822=((r02)*(sj5));
31540 IkReal x9823=((cj6)*(r10));
31541 IkReal x9824=((cj5)*(sj6));
31542 IkReal x9825=((cj5)*(r01));
31543 IkReal x9826=((sj0)*(x9811));
31544 IkReal x9827=((r00)*(x9824));
31545 IkReal x9828=((cj0)*(x9811));
31546 IkReal x9829=((sj0)*(x9812));
31547 IkReal x9830=((r20)*(x9812));
31548 IkReal x9831=((cj0)*(x9812));
31549 IkReal x9832=((r21)*(x9811));
31550 IkReal x9833=((r21)*(x9812));
31551 IkReal x9834=((r20)*(x9811));
31552 IkReal x9835=((x9812)*(x9821));
31553 IkReal x9836=((r01)*(sj6)*(x9812));
31554 IkReal x9837=((cj5)*(r10)*(x9819));
31555 evalcond[0]=((IkReal(1.00000000000000))+(((sj6)*(x9833)))+(((x9811)*(x9813)))+(((x9824)*(x9834)))+(((IkReal(-1.00000000000000))*(x9814)*(x9830)))+(((x9817)*(x9832))));
31556 evalcond[1]=((((IkReal(-1.00000000000000))*(x9819)*(x9832)))+(((cj6)*(x9834)))+(((x9817)*(x9833)))+(((x9812)*(x9813)))+(((x9824)*(x9830))));
31557 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x9811)*(x9815)*(x9824)))+(((IkReal(-1.00000000000000))*(r00)*(x9814)*(x9829)))+(((x9826)*(x9827)))+(((IkReal(-1.00000000000000))*(x9814)*(x9816)*(x9828)))+(((r01)*(sj6)*(x9829)))+(((r01)*(x9817)*(x9826)))+(((x9822)*(x9826)))+(((IkReal(-1.00000000000000))*(x9812)*(x9815)*(x9818)))+(((IkReal(-1.00000000000000))*(x9811)*(x9815)*(x9821)))+(((x9823)*(x9831))));
31558 evalcond[3]=((((x9820)*(x9826)))+(((IkReal(-1.00000000000000))*(r01)*(x9819)*(x9826)))+(((r01)*(x9817)*(x9829)))+(((IkReal(-1.00000000000000))*(r10)*(x9812)*(x9815)*(x9824)))+(((x9822)*(x9829)))+(((IkReal(-1.00000000000000))*(x9814)*(x9816)*(x9831)))+(((IkReal(-1.00000000000000))*(r10)*(x9814)*(x9828)))+(((x9827)*(x9829)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x9818)*(x9828)))+(((IkReal(-1.00000000000000))*(x9815)*(x9835))));
31559 evalcond[4]=((((x9820)*(x9831)))+(((IkReal(-1.00000000000000))*(x9814)*(x9816)*(x9826)))+(((IkReal(-1.00000000000000))*(x9811)*(x9815)*(x9822)))+(((IkReal(-1.00000000000000))*(x9818)*(x9829)))+(((IkReal(-1.00000000000000))*(x9821)*(x9826)))+(((x9823)*(x9829)))+(((IkReal(-1.00000000000000))*(x9814)*(x9825)*(x9828)))+(((IkReal(-1.00000000000000))*(x9815)*(x9836)))+(((IkReal(-1.00000000000000))*(x9826)*(x9837)))+(((IkReal(-1.00000000000000))*(x9811)*(x9815)*(x9827))));
31560 evalcond[5]=((((r01)*(sj6)*(x9828)))+(((IkReal(-1.00000000000000))*(r10)*(x9814)*(x9826)))+(((IkReal(-1.00000000000000))*(x9812)*(x9815)*(x9822)))+(((IkReal(-1.00000000000000))*(x9812)*(x9815)*(x9827)))+(((IkReal(-1.00000000000000))*(x9814)*(x9816)*(x9829)))+(((IkReal(-1.00000000000000))*(x9821)*(x9829)))+(((x9818)*(x9826)))+(((IkReal(-1.00000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x9829)*(x9837)))+(((IkReal(-1.00000000000000))*(x9814)*(x9825)*(x9831)))+(((IkReal(-1.00000000000000))*(r00)*(x9814)*(x9828))));
31561 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
31562 {
31563 continue;
31564 }
31565 }
31566 
31567 {
31568 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
31569 vinfos[0].jointtype = 1;
31570 vinfos[0].foffset = j0;
31571 vinfos[0].indices[0] = _ij0[0];
31572 vinfos[0].indices[1] = _ij0[1];
31573 vinfos[0].maxsolutions = _nj0;
31574 vinfos[1].jointtype = 1;
31575 vinfos[1].foffset = j1;
31576 vinfos[1].indices[0] = _ij1[0];
31577 vinfos[1].indices[1] = _ij1[1];
31578 vinfos[1].maxsolutions = _nj1;
31579 vinfos[2].jointtype = 1;
31580 vinfos[2].foffset = j2;
31581 vinfos[2].indices[0] = _ij2[0];
31582 vinfos[2].indices[1] = _ij2[1];
31583 vinfos[2].maxsolutions = _nj2;
31584 vinfos[3].jointtype = 1;
31585 vinfos[3].foffset = j3;
31586 vinfos[3].indices[0] = _ij3[0];
31587 vinfos[3].indices[1] = _ij3[1];
31588 vinfos[3].maxsolutions = _nj3;
31589 vinfos[4].jointtype = 1;
31590 vinfos[4].foffset = j4;
31591 vinfos[4].indices[0] = _ij4[0];
31592 vinfos[4].indices[1] = _ij4[1];
31593 vinfos[4].maxsolutions = _nj4;
31594 vinfos[5].jointtype = 1;
31595 vinfos[5].foffset = j5;
31596 vinfos[5].indices[0] = _ij5[0];
31597 vinfos[5].indices[1] = _ij5[1];
31598 vinfos[5].maxsolutions = _nj5;
31599 vinfos[6].jointtype = 1;
31600 vinfos[6].foffset = j6;
31601 vinfos[6].indices[0] = _ij6[0];
31602 vinfos[6].indices[1] = _ij6[1];
31603 vinfos[6].maxsolutions = _nj6;
31604 std::vector<int> vfree(0);
31605 solutions.AddSolution(vinfos,vfree);
31606 }
31607 }
31608 }
31609 
31610 }
31611 
31612 }
31613 
31614 } else
31615 {
31616 {
31617 IkReal j4array[1], cj4array[1], sj4array[1];
31618 bool j4valid[1]={false};
31619 _nj4 = 1;
31620 if( IKabs(((gconst33)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
31621     continue;
31622 j4array[0]=IKatan2(((gconst33)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst33)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
31623 sj4array[0]=IKsin(j4array[0]);
31624 cj4array[0]=IKcos(j4array[0]);
31625 if( j4array[0] > IKPI )
31626 {
31627     j4array[0]-=IK2PI;
31628 }
31629 else if( j4array[0] < -IKPI )
31630 {    j4array[0]+=IK2PI;
31631 }
31632 j4valid[0] = true;
31633 for(int ij4 = 0; ij4 < 1; ++ij4)
31634 {
31635 if( !j4valid[ij4] )
31636 {
31637     continue;
31638 }
31639 _ij4[0] = ij4; _ij4[1] = -1;
31640 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
31641 {
31642 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
31643 {
31644     j4valid[iij4]=false; _ij4[1] = iij4; break; 
31645 }
31646 }
31647 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
31648 {
31649 IkReal evalcond[6];
31650 IkReal x9838=IKsin(j4);
31651 IkReal x9839=IKcos(j4);
31652 IkReal x9840=((r22)*(sj5));
31653 IkReal x9841=((IkReal(1.00000000000000))*(cj6));
31654 IkReal x9842=((IkReal(1.00000000000000))*(cj0));
31655 IkReal x9843=((cj5)*(r11));
31656 IkReal x9844=((cj5)*(cj6));
31657 IkReal x9845=((r11)*(sj6));
31658 IkReal x9846=((IkReal(1.00000000000000))*(sj6));
31659 IkReal x9847=((cj6)*(r00));
31660 IkReal x9848=((r12)*(sj5));
31661 IkReal x9849=((r02)*(sj5));
31662 IkReal x9850=((cj6)*(r10));
31663 IkReal x9851=((cj5)*(sj6));
31664 IkReal x9852=((cj5)*(r01));
31665 IkReal x9853=((sj0)*(x9838));
31666 IkReal x9854=((r00)*(x9851));
31667 IkReal x9855=((cj0)*(x9838));
31668 IkReal x9856=((sj0)*(x9839));
31669 IkReal x9857=((r20)*(x9839));
31670 IkReal x9858=((cj0)*(x9839));
31671 IkReal x9859=((r21)*(x9838));
31672 IkReal x9860=((r21)*(x9839));
31673 IkReal x9861=((r20)*(x9838));
31674 IkReal x9862=((x9839)*(x9848));
31675 IkReal x9863=((r01)*(sj6)*(x9839));
31676 IkReal x9864=((cj5)*(r10)*(x9846));
31677 evalcond[0]=((IkReal(1.00000000000000))+(((sj6)*(x9860)))+(((x9838)*(x9840)))+(((IkReal(-1.00000000000000))*(x9841)*(x9857)))+(((x9844)*(x9859)))+(((x9851)*(x9861))));
31678 evalcond[1]=((((x9844)*(x9860)))+(((cj6)*(x9861)))+(((x9839)*(x9840)))+(((IkReal(-1.00000000000000))*(x9846)*(x9859)))+(((x9851)*(x9857))));
31679 evalcond[2]=((((x9850)*(x9858)))+(((r01)*(x9844)*(x9853)))+(((r01)*(sj6)*(x9856)))+(((IkReal(-1.00000000000000))*(x9838)*(x9842)*(x9848)))+(((x9849)*(x9853)))+(((IkReal(-1.00000000000000))*(r00)*(x9841)*(x9856)))+(((IkReal(-1.00000000000000))*(r10)*(x9838)*(x9842)*(x9851)))+(((IkReal(-1.00000000000000))*(x9839)*(x9842)*(x9845)))+(((IkReal(-1.00000000000000))*(x9841)*(x9843)*(x9855)))+(((x9853)*(x9854))));
31680 evalcond[3]=((((IkReal(-1.00000000000000))*(x9841)*(x9843)*(x9858)))+(((x9845)*(x9855)))+(((IkReal(-1.00000000000000))*(r01)*(x9846)*(x9853)))+(((IkReal(-1.00000000000000))*(x9842)*(x9862)))+(((x9849)*(x9856)))+(((IkReal(-1.00000000000000))*(r10)*(x9839)*(x9842)*(x9851)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x9847)*(x9853)))+(((r01)*(x9844)*(x9856)))+(((x9854)*(x9856)))+(((IkReal(-1.00000000000000))*(r10)*(x9841)*(x9855))));
31681 evalcond[4]=((((IkReal(-1.00000000000000))*(x9838)*(x9842)*(x9854)))+(((x9850)*(x9856)))+(((IkReal(-1.00000000000000))*(x9841)*(x9852)*(x9855)))+(((IkReal(-1.00000000000000))*(x9845)*(x9856)))+(((IkReal(-1.00000000000000))*(x9842)*(x9863)))+(((IkReal(-1.00000000000000))*(x9848)*(x9853)))+(((x9847)*(x9858)))+(((IkReal(-1.00000000000000))*(x9841)*(x9843)*(x9853)))+(((IkReal(-1.00000000000000))*(x9838)*(x9842)*(x9849)))+(((IkReal(-1.00000000000000))*(x9853)*(x9864))));
31682 evalcond[5]=((((IkReal(-1.00000000000000))*(x9839)*(x9842)*(x9849)))+(((IkReal(-1.00000000000000))*(x9856)*(x9864)))+(((IkReal(-1.00000000000000))*(x9841)*(x9843)*(x9856)))+(((IkReal(-1.00000000000000))*(x9848)*(x9856)))+(((IkReal(-1.00000000000000))*(x9841)*(x9852)*(x9858)))+(((IkReal(-1.00000000000000))*(x9839)*(x9842)*(x9854)))+(((IkReal(-1.00000000000000))*(sj3)))+(((r01)*(sj6)*(x9855)))+(((IkReal(-1.00000000000000))*(r10)*(x9841)*(x9853)))+(((IkReal(-1.00000000000000))*(r00)*(x9841)*(x9855)))+(((x9845)*(x9853))));
31683 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
31684 {
31685 continue;
31686 }
31687 }
31688 
31689 {
31690 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
31691 vinfos[0].jointtype = 1;
31692 vinfos[0].foffset = j0;
31693 vinfos[0].indices[0] = _ij0[0];
31694 vinfos[0].indices[1] = _ij0[1];
31695 vinfos[0].maxsolutions = _nj0;
31696 vinfos[1].jointtype = 1;
31697 vinfos[1].foffset = j1;
31698 vinfos[1].indices[0] = _ij1[0];
31699 vinfos[1].indices[1] = _ij1[1];
31700 vinfos[1].maxsolutions = _nj1;
31701 vinfos[2].jointtype = 1;
31702 vinfos[2].foffset = j2;
31703 vinfos[2].indices[0] = _ij2[0];
31704 vinfos[2].indices[1] = _ij2[1];
31705 vinfos[2].maxsolutions = _nj2;
31706 vinfos[3].jointtype = 1;
31707 vinfos[3].foffset = j3;
31708 vinfos[3].indices[0] = _ij3[0];
31709 vinfos[3].indices[1] = _ij3[1];
31710 vinfos[3].maxsolutions = _nj3;
31711 vinfos[4].jointtype = 1;
31712 vinfos[4].foffset = j4;
31713 vinfos[4].indices[0] = _ij4[0];
31714 vinfos[4].indices[1] = _ij4[1];
31715 vinfos[4].maxsolutions = _nj4;
31716 vinfos[5].jointtype = 1;
31717 vinfos[5].foffset = j5;
31718 vinfos[5].indices[0] = _ij5[0];
31719 vinfos[5].indices[1] = _ij5[1];
31720 vinfos[5].maxsolutions = _nj5;
31721 vinfos[6].jointtype = 1;
31722 vinfos[6].foffset = j6;
31723 vinfos[6].indices[0] = _ij6[0];
31724 vinfos[6].indices[1] = _ij6[1];
31725 vinfos[6].maxsolutions = _nj6;
31726 std::vector<int> vfree(0);
31727 solutions.AddSolution(vinfos,vfree);
31728 }
31729 }
31730 }
31731 
31732 }
31733 
31734 }
31735 }
31736 }
31737 
31738 } else
31739 {
31740 IkReal x9865=((cj5)*(r22));
31741 IkReal x9866=((IkReal(0.374290000000000))*(sj5));
31742 IkReal x9867=((cj0)*(sj6));
31743 IkReal x9868=((cj6)*(r21));
31744 IkReal x9869=((IkReal(0.0100000000000000))*(sj5));
31745 IkReal x9870=((cj0)*(r02));
31746 IkReal x9871=((IkReal(0.0100000000000000))*(cj5));
31747 IkReal x9872=((IkReal(1.00000000000000))*(py));
31748 IkReal x9873=((r01)*(sj0));
31749 IkReal x9874=((r20)*(sj6));
31750 IkReal x9875=((r11)*(sj0));
31751 IkReal x9876=((IkReal(0.374290000000000))*(cj5));
31752 IkReal x9877=((cj0)*(r12));
31753 IkReal x9878=((sj0)*(x9876));
31754 IkReal x9879=((cj6)*(x9871));
31755 IkReal x9880=((r10)*(sj0)*(sj6));
31756 IkReal x9881=((r00)*(sj0)*(sj6));
31757 IkReal x9882=((cj0)*(cj6)*(x9866));
31758 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
31759 evalcond[1]=((((IkReal(-1.00000000000000))*(x9865)))+(((sj5)*(x9868)))+(((sj5)*(x9874))));
31760 evalcond[2]=((((IkReal(-1.00000000000000))*(x9868)*(x9871)))+(((IkReal(-0.374290000000000))*(x9865)))+(((IkReal(-1.00000000000000))*(r22)*(x9869)))+(((x9866)*(x9868)))+(((x9866)*(x9874)))+(((IkReal(-1.00000000000000))*(x9871)*(x9874)))+(pz));
31761 evalcond[3]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x9873)*(x9879)))+(((r10)*(x9867)*(x9871)))+(((cj6)*(x9866)*(x9873)))+(((IkReal(-1.00000000000000))*(x9871)*(x9881)))+(((IkReal(-1.00000000000000))*(r10)*(x9866)*(x9867)))+(((IkReal(-1.00000000000000))*(cj0)*(x9872)))+(((IkReal(-1.00000000000000))*(r02)*(x9878)))+(((x9866)*(x9881)))+(((cj0)*(r11)*(x9879)))+(((x9876)*(x9877)))+(((x9869)*(x9877)))+(((IkReal(-1.00000000000000))*(r11)*(x9882)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x9869))));
31762 evalcond[4]=((IkReal(-0.295420000000000))+(((r00)*(x9867)*(x9871)))+(((x9875)*(x9879)))+(((IkReal(-1.00000000000000))*(cj0)*(px)))+(((x9870)*(x9876)))+(((IkReal(-1.00000000000000))*(r01)*(x9882)))+(((IkReal(-1.00000000000000))*(x9866)*(x9880)))+(((r12)*(sj0)*(x9869)))+(((x9869)*(x9870)))+(((cj0)*(r01)*(x9879)))+(((IkReal(-1.00000000000000))*(sj0)*(x9872)))+(((IkReal(-1.00000000000000))*(r00)*(x9866)*(x9867)))+(((x9871)*(x9880)))+(((r12)*(x9878)))+(((IkReal(-1.00000000000000))*(cj6)*(x9866)*(x9875))));
31763 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  )
31764 {
31765 {
31766 IkReal j3array[1], cj3array[1], sj3array[1];
31767 bool j3valid[1]={false};
31768 _nj3 = 1;
31769 IkReal x9883=((IkReal(1.00000000000000))*(cj5));
31770 IkReal x9884=((r10)*(sj5)*(sj6));
31771 IkReal x9885=((cj6)*(sj0)*(sj5));
31772 IkReal x9886=((r00)*(sj5)*(sj6));
31773 IkReal x9887=((cj0)*(cj6)*(sj5));
31774 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x9883)))+(((cj0)*(x9884)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x9885)))+(((IkReal(-1.00000000000000))*(sj0)*(x9886)))+(((r11)*(x9887))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r11)*(x9885)))+(((r01)*(x9887)))+(((sj0)*(x9884)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9883)))+(((cj0)*(x9886)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9883))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x9883)))+(((cj0)*(x9884)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x9885)))+(((IkReal(-1.00000000000000))*(sj0)*(x9886)))+(((r11)*(x9887)))))+IKsqr(((((r11)*(x9885)))+(((r01)*(x9887)))+(((sj0)*(x9884)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9883)))+(((cj0)*(x9886)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9883)))))-1) <= IKFAST_SINCOS_THRESH )
31775     continue;
31776 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x9883)))+(((cj0)*(x9884)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x9885)))+(((IkReal(-1.00000000000000))*(sj0)*(x9886)))+(((r11)*(x9887)))), ((((r11)*(x9885)))+(((r01)*(x9887)))+(((sj0)*(x9884)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x9883)))+(((cj0)*(x9886)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x9883)))));
31777 sj3array[0]=IKsin(j3array[0]);
31778 cj3array[0]=IKcos(j3array[0]);
31779 if( j3array[0] > IKPI )
31780 {
31781     j3array[0]-=IK2PI;
31782 }
31783 else if( j3array[0] < -IKPI )
31784 {    j3array[0]+=IK2PI;
31785 }
31786 j3valid[0] = true;
31787 for(int ij3 = 0; ij3 < 1; ++ij3)
31788 {
31789 if( !j3valid[ij3] )
31790 {
31791     continue;
31792 }
31793 _ij3[0] = ij3; _ij3[1] = -1;
31794 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
31795 {
31796 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
31797 {
31798     j3valid[iij3]=false; _ij3[1] = iij3; break; 
31799 }
31800 }
31801 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
31802 {
31803 IkReal evalcond[2];
31804 IkReal x9888=((cj0)*(cj5));
31805 IkReal x9889=((IkReal(1.00000000000000))*(cj0));
31806 IkReal x9890=((cj6)*(r11));
31807 IkReal x9891=((r10)*(sj6));
31808 IkReal x9892=((cj5)*(sj0));
31809 IkReal x9893=((r00)*(sj5)*(sj6));
31810 IkReal x9894=((cj6)*(r01)*(sj5));
31811 IkReal x9895=((IkReal(1.00000000000000))*(sj0)*(sj5));
31812 evalcond[0]=((((sj0)*(x9893)))+(((IkReal(-1.00000000000000))*(sj5)*(x9889)*(x9891)))+(((r12)*(x9888)))+(((sj0)*(x9894)))+(((IkReal(-1.00000000000000))*(sj5)*(x9889)*(x9890)))+(IKsin(j3))+(((IkReal(-1.00000000000000))*(r02)*(x9892))));
31813 evalcond[1]=((((IkReal(-1.00000000000000))*(x9890)*(x9895)))+(((IkReal(-1.00000000000000))*(x9891)*(x9895)))+(((IkReal(-1.00000000000000))*(x9889)*(x9893)))+(((r02)*(x9888)))+(((r12)*(x9892)))+(IKcos(j3))+(((IkReal(-1.00000000000000))*(x9889)*(x9894))));
31814 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
31815 {
31816 continue;
31817 }
31818 }
31819 
31820 {
31821 IkReal dummyeval[1];
31822 IkReal gconst37;
31823 IkReal x9896=(cj5)*(cj5);
31824 IkReal x9897=(r20)*(r20);
31825 IkReal x9898=(sj6)*(sj6);
31826 IkReal x9899=(cj6)*(cj6);
31827 IkReal x9900=(r21)*(r21);
31828 IkReal x9901=((cj6)*(r21));
31829 IkReal x9902=((IkReal(2.00000000000000))*(r20)*(sj6));
31830 IkReal x9903=((cj5)*(r22)*(sj5));
31831 gconst37=IKsign(((((x9896)*(x9899)*(x9900)))+(((x9896)*(x9897)*(x9898)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x9902)*(x9903)))+(((x9898)*(x9900)))+(((IkReal(-1.00000000000000))*(x9901)*(x9902)))+(((IkReal(2.00000000000000))*(x9901)*(x9903)))+(((x9897)*(x9899)))+(((x9896)*(x9901)*(x9902)))));
31832 IkReal x9904=(cj5)*(cj5);
31833 IkReal x9905=(r20)*(r20);
31834 IkReal x9906=(sj6)*(sj6);
31835 IkReal x9907=(cj6)*(cj6);
31836 IkReal x9908=(r21)*(r21);
31837 IkReal x9909=((cj6)*(r21));
31838 IkReal x9910=((IkReal(2.00000000000000))*(r20)*(sj6));
31839 IkReal x9911=((cj5)*(r22)*(sj5));
31840 dummyeval[0]=((((x9906)*(x9908)))+(((x9904)*(x9905)*(x9906)))+(((IkReal(-1.00000000000000))*(x9909)*(x9910)))+((((r22)*(r22))*((sj5)*(sj5))))+(((x9910)*(x9911)))+(((IkReal(2.00000000000000))*(x9909)*(x9911)))+(((x9905)*(x9907)))+(((x9904)*(x9907)*(x9908)))+(((x9904)*(x9909)*(x9910))));
31841 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31842 {
31843 {
31844 IkReal dummyeval[1];
31845 IkReal gconst38;
31846 IkReal x9912=(cj6)*(cj6);
31847 IkReal x9913=(sj6)*(sj6);
31848 IkReal x9914=((IkReal(1.00000000000000))*(r21));
31849 IkReal x9915=((cj6)*(r20));
31850 IkReal x9916=((r22)*(sj5));
31851 IkReal x9917=((r01)*(sj0));
31852 IkReal x9918=((r00)*(sj0));
31853 IkReal x9919=((cj0)*(r10));
31854 IkReal x9920=((r02)*(sj0)*(sj5));
31855 IkReal x9921=((cj5)*(x9912));
31856 IkReal x9922=((cj0)*(r12)*(sj5));
31857 IkReal x9923=((IkReal(1.00000000000000))*(cj0)*(r11));
31858 IkReal x9924=((cj5)*(x9913));
31859 IkReal x9925=((r20)*(x9924));
31860 gconst38=IKsign(((((IkReal(-1.00000000000000))*(x9923)*(x9925)))+(((IkReal(-1.00000000000000))*(x9915)*(x9922)))+(((IkReal(-1.00000000000000))*(sj6)*(x9916)*(x9923)))+(((r21)*(x9919)*(x9921)))+(((cj6)*(x9916)*(x9919)))+(((IkReal(-1.00000000000000))*(x9914)*(x9918)*(x9924)))+(((IkReal(-1.00000000000000))*(r20)*(x9921)*(x9923)))+(((x9915)*(x9920)))+(((IkReal(-1.00000000000000))*(sj6)*(x9914)*(x9920)))+(((r21)*(x9919)*(x9924)))+(((sj6)*(x9916)*(x9917)))+(((r20)*(x9917)*(x9921)))+(((r21)*(sj6)*(x9922)))+(((x9917)*(x9925)))+(((IkReal(-1.00000000000000))*(cj6)*(x9916)*(x9918)))+(((IkReal(-1.00000000000000))*(x9914)*(x9918)*(x9921)))));
31861 IkReal x9926=(cj6)*(cj6);
31862 IkReal x9927=(sj6)*(sj6);
31863 IkReal x9928=((IkReal(1.00000000000000))*(r21));
31864 IkReal x9929=((cj6)*(r20));
31865 IkReal x9930=((r22)*(sj5));
31866 IkReal x9931=((r01)*(sj0));
31867 IkReal x9932=((r00)*(sj0));
31868 IkReal x9933=((cj0)*(r10));
31869 IkReal x9934=((r02)*(sj0)*(sj5));
31870 IkReal x9935=((cj5)*(x9926));
31871 IkReal x9936=((cj0)*(r12)*(sj5));
31872 IkReal x9937=((IkReal(1.00000000000000))*(cj0)*(r11));
31873 IkReal x9938=((cj5)*(x9927));
31874 IkReal x9939=((r20)*(x9938));
31875 dummyeval[0]=((((IkReal(-1.00000000000000))*(x9928)*(x9932)*(x9938)))+(((IkReal(-1.00000000000000))*(r20)*(x9935)*(x9937)))+(((IkReal(-1.00000000000000))*(x9929)*(x9936)))+(((sj6)*(x9930)*(x9931)))+(((x9929)*(x9934)))+(((IkReal(-1.00000000000000))*(cj6)*(x9930)*(x9932)))+(((IkReal(-1.00000000000000))*(x9928)*(x9932)*(x9935)))+(((r20)*(x9931)*(x9935)))+(((IkReal(-1.00000000000000))*(sj6)*(x9928)*(x9934)))+(((r21)*(x9933)*(x9938)))+(((r21)*(sj6)*(x9936)))+(((cj6)*(x9930)*(x9933)))+(((IkReal(-1.00000000000000))*(sj6)*(x9930)*(x9937)))+(((IkReal(-1.00000000000000))*(x9937)*(x9939)))+(((r21)*(x9933)*(x9935)))+(((x9931)*(x9939))));
31876 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
31877 {
31878 continue;
31879 
31880 } else
31881 {
31882 {
31883 IkReal j4array[1], cj4array[1], sj4array[1];
31884 bool j4valid[1]={false};
31885 _nj4 = 1;
31886 IkReal x9940=((sj0)*(sj6));
31887 IkReal x9941=((cj0)*(r10));
31888 IkReal x9942=((IkReal(1.00000000000000))*(cj5));
31889 IkReal x9943=((cj6)*(sj0));
31890 IkReal x9944=((cj0)*(r11));
31891 if( IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(sj6)*(x9944)))+(((IkReal(-1.00000000000000))*(r00)*(x9943)))+(((r01)*(x9940)))+(((cj6)*(x9941))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(r01)*(x9942)*(x9943)))+(((IkReal(-1.00000000000000))*(r00)*(x9940)*(x9942)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(sj6)*(x9941)))+(((cj5)*(cj6)*(x9944))))))) < IKFAST_ATAN2_MAGTHRESH )
31892     continue;
31893 j4array[0]=IKatan2(((gconst38)*(((((IkReal(-1.00000000000000))*(sj6)*(x9944)))+(((IkReal(-1.00000000000000))*(r00)*(x9943)))+(((r01)*(x9940)))+(((cj6)*(x9941)))))), ((gconst38)*(((((IkReal(-1.00000000000000))*(r01)*(x9942)*(x9943)))+(((IkReal(-1.00000000000000))*(r00)*(x9940)*(x9942)))+(((cj0)*(r12)*(sj5)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(sj5)))+(((cj5)*(sj6)*(x9941)))+(((cj5)*(cj6)*(x9944)))))));
31894 sj4array[0]=IKsin(j4array[0]);
31895 cj4array[0]=IKcos(j4array[0]);
31896 if( j4array[0] > IKPI )
31897 {
31898     j4array[0]-=IK2PI;
31899 }
31900 else if( j4array[0] < -IKPI )
31901 {    j4array[0]+=IK2PI;
31902 }
31903 j4valid[0] = true;
31904 for(int ij4 = 0; ij4 < 1; ++ij4)
31905 {
31906 if( !j4valid[ij4] )
31907 {
31908     continue;
31909 }
31910 _ij4[0] = ij4; _ij4[1] = -1;
31911 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
31912 {
31913 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
31914 {
31915     j4valid[iij4]=false; _ij4[1] = iij4; break; 
31916 }
31917 }
31918 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
31919 {
31920 IkReal evalcond[6];
31921 IkReal x9945=IKsin(j4);
31922 IkReal x9946=IKcos(j4);
31923 IkReal x9947=((r22)*(sj5));
31924 IkReal x9948=((IkReal(1.00000000000000))*(cj6));
31925 IkReal x9949=((IkReal(1.00000000000000))*(cj0));
31926 IkReal x9950=((cj5)*(r11));
31927 IkReal x9951=((cj5)*(cj6));
31928 IkReal x9952=((r11)*(sj6));
31929 IkReal x9953=((IkReal(1.00000000000000))*(sj6));
31930 IkReal x9954=((cj6)*(r00));
31931 IkReal x9955=((r12)*(sj5));
31932 IkReal x9956=((r02)*(sj5));
31933 IkReal x9957=((cj6)*(r10));
31934 IkReal x9958=((cj5)*(sj6));
31935 IkReal x9959=((cj5)*(r01));
31936 IkReal x9960=((sj0)*(x9945));
31937 IkReal x9961=((r00)*(x9958));
31938 IkReal x9962=((cj0)*(x9945));
31939 IkReal x9963=((sj0)*(x9946));
31940 IkReal x9964=((r20)*(x9946));
31941 IkReal x9965=((cj0)*(x9946));
31942 IkReal x9966=((r21)*(x9945));
31943 IkReal x9967=((r21)*(x9946));
31944 IkReal x9968=((r20)*(x9945));
31945 IkReal x9969=((x9946)*(x9955));
31946 IkReal x9970=((r01)*(sj6)*(x9946));
31947 IkReal x9971=((cj5)*(r10)*(x9953));
31948 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x9948)*(x9964)))+(((sj6)*(x9967)))+(((x9958)*(x9968)))+(((x9945)*(x9947)))+(((x9951)*(x9966))));
31949 evalcond[1]=((((cj6)*(x9968)))+(((IkReal(-1.00000000000000))*(x9953)*(x9966)))+(((x9958)*(x9964)))+(((x9946)*(x9947)))+(((x9951)*(x9967))));
31950 evalcond[2]=((((x9960)*(x9961)))+(((IkReal(-1.00000000000000))*(x9946)*(x9949)*(x9952)))+(((x9957)*(x9965)))+(((IkReal(-1.00000000000000))*(r00)*(x9948)*(x9963)))+(((IkReal(-1.00000000000000))*(r10)*(x9945)*(x9949)*(x9958)))+(((r01)*(x9951)*(x9960)))+(((IkReal(-1.00000000000000))*(x9945)*(x9949)*(x9955)))+(((r01)*(sj6)*(x9963)))+(((IkReal(-1.00000000000000))*(x9948)*(x9950)*(x9962)))+(((x9956)*(x9960))));
31951 evalcond[3]=((((x9961)*(x9963)))+(((IkReal(-1.00000000000000))*(r10)*(x9946)*(x9949)*(x9958)))+(((IkReal(-1.00000000000000))*(r01)*(x9953)*(x9960)))+(((x9952)*(x9962)))+(((x9956)*(x9963)))+(((IkReal(-1.00000000000000))*(x9948)*(x9950)*(x9965)))+(((IkReal(-1.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(r10)*(x9948)*(x9962)))+(((r01)*(x9951)*(x9963)))+(((x9954)*(x9960)))+(((IkReal(-1.00000000000000))*(x9949)*(x9969))));
31952 evalcond[4]=((((IkReal(-1.00000000000000))*(x9945)*(x9949)*(x9956)))+(((IkReal(-1.00000000000000))*(x9945)*(x9949)*(x9961)))+(((IkReal(-1.00000000000000))*(x9948)*(x9959)*(x9962)))+(((IkReal(-1.00000000000000))*(x9952)*(x9963)))+(((IkReal(-1.00000000000000))*(x9949)*(x9970)))+(((x9957)*(x9963)))+(((x9954)*(x9965)))+(((IkReal(-1.00000000000000))*(x9948)*(x9950)*(x9960)))+(((IkReal(-1.00000000000000))*(x9955)*(x9960)))+(((IkReal(-1.00000000000000))*(x9960)*(x9971))));
31953 evalcond[5]=((((IkReal(-1.00000000000000))*(x9963)*(x9971)))+(((IkReal(-1.00000000000000))*(x9955)*(x9963)))+(((IkReal(-1.00000000000000))*(x9948)*(x9950)*(x9963)))+(sj3)+(((IkReal(-1.00000000000000))*(x9946)*(x9949)*(x9956)))+(((x9952)*(x9960)))+(((IkReal(-1.00000000000000))*(x9948)*(x9959)*(x9965)))+(((r01)*(sj6)*(x9962)))+(((IkReal(-1.00000000000000))*(r00)*(x9948)*(x9962)))+(((IkReal(-1.00000000000000))*(r10)*(x9948)*(x9960)))+(((IkReal(-1.00000000000000))*(x9946)*(x9949)*(x9961))));
31954 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
31955 {
31956 continue;
31957 }
31958 }
31959 
31960 {
31961 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
31962 vinfos[0].jointtype = 1;
31963 vinfos[0].foffset = j0;
31964 vinfos[0].indices[0] = _ij0[0];
31965 vinfos[0].indices[1] = _ij0[1];
31966 vinfos[0].maxsolutions = _nj0;
31967 vinfos[1].jointtype = 1;
31968 vinfos[1].foffset = j1;
31969 vinfos[1].indices[0] = _ij1[0];
31970 vinfos[1].indices[1] = _ij1[1];
31971 vinfos[1].maxsolutions = _nj1;
31972 vinfos[2].jointtype = 1;
31973 vinfos[2].foffset = j2;
31974 vinfos[2].indices[0] = _ij2[0];
31975 vinfos[2].indices[1] = _ij2[1];
31976 vinfos[2].maxsolutions = _nj2;
31977 vinfos[3].jointtype = 1;
31978 vinfos[3].foffset = j3;
31979 vinfos[3].indices[0] = _ij3[0];
31980 vinfos[3].indices[1] = _ij3[1];
31981 vinfos[3].maxsolutions = _nj3;
31982 vinfos[4].jointtype = 1;
31983 vinfos[4].foffset = j4;
31984 vinfos[4].indices[0] = _ij4[0];
31985 vinfos[4].indices[1] = _ij4[1];
31986 vinfos[4].maxsolutions = _nj4;
31987 vinfos[5].jointtype = 1;
31988 vinfos[5].foffset = j5;
31989 vinfos[5].indices[0] = _ij5[0];
31990 vinfos[5].indices[1] = _ij5[1];
31991 vinfos[5].maxsolutions = _nj5;
31992 vinfos[6].jointtype = 1;
31993 vinfos[6].foffset = j6;
31994 vinfos[6].indices[0] = _ij6[0];
31995 vinfos[6].indices[1] = _ij6[1];
31996 vinfos[6].maxsolutions = _nj6;
31997 std::vector<int> vfree(0);
31998 solutions.AddSolution(vinfos,vfree);
31999 }
32000 }
32001 }
32002 
32003 }
32004 
32005 }
32006 
32007 } else
32008 {
32009 {
32010 IkReal j4array[1], cj4array[1], sj4array[1];
32011 bool j4valid[1]={false};
32012 _nj4 = 1;
32013 if( IKabs(((gconst37)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20))))))) < IKFAST_ATAN2_MAGTHRESH )
32014     continue;
32015 j4array[0]=IKatan2(((gconst37)*(((((cj5)*(r20)*(sj6)))+(((r22)*(sj5)))+(((cj5)*(cj6)*(r21)))))), ((gconst37)*(((((r21)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)))))));
32016 sj4array[0]=IKsin(j4array[0]);
32017 cj4array[0]=IKcos(j4array[0]);
32018 if( j4array[0] > IKPI )
32019 {
32020     j4array[0]-=IK2PI;
32021 }
32022 else if( j4array[0] < -IKPI )
32023 {    j4array[0]+=IK2PI;
32024 }
32025 j4valid[0] = true;
32026 for(int ij4 = 0; ij4 < 1; ++ij4)
32027 {
32028 if( !j4valid[ij4] )
32029 {
32030     continue;
32031 }
32032 _ij4[0] = ij4; _ij4[1] = -1;
32033 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
32034 {
32035 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
32036 {
32037     j4valid[iij4]=false; _ij4[1] = iij4; break; 
32038 }
32039 }
32040 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
32041 {
32042 IkReal evalcond[6];
32043 IkReal x9972=IKsin(j4);
32044 IkReal x9973=IKcos(j4);
32045 IkReal x9974=((r22)*(sj5));
32046 IkReal x9975=((IkReal(1.00000000000000))*(cj6));
32047 IkReal x9976=((IkReal(1.00000000000000))*(cj0));
32048 IkReal x9977=((cj5)*(r11));
32049 IkReal x9978=((cj5)*(cj6));
32050 IkReal x9979=((r11)*(sj6));
32051 IkReal x9980=((IkReal(1.00000000000000))*(sj6));
32052 IkReal x9981=((cj6)*(r00));
32053 IkReal x9982=((r12)*(sj5));
32054 IkReal x9983=((r02)*(sj5));
32055 IkReal x9984=((cj6)*(r10));
32056 IkReal x9985=((cj5)*(sj6));
32057 IkReal x9986=((cj5)*(r01));
32058 IkReal x9987=((sj0)*(x9972));
32059 IkReal x9988=((r00)*(x9985));
32060 IkReal x9989=((cj0)*(x9972));
32061 IkReal x9990=((sj0)*(x9973));
32062 IkReal x9991=((r20)*(x9973));
32063 IkReal x9992=((cj0)*(x9973));
32064 IkReal x9993=((r21)*(x9972));
32065 IkReal x9994=((r21)*(x9973));
32066 IkReal x9995=((r20)*(x9972));
32067 IkReal x9996=((x9973)*(x9982));
32068 IkReal x9997=((r01)*(sj6)*(x9973));
32069 IkReal x9998=((cj5)*(r10)*(x9980));
32070 evalcond[0]=((IkReal(-1.00000000000000))+(((x9978)*(x9993)))+(((x9972)*(x9974)))+(((x9985)*(x9995)))+(((IkReal(-1.00000000000000))*(x9975)*(x9991)))+(((sj6)*(x9994))));
32071 evalcond[1]=((((x9978)*(x9994)))+(((x9973)*(x9974)))+(((IkReal(-1.00000000000000))*(x9980)*(x9993)))+(((x9985)*(x9991)))+(((cj6)*(x9995))));
32072 evalcond[2]=((((IkReal(-1.00000000000000))*(x9972)*(x9976)*(x9982)))+(((IkReal(-1.00000000000000))*(x9975)*(x9977)*(x9989)))+(((r01)*(x9978)*(x9987)))+(((IkReal(-1.00000000000000))*(r00)*(x9975)*(x9990)))+(((r01)*(sj6)*(x9990)))+(((IkReal(-1.00000000000000))*(r10)*(x9972)*(x9976)*(x9985)))+(((x9987)*(x9988)))+(((IkReal(-1.00000000000000))*(x9973)*(x9976)*(x9979)))+(((x9984)*(x9992)))+(((x9983)*(x9987))));
32073 evalcond[3]=((((IkReal(-1.00000000000000))*(x9976)*(x9996)))+(((x9979)*(x9989)))+(((x9988)*(x9990)))+(((IkReal(-1.00000000000000))*(r10)*(x9973)*(x9976)*(x9985)))+(((IkReal(-1.00000000000000))*(r01)*(x9980)*(x9987)))+(((x9983)*(x9990)))+(((IkReal(-1.00000000000000))*(x9975)*(x9977)*(x9992)))+(((x9981)*(x9987)))+(((IkReal(-1.00000000000000))*(cj3)))+(((r01)*(x9978)*(x9990)))+(((IkReal(-1.00000000000000))*(r10)*(x9975)*(x9989))));
32074 evalcond[4]=((((IkReal(-1.00000000000000))*(x9972)*(x9976)*(x9983)))+(((IkReal(-1.00000000000000))*(x9987)*(x9998)))+(((IkReal(-1.00000000000000))*(x9982)*(x9987)))+(((IkReal(-1.00000000000000))*(x9972)*(x9976)*(x9988)))+(((IkReal(-1.00000000000000))*(x9976)*(x9997)))+(((IkReal(-1.00000000000000))*(x9979)*(x9990)))+(((IkReal(-1.00000000000000))*(x9975)*(x9986)*(x9989)))+(((IkReal(-1.00000000000000))*(x9975)*(x9977)*(x9987)))+(((x9984)*(x9990)))+(((x9981)*(x9992))));
32075 evalcond[5]=((((IkReal(-1.00000000000000))*(x9973)*(x9976)*(x9988)))+(sj3)+(((IkReal(-1.00000000000000))*(x9975)*(x9986)*(x9992)))+(((IkReal(-1.00000000000000))*(x9990)*(x9998)))+(((IkReal(-1.00000000000000))*(r10)*(x9975)*(x9987)))+(((IkReal(-1.00000000000000))*(r00)*(x9975)*(x9989)))+(((x9979)*(x9987)))+(((IkReal(-1.00000000000000))*(x9975)*(x9977)*(x9990)))+(((IkReal(-1.00000000000000))*(x9982)*(x9990)))+(((r01)*(sj6)*(x9989)))+(((IkReal(-1.00000000000000))*(x9973)*(x9976)*(x9983))));
32076 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
32077 {
32078 continue;
32079 }
32080 }
32081 
32082 {
32083 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
32084 vinfos[0].jointtype = 1;
32085 vinfos[0].foffset = j0;
32086 vinfos[0].indices[0] = _ij0[0];
32087 vinfos[0].indices[1] = _ij0[1];
32088 vinfos[0].maxsolutions = _nj0;
32089 vinfos[1].jointtype = 1;
32090 vinfos[1].foffset = j1;
32091 vinfos[1].indices[0] = _ij1[0];
32092 vinfos[1].indices[1] = _ij1[1];
32093 vinfos[1].maxsolutions = _nj1;
32094 vinfos[2].jointtype = 1;
32095 vinfos[2].foffset = j2;
32096 vinfos[2].indices[0] = _ij2[0];
32097 vinfos[2].indices[1] = _ij2[1];
32098 vinfos[2].maxsolutions = _nj2;
32099 vinfos[3].jointtype = 1;
32100 vinfos[3].foffset = j3;
32101 vinfos[3].indices[0] = _ij3[0];
32102 vinfos[3].indices[1] = _ij3[1];
32103 vinfos[3].maxsolutions = _nj3;
32104 vinfos[4].jointtype = 1;
32105 vinfos[4].foffset = j4;
32106 vinfos[4].indices[0] = _ij4[0];
32107 vinfos[4].indices[1] = _ij4[1];
32108 vinfos[4].maxsolutions = _nj4;
32109 vinfos[5].jointtype = 1;
32110 vinfos[5].foffset = j5;
32111 vinfos[5].indices[0] = _ij5[0];
32112 vinfos[5].indices[1] = _ij5[1];
32113 vinfos[5].maxsolutions = _nj5;
32114 vinfos[6].jointtype = 1;
32115 vinfos[6].foffset = j6;
32116 vinfos[6].indices[0] = _ij6[0];
32117 vinfos[6].indices[1] = _ij6[1];
32118 vinfos[6].maxsolutions = _nj6;
32119 std::vector<int> vfree(0);
32120 solutions.AddSolution(vinfos,vfree);
32121 }
32122 }
32123 }
32124 
32125 }
32126 
32127 }
32128 }
32129 }
32130 
32131 } else
32132 {
32133 if( 1 )
32134 {
32135 continue;
32136 
32137 } else
32138 {
32139 }
32140 }
32141 }
32142 }
32143 
32144 } else
32145 {
32146 {
32147 IkReal j3array[1], cj3array[1], sj3array[1];
32148 bool j3valid[1]={false};
32149 _nj3 = 1;
32150 IkReal x9999=((sj5)*(sj6));
32151 IkReal x10000=((IkReal(1.00000000000000))*(sj0));
32152 IkReal x10001=((cj6)*(sj5));
32153 IkReal x10002=((IkReal(1.00000000000000))*(cj5));
32154 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10002)))+(((IkReal(-1.00000000000000))*(r01)*(x10000)*(x10001)))+(((cj0)*(r11)*(x10001)))+(((IkReal(-1.00000000000000))*(r00)*(x10000)*(x9999)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x9999))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x9999)))+(((IkReal(-1.00000000000000))*(r22)*(x10002)))+(((r21)*(x10001))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10002)))+(((IkReal(-1.00000000000000))*(r01)*(x10000)*(x10001)))+(((cj0)*(r11)*(x10001)))+(((IkReal(-1.00000000000000))*(r00)*(x10000)*(x9999)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x9999)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x9999)))+(((IkReal(-1.00000000000000))*(r22)*(x10002)))+(((r21)*(x10001)))))))-1) <= IKFAST_SINCOS_THRESH )
32155     continue;
32156 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10002)))+(((IkReal(-1.00000000000000))*(r01)*(x10000)*(x10001)))+(((cj0)*(r11)*(x10001)))+(((IkReal(-1.00000000000000))*(r00)*(x10000)*(x9999)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r10)*(x9999)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r20)*(x9999)))+(((IkReal(-1.00000000000000))*(r22)*(x10002)))+(((r21)*(x10001)))))));
32157 sj3array[0]=IKsin(j3array[0]);
32158 cj3array[0]=IKcos(j3array[0]);
32159 if( j3array[0] > IKPI )
32160 {
32161     j3array[0]-=IK2PI;
32162 }
32163 else if( j3array[0] < -IKPI )
32164 {    j3array[0]+=IK2PI;
32165 }
32166 j3valid[0] = true;
32167 for(int ij3 = 0; ij3 < 1; ++ij3)
32168 {
32169 if( !j3valid[ij3] )
32170 {
32171     continue;
32172 }
32173 _ij3[0] = ij3; _ij3[1] = -1;
32174 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
32175 {
32176 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
32177 {
32178     j3valid[iij3]=false; _ij3[1] = iij3; break; 
32179 }
32180 }
32181 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
32182 {
32183 IkReal evalcond[3];
32184 IkReal x10003=IKcos(j3);
32185 IkReal x10004=((sj5)*(sj6));
32186 IkReal x10005=((cj0)*(cj5));
32187 IkReal x10006=((IkReal(1.00000000000000))*(cj0));
32188 IkReal x10007=((IkReal(1.00000000000000))*(sj0));
32189 IkReal x10008=((IkReal(1.00000000000000))*(x10003));
32190 IkReal x10009=((cj6)*(r01)*(sj5));
32191 IkReal x10010=((cj6)*(r11)*(sj5));
32192 evalcond[0]=((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x10008)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x10004))));
32193 evalcond[1]=((((IkReal(-1.00000000000000))*(x10006)*(x10010)))+(((sj0)*(x10009)))+(((r12)*(x10005)))+(((IkReal(-1.00000000000000))*(r10)*(x10004)*(x10006)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x10007)))+(IKsin(j3))+(((r00)*(sj0)*(x10004))));
32194 evalcond[2]=((((IkReal(-1.00000000000000))*(x10007)*(x10010)))+(((IkReal(-1.00000000000000))*(r00)*(x10004)*(x10006)))+(((cj5)*(r12)*(sj0)))+(((r02)*(x10005)))+(((IkReal(-1.00000000000000))*(r10)*(x10004)*(x10007)))+(((IkReal(-1.00000000000000))*(cj1)*(x10008)))+(((IkReal(-1.00000000000000))*(x10006)*(x10009))));
32195 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
32196 {
32197 continue;
32198 }
32199 }
32200 
32201 {
32202 IkReal dummyeval[1];
32203 IkReal gconst28;
32204 IkReal x10011=(r21)*(r21);
32205 IkReal x10012=(cj5)*(cj5);
32206 IkReal x10013=(sj6)*(sj6);
32207 IkReal x10014=(cj6)*(cj6);
32208 IkReal x10015=(r20)*(r20);
32209 IkReal x10016=((cj6)*(r21));
32210 IkReal x10017=((IkReal(2.00000000000000))*(r20)*(sj6));
32211 IkReal x10018=((cj5)*(r22)*(sj5));
32212 IkReal x10019=((IkReal(1.00000000000000))*(x10013));
32213 IkReal x10020=((IkReal(1.00000000000000))*(x10014));
32214 gconst28=IKsign(((((IkReal(-1.00000000000000))*(x10011)*(x10012)*(x10020)))+(((IkReal(-1.00000000000000))*(x10012)*(x10016)*(x10017)))+(((IkReal(-2.00000000000000))*(x10016)*(x10018)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x10015)*(x10020)))+(((IkReal(-1.00000000000000))*(x10011)*(x10019)))+(((x10016)*(x10017)))+(((IkReal(-1.00000000000000))*(x10012)*(x10015)*(x10019)))+(((IkReal(-1.00000000000000))*(x10017)*(x10018)))));
32215 IkReal x10021=(r21)*(r21);
32216 IkReal x10022=(cj5)*(cj5);
32217 IkReal x10023=(sj6)*(sj6);
32218 IkReal x10024=(cj6)*(cj6);
32219 IkReal x10025=(r20)*(r20);
32220 IkReal x10026=((cj6)*(r21));
32221 IkReal x10027=((IkReal(2.00000000000000))*(r20)*(sj6));
32222 IkReal x10028=((cj5)*(r22)*(sj5));
32223 IkReal x10029=((IkReal(1.00000000000000))*(x10023));
32224 IkReal x10030=((IkReal(1.00000000000000))*(x10024));
32225 dummyeval[0]=((((IkReal(-1.00000000000000))*(x10022)*(x10025)*(x10029)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x10021)*(x10022)*(x10030)))+(((IkReal(-1.00000000000000))*(x10025)*(x10030)))+(((IkReal(-1.00000000000000))*(x10022)*(x10026)*(x10027)))+(((IkReal(-2.00000000000000))*(x10026)*(x10028)))+(((x10026)*(x10027)))+(((IkReal(-1.00000000000000))*(x10021)*(x10029)))+(((IkReal(-1.00000000000000))*(x10027)*(x10028))));
32226 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
32227 {
32228 {
32229 IkReal dummyeval[1];
32230 IkReal gconst29;
32231 IkReal x10031=(cj6)*(cj6);
32232 IkReal x10032=(sj6)*(sj6);
32233 IkReal x10033=((IkReal(1.00000000000000))*(r01));
32234 IkReal x10034=((sj0)*(sj5));
32235 IkReal x10035=((cj6)*(r22));
32236 IkReal x10036=((r21)*(sj6));
32237 IkReal x10037=((r00)*(r21));
32238 IkReal x10038=((cj0)*(sj5));
32239 IkReal x10039=((cj6)*(r20));
32240 IkReal x10040=((r22)*(sj6));
32241 IkReal x10041=((cj0)*(cj5));
32242 IkReal x10042=((IkReal(1.00000000000000))*(r10));
32243 IkReal x10043=((cj5)*(sj0));
32244 IkReal x10044=((r20)*(x10032));
32245 IkReal x10045=((x10031)*(x10043));
32246 gconst29=IKsign(((((r11)*(r20)*(x10031)*(x10041)))+(((IkReal(-1.00000000000000))*(r21)*(x10031)*(x10041)*(x10042)))+(((IkReal(-1.00000000000000))*(r20)*(x10033)*(x10045)))+(((r12)*(x10038)*(x10039)))+(((IkReal(-1.00000000000000))*(r12)*(x10036)*(x10038)))+(((IkReal(-1.00000000000000))*(x10033)*(x10034)*(x10040)))+(((IkReal(-1.00000000000000))*(r21)*(x10032)*(x10041)*(x10042)))+(((r02)*(x10034)*(x10036)))+(((IkReal(-1.00000000000000))*(x10033)*(x10043)*(x10044)))+(((r11)*(x10041)*(x10044)))+(((IkReal(-1.00000000000000))*(x10035)*(x10038)*(x10042)))+(((IkReal(-1.00000000000000))*(r02)*(x10034)*(x10039)))+(((x10037)*(x10045)))+(((r00)*(x10034)*(x10035)))+(((x10032)*(x10037)*(x10043)))+(((r11)*(x10038)*(x10040)))));
32247 IkReal x10046=(cj6)*(cj6);
32248 IkReal x10047=(sj6)*(sj6);
32249 IkReal x10048=((IkReal(1.00000000000000))*(r01));
32250 IkReal x10049=((sj0)*(sj5));
32251 IkReal x10050=((cj6)*(r22));
32252 IkReal x10051=((r21)*(sj6));
32253 IkReal x10052=((r00)*(r21));
32254 IkReal x10053=((cj0)*(sj5));
32255 IkReal x10054=((cj6)*(r20));
32256 IkReal x10055=((r22)*(sj6));
32257 IkReal x10056=((cj0)*(cj5));
32258 IkReal x10057=((IkReal(1.00000000000000))*(r10));
32259 IkReal x10058=((cj5)*(sj0));
32260 IkReal x10059=((r20)*(x10047));
32261 IkReal x10060=((x10046)*(x10058));
32262 dummyeval[0]=((((r11)*(x10053)*(x10055)))+(((x10047)*(x10052)*(x10058)))+(((r11)*(r20)*(x10046)*(x10056)))+(((r12)*(x10053)*(x10054)))+(((IkReal(-1.00000000000000))*(r20)*(x10048)*(x10060)))+(((IkReal(-1.00000000000000))*(x10048)*(x10058)*(x10059)))+(((IkReal(-1.00000000000000))*(x10050)*(x10053)*(x10057)))+(((r00)*(x10049)*(x10050)))+(((IkReal(-1.00000000000000))*(x10048)*(x10049)*(x10055)))+(((IkReal(-1.00000000000000))*(r02)*(x10049)*(x10054)))+(((x10052)*(x10060)))+(((IkReal(-1.00000000000000))*(r21)*(x10047)*(x10056)*(x10057)))+(((IkReal(-1.00000000000000))*(r21)*(x10046)*(x10056)*(x10057)))+(((r11)*(x10056)*(x10059)))+(((IkReal(-1.00000000000000))*(r12)*(x10051)*(x10053)))+(((r02)*(x10049)*(x10051))));
32263 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
32264 {
32265 continue;
32266 
32267 } else
32268 {
32269 {
32270 IkReal j4array[1], cj4array[1], sj4array[1];
32271 bool j4valid[1]={false};
32272 _nj4 = 1;
32273 IkReal x10061=((cj1)*(cj6));
32274 IkReal x10062=((IkReal(1.00000000000000))*(sj0));
32275 IkReal x10063=((cj0)*(r10));
32276 IkReal x10064=((cj1)*(sj5));
32277 IkReal x10065=((cj1)*(sj6));
32278 IkReal x10066=((cj0)*(r11));
32279 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(r00)*(x10061)*(x10062)))+(((x10061)*(x10063)))+(((IkReal(-1.00000000000000))*(x10065)*(x10066)))+(((r01)*(sj0)*(x10065))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10061)*(x10062)))+(((IkReal(-1.00000000000000))*(r02)*(x10062)*(x10064)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10062)*(x10065)))+(((cj0)*(r12)*(x10064)))+(((cj5)*(x10063)*(x10065)))+(((cj5)*(x10061)*(x10066))))))) < IKFAST_ATAN2_MAGTHRESH )
32280     continue;
32281 j4array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(r00)*(x10061)*(x10062)))+(((x10061)*(x10063)))+(((IkReal(-1.00000000000000))*(x10065)*(x10066)))+(((r01)*(sj0)*(x10065)))))), ((gconst29)*(((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10061)*(x10062)))+(((IkReal(-1.00000000000000))*(r02)*(x10062)*(x10064)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10062)*(x10065)))+(((cj0)*(r12)*(x10064)))+(((cj5)*(x10063)*(x10065)))+(((cj5)*(x10061)*(x10066)))))));
32282 sj4array[0]=IKsin(j4array[0]);
32283 cj4array[0]=IKcos(j4array[0]);
32284 if( j4array[0] > IKPI )
32285 {
32286     j4array[0]-=IK2PI;
32287 }
32288 else if( j4array[0] < -IKPI )
32289 {    j4array[0]+=IK2PI;
32290 }
32291 j4valid[0] = true;
32292 for(int ij4 = 0; ij4 < 1; ++ij4)
32293 {
32294 if( !j4valid[ij4] )
32295 {
32296     continue;
32297 }
32298 _ij4[0] = ij4; _ij4[1] = -1;
32299 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
32300 {
32301 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
32302 {
32303     j4valid[iij4]=false; _ij4[1] = iij4; break; 
32304 }
32305 }
32306 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
32307 {
32308 IkReal evalcond[6];
32309 IkReal x10067=IKsin(j4);
32310 IkReal x10068=IKcos(j4);
32311 IkReal x10069=((r22)*(sj5));
32312 IkReal x10070=((IkReal(1.00000000000000))*(cj6));
32313 IkReal x10071=((IkReal(1.00000000000000))*(cj0));
32314 IkReal x10072=((IkReal(1.00000000000000))*(sj1));
32315 IkReal x10073=((cj5)*(r11));
32316 IkReal x10074=((cj5)*(cj6));
32317 IkReal x10075=((r11)*(sj6));
32318 IkReal x10076=((IkReal(1.00000000000000))*(sj6));
32319 IkReal x10077=((cj6)*(r00));
32320 IkReal x10078=((r12)*(sj5));
32321 IkReal x10079=((r02)*(sj5));
32322 IkReal x10080=((cj6)*(r10));
32323 IkReal x10081=((cj5)*(sj6));
32324 IkReal x10082=((cj5)*(r01));
32325 IkReal x10083=((sj0)*(x10067));
32326 IkReal x10084=((r00)*(x10081));
32327 IkReal x10085=((cj0)*(x10067));
32328 IkReal x10086=((sj0)*(x10068));
32329 IkReal x10087=((r20)*(x10068));
32330 IkReal x10088=((cj0)*(x10068));
32331 IkReal x10089=((r21)*(x10067));
32332 IkReal x10090=((r21)*(x10068));
32333 IkReal x10091=((r20)*(x10067));
32334 IkReal x10092=((x10068)*(x10078));
32335 IkReal x10093=((r01)*(sj6)*(x10068));
32336 IkReal x10094=((cj5)*(r10)*(x10076));
32337 evalcond[0]=((((IkReal(-1.00000000000000))*(x10070)*(x10087)))+(((x10074)*(x10089)))+(cj1)+(((x10081)*(x10091)))+(((sj6)*(x10090)))+(((x10067)*(x10069))));
32338 evalcond[1]=((((IkReal(-1.00000000000000))*(sj3)*(x10072)))+(((x10074)*(x10090)))+(((cj6)*(x10091)))+(((IkReal(-1.00000000000000))*(x10076)*(x10089)))+(((x10081)*(x10087)))+(((x10068)*(x10069))));
32339 evalcond[2]=((((IkReal(-1.00000000000000))*(x10068)*(x10071)*(x10075)))+(((x10080)*(x10088)))+(((r01)*(x10074)*(x10083)))+(((r01)*(sj6)*(x10086)))+(((x10079)*(x10083)))+(((IkReal(-1.00000000000000))*(r00)*(x10070)*(x10086)))+(((IkReal(-1.00000000000000))*(r10)*(x10067)*(x10071)*(x10081)))+(((x10083)*(x10084)))+(((IkReal(-1.00000000000000))*(x10070)*(x10073)*(x10085)))+(((IkReal(-1.00000000000000))*(x10067)*(x10071)*(x10078))));
32340 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x10068)*(x10071)*(x10081)))+(((IkReal(-1.00000000000000))*(r10)*(x10070)*(x10085)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x10084)*(x10086)))+(((IkReal(-1.00000000000000))*(r01)*(x10076)*(x10083)))+(((IkReal(-1.00000000000000))*(x10071)*(x10092)))+(((x10079)*(x10086)))+(((IkReal(-1.00000000000000))*(x10070)*(x10073)*(x10088)))+(((x10075)*(x10085)))+(((x10077)*(x10083)))+(((r01)*(x10074)*(x10086))));
32341 evalcond[4]=((((IkReal(-1.00000000000000))*(x10078)*(x10083)))+(((IkReal(-1.00000000000000))*(x10067)*(x10071)*(x10084)))+(((IkReal(-1.00000000000000))*(x10083)*(x10094)))+(((IkReal(-1.00000000000000))*(x10070)*(x10082)*(x10085)))+(((x10077)*(x10088)))+(((IkReal(-1.00000000000000))*(x10067)*(x10071)*(x10079)))+(((IkReal(-1.00000000000000))*(x10070)*(x10073)*(x10083)))+(((IkReal(-1.00000000000000))*(x10075)*(x10086)))+(((IkReal(-1.00000000000000))*(x10071)*(x10093)))+(((x10080)*(x10086)))+(((IkReal(-1.00000000000000))*(x10072))));
32342 evalcond[5]=((((IkReal(-1.00000000000000))*(x10070)*(x10082)*(x10088)))+(((IkReal(-1.00000000000000))*(x10068)*(x10071)*(x10079)))+(((IkReal(-1.00000000000000))*(x10078)*(x10086)))+(((IkReal(-1.00000000000000))*(x10070)*(x10073)*(x10086)))+(((IkReal(-1.00000000000000))*(r00)*(x10070)*(x10085)))+(((IkReal(-1.00000000000000))*(x10086)*(x10094)))+(((IkReal(-1.00000000000000))*(r10)*(x10070)*(x10083)))+(((IkReal(-1.00000000000000))*(cj1)*(sj3)))+(((r01)*(sj6)*(x10085)))+(((IkReal(-1.00000000000000))*(x10068)*(x10071)*(x10084)))+(((x10075)*(x10083))));
32343 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
32344 {
32345 continue;
32346 }
32347 }
32348 
32349 {
32350 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
32351 vinfos[0].jointtype = 1;
32352 vinfos[0].foffset = j0;
32353 vinfos[0].indices[0] = _ij0[0];
32354 vinfos[0].indices[1] = _ij0[1];
32355 vinfos[0].maxsolutions = _nj0;
32356 vinfos[1].jointtype = 1;
32357 vinfos[1].foffset = j1;
32358 vinfos[1].indices[0] = _ij1[0];
32359 vinfos[1].indices[1] = _ij1[1];
32360 vinfos[1].maxsolutions = _nj1;
32361 vinfos[2].jointtype = 1;
32362 vinfos[2].foffset = j2;
32363 vinfos[2].indices[0] = _ij2[0];
32364 vinfos[2].indices[1] = _ij2[1];
32365 vinfos[2].maxsolutions = _nj2;
32366 vinfos[3].jointtype = 1;
32367 vinfos[3].foffset = j3;
32368 vinfos[3].indices[0] = _ij3[0];
32369 vinfos[3].indices[1] = _ij3[1];
32370 vinfos[3].maxsolutions = _nj3;
32371 vinfos[4].jointtype = 1;
32372 vinfos[4].foffset = j4;
32373 vinfos[4].indices[0] = _ij4[0];
32374 vinfos[4].indices[1] = _ij4[1];
32375 vinfos[4].maxsolutions = _nj4;
32376 vinfos[5].jointtype = 1;
32377 vinfos[5].foffset = j5;
32378 vinfos[5].indices[0] = _ij5[0];
32379 vinfos[5].indices[1] = _ij5[1];
32380 vinfos[5].maxsolutions = _nj5;
32381 vinfos[6].jointtype = 1;
32382 vinfos[6].foffset = j6;
32383 vinfos[6].indices[0] = _ij6[0];
32384 vinfos[6].indices[1] = _ij6[1];
32385 vinfos[6].maxsolutions = _nj6;
32386 std::vector<int> vfree(0);
32387 solutions.AddSolution(vinfos,vfree);
32388 }
32389 }
32390 }
32391 
32392 }
32393 
32394 }
32395 
32396 } else
32397 {
32398 {
32399 IkReal j4array[1], cj4array[1], sj4array[1];
32400 bool j4valid[1]={false};
32401 _nj4 = 1;
32402 IkReal x10095=((cj1)*(r20));
32403 IkReal x10096=((cj5)*(sj6));
32404 IkReal x10097=((sj1)*(sj3));
32405 IkReal x10098=((r21)*(sj6));
32406 IkReal x10099=((r22)*(sj5));
32407 IkReal x10100=((IkReal(1.00000000000000))*(cj6));
32408 IkReal x10101=((cj5)*(r21));
32409 if( IKabs(((gconst28)*(((((x10097)*(x10098)))+(((cj1)*(cj6)*(x10101)))+(((x10095)*(x10096)))+(((IkReal(-1.00000000000000))*(r20)*(x10097)*(x10100)))+(((cj1)*(x10099))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((cj1)*(x10098)))+(((IkReal(-1.00000000000000))*(r20)*(x10096)*(x10097)))+(((IkReal(-1.00000000000000))*(x10097)*(x10100)*(x10101)))+(((IkReal(-1.00000000000000))*(x10097)*(x10099)))+(((IkReal(-1.00000000000000))*(x10095)*(x10100))))))) < IKFAST_ATAN2_MAGTHRESH )
32410     continue;
32411 j4array[0]=IKatan2(((gconst28)*(((((x10097)*(x10098)))+(((cj1)*(cj6)*(x10101)))+(((x10095)*(x10096)))+(((IkReal(-1.00000000000000))*(r20)*(x10097)*(x10100)))+(((cj1)*(x10099)))))), ((gconst28)*(((((cj1)*(x10098)))+(((IkReal(-1.00000000000000))*(r20)*(x10096)*(x10097)))+(((IkReal(-1.00000000000000))*(x10097)*(x10100)*(x10101)))+(((IkReal(-1.00000000000000))*(x10097)*(x10099)))+(((IkReal(-1.00000000000000))*(x10095)*(x10100)))))));
32412 sj4array[0]=IKsin(j4array[0]);
32413 cj4array[0]=IKcos(j4array[0]);
32414 if( j4array[0] > IKPI )
32415 {
32416     j4array[0]-=IK2PI;
32417 }
32418 else if( j4array[0] < -IKPI )
32419 {    j4array[0]+=IK2PI;
32420 }
32421 j4valid[0] = true;
32422 for(int ij4 = 0; ij4 < 1; ++ij4)
32423 {
32424 if( !j4valid[ij4] )
32425 {
32426     continue;
32427 }
32428 _ij4[0] = ij4; _ij4[1] = -1;
32429 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
32430 {
32431 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
32432 {
32433     j4valid[iij4]=false; _ij4[1] = iij4; break; 
32434 }
32435 }
32436 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
32437 {
32438 IkReal evalcond[6];
32439 IkReal x10102=IKsin(j4);
32440 IkReal x10103=IKcos(j4);
32441 IkReal x10104=((r22)*(sj5));
32442 IkReal x10105=((IkReal(1.00000000000000))*(cj6));
32443 IkReal x10106=((IkReal(1.00000000000000))*(cj0));
32444 IkReal x10107=((IkReal(1.00000000000000))*(sj1));
32445 IkReal x10108=((cj5)*(r11));
32446 IkReal x10109=((cj5)*(cj6));
32447 IkReal x10110=((r11)*(sj6));
32448 IkReal x10111=((IkReal(1.00000000000000))*(sj6));
32449 IkReal x10112=((cj6)*(r00));
32450 IkReal x10113=((r12)*(sj5));
32451 IkReal x10114=((r02)*(sj5));
32452 IkReal x10115=((cj6)*(r10));
32453 IkReal x10116=((cj5)*(sj6));
32454 IkReal x10117=((cj5)*(r01));
32455 IkReal x10118=((sj0)*(x10102));
32456 IkReal x10119=((r00)*(x10116));
32457 IkReal x10120=((cj0)*(x10102));
32458 IkReal x10121=((sj0)*(x10103));
32459 IkReal x10122=((r20)*(x10103));
32460 IkReal x10123=((cj0)*(x10103));
32461 IkReal x10124=((r21)*(x10102));
32462 IkReal x10125=((r21)*(x10103));
32463 IkReal x10126=((r20)*(x10102));
32464 IkReal x10127=((x10103)*(x10113));
32465 IkReal x10128=((r01)*(sj6)*(x10103));
32466 IkReal x10129=((cj5)*(r10)*(x10111));
32467 evalcond[0]=((((x10102)*(x10104)))+(((x10116)*(x10126)))+(((sj6)*(x10125)))+(((x10109)*(x10124)))+(cj1)+(((IkReal(-1.00000000000000))*(x10105)*(x10122))));
32468 evalcond[1]=((((x10116)*(x10122)))+(((IkReal(-1.00000000000000))*(sj3)*(x10107)))+(((x10109)*(x10125)))+(((cj6)*(x10126)))+(((x10103)*(x10104)))+(((IkReal(-1.00000000000000))*(x10111)*(x10124))));
32469 evalcond[2]=((((r01)*(sj6)*(x10121)))+(((x10114)*(x10118)))+(((IkReal(-1.00000000000000))*(x10105)*(x10108)*(x10120)))+(((IkReal(-1.00000000000000))*(x10103)*(x10106)*(x10110)))+(((r01)*(x10109)*(x10118)))+(((x10115)*(x10123)))+(((IkReal(-1.00000000000000))*(r10)*(x10102)*(x10106)*(x10116)))+(((x10118)*(x10119)))+(((IkReal(-1.00000000000000))*(r00)*(x10105)*(x10121)))+(((IkReal(-1.00000000000000))*(x10102)*(x10106)*(x10113))));
32470 evalcond[3]=((((IkReal(-1.00000000000000))*(x10105)*(x10108)*(x10123)))+(((x10110)*(x10120)))+(((IkReal(-1.00000000000000))*(r10)*(x10103)*(x10106)*(x10116)))+(((x10112)*(x10118)))+(((IkReal(-1.00000000000000))*(r01)*(x10111)*(x10118)))+(((IkReal(-1.00000000000000))*(cj3)))+(((x10119)*(x10121)))+(((x10114)*(x10121)))+(((r01)*(x10109)*(x10121)))+(((IkReal(-1.00000000000000))*(x10106)*(x10127)))+(((IkReal(-1.00000000000000))*(r10)*(x10105)*(x10120))));
32471 evalcond[4]=((((x10112)*(x10123)))+(((IkReal(-1.00000000000000))*(x10113)*(x10118)))+(((IkReal(-1.00000000000000))*(x10106)*(x10128)))+(((IkReal(-1.00000000000000))*(x10102)*(x10106)*(x10119)))+(((x10115)*(x10121)))+(((IkReal(-1.00000000000000))*(x10105)*(x10117)*(x10120)))+(((IkReal(-1.00000000000000))*(x10107)))+(((IkReal(-1.00000000000000))*(x10118)*(x10129)))+(((IkReal(-1.00000000000000))*(x10110)*(x10121)))+(((IkReal(-1.00000000000000))*(x10105)*(x10108)*(x10118)))+(((IkReal(-1.00000000000000))*(x10102)*(x10106)*(x10114))));
32472 evalcond[5]=((((IkReal(-1.00000000000000))*(x10103)*(x10106)*(x10119)))+(((IkReal(-1.00000000000000))*(r10)*(x10105)*(x10118)))+(((IkReal(-1.00000000000000))*(x10121)*(x10129)))+(((IkReal(-1.00000000000000))*(r00)*(x10105)*(x10120)))+(((IkReal(-1.00000000000000))*(x10105)*(x10108)*(x10121)))+(((r01)*(sj6)*(x10120)))+(((IkReal(-1.00000000000000))*(cj1)*(sj3)))+(((IkReal(-1.00000000000000))*(x10113)*(x10121)))+(((IkReal(-1.00000000000000))*(x10103)*(x10106)*(x10114)))+(((IkReal(-1.00000000000000))*(x10105)*(x10117)*(x10123)))+(((x10110)*(x10118))));
32473 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
32474 {
32475 continue;
32476 }
32477 }
32478 
32479 {
32480 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
32481 vinfos[0].jointtype = 1;
32482 vinfos[0].foffset = j0;
32483 vinfos[0].indices[0] = _ij0[0];
32484 vinfos[0].indices[1] = _ij0[1];
32485 vinfos[0].maxsolutions = _nj0;
32486 vinfos[1].jointtype = 1;
32487 vinfos[1].foffset = j1;
32488 vinfos[1].indices[0] = _ij1[0];
32489 vinfos[1].indices[1] = _ij1[1];
32490 vinfos[1].maxsolutions = _nj1;
32491 vinfos[2].jointtype = 1;
32492 vinfos[2].foffset = j2;
32493 vinfos[2].indices[0] = _ij2[0];
32494 vinfos[2].indices[1] = _ij2[1];
32495 vinfos[2].maxsolutions = _nj2;
32496 vinfos[3].jointtype = 1;
32497 vinfos[3].foffset = j3;
32498 vinfos[3].indices[0] = _ij3[0];
32499 vinfos[3].indices[1] = _ij3[1];
32500 vinfos[3].maxsolutions = _nj3;
32501 vinfos[4].jointtype = 1;
32502 vinfos[4].foffset = j4;
32503 vinfos[4].indices[0] = _ij4[0];
32504 vinfos[4].indices[1] = _ij4[1];
32505 vinfos[4].maxsolutions = _nj4;
32506 vinfos[5].jointtype = 1;
32507 vinfos[5].foffset = j5;
32508 vinfos[5].indices[0] = _ij5[0];
32509 vinfos[5].indices[1] = _ij5[1];
32510 vinfos[5].maxsolutions = _nj5;
32511 vinfos[6].jointtype = 1;
32512 vinfos[6].foffset = j6;
32513 vinfos[6].indices[0] = _ij6[0];
32514 vinfos[6].indices[1] = _ij6[1];
32515 vinfos[6].maxsolutions = _nj6;
32516 std::vector<int> vfree(0);
32517 solutions.AddSolution(vinfos,vfree);
32518 }
32519 }
32520 }
32521 
32522 }
32523 
32524 }
32525 }
32526 }
32527 
32528 }
32529 
32530 }
32531 
32532 } else
32533 {
32534 {
32535 IkReal j4array[1], cj4array[1], sj4array[1];
32536 bool j4valid[1]={false};
32537 _nj4 = 1;
32538 IkReal x10130=((IkReal(1.00000000000000))*(sj1));
32539 IkReal x10131=((cj0)*(cj1));
32540 IkReal x10132=((cj1)*(sj0));
32541 IkReal x10133=((cj5)*(sj6));
32542 IkReal x10134=((cj5)*(cj6));
32543 IkReal x10135=((sj6)*(x10131));
32544 IkReal x10136=((cj6)*(x10132));
32545 if( IKabs(((gconst27)*(((((cj6)*(r00)*(x10131)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(x10130)))+(((IkReal(-1.00000000000000))*(r01)*(x10135)))+(((IkReal(-1.00000000000000))*(r11)*(sj6)*(x10132)))+(((r10)*(x10136)))+(((r21)*(sj1)*(sj6))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(r20)*(x10130)*(x10133)))+(((r10)*(x10132)*(x10133)))+(((r00)*(x10131)*(x10133)))+(((r12)*(sj5)*(x10132)))+(((r02)*(sj5)*(x10131)))+(((r01)*(x10131)*(x10134)))+(((IkReal(-1.00000000000000))*(r21)*(x10130)*(x10134)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x10130)))+(((r11)*(x10132)*(x10134))))))) < IKFAST_ATAN2_MAGTHRESH )
32546     continue;
32547 j4array[0]=IKatan2(((gconst27)*(((((cj6)*(r00)*(x10131)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(x10130)))+(((IkReal(-1.00000000000000))*(r01)*(x10135)))+(((IkReal(-1.00000000000000))*(r11)*(sj6)*(x10132)))+(((r10)*(x10136)))+(((r21)*(sj1)*(sj6)))))), ((gconst27)*(((((IkReal(-1.00000000000000))*(r20)*(x10130)*(x10133)))+(((r10)*(x10132)*(x10133)))+(((r00)*(x10131)*(x10133)))+(((r12)*(sj5)*(x10132)))+(((r02)*(sj5)*(x10131)))+(((r01)*(x10131)*(x10134)))+(((IkReal(-1.00000000000000))*(r21)*(x10130)*(x10134)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x10130)))+(((r11)*(x10132)*(x10134)))))));
32548 sj4array[0]=IKsin(j4array[0]);
32549 cj4array[0]=IKcos(j4array[0]);
32550 if( j4array[0] > IKPI )
32551 {
32552     j4array[0]-=IK2PI;
32553 }
32554 else if( j4array[0] < -IKPI )
32555 {    j4array[0]+=IK2PI;
32556 }
32557 j4valid[0] = true;
32558 for(int ij4 = 0; ij4 < 1; ++ij4)
32559 {
32560 if( !j4valid[ij4] )
32561 {
32562     continue;
32563 }
32564 _ij4[0] = ij4; _ij4[1] = -1;
32565 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
32566 {
32567 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
32568 {
32569     j4valid[iij4]=false; _ij4[1] = iij4; break; 
32570 }
32571 }
32572 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
32573 {
32574 IkReal evalcond[3];
32575 IkReal x10137=IKsin(j4);
32576 IkReal x10138=IKcos(j4);
32577 IkReal x10139=((r00)*(sj6));
32578 IkReal x10140=((cj6)*(r01));
32579 IkReal x10141=((IkReal(1.00000000000000))*(cj0));
32580 IkReal x10142=((IkReal(1.00000000000000))*(sj0));
32581 IkReal x10143=((r10)*(sj6));
32582 IkReal x10144=((sj5)*(x10137));
32583 IkReal x10145=((IkReal(1.00000000000000))*(cj6)*(r11));
32584 IkReal x10146=((cj5)*(x10137));
32585 IkReal x10147=((cj6)*(x10138));
32586 IkReal x10148=((sj0)*(x10146));
32587 IkReal x10149=((r01)*(sj6)*(x10138));
32588 IkReal x10150=((r11)*(sj6)*(x10138));
32589 evalcond[0]=((((r21)*(sj6)*(x10138)))+(((cj6)*(r21)*(x10146)))+(cj1)+(((r22)*(x10144)))+(((r20)*(sj6)*(x10146)))+(((IkReal(-1.00000000000000))*(r20)*(x10147))));
32590 evalcond[1]=((((x10139)*(x10148)))+(((IkReal(-1.00000000000000))*(x10141)*(x10150)))+(((cj0)*(r10)*(x10147)))+(((IkReal(-1.00000000000000))*(r00)*(x10142)*(x10147)))+(((IkReal(-1.00000000000000))*(x10141)*(x10143)*(x10146)))+(((r02)*(sj0)*(x10144)))+(((x10140)*(x10148)))+(((IkReal(-1.00000000000000))*(r12)*(x10141)*(x10144)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10141)*(x10146)))+(((sj0)*(x10149))));
32591 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x10141)*(x10144)))+(((IkReal(-1.00000000000000))*(x10140)*(x10141)*(x10146)))+(((IkReal(-1.00000000000000))*(x10139)*(x10141)*(x10146)))+(((IkReal(-1.00000000000000))*(r12)*(x10142)*(x10144)))+(((IkReal(-1.00000000000000))*(x10141)*(x10149)))+(((cj0)*(r00)*(x10147)))+(((r10)*(sj0)*(x10147)))+(((IkReal(-1.00000000000000))*(x10142)*(x10143)*(x10146)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10142)*(x10146)))+(((IkReal(-1.00000000000000))*(x10142)*(x10150))));
32592 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
32593 {
32594 continue;
32595 }
32596 }
32597 
32598 {
32599 IkReal dummyeval[1];
32600 IkReal gconst30;
32601 gconst30=IKsign(sj1);
32602 dummyeval[0]=sj1;
32603 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
32604 {
32605 {
32606 IkReal dummyeval[1];
32607 dummyeval[0]=sj1;
32608 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
32609 {
32610 {
32611 IkReal dummyeval[1];
32612 dummyeval[0]=cj1;
32613 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
32614 {
32615 {
32616 IkReal evalcond[9];
32617 IkReal x10151=((IkReal(1.00000000000000))*(cj0));
32618 IkReal x10152=((cj4)*(sj6));
32619 IkReal x10153=((sj0)*(sj6));
32620 IkReal x10154=((cj5)*(sj4));
32621 IkReal x10155=((IkReal(0.374290000000000))*(sj5));
32622 IkReal x10156=((sj4)*(sj5));
32623 IkReal x10157=((cj0)*(cj6));
32624 IkReal x10158=((IkReal(0.0100000000000000))*(cj5));
32625 IkReal x10159=((cj4)*(sj5));
32626 IkReal x10160=((cj5)*(sj0));
32627 IkReal x10161=((IkReal(0.374290000000000))*(r02));
32628 IkReal x10162=((r20)*(sj6));
32629 IkReal x10163=((cj6)*(r21));
32630 IkReal x10164=((IkReal(1.00000000000000))*(sj0));
32631 IkReal x10165=((cj0)*(sj6));
32632 IkReal x10166=((cj4)*(cj6));
32633 IkReal x10167=((IkReal(0.374290000000000))*(r12));
32634 IkReal x10168=((cj0)*(cj5));
32635 IkReal x10169=((cj6)*(sj5));
32636 IkReal x10170=((cj6)*(r01));
32637 IkReal x10171=((r00)*(sj6));
32638 IkReal x10172=((IkReal(0.0100000000000000))*(sj5));
32639 IkReal x10173=((cj6)*(r11));
32640 IkReal x10174=((IkReal(1.00000000000000))*(r10));
32641 IkReal x10175=((r02)*(sj0));
32642 IkReal x10176=((cj6)*(sj4));
32643 IkReal x10177=((r12)*(x10164));
32644 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
32645 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x10166)))+(((r22)*(x10156)))+(((r21)*(x10152)))+(((x10154)*(x10163)))+(((x10154)*(x10162))));
32646 evalcond[2]=((IkReal(0.364420000000000))+(((x10155)*(x10163)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x10155)*(x10162)))+(((IkReal(-1.00000000000000))*(x10158)*(x10162)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x10172)))+(((IkReal(-1.00000000000000))*(x10158)*(x10163))));
32647 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x10153)*(x10174)))+(((IkReal(-1.00000000000000))*(sj5)*(x10151)*(x10171)))+(((IkReal(-1.00000000000000))*(r11)*(x10164)*(x10169)))+(((r02)*(x10168)))+(((IkReal(-1.00000000000000))*(r01)*(x10151)*(x10169)))+(((r12)*(x10160))));
32648 evalcond[4]=((((r00)*(x10153)*(x10154)))+(((IkReal(-1.00000000000000))*(r11)*(x10151)*(x10152)))+(((r01)*(sj0)*(x10152)))+(((IkReal(-1.00000000000000))*(r00)*(x10164)*(x10166)))+(((IkReal(-1.00000000000000))*(r12)*(x10151)*(x10156)))+(((x10156)*(x10175)))+(((cj4)*(r10)*(x10157)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x10151)*(x10154)))+(((sj0)*(x10154)*(x10170)))+(((IkReal(-1.00000000000000))*(x10151)*(x10154)*(x10173))));
32649 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x10151)*(x10154)*(x10170)))+(((r10)*(sj0)*(x10166)))+(((IkReal(-1.00000000000000))*(r02)*(x10151)*(x10156)))+(((IkReal(-1.00000000000000))*(r11)*(x10152)*(x10164)))+(((IkReal(-1.00000000000000))*(x10151)*(x10154)*(x10171)))+(((cj4)*(r00)*(x10157)))+(((IkReal(-1.00000000000000))*(r01)*(x10151)*(x10152)))+(((IkReal(-1.00000000000000))*(x10153)*(x10154)*(x10174)))+(((IkReal(-1.00000000000000))*(x10154)*(x10164)*(x10173)))+(((IkReal(-1.00000000000000))*(x10156)*(x10177))));
32650 evalcond[6]=((IkReal(-0.0690000000000000))+(((r10)*(x10158)*(x10165)))+(((IkReal(-1.00000000000000))*(x10160)*(x10161)))+(((cj0)*(r12)*(x10172)))+(((IkReal(-1.00000000000000))*(x10172)*(x10175)))+(((IkReal(-1.00000000000000))*(r10)*(x10155)*(x10165)))+(((r11)*(x10157)*(x10158)))+(((IkReal(-1.00000000000000))*(r00)*(x10153)*(x10158)))+(((IkReal(-1.00000000000000))*(sj0)*(x10158)*(x10170)))+(((IkReal(-1.00000000000000))*(py)*(x10151)))+(((px)*(sj0)))+(((x10167)*(x10168)))+(((r00)*(x10153)*(x10155)))+(((sj0)*(x10155)*(x10170)))+(((IkReal(-1.00000000000000))*(r11)*(x10155)*(x10157))));
32651 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10151)*(x10166)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10151)*(x10152)))+(((IkReal(-1.00000000000000))*(r00)*(x10151)*(x10176)))+(((IkReal(-1.00000000000000))*(r11)*(x10160)*(x10166)))+(((r01)*(sj4)*(x10165)))+(((r11)*(sj4)*(x10153)))+(((IkReal(-1.00000000000000))*(x10159)*(x10177)))+(((IkReal(-1.00000000000000))*(r02)*(x10151)*(x10159)))+(((IkReal(-1.00000000000000))*(r10)*(x10164)*(x10176)))+(((IkReal(-1.00000000000000))*(x10152)*(x10160)*(x10174))));
32652 evalcond[8]=((IkReal(0.0690000000000000))+(((r00)*(x10158)*(x10165)))+(((x10160)*(x10167)))+(((cj0)*(r02)*(x10172)))+(((IkReal(-1.00000000000000))*(r01)*(x10155)*(x10157)))+(((IkReal(-1.00000000000000))*(px)*(x10151)))+(((r12)*(sj0)*(x10172)))+(((IkReal(-1.00000000000000))*(py)*(x10164)))+(((IkReal(-1.00000000000000))*(r10)*(x10153)*(x10155)))+(((r10)*(x10153)*(x10158)))+(((r01)*(x10157)*(x10158)))+(((sj0)*(x10158)*(x10173)))+(((IkReal(-1.00000000000000))*(r00)*(x10155)*(x10165)))+(((x10161)*(x10168)))+(((IkReal(-1.00000000000000))*(sj0)*(x10155)*(x10173))));
32653 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
32654 {
32655 {
32656 IkReal j3array[1], cj3array[1], sj3array[1];
32657 bool j3valid[1]={false};
32658 _nj3 = 1;
32659 IkReal x10178=((r20)*(sj6));
32660 IkReal x10179=((cj4)*(cj5));
32661 IkReal x10180=((cj6)*(r21));
32662 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10178)*(x10179)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10179)*(x10180))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x10178)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10180))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10178)*(x10179)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10179)*(x10180)))))+IKsqr(((((sj5)*(x10178)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10180)))))-1) <= IKFAST_SINCOS_THRESH )
32663     continue;
32664 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10178)*(x10179)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10179)*(x10180)))), ((((sj5)*(x10178)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10180)))));
32665 sj3array[0]=IKsin(j3array[0]);
32666 cj3array[0]=IKcos(j3array[0]);
32667 if( j3array[0] > IKPI )
32668 {
32669     j3array[0]-=IK2PI;
32670 }
32671 else if( j3array[0] < -IKPI )
32672 {    j3array[0]+=IK2PI;
32673 }
32674 j3valid[0] = true;
32675 for(int ij3 = 0; ij3 < 1; ++ij3)
32676 {
32677 if( !j3valid[ij3] )
32678 {
32679     continue;
32680 }
32681 _ij3[0] = ij3; _ij3[1] = -1;
32682 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
32683 {
32684 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
32685 {
32686     j3valid[iij3]=false; _ij3[1] = iij3; break; 
32687 }
32688 }
32689 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
32690 {
32691 IkReal evalcond[4];
32692 IkReal x10181=IKsin(j3);
32693 IkReal x10182=((sj0)*(sj5));
32694 IkReal x10183=((r00)*(sj6));
32695 IkReal x10184=((cj6)*(r01));
32696 IkReal x10185=((cj5)*(sj0));
32697 IkReal x10186=((cj0)*(cj5));
32698 IkReal x10187=((cj6)*(sj4));
32699 IkReal x10188=((sj4)*(sj6));
32700 IkReal x10189=((cj0)*(r11));
32701 IkReal x10190=((cj4)*(cj6));
32702 IkReal x10191=((cj4)*(sj6));
32703 IkReal x10192=((IkReal(1.00000000000000))*(cj0));
32704 IkReal x10193=((cj4)*(sj5));
32705 IkReal x10194=((sj5)*(sj6));
32706 IkReal x10195=((cj6)*(sj5));
32707 IkReal x10196=((IkReal(1.00000000000000))*(IKcos(j3)));
32708 evalcond[0]=((((r20)*(x10194)))+(((IkReal(-1.00000000000000))*(x10196)))+(((r21)*(x10195)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
32709 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x10188)))+(((cj5)*(r20)*(x10191)))+(((cj5)*(r21)*(x10190)))+(((r22)*(x10193)))+(((r20)*(x10187)))+(((IkReal(-1.00000000000000))*(x10181))));
32710 evalcond[2]=((((x10182)*(x10184)))+(((x10182)*(x10183)))+(((IkReal(-1.00000000000000))*(x10189)*(x10195)))+(x10181)+(((IkReal(-1.00000000000000))*(r02)*(x10185)))+(((IkReal(-1.00000000000000))*(r10)*(x10192)*(x10194)))+(((r12)*(x10186))));
32711 evalcond[3]=((((cj4)*(x10183)*(x10185)))+(((cj4)*(x10184)*(x10185)))+(((IkReal(-1.00000000000000))*(x10196)))+(((r00)*(sj0)*(x10187)))+(((IkReal(-1.00000000000000))*(r10)*(x10187)*(x10192)))+(((IkReal(-1.00000000000000))*(r11)*(x10186)*(x10190)))+(((x10188)*(x10189)))+(((cj4)*(r02)*(x10182)))+(((IkReal(-1.00000000000000))*(r12)*(x10192)*(x10193)))+(((IkReal(-1.00000000000000))*(r10)*(x10186)*(x10191)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x10188))));
32712 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
32713 {
32714 continue;
32715 }
32716 }
32717 
32718 {
32719 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
32720 vinfos[0].jointtype = 1;
32721 vinfos[0].foffset = j0;
32722 vinfos[0].indices[0] = _ij0[0];
32723 vinfos[0].indices[1] = _ij0[1];
32724 vinfos[0].maxsolutions = _nj0;
32725 vinfos[1].jointtype = 1;
32726 vinfos[1].foffset = j1;
32727 vinfos[1].indices[0] = _ij1[0];
32728 vinfos[1].indices[1] = _ij1[1];
32729 vinfos[1].maxsolutions = _nj1;
32730 vinfos[2].jointtype = 1;
32731 vinfos[2].foffset = j2;
32732 vinfos[2].indices[0] = _ij2[0];
32733 vinfos[2].indices[1] = _ij2[1];
32734 vinfos[2].maxsolutions = _nj2;
32735 vinfos[3].jointtype = 1;
32736 vinfos[3].foffset = j3;
32737 vinfos[3].indices[0] = _ij3[0];
32738 vinfos[3].indices[1] = _ij3[1];
32739 vinfos[3].maxsolutions = _nj3;
32740 vinfos[4].jointtype = 1;
32741 vinfos[4].foffset = j4;
32742 vinfos[4].indices[0] = _ij4[0];
32743 vinfos[4].indices[1] = _ij4[1];
32744 vinfos[4].maxsolutions = _nj4;
32745 vinfos[5].jointtype = 1;
32746 vinfos[5].foffset = j5;
32747 vinfos[5].indices[0] = _ij5[0];
32748 vinfos[5].indices[1] = _ij5[1];
32749 vinfos[5].maxsolutions = _nj5;
32750 vinfos[6].jointtype = 1;
32751 vinfos[6].foffset = j6;
32752 vinfos[6].indices[0] = _ij6[0];
32753 vinfos[6].indices[1] = _ij6[1];
32754 vinfos[6].maxsolutions = _nj6;
32755 std::vector<int> vfree(0);
32756 solutions.AddSolution(vinfos,vfree);
32757 }
32758 }
32759 }
32760 
32761 } else
32762 {
32763 IkReal x10197=((IkReal(1.00000000000000))*(cj0));
32764 IkReal x10198=((cj4)*(sj6));
32765 IkReal x10199=((sj0)*(sj6));
32766 IkReal x10200=((cj5)*(sj4));
32767 IkReal x10201=((IkReal(0.374290000000000))*(sj5));
32768 IkReal x10202=((sj4)*(sj5));
32769 IkReal x10203=((cj0)*(cj6));
32770 IkReal x10204=((IkReal(0.0100000000000000))*(cj5));
32771 IkReal x10205=((cj4)*(sj5));
32772 IkReal x10206=((cj5)*(sj0));
32773 IkReal x10207=((IkReal(0.374290000000000))*(r02));
32774 IkReal x10208=((r20)*(sj6));
32775 IkReal x10209=((cj6)*(r21));
32776 IkReal x10210=((IkReal(1.00000000000000))*(sj0));
32777 IkReal x10211=((cj0)*(sj6));
32778 IkReal x10212=((cj4)*(cj6));
32779 IkReal x10213=((IkReal(0.374290000000000))*(r12));
32780 IkReal x10214=((cj0)*(cj5));
32781 IkReal x10215=((cj6)*(sj5));
32782 IkReal x10216=((cj6)*(r01));
32783 IkReal x10217=((r00)*(sj6));
32784 IkReal x10218=((IkReal(0.0100000000000000))*(sj5));
32785 IkReal x10219=((cj6)*(r11));
32786 IkReal x10220=((IkReal(1.00000000000000))*(r10));
32787 IkReal x10221=((r02)*(sj0));
32788 IkReal x10222=((cj6)*(sj4));
32789 IkReal x10223=((r12)*(x10210));
32790 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
32791 evalcond[1]=((((x10200)*(x10209)))+(((r22)*(x10202)))+(((r21)*(x10198)))+(((IkReal(-1.00000000000000))*(r20)*(x10212)))+(((x10200)*(x10208))));
32792 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x10204)*(x10209)))+(((x10201)*(x10209)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x10204)*(x10208)))+(((x10201)*(x10208)))+(((IkReal(-1.00000000000000))*(r22)*(x10218))));
32793 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x10210)*(x10215)))+(((r02)*(x10214)))+(((r12)*(x10206)))+(((IkReal(-1.00000000000000))*(r01)*(x10197)*(x10215)))+(((IkReal(-1.00000000000000))*(sj5)*(x10199)*(x10220)))+(((IkReal(-1.00000000000000))*(sj5)*(x10197)*(x10217))));
32794 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x10210)*(x10212)))+(((r00)*(x10199)*(x10200)))+(((sj0)*(x10200)*(x10216)))+(((cj4)*(r10)*(x10203)))+(((x10202)*(x10221)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x10197)*(x10200)))+(((IkReal(-1.00000000000000))*(r12)*(x10197)*(x10202)))+(((IkReal(-1.00000000000000))*(r11)*(x10197)*(x10198)))+(((IkReal(-1.00000000000000))*(x10197)*(x10200)*(x10219)))+(((r01)*(sj0)*(x10198))));
32795 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x10197)*(x10200)*(x10216)))+(((IkReal(-1.00000000000000))*(x10200)*(x10210)*(x10219)))+(((cj4)*(r00)*(x10203)))+(((IkReal(-1.00000000000000))*(x10202)*(x10223)))+(((IkReal(-1.00000000000000))*(r11)*(x10198)*(x10210)))+(((IkReal(-1.00000000000000))*(r01)*(x10197)*(x10198)))+(((IkReal(-1.00000000000000))*(x10199)*(x10200)*(x10220)))+(((r10)*(sj0)*(x10212)))+(((IkReal(-1.00000000000000))*(x10197)*(x10200)*(x10217)))+(((IkReal(-1.00000000000000))*(r02)*(x10197)*(x10202))));
32796 evalcond[6]=((IkReal(-0.0690000000000000))+(((r11)*(x10203)*(x10204)))+(((r00)*(x10199)*(x10201)))+(((IkReal(-1.00000000000000))*(x10218)*(x10221)))+(((x10213)*(x10214)))+(((IkReal(-1.00000000000000))*(r10)*(x10201)*(x10211)))+(((IkReal(-1.00000000000000))*(r00)*(x10199)*(x10204)))+(((IkReal(-1.00000000000000))*(r11)*(x10201)*(x10203)))+(((cj0)*(r12)*(x10218)))+(((sj0)*(x10201)*(x10216)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x10197)))+(((IkReal(-1.00000000000000))*(x10206)*(x10207)))+(((IkReal(-1.00000000000000))*(sj0)*(x10204)*(x10216)))+(((r10)*(x10204)*(x10211))));
32797 evalcond[7]=((((IkReal(-1.00000000000000))*(x10205)*(x10223)))+(((IkReal(-1.00000000000000))*(r10)*(x10210)*(x10222)))+(((IkReal(-1.00000000000000))*(x10198)*(x10206)*(x10220)))+(((IkReal(-1.00000000000000))*(r00)*(x10197)*(x10222)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10197)*(x10198)))+(((r11)*(sj4)*(x10199)))+(((IkReal(-1.00000000000000))*(r11)*(x10206)*(x10212)))+(((r01)*(sj4)*(x10211)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10197)*(x10212)))+(((IkReal(-1.00000000000000))*(r02)*(x10197)*(x10205))));
32798 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x10197)))+(((IkReal(-1.00000000000000))*(sj0)*(x10201)*(x10219)))+(((r01)*(x10203)*(x10204)))+(((sj0)*(x10204)*(x10219)))+(((IkReal(-1.00000000000000))*(r01)*(x10201)*(x10203)))+(((r10)*(x10199)*(x10204)))+(((x10206)*(x10213)))+(((x10207)*(x10214)))+(((IkReal(-1.00000000000000))*(r00)*(x10201)*(x10211)))+(((IkReal(-1.00000000000000))*(py)*(x10210)))+(((cj0)*(r02)*(x10218)))+(((IkReal(-1.00000000000000))*(r10)*(x10199)*(x10201)))+(((r12)*(sj0)*(x10218)))+(((r00)*(x10204)*(x10211))));
32799 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
32800 {
32801 {
32802 IkReal j3array[1], cj3array[1], sj3array[1];
32803 bool j3valid[1]={false};
32804 _nj3 = 1;
32805 IkReal x10224=((IkReal(1.00000000000000))*(sj5));
32806 IkReal x10225=((cj6)*(r21));
32807 IkReal x10226=((r20)*(sj6));
32808 IkReal x10227=((IkReal(1.00000000000000))*(cj4)*(cj5));
32809 if( IKabs(((((IkReal(-1.00000000000000))*(x10225)*(x10227)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10224)))+(((IkReal(-1.00000000000000))*(x10226)*(x10227)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10224)*(x10226)))+(((IkReal(-1.00000000000000))*(x10224)*(x10225))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x10225)*(x10227)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10224)))+(((IkReal(-1.00000000000000))*(x10226)*(x10227)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10224)*(x10226)))+(((IkReal(-1.00000000000000))*(x10224)*(x10225)))))-1) <= IKFAST_SINCOS_THRESH )
32810     continue;
32811 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x10225)*(x10227)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10224)))+(((IkReal(-1.00000000000000))*(x10226)*(x10227)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10224)*(x10226)))+(((IkReal(-1.00000000000000))*(x10224)*(x10225)))));
32812 sj3array[0]=IKsin(j3array[0]);
32813 cj3array[0]=IKcos(j3array[0]);
32814 if( j3array[0] > IKPI )
32815 {
32816     j3array[0]-=IK2PI;
32817 }
32818 else if( j3array[0] < -IKPI )
32819 {    j3array[0]+=IK2PI;
32820 }
32821 j3valid[0] = true;
32822 for(int ij3 = 0; ij3 < 1; ++ij3)
32823 {
32824 if( !j3valid[ij3] )
32825 {
32826     continue;
32827 }
32828 _ij3[0] = ij3; _ij3[1] = -1;
32829 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
32830 {
32831 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
32832 {
32833     j3valid[iij3]=false; _ij3[1] = iij3; break; 
32834 }
32835 }
32836 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
32837 {
32838 IkReal evalcond[4];
32839 IkReal x10228=IKsin(j3);
32840 IkReal x10229=IKcos(j3);
32841 IkReal x10230=((sj0)*(sj5));
32842 IkReal x10231=((r00)*(sj6));
32843 IkReal x10232=((cj6)*(r01));
32844 IkReal x10233=((cj0)*(cj5));
32845 IkReal x10234=((IkReal(1.00000000000000))*(cj5));
32846 IkReal x10235=((cj4)*(cj5));
32847 IkReal x10236=((cj6)*(sj4));
32848 IkReal x10237=((sj4)*(sj6));
32849 IkReal x10238=((cj0)*(r11));
32850 IkReal x10239=((IkReal(1.00000000000000))*(cj4));
32851 IkReal x10240=((cj6)*(r21));
32852 IkReal x10241=((r20)*(sj6));
32853 IkReal x10242=((cj0)*(sj5));
32854 IkReal x10243=((r10)*(sj6));
32855 evalcond[0]=((((sj5)*(x10240)))+(((sj5)*(x10241)))+(((IkReal(-1.00000000000000))*(r22)*(x10234)))+(x10229));
32856 evalcond[1]=((((x10235)*(x10240)))+(x10228)+(((IkReal(-1.00000000000000))*(r21)*(x10237)))+(((cj4)*(r22)*(sj5)))+(((x10235)*(x10241)))+(((r20)*(x10236))));
32857 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x10234)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x10238)))+(((IkReal(-1.00000000000000))*(x10242)*(x10243)))+(x10228)+(((r12)*(x10233)))+(((x10230)*(x10232)))+(((x10230)*(x10231))));
32858 evalcond[3]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10233)*(x10239)))+(((r00)*(sj0)*(x10236)))+(((IkReal(-1.00000000000000))*(x10229)))+(((x10237)*(x10238)))+(((cj4)*(r02)*(x10230)))+(((IkReal(-1.00000000000000))*(r12)*(x10239)*(x10242)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x10237)))+(((sj0)*(x10232)*(x10235)))+(((sj0)*(x10231)*(x10235)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x10236)))+(((IkReal(-1.00000000000000))*(x10233)*(x10239)*(x10243))));
32859 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
32860 {
32861 continue;
32862 }
32863 }
32864 
32865 {
32866 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
32867 vinfos[0].jointtype = 1;
32868 vinfos[0].foffset = j0;
32869 vinfos[0].indices[0] = _ij0[0];
32870 vinfos[0].indices[1] = _ij0[1];
32871 vinfos[0].maxsolutions = _nj0;
32872 vinfos[1].jointtype = 1;
32873 vinfos[1].foffset = j1;
32874 vinfos[1].indices[0] = _ij1[0];
32875 vinfos[1].indices[1] = _ij1[1];
32876 vinfos[1].maxsolutions = _nj1;
32877 vinfos[2].jointtype = 1;
32878 vinfos[2].foffset = j2;
32879 vinfos[2].indices[0] = _ij2[0];
32880 vinfos[2].indices[1] = _ij2[1];
32881 vinfos[2].maxsolutions = _nj2;
32882 vinfos[3].jointtype = 1;
32883 vinfos[3].foffset = j3;
32884 vinfos[3].indices[0] = _ij3[0];
32885 vinfos[3].indices[1] = _ij3[1];
32886 vinfos[3].maxsolutions = _nj3;
32887 vinfos[4].jointtype = 1;
32888 vinfos[4].foffset = j4;
32889 vinfos[4].indices[0] = _ij4[0];
32890 vinfos[4].indices[1] = _ij4[1];
32891 vinfos[4].maxsolutions = _nj4;
32892 vinfos[5].jointtype = 1;
32893 vinfos[5].foffset = j5;
32894 vinfos[5].indices[0] = _ij5[0];
32895 vinfos[5].indices[1] = _ij5[1];
32896 vinfos[5].maxsolutions = _nj5;
32897 vinfos[6].jointtype = 1;
32898 vinfos[6].foffset = j6;
32899 vinfos[6].indices[0] = _ij6[0];
32900 vinfos[6].indices[1] = _ij6[1];
32901 vinfos[6].maxsolutions = _nj6;
32902 std::vector<int> vfree(0);
32903 solutions.AddSolution(vinfos,vfree);
32904 }
32905 }
32906 }
32907 
32908 } else
32909 {
32910 IkReal x10244=((IkReal(1.00000000000000))*(cj0));
32911 IkReal x10245=((cj4)*(sj6));
32912 IkReal x10246=((sj0)*(sj4));
32913 IkReal x10247=((cj5)*(sj6));
32914 IkReal x10248=((sj4)*(sj5));
32915 IkReal x10249=((r12)*(sj5));
32916 IkReal x10250=((IkReal(0.374290000000000))*(cj5));
32917 IkReal x10251=((r02)*(sj0));
32918 IkReal x10252=((r20)*(sj4));
32919 IkReal x10253=((IkReal(1.00000000000000))*(sj0));
32920 IkReal x10254=((IkReal(1.00000000000000))*(cj5));
32921 IkReal x10255=((cj0)*(r10));
32922 IkReal x10256=((cj4)*(cj6));
32923 IkReal x10257=((r00)*(sj0));
32924 IkReal x10258=((cj6)*(r21));
32925 IkReal x10259=((IkReal(0.374290000000000))*(sj5));
32926 IkReal x10260=((cj0)*(r00));
32927 IkReal x10261=((IkReal(0.0100000000000000))*(sj5));
32928 IkReal x10262=((cj0)*(r02));
32929 IkReal x10263=((cj5)*(sj4));
32930 IkReal x10264=((cj6)*(r01));
32931 IkReal x10265=((cj6)*(r11));
32932 IkReal x10266=((r01)*(sj0));
32933 IkReal x10267=((r10)*(sj0));
32934 IkReal x10268=((IkReal(0.0100000000000000))*(cj5)*(cj6));
32935 IkReal x10269=((sj6)*(x10259));
32936 IkReal x10270=((cj0)*(cj6)*(x10259));
32937 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
32938 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x10254)))+(((sj5)*(x10258)))+(((r20)*(sj5)*(sj6))));
32939 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x10256)))+(((x10247)*(x10252)))+(((x10258)*(x10263)))+(((r22)*(x10248)))+(((r21)*(x10245))));
32940 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x10250)))+(((r20)*(x10269)))+(((x10258)*(x10259)))+(((IkReal(-0.0100000000000000))*(r20)*(x10247)))+(pz)+(((IkReal(-0.0100000000000000))*(cj5)*(x10258)))+(((IkReal(-1.00000000000000))*(r22)*(x10261))));
32941 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x10245)))+(((cj5)*(r21)*(x10256)))+(((cj6)*(x10252))));
32942 evalcond[5]=((((IkReal(-1.00000000000000))*(x10244)*(x10263)*(x10265)))+(((IkReal(-1.00000000000000))*(r11)*(x10244)*(x10245)))+(((cj5)*(x10246)*(x10264)))+(((r02)*(sj5)*(x10246)))+(((x10245)*(x10266)))+(((IkReal(-1.00000000000000))*(r12)*(x10244)*(x10248)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x10244)*(x10247)))+(((IkReal(-1.00000000000000))*(r00)*(x10253)*(x10256)))+(((r00)*(x10246)*(x10247)))+(((x10255)*(x10256))));
32943 evalcond[6]=((((IkReal(-1.00000000000000))*(x10244)*(x10263)*(x10264)))+(((IkReal(-1.00000000000000))*(r02)*(x10244)*(x10248)))+(((IkReal(-1.00000000000000))*(r10)*(x10246)*(x10247)))+(((IkReal(-1.00000000000000))*(x10246)*(x10249)))+(((IkReal(-1.00000000000000))*(x10246)*(x10254)*(x10265)))+(((IkReal(-1.00000000000000))*(r11)*(x10245)*(x10253)))+(((x10256)*(x10260)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x10244)*(x10247)))+(((IkReal(-1.00000000000000))*(r01)*(x10244)*(x10245)))+(((x10256)*(x10267))));
32944 evalcond[7]=((IkReal(-0.0690000000000000))+(((sj0)*(x10259)*(x10264)))+(((cj0)*(r12)*(x10250)))+(((IkReal(-0.0100000000000000))*(x10247)*(x10257)))+(((IkReal(-1.00000000000000))*(x10251)*(x10261)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10265)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x10264)))+(((IkReal(0.0100000000000000))*(x10247)*(x10255)))+(((IkReal(-1.00000000000000))*(x10255)*(x10269)))+(((IkReal(-1.00000000000000))*(py)*(x10244)))+(((IkReal(-1.00000000000000))*(cj0)*(x10259)*(x10265)))+(((px)*(sj0)))+(((x10257)*(x10269)))+(((IkReal(-1.00000000000000))*(x10250)*(x10251)))+(((IkReal(0.0100000000000000))*(cj0)*(x10249))));
32945 evalcond[8]=((IkReal(0.433420000000000))+(((r12)*(sj0)*(x10250)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x10265)))+(((IkReal(-1.00000000000000))*(py)*(x10253)))+(((IkReal(-1.00000000000000))*(cj0)*(x10259)*(x10264)))+(((IkReal(-1.00000000000000))*(px)*(x10244)))+(((IkReal(-1.00000000000000))*(x10260)*(x10269)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10264)))+(((x10261)*(x10262)))+(((IkReal(-1.00000000000000))*(sj0)*(x10259)*(x10265)))+(((IkReal(0.0100000000000000))*(sj0)*(x10249)))+(((IkReal(0.0100000000000000))*(x10247)*(x10267)))+(((x10250)*(x10262)))+(((IkReal(-1.00000000000000))*(x10267)*(x10269)))+(((IkReal(0.0100000000000000))*(x10247)*(x10260))));
32946 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
32947 {
32948 {
32949 IkReal j3array[1], cj3array[1], sj3array[1];
32950 bool j3valid[1]={false};
32951 _nj3 = 1;
32952 IkReal x10271=((cj5)*(r02));
32953 IkReal x10272=((cj0)*(sj5));
32954 IkReal x10273=((r10)*(sj6));
32955 IkReal x10274=((IkReal(1.00000000000000))*(cj6));
32956 IkReal x10275=((sj0)*(sj5));
32957 IkReal x10276=((cj5)*(r12));
32958 IkReal x10277=((IkReal(1.00000000000000))*(r00)*(sj6));
32959 if( IKabs(((((IkReal(-1.00000000000000))*(r01)*(x10274)*(x10275)))+(((cj6)*(r11)*(x10272)))+(((x10272)*(x10273)))+(((IkReal(-1.00000000000000))*(x10275)*(x10277)))+(((IkReal(-1.00000000000000))*(cj0)*(x10276)))+(((sj0)*(x10271))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x10272)*(x10277)))+(((IkReal(-1.00000000000000))*(r11)*(x10274)*(x10275)))+(((IkReal(-1.00000000000000))*(r01)*(x10272)*(x10274)))+(((IkReal(-1.00000000000000))*(x10273)*(x10275)))+(((cj0)*(x10271)))+(((sj0)*(x10276))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x10274)*(x10275)))+(((cj6)*(r11)*(x10272)))+(((x10272)*(x10273)))+(((IkReal(-1.00000000000000))*(x10275)*(x10277)))+(((IkReal(-1.00000000000000))*(cj0)*(x10276)))+(((sj0)*(x10271)))))+IKsqr(((((IkReal(-1.00000000000000))*(x10272)*(x10277)))+(((IkReal(-1.00000000000000))*(r11)*(x10274)*(x10275)))+(((IkReal(-1.00000000000000))*(r01)*(x10272)*(x10274)))+(((IkReal(-1.00000000000000))*(x10273)*(x10275)))+(((cj0)*(x10271)))+(((sj0)*(x10276)))))-1) <= IKFAST_SINCOS_THRESH )
32960     continue;
32961 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r01)*(x10274)*(x10275)))+(((cj6)*(r11)*(x10272)))+(((x10272)*(x10273)))+(((IkReal(-1.00000000000000))*(x10275)*(x10277)))+(((IkReal(-1.00000000000000))*(cj0)*(x10276)))+(((sj0)*(x10271)))), ((((IkReal(-1.00000000000000))*(x10272)*(x10277)))+(((IkReal(-1.00000000000000))*(r11)*(x10274)*(x10275)))+(((IkReal(-1.00000000000000))*(r01)*(x10272)*(x10274)))+(((IkReal(-1.00000000000000))*(x10273)*(x10275)))+(((cj0)*(x10271)))+(((sj0)*(x10276)))));
32962 sj3array[0]=IKsin(j3array[0]);
32963 cj3array[0]=IKcos(j3array[0]);
32964 if( j3array[0] > IKPI )
32965 {
32966     j3array[0]-=IK2PI;
32967 }
32968 else if( j3array[0] < -IKPI )
32969 {    j3array[0]+=IK2PI;
32970 }
32971 j3valid[0] = true;
32972 for(int ij3 = 0; ij3 < 1; ++ij3)
32973 {
32974 if( !j3valid[ij3] )
32975 {
32976     continue;
32977 }
32978 _ij3[0] = ij3; _ij3[1] = -1;
32979 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
32980 {
32981 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
32982 {
32983     j3valid[iij3]=false; _ij3[1] = iij3; break; 
32984 }
32985 }
32986 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
32987 {
32988 IkReal evalcond[4];
32989 IkReal x10278=IKsin(j3);
32990 IkReal x10279=((sj0)*(sj5));
32991 IkReal x10280=((r00)*(sj6));
32992 IkReal x10281=((IkReal(1.00000000000000))*(cj4));
32993 IkReal x10282=((cj6)*(sj0));
32994 IkReal x10283=((r00)*(sj4));
32995 IkReal x10284=((cj0)*(cj5));
32996 IkReal x10285=((cj6)*(r01));
32997 IkReal x10286=((cj5)*(sj0));
32998 IkReal x10287=((cj0)*(sj5));
32999 IkReal x10288=((cj6)*(r11));
33000 IkReal x10289=((r10)*(sj6));
33001 IkReal x10290=((r10)*(sj4));
33002 IkReal x10291=((IkReal(1.00000000000000))*(IKcos(j3)));
33003 IkReal x10292=((cj0)*(sj4)*(sj6));
33004 IkReal x10293=((sj0)*(sj4)*(sj6));
33005 IkReal x10294=((IkReal(1.00000000000000))*(cj0)*(cj6));
33006 evalcond[0]=((x10278)+(((r12)*(x10284)))+(((x10279)*(x10280)))+(((x10279)*(x10285)))+(((IkReal(-1.00000000000000))*(x10287)*(x10288)))+(((IkReal(-1.00000000000000))*(r02)*(x10286)))+(((IkReal(-1.00000000000000))*(x10287)*(x10289))));
33007 evalcond[1]=((((r12)*(x10286)))+(((IkReal(-1.00000000000000))*(x10279)*(x10289)))+(((r02)*(x10284)))+(((IkReal(-1.00000000000000))*(x10291)))+(((IkReal(-1.00000000000000))*(x10285)*(x10287)))+(((IkReal(-1.00000000000000))*(x10280)*(x10287)))+(((IkReal(-1.00000000000000))*(x10279)*(x10288))));
33008 evalcond[2]=((((cj4)*(r02)*(x10279)))+(((IkReal(-1.00000000000000))*(x10290)*(x10294)))+(((IkReal(-1.00000000000000))*(x10291)))+(((IkReal(-1.00000000000000))*(r12)*(x10281)*(x10287)))+(((IkReal(-1.00000000000000))*(x10281)*(x10284)*(x10288)))+(((IkReal(-1.00000000000000))*(r01)*(x10293)))+(((r11)*(x10292)))+(((cj4)*(cj5)*(r01)*(x10282)))+(((IkReal(-1.00000000000000))*(x10281)*(x10284)*(x10289)))+(((x10282)*(x10283)))+(((cj4)*(x10280)*(x10286))));
33009 evalcond[3]=((((IkReal(-1.00000000000000))*(x10281)*(x10284)*(x10285)))+(((IkReal(-1.00000000000000))*(r12)*(x10279)*(x10281)))+(((IkReal(-1.00000000000000))*(x10281)*(x10286)*(x10289)))+(((r01)*(x10292)))+(((IkReal(-1.00000000000000))*(x10283)*(x10294)))+(((IkReal(-1.00000000000000))*(r02)*(x10281)*(x10287)))+(((IkReal(-1.00000000000000))*(x10282)*(x10290)))+(((IkReal(-1.00000000000000))*(x10280)*(x10281)*(x10284)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x10281)*(x10282)))+(((r11)*(x10293)))+(((IkReal(-1.00000000000000))*(x10278))));
33010 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
33011 {
33012 continue;
33013 }
33014 }
33015 
33016 {
33017 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33018 vinfos[0].jointtype = 1;
33019 vinfos[0].foffset = j0;
33020 vinfos[0].indices[0] = _ij0[0];
33021 vinfos[0].indices[1] = _ij0[1];
33022 vinfos[0].maxsolutions = _nj0;
33023 vinfos[1].jointtype = 1;
33024 vinfos[1].foffset = j1;
33025 vinfos[1].indices[0] = _ij1[0];
33026 vinfos[1].indices[1] = _ij1[1];
33027 vinfos[1].maxsolutions = _nj1;
33028 vinfos[2].jointtype = 1;
33029 vinfos[2].foffset = j2;
33030 vinfos[2].indices[0] = _ij2[0];
33031 vinfos[2].indices[1] = _ij2[1];
33032 vinfos[2].maxsolutions = _nj2;
33033 vinfos[3].jointtype = 1;
33034 vinfos[3].foffset = j3;
33035 vinfos[3].indices[0] = _ij3[0];
33036 vinfos[3].indices[1] = _ij3[1];
33037 vinfos[3].maxsolutions = _nj3;
33038 vinfos[4].jointtype = 1;
33039 vinfos[4].foffset = j4;
33040 vinfos[4].indices[0] = _ij4[0];
33041 vinfos[4].indices[1] = _ij4[1];
33042 vinfos[4].maxsolutions = _nj4;
33043 vinfos[5].jointtype = 1;
33044 vinfos[5].foffset = j5;
33045 vinfos[5].indices[0] = _ij5[0];
33046 vinfos[5].indices[1] = _ij5[1];
33047 vinfos[5].maxsolutions = _nj5;
33048 vinfos[6].jointtype = 1;
33049 vinfos[6].foffset = j6;
33050 vinfos[6].indices[0] = _ij6[0];
33051 vinfos[6].indices[1] = _ij6[1];
33052 vinfos[6].maxsolutions = _nj6;
33053 std::vector<int> vfree(0);
33054 solutions.AddSolution(vinfos,vfree);
33055 }
33056 }
33057 }
33058 
33059 } else
33060 {
33061 IkReal x10295=((IkReal(1.00000000000000))*(cj0));
33062 IkReal x10296=((cj4)*(sj6));
33063 IkReal x10297=((sj0)*(sj4));
33064 IkReal x10298=((cj5)*(sj6));
33065 IkReal x10299=((sj4)*(sj5));
33066 IkReal x10300=((r12)*(sj5));
33067 IkReal x10301=((IkReal(0.374290000000000))*(cj5));
33068 IkReal x10302=((r02)*(sj0));
33069 IkReal x10303=((r20)*(sj4));
33070 IkReal x10304=((IkReal(1.00000000000000))*(sj0));
33071 IkReal x10305=((IkReal(1.00000000000000))*(cj5));
33072 IkReal x10306=((cj0)*(r10));
33073 IkReal x10307=((cj4)*(cj6));
33074 IkReal x10308=((r00)*(sj0));
33075 IkReal x10309=((cj6)*(r21));
33076 IkReal x10310=((IkReal(0.374290000000000))*(sj5));
33077 IkReal x10311=((cj0)*(r00));
33078 IkReal x10312=((IkReal(0.0100000000000000))*(sj5));
33079 IkReal x10313=((cj0)*(r02));
33080 IkReal x10314=((cj5)*(sj4));
33081 IkReal x10315=((cj6)*(r01));
33082 IkReal x10316=((cj6)*(r11));
33083 IkReal x10317=((r01)*(sj0));
33084 IkReal x10318=((r10)*(sj0));
33085 IkReal x10319=((IkReal(0.0100000000000000))*(cj5)*(cj6));
33086 IkReal x10320=((sj6)*(x10310));
33087 IkReal x10321=((cj0)*(cj6)*(x10310));
33088 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
33089 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x10305)))+(((sj5)*(x10309)))+(((r20)*(sj5)*(sj6))));
33090 evalcond[2]=((IkReal(-1.00000000000000))+(((r21)*(x10296)))+(((x10298)*(x10303)))+(((x10309)*(x10314)))+(((IkReal(-1.00000000000000))*(r20)*(x10307)))+(((r22)*(x10299))));
33091 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x10312)))+(((r20)*(x10320)))+(((IkReal(-0.0100000000000000))*(cj5)*(x10309)))+(((IkReal(-0.0100000000000000))*(r20)*(x10298)))+(((x10309)*(x10310)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x10301))));
33092 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x10307)))+(((cj5)*(r20)*(x10296)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x10303))));
33093 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(x10295)*(x10296)))+(((cj5)*(x10297)*(x10315)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x10295)*(x10298)))+(((x10296)*(x10317)))+(((r02)*(sj5)*(x10297)))+(((IkReal(-1.00000000000000))*(r12)*(x10295)*(x10299)))+(((r00)*(x10297)*(x10298)))+(((x10306)*(x10307)))+(((IkReal(-1.00000000000000))*(r00)*(x10304)*(x10307)))+(((IkReal(-1.00000000000000))*(x10295)*(x10314)*(x10316))));
33094 evalcond[6]=((((IkReal(-1.00000000000000))*(x10297)*(x10305)*(x10316)))+(((IkReal(-1.00000000000000))*(x10295)*(x10314)*(x10315)))+(((IkReal(-1.00000000000000))*(r02)*(x10295)*(x10299)))+(((x10307)*(x10311)))+(((IkReal(-1.00000000000000))*(r11)*(x10296)*(x10304)))+(((IkReal(-1.00000000000000))*(r01)*(x10295)*(x10296)))+(((x10307)*(x10318)))+(((IkReal(-1.00000000000000))*(x10297)*(x10300)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x10295)*(x10298)))+(((IkReal(-1.00000000000000))*(r10)*(x10297)*(x10298))));
33095 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(0.0100000000000000))*(x10298)*(x10306)))+(((IkReal(-1.00000000000000))*(cj0)*(x10310)*(x10316)))+(((IkReal(-1.00000000000000))*(x10306)*(x10320)))+(((cj0)*(r12)*(x10301)))+(((IkReal(-1.00000000000000))*(x10301)*(x10302)))+(((IkReal(-1.00000000000000))*(x10302)*(x10312)))+(((x10308)*(x10320)))+(((IkReal(-0.0100000000000000))*(x10298)*(x10308)))+(((IkReal(-1.00000000000000))*(py)*(x10295)))+(((sj0)*(x10310)*(x10315)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x10315)))+(((IkReal(0.0100000000000000))*(cj0)*(x10300)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10316)))+(((px)*(sj0))));
33096 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(px)*(x10295)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10315)))+(((IkReal(0.0100000000000000))*(x10298)*(x10311)))+(((IkReal(0.0100000000000000))*(sj0)*(x10300)))+(((IkReal(0.0100000000000000))*(x10298)*(x10318)))+(((IkReal(-1.00000000000000))*(py)*(x10304)))+(((IkReal(-1.00000000000000))*(x10318)*(x10320)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x10316)))+(((r12)*(sj0)*(x10301)))+(((IkReal(-1.00000000000000))*(x10311)*(x10320)))+(((IkReal(-1.00000000000000))*(cj0)*(x10310)*(x10315)))+(((x10312)*(x10313)))+(((IkReal(-1.00000000000000))*(sj0)*(x10310)*(x10316)))+(((x10301)*(x10313))));
33097 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
33098 {
33099 {
33100 IkReal j3array[1], cj3array[1], sj3array[1];
33101 bool j3valid[1]={false};
33102 _nj3 = 1;
33103 IkReal x10322=((IkReal(1.00000000000000))*(cj5));
33104 IkReal x10323=((r10)*(sj5)*(sj6));
33105 IkReal x10324=((cj6)*(sj0)*(sj5));
33106 IkReal x10325=((r00)*(sj5)*(sj6));
33107 IkReal x10326=((cj0)*(cj6)*(sj5));
33108 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10322)))+(((r11)*(x10326)))+(((cj0)*(x10323)))+(((IkReal(-1.00000000000000))*(sj0)*(x10325)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x10324))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj0)*(x10323)))+(((cj0)*(x10325)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10322)))+(((r11)*(x10324)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10322)))+(((r01)*(x10326))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10322)))+(((r11)*(x10326)))+(((cj0)*(x10323)))+(((IkReal(-1.00000000000000))*(sj0)*(x10325)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x10324)))))+IKsqr(((((sj0)*(x10323)))+(((cj0)*(x10325)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10322)))+(((r11)*(x10324)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10322)))+(((r01)*(x10326)))))-1) <= IKFAST_SINCOS_THRESH )
33109     continue;
33110 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10322)))+(((r11)*(x10326)))+(((cj0)*(x10323)))+(((IkReal(-1.00000000000000))*(sj0)*(x10325)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x10324)))), ((((sj0)*(x10323)))+(((cj0)*(x10325)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10322)))+(((r11)*(x10324)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10322)))+(((r01)*(x10326)))));
33111 sj3array[0]=IKsin(j3array[0]);
33112 cj3array[0]=IKcos(j3array[0]);
33113 if( j3array[0] > IKPI )
33114 {
33115     j3array[0]-=IK2PI;
33116 }
33117 else if( j3array[0] < -IKPI )
33118 {    j3array[0]+=IK2PI;
33119 }
33120 j3valid[0] = true;
33121 for(int ij3 = 0; ij3 < 1; ++ij3)
33122 {
33123 if( !j3valid[ij3] )
33124 {
33125     continue;
33126 }
33127 _ij3[0] = ij3; _ij3[1] = -1;
33128 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33129 {
33130 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33131 {
33132     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33133 }
33134 }
33135 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33136 {
33137 IkReal evalcond[4];
33138 IkReal x10327=IKcos(j3);
33139 IkReal x10328=IKsin(j3);
33140 IkReal x10329=((sj0)*(sj5));
33141 IkReal x10330=((r00)*(sj6));
33142 IkReal x10331=((IkReal(1.00000000000000))*(cj4));
33143 IkReal x10332=((cj6)*(sj0));
33144 IkReal x10333=((r00)*(sj4));
33145 IkReal x10334=((cj0)*(cj5));
33146 IkReal x10335=((cj6)*(r01));
33147 IkReal x10336=((cj5)*(sj0));
33148 IkReal x10337=((cj0)*(sj5));
33149 IkReal x10338=((cj6)*(r11));
33150 IkReal x10339=((r10)*(sj6));
33151 IkReal x10340=((r10)*(sj4));
33152 IkReal x10341=((cj0)*(sj4)*(sj6));
33153 IkReal x10342=((sj0)*(sj4)*(sj6));
33154 IkReal x10343=((IkReal(1.00000000000000))*(cj0)*(cj6));
33155 evalcond[0]=((x10328)+(((x10329)*(x10330)))+(((IkReal(-1.00000000000000))*(r02)*(x10336)))+(((IkReal(-1.00000000000000))*(x10337)*(x10339)))+(((r12)*(x10334)))+(((IkReal(-1.00000000000000))*(x10337)*(x10338)))+(((x10329)*(x10335))));
33156 evalcond[1]=((((r12)*(x10336)))+(x10327)+(((IkReal(-1.00000000000000))*(x10330)*(x10337)))+(((IkReal(-1.00000000000000))*(x10329)*(x10338)))+(((IkReal(-1.00000000000000))*(x10335)*(x10337)))+(((r02)*(x10334)))+(((IkReal(-1.00000000000000))*(x10329)*(x10339))));
33157 evalcond[2]=((((IkReal(-1.00000000000000))*(x10331)*(x10334)*(x10339)))+(((IkReal(-1.00000000000000))*(x10340)*(x10343)))+(((IkReal(-1.00000000000000))*(x10331)*(x10334)*(x10338)))+(((x10332)*(x10333)))+(((IkReal(-1.00000000000000))*(r12)*(x10331)*(x10337)))+(((IkReal(-1.00000000000000))*(r01)*(x10342)))+(((cj4)*(r02)*(x10329)))+(((cj4)*(x10330)*(x10336)))+(((IkReal(-1.00000000000000))*(x10327)))+(((cj4)*(cj5)*(r01)*(x10332)))+(((r11)*(x10341))));
33158 evalcond[3]=((((r11)*(x10342)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x10331)*(x10332)))+(x10328)+(((IkReal(-1.00000000000000))*(x10330)*(x10331)*(x10334)))+(((IkReal(-1.00000000000000))*(r12)*(x10329)*(x10331)))+(((IkReal(-1.00000000000000))*(r02)*(x10331)*(x10337)))+(((r01)*(x10341)))+(((IkReal(-1.00000000000000))*(x10331)*(x10334)*(x10335)))+(((IkReal(-1.00000000000000))*(x10331)*(x10336)*(x10339)))+(((IkReal(-1.00000000000000))*(x10333)*(x10343)))+(((IkReal(-1.00000000000000))*(x10332)*(x10340))));
33159 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
33160 {
33161 continue;
33162 }
33163 }
33164 
33165 {
33166 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33167 vinfos[0].jointtype = 1;
33168 vinfos[0].foffset = j0;
33169 vinfos[0].indices[0] = _ij0[0];
33170 vinfos[0].indices[1] = _ij0[1];
33171 vinfos[0].maxsolutions = _nj0;
33172 vinfos[1].jointtype = 1;
33173 vinfos[1].foffset = j1;
33174 vinfos[1].indices[0] = _ij1[0];
33175 vinfos[1].indices[1] = _ij1[1];
33176 vinfos[1].maxsolutions = _nj1;
33177 vinfos[2].jointtype = 1;
33178 vinfos[2].foffset = j2;
33179 vinfos[2].indices[0] = _ij2[0];
33180 vinfos[2].indices[1] = _ij2[1];
33181 vinfos[2].maxsolutions = _nj2;
33182 vinfos[3].jointtype = 1;
33183 vinfos[3].foffset = j3;
33184 vinfos[3].indices[0] = _ij3[0];
33185 vinfos[3].indices[1] = _ij3[1];
33186 vinfos[3].maxsolutions = _nj3;
33187 vinfos[4].jointtype = 1;
33188 vinfos[4].foffset = j4;
33189 vinfos[4].indices[0] = _ij4[0];
33190 vinfos[4].indices[1] = _ij4[1];
33191 vinfos[4].maxsolutions = _nj4;
33192 vinfos[5].jointtype = 1;
33193 vinfos[5].foffset = j5;
33194 vinfos[5].indices[0] = _ij5[0];
33195 vinfos[5].indices[1] = _ij5[1];
33196 vinfos[5].maxsolutions = _nj5;
33197 vinfos[6].jointtype = 1;
33198 vinfos[6].foffset = j6;
33199 vinfos[6].indices[0] = _ij6[0];
33200 vinfos[6].indices[1] = _ij6[1];
33201 vinfos[6].maxsolutions = _nj6;
33202 std::vector<int> vfree(0);
33203 solutions.AddSolution(vinfos,vfree);
33204 }
33205 }
33206 }
33207 
33208 } else
33209 {
33210 if( 1 )
33211 {
33212 continue;
33213 
33214 } else
33215 {
33216 }
33217 }
33218 }
33219 }
33220 }
33221 }
33222 
33223 } else
33224 {
33225 {
33226 IkReal j3array[1], cj3array[1], sj3array[1];
33227 bool j3valid[1]={false};
33228 _nj3 = 1;
33229 IkReal x10344=((cj5)*(r02));
33230 IkReal x10345=((cj0)*(sj5));
33231 IkReal x10346=((r10)*(sj6));
33232 IkReal x10347=((IkReal(1.00000000000000))*(cj6));
33233 IkReal x10348=((sj0)*(sj5));
33234 IkReal x10349=((cj5)*(r12));
33235 IkReal x10350=((IkReal(1.00000000000000))*(r00)*(sj6));
33236 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x10349)))+(((IkReal(-1.00000000000000))*(x10348)*(x10350)))+(((x10345)*(x10346)))+(((cj6)*(r11)*(x10345)))+(((sj0)*(x10344)))+(((IkReal(-1.00000000000000))*(r01)*(x10347)*(x10348))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x10349)))+(((IkReal(-1.00000000000000))*(r11)*(x10347)*(x10348)))+(((cj0)*(x10344)))+(((IkReal(-1.00000000000000))*(x10345)*(x10350)))+(((IkReal(-1.00000000000000))*(r01)*(x10345)*(x10347)))+(((IkReal(-1.00000000000000))*(x10346)*(x10348))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x10349)))+(((IkReal(-1.00000000000000))*(x10348)*(x10350)))+(((x10345)*(x10346)))+(((cj6)*(r11)*(x10345)))+(((sj0)*(x10344)))+(((IkReal(-1.00000000000000))*(r01)*(x10347)*(x10348)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x10349)))+(((IkReal(-1.00000000000000))*(r11)*(x10347)*(x10348)))+(((cj0)*(x10344)))+(((IkReal(-1.00000000000000))*(x10345)*(x10350)))+(((IkReal(-1.00000000000000))*(r01)*(x10345)*(x10347)))+(((IkReal(-1.00000000000000))*(x10346)*(x10348)))))))-1) <= IKFAST_SINCOS_THRESH )
33237     continue;
33238 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x10349)))+(((IkReal(-1.00000000000000))*(x10348)*(x10350)))+(((x10345)*(x10346)))+(((cj6)*(r11)*(x10345)))+(((sj0)*(x10344)))+(((IkReal(-1.00000000000000))*(r01)*(x10347)*(x10348)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((sj0)*(x10349)))+(((IkReal(-1.00000000000000))*(r11)*(x10347)*(x10348)))+(((cj0)*(x10344)))+(((IkReal(-1.00000000000000))*(x10345)*(x10350)))+(((IkReal(-1.00000000000000))*(r01)*(x10345)*(x10347)))+(((IkReal(-1.00000000000000))*(x10346)*(x10348)))))));
33239 sj3array[0]=IKsin(j3array[0]);
33240 cj3array[0]=IKcos(j3array[0]);
33241 if( j3array[0] > IKPI )
33242 {
33243     j3array[0]-=IK2PI;
33244 }
33245 else if( j3array[0] < -IKPI )
33246 {    j3array[0]+=IK2PI;
33247 }
33248 j3valid[0] = true;
33249 for(int ij3 = 0; ij3 < 1; ++ij3)
33250 {
33251 if( !j3valid[ij3] )
33252 {
33253     continue;
33254 }
33255 _ij3[0] = ij3; _ij3[1] = -1;
33256 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33257 {
33258 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33259 {
33260     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33261 }
33262 }
33263 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33264 {
33265 IkReal evalcond[6];
33266 IkReal x10351=IKsin(j3);
33267 IkReal x10352=IKcos(j3);
33268 IkReal x10353=((sj0)*(sj5));
33269 IkReal x10354=((r00)*(sj6));
33270 IkReal x10355=((IkReal(1.00000000000000))*(cj4));
33271 IkReal x10356=((cj6)*(r01));
33272 IkReal x10357=((cj0)*(cj5));
33273 IkReal x10358=((cj5)*(sj0));
33274 IkReal x10359=((cj6)*(r11));
33275 IkReal x10360=((cj0)*(sj5));
33276 IkReal x10361=((IkReal(1.00000000000000))*(cj1));
33277 IkReal x10362=((cj6)*(sj4));
33278 IkReal x10363=((IkReal(1.00000000000000))*(sj1));
33279 IkReal x10364=((cj4)*(cj5));
33280 IkReal x10365=((cj6)*(r21));
33281 IkReal x10366=((r20)*(sj6));
33282 IkReal x10367=((r10)*(sj6));
33283 IkReal x10368=((IkReal(1.00000000000000))*(cj0));
33284 IkReal x10369=((cj0)*(sj4)*(sj6));
33285 IkReal x10370=((sj0)*(sj4)*(sj6));
33286 evalcond[0]=((((sj5)*(x10365)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10366)))+(((IkReal(-1.00000000000000))*(x10352)*(x10363))));
33287 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x10351)*(x10363)))+(((x10364)*(x10365)))+(((x10364)*(x10366)))+(((r20)*(x10362))));
33288 evalcond[2]=((((r12)*(x10357)))+(((x10353)*(x10356)))+(((IkReal(-1.00000000000000))*(x10359)*(x10360)))+(x10351)+(((x10353)*(x10354)))+(((IkReal(-1.00000000000000))*(x10360)*(x10367)))+(((IkReal(-1.00000000000000))*(r02)*(x10358))));
33289 evalcond[3]=((((IkReal(-1.00000000000000))*(x10352)*(x10361)))+(((r12)*(x10358)))+(((IkReal(-1.00000000000000))*(x10353)*(x10359)))+(((IkReal(-1.00000000000000))*(x10354)*(x10360)))+(((r02)*(x10357)))+(((IkReal(-1.00000000000000))*(x10353)*(x10367)))+(((IkReal(-1.00000000000000))*(x10356)*(x10360))));
33290 evalcond[4]=((((IkReal(-1.00000000000000))*(x10355)*(x10357)*(x10367)))+(((IkReal(-1.00000000000000))*(x10355)*(x10357)*(x10359)))+(((r11)*(x10369)))+(((cj4)*(r02)*(x10353)))+(((cj4)*(x10354)*(x10358)))+(((cj4)*(x10356)*(x10358)))+(((r00)*(sj0)*(x10362)))+(((IkReal(-1.00000000000000))*(r10)*(x10362)*(x10368)))+(((IkReal(-1.00000000000000))*(r01)*(x10370)))+(((IkReal(-1.00000000000000))*(r12)*(x10355)*(x10360)))+(((IkReal(-1.00000000000000))*(x10352))));
33291 evalcond[5]=((((IkReal(-1.00000000000000))*(x10354)*(x10355)*(x10357)))+(((IkReal(-1.00000000000000))*(r02)*(x10355)*(x10360)))+(((IkReal(-1.00000000000000))*(x10351)*(x10361)))+(((IkReal(-1.00000000000000))*(r12)*(x10353)*(x10355)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10362)))+(((IkReal(-1.00000000000000))*(x10355)*(x10356)*(x10357)))+(((IkReal(-1.00000000000000))*(x10355)*(x10358)*(x10367)))+(((r01)*(x10369)))+(((IkReal(-1.00000000000000))*(r00)*(x10362)*(x10368)))+(((r11)*(x10370)))+(((IkReal(-1.00000000000000))*(x10355)*(x10358)*(x10359))));
33292 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
33293 {
33294 continue;
33295 }
33296 }
33297 
33298 {
33299 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33300 vinfos[0].jointtype = 1;
33301 vinfos[0].foffset = j0;
33302 vinfos[0].indices[0] = _ij0[0];
33303 vinfos[0].indices[1] = _ij0[1];
33304 vinfos[0].maxsolutions = _nj0;
33305 vinfos[1].jointtype = 1;
33306 vinfos[1].foffset = j1;
33307 vinfos[1].indices[0] = _ij1[0];
33308 vinfos[1].indices[1] = _ij1[1];
33309 vinfos[1].maxsolutions = _nj1;
33310 vinfos[2].jointtype = 1;
33311 vinfos[2].foffset = j2;
33312 vinfos[2].indices[0] = _ij2[0];
33313 vinfos[2].indices[1] = _ij2[1];
33314 vinfos[2].maxsolutions = _nj2;
33315 vinfos[3].jointtype = 1;
33316 vinfos[3].foffset = j3;
33317 vinfos[3].indices[0] = _ij3[0];
33318 vinfos[3].indices[1] = _ij3[1];
33319 vinfos[3].maxsolutions = _nj3;
33320 vinfos[4].jointtype = 1;
33321 vinfos[4].foffset = j4;
33322 vinfos[4].indices[0] = _ij4[0];
33323 vinfos[4].indices[1] = _ij4[1];
33324 vinfos[4].maxsolutions = _nj4;
33325 vinfos[5].jointtype = 1;
33326 vinfos[5].foffset = j5;
33327 vinfos[5].indices[0] = _ij5[0];
33328 vinfos[5].indices[1] = _ij5[1];
33329 vinfos[5].maxsolutions = _nj5;
33330 vinfos[6].jointtype = 1;
33331 vinfos[6].foffset = j6;
33332 vinfos[6].indices[0] = _ij6[0];
33333 vinfos[6].indices[1] = _ij6[1];
33334 vinfos[6].maxsolutions = _nj6;
33335 std::vector<int> vfree(0);
33336 solutions.AddSolution(vinfos,vfree);
33337 }
33338 }
33339 }
33340 
33341 }
33342 
33343 }
33344 
33345 } else
33346 {
33347 {
33348 IkReal j3array[1], cj3array[1], sj3array[1];
33349 bool j3valid[1]={false};
33350 _nj3 = 1;
33351 IkReal x10371=((sj5)*(sj6));
33352 IkReal x10372=((IkReal(1.00000000000000))*(sj0));
33353 IkReal x10373=((cj6)*(sj5));
33354 IkReal x10374=((IkReal(1.00000000000000))*(cj5));
33355 if( IKabs(((((cj0)*(r11)*(x10373)))+(((IkReal(-1.00000000000000))*(r01)*(x10372)*(x10373)))+(((cj0)*(r10)*(x10371)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x10371)*(x10372)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10374))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10374)))+(((r20)*(x10371)))+(((r21)*(x10373))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r11)*(x10373)))+(((IkReal(-1.00000000000000))*(r01)*(x10372)*(x10373)))+(((cj0)*(r10)*(x10371)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x10371)*(x10372)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10374)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10374)))+(((r20)*(x10371)))+(((r21)*(x10373)))))))-1) <= IKFAST_SINCOS_THRESH )
33356     continue;
33357 j3array[0]=IKatan2(((((cj0)*(r11)*(x10373)))+(((IkReal(-1.00000000000000))*(r01)*(x10372)*(x10373)))+(((cj0)*(r10)*(x10371)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x10371)*(x10372)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10374)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10374)))+(((r20)*(x10371)))+(((r21)*(x10373)))))));
33358 sj3array[0]=IKsin(j3array[0]);
33359 cj3array[0]=IKcos(j3array[0]);
33360 if( j3array[0] > IKPI )
33361 {
33362     j3array[0]-=IK2PI;
33363 }
33364 else if( j3array[0] < -IKPI )
33365 {    j3array[0]+=IK2PI;
33366 }
33367 j3valid[0] = true;
33368 for(int ij3 = 0; ij3 < 1; ++ij3)
33369 {
33370 if( !j3valid[ij3] )
33371 {
33372     continue;
33373 }
33374 _ij3[0] = ij3; _ij3[1] = -1;
33375 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33376 {
33377 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33378 {
33379     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33380 }
33381 }
33382 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33383 {
33384 IkReal evalcond[6];
33385 IkReal x10375=IKsin(j3);
33386 IkReal x10376=IKcos(j3);
33387 IkReal x10377=((sj0)*(sj5));
33388 IkReal x10378=((r00)*(sj6));
33389 IkReal x10379=((IkReal(1.00000000000000))*(cj4));
33390 IkReal x10380=((cj6)*(r01));
33391 IkReal x10381=((cj0)*(cj5));
33392 IkReal x10382=((cj5)*(sj0));
33393 IkReal x10383=((cj6)*(r11));
33394 IkReal x10384=((cj0)*(sj5));
33395 IkReal x10385=((IkReal(1.00000000000000))*(cj1));
33396 IkReal x10386=((cj6)*(sj4));
33397 IkReal x10387=((IkReal(1.00000000000000))*(sj1));
33398 IkReal x10388=((cj4)*(cj5));
33399 IkReal x10389=((cj6)*(r21));
33400 IkReal x10390=((r20)*(sj6));
33401 IkReal x10391=((r10)*(sj6));
33402 IkReal x10392=((IkReal(1.00000000000000))*(cj0));
33403 IkReal x10393=((cj0)*(sj4)*(sj6));
33404 IkReal x10394=((sj0)*(sj4)*(sj6));
33405 evalcond[0]=((((sj5)*(x10390)))+(((IkReal(-1.00000000000000))*(x10376)*(x10387)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10389))));
33406 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10388)*(x10390)))+(((r20)*(x10386)))+(((cj4)*(r22)*(sj5)))+(((x10388)*(x10389)))+(((IkReal(-1.00000000000000))*(x10375)*(x10387))));
33407 evalcond[2]=((((x10377)*(x10378)))+(((IkReal(-1.00000000000000))*(x10384)*(x10391)))+(((IkReal(-1.00000000000000))*(x10383)*(x10384)))+(((IkReal(-1.00000000000000))*(r02)*(x10382)))+(x10375)+(((r12)*(x10381)))+(((x10377)*(x10380))));
33408 evalcond[3]=((((IkReal(-1.00000000000000))*(x10377)*(x10391)))+(((IkReal(-1.00000000000000))*(x10378)*(x10384)))+(((IkReal(-1.00000000000000))*(x10376)*(x10385)))+(((IkReal(-1.00000000000000))*(x10377)*(x10383)))+(((r12)*(x10382)))+(((IkReal(-1.00000000000000))*(x10380)*(x10384)))+(((r02)*(x10381))));
33409 evalcond[4]=((((IkReal(-1.00000000000000))*(x10379)*(x10381)*(x10391)))+(((cj4)*(x10380)*(x10382)))+(((r00)*(sj0)*(x10386)))+(((cj4)*(x10378)*(x10382)))+(((cj4)*(r02)*(x10377)))+(((IkReal(-1.00000000000000))*(r12)*(x10379)*(x10384)))+(((IkReal(-1.00000000000000))*(r10)*(x10386)*(x10392)))+(((IkReal(-1.00000000000000))*(x10379)*(x10381)*(x10383)))+(((IkReal(-1.00000000000000))*(r01)*(x10394)))+(((r11)*(x10393)))+(((IkReal(-1.00000000000000))*(x10376))));
33410 evalcond[5]=((((IkReal(-1.00000000000000))*(x10379)*(x10380)*(x10381)))+(((IkReal(-1.00000000000000))*(x10379)*(x10382)*(x10383)))+(((IkReal(-1.00000000000000))*(x10378)*(x10379)*(x10381)))+(((IkReal(-1.00000000000000))*(x10375)*(x10385)))+(((IkReal(-1.00000000000000))*(r12)*(x10377)*(x10379)))+(((r01)*(x10393)))+(((r11)*(x10394)))+(((IkReal(-1.00000000000000))*(r02)*(x10379)*(x10384)))+(((IkReal(-1.00000000000000))*(x10379)*(x10382)*(x10391)))+(((IkReal(-1.00000000000000))*(r00)*(x10386)*(x10392)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10386))));
33411 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
33412 {
33413 continue;
33414 }
33415 }
33416 
33417 {
33418 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33419 vinfos[0].jointtype = 1;
33420 vinfos[0].foffset = j0;
33421 vinfos[0].indices[0] = _ij0[0];
33422 vinfos[0].indices[1] = _ij0[1];
33423 vinfos[0].maxsolutions = _nj0;
33424 vinfos[1].jointtype = 1;
33425 vinfos[1].foffset = j1;
33426 vinfos[1].indices[0] = _ij1[0];
33427 vinfos[1].indices[1] = _ij1[1];
33428 vinfos[1].maxsolutions = _nj1;
33429 vinfos[2].jointtype = 1;
33430 vinfos[2].foffset = j2;
33431 vinfos[2].indices[0] = _ij2[0];
33432 vinfos[2].indices[1] = _ij2[1];
33433 vinfos[2].maxsolutions = _nj2;
33434 vinfos[3].jointtype = 1;
33435 vinfos[3].foffset = j3;
33436 vinfos[3].indices[0] = _ij3[0];
33437 vinfos[3].indices[1] = _ij3[1];
33438 vinfos[3].maxsolutions = _nj3;
33439 vinfos[4].jointtype = 1;
33440 vinfos[4].foffset = j4;
33441 vinfos[4].indices[0] = _ij4[0];
33442 vinfos[4].indices[1] = _ij4[1];
33443 vinfos[4].maxsolutions = _nj4;
33444 vinfos[5].jointtype = 1;
33445 vinfos[5].foffset = j5;
33446 vinfos[5].indices[0] = _ij5[0];
33447 vinfos[5].indices[1] = _ij5[1];
33448 vinfos[5].maxsolutions = _nj5;
33449 vinfos[6].jointtype = 1;
33450 vinfos[6].foffset = j6;
33451 vinfos[6].indices[0] = _ij6[0];
33452 vinfos[6].indices[1] = _ij6[1];
33453 vinfos[6].maxsolutions = _nj6;
33454 std::vector<int> vfree(0);
33455 solutions.AddSolution(vinfos,vfree);
33456 }
33457 }
33458 }
33459 
33460 }
33461 
33462 }
33463 
33464 } else
33465 {
33466 {
33467 IkReal j3array[1], cj3array[1], sj3array[1];
33468 bool j3valid[1]={false};
33469 _nj3 = 1;
33470 IkReal x10395=((r20)*(sj6));
33471 IkReal x10396=((cj4)*(cj5));
33472 IkReal x10397=((cj6)*(r21));
33473 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10395)*(x10396)))+(((x10396)*(x10397))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((sj5)*(x10395)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10397))))))) < IKFAST_ATAN2_MAGTHRESH )
33474     continue;
33475 j3array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10395)*(x10396)))+(((x10396)*(x10397)))))), ((gconst30)*(((((sj5)*(x10395)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10397)))))));
33476 sj3array[0]=IKsin(j3array[0]);
33477 cj3array[0]=IKcos(j3array[0]);
33478 if( j3array[0] > IKPI )
33479 {
33480     j3array[0]-=IK2PI;
33481 }
33482 else if( j3array[0] < -IKPI )
33483 {    j3array[0]+=IK2PI;
33484 }
33485 j3valid[0] = true;
33486 for(int ij3 = 0; ij3 < 1; ++ij3)
33487 {
33488 if( !j3valid[ij3] )
33489 {
33490     continue;
33491 }
33492 _ij3[0] = ij3; _ij3[1] = -1;
33493 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33494 {
33495 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33496 {
33497     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33498 }
33499 }
33500 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33501 {
33502 IkReal evalcond[6];
33503 IkReal x10398=IKsin(j3);
33504 IkReal x10399=IKcos(j3);
33505 IkReal x10400=((sj0)*(sj5));
33506 IkReal x10401=((r00)*(sj6));
33507 IkReal x10402=((IkReal(1.00000000000000))*(cj4));
33508 IkReal x10403=((cj6)*(r01));
33509 IkReal x10404=((cj0)*(cj5));
33510 IkReal x10405=((cj5)*(sj0));
33511 IkReal x10406=((cj6)*(r11));
33512 IkReal x10407=((cj0)*(sj5));
33513 IkReal x10408=((IkReal(1.00000000000000))*(cj1));
33514 IkReal x10409=((cj6)*(sj4));
33515 IkReal x10410=((IkReal(1.00000000000000))*(sj1));
33516 IkReal x10411=((cj4)*(cj5));
33517 IkReal x10412=((cj6)*(r21));
33518 IkReal x10413=((r20)*(sj6));
33519 IkReal x10414=((r10)*(sj6));
33520 IkReal x10415=((IkReal(1.00000000000000))*(cj0));
33521 IkReal x10416=((cj0)*(sj4)*(sj6));
33522 IkReal x10417=((sj0)*(sj4)*(sj6));
33523 evalcond[0]=((((sj5)*(x10412)))+(((sj5)*(x10413)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10399)*(x10410))));
33524 evalcond[1]=((((IkReal(-1.00000000000000))*(x10398)*(x10410)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x10409)))+(((x10411)*(x10412)))+(((cj4)*(r22)*(sj5)))+(((x10411)*(x10413))));
33525 evalcond[2]=((((x10400)*(x10403)))+(((IkReal(-1.00000000000000))*(x10407)*(x10414)))+(((r12)*(x10404)))+(((IkReal(-1.00000000000000))*(r02)*(x10405)))+(((x10400)*(x10401)))+(((IkReal(-1.00000000000000))*(x10406)*(x10407)))+(x10398));
33526 evalcond[3]=((((r12)*(x10405)))+(((r02)*(x10404)))+(((IkReal(-1.00000000000000))*(x10400)*(x10406)))+(((IkReal(-1.00000000000000))*(x10403)*(x10407)))+(((IkReal(-1.00000000000000))*(x10399)*(x10408)))+(((IkReal(-1.00000000000000))*(x10401)*(x10407)))+(((IkReal(-1.00000000000000))*(x10400)*(x10414))));
33527 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x10409)*(x10415)))+(((r00)*(sj0)*(x10409)))+(((IkReal(-1.00000000000000))*(x10402)*(x10404)*(x10406)))+(((r11)*(x10416)))+(((IkReal(-1.00000000000000))*(x10399)))+(((cj4)*(x10403)*(x10405)))+(((IkReal(-1.00000000000000))*(r01)*(x10417)))+(((IkReal(-1.00000000000000))*(r12)*(x10402)*(x10407)))+(((cj4)*(x10401)*(x10405)))+(((cj4)*(r02)*(x10400)))+(((IkReal(-1.00000000000000))*(x10402)*(x10404)*(x10414))));
33528 evalcond[5]=((((r11)*(x10417)))+(((IkReal(-1.00000000000000))*(x10401)*(x10402)*(x10404)))+(((IkReal(-1.00000000000000))*(x10402)*(x10405)*(x10414)))+(((IkReal(-1.00000000000000))*(x10402)*(x10405)*(x10406)))+(((IkReal(-1.00000000000000))*(x10402)*(x10403)*(x10404)))+(((r01)*(x10416)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10409)))+(((IkReal(-1.00000000000000))*(x10398)*(x10408)))+(((IkReal(-1.00000000000000))*(r00)*(x10409)*(x10415)))+(((IkReal(-1.00000000000000))*(r02)*(x10402)*(x10407)))+(((IkReal(-1.00000000000000))*(r12)*(x10400)*(x10402))));
33529 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
33530 {
33531 continue;
33532 }
33533 }
33534 
33535 {
33536 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33537 vinfos[0].jointtype = 1;
33538 vinfos[0].foffset = j0;
33539 vinfos[0].indices[0] = _ij0[0];
33540 vinfos[0].indices[1] = _ij0[1];
33541 vinfos[0].maxsolutions = _nj0;
33542 vinfos[1].jointtype = 1;
33543 vinfos[1].foffset = j1;
33544 vinfos[1].indices[0] = _ij1[0];
33545 vinfos[1].indices[1] = _ij1[1];
33546 vinfos[1].maxsolutions = _nj1;
33547 vinfos[2].jointtype = 1;
33548 vinfos[2].foffset = j2;
33549 vinfos[2].indices[0] = _ij2[0];
33550 vinfos[2].indices[1] = _ij2[1];
33551 vinfos[2].maxsolutions = _nj2;
33552 vinfos[3].jointtype = 1;
33553 vinfos[3].foffset = j3;
33554 vinfos[3].indices[0] = _ij3[0];
33555 vinfos[3].indices[1] = _ij3[1];
33556 vinfos[3].maxsolutions = _nj3;
33557 vinfos[4].jointtype = 1;
33558 vinfos[4].foffset = j4;
33559 vinfos[4].indices[0] = _ij4[0];
33560 vinfos[4].indices[1] = _ij4[1];
33561 vinfos[4].maxsolutions = _nj4;
33562 vinfos[5].jointtype = 1;
33563 vinfos[5].foffset = j5;
33564 vinfos[5].indices[0] = _ij5[0];
33565 vinfos[5].indices[1] = _ij5[1];
33566 vinfos[5].maxsolutions = _nj5;
33567 vinfos[6].jointtype = 1;
33568 vinfos[6].foffset = j6;
33569 vinfos[6].indices[0] = _ij6[0];
33570 vinfos[6].indices[1] = _ij6[1];
33571 vinfos[6].maxsolutions = _nj6;
33572 std::vector<int> vfree(0);
33573 solutions.AddSolution(vinfos,vfree);
33574 }
33575 }
33576 }
33577 
33578 }
33579 
33580 }
33581 }
33582 }
33583 
33584 }
33585 
33586 }
33587 
33588 } else
33589 {
33590 {
33591 IkReal j4array[1], cj4array[1], sj4array[1];
33592 bool j4valid[1]={false};
33593 _nj4 = 1;
33594 IkReal x10418=((cj1)*(sj6));
33595 IkReal x10419=((r01)*(sj0));
33596 IkReal x10420=((cj0)*(r11));
33597 IkReal x10421=((cj1)*(cj6));
33598 IkReal x10422=((cj0)*(r10));
33599 IkReal x10423=((IkReal(1.00000000000000))*(sj0));
33600 IkReal x10424=((cj1)*(sj5));
33601 if( IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(r00)*(x10421)*(x10423)))+(((IkReal(-1.00000000000000))*(x10418)*(x10420)))+(((x10421)*(x10422)))+(((x10418)*(x10419))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(cj5)*(x10419)*(x10421)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10418)*(x10423)))+(((IkReal(-1.00000000000000))*(r02)*(x10423)*(x10424)))+(((cj5)*(x10418)*(x10422)))+(((cj5)*(x10420)*(x10421)))+(((cj0)*(r12)*(x10424))))))) < IKFAST_ATAN2_MAGTHRESH )
33602     continue;
33603 j4array[0]=IKatan2(((gconst26)*(((((IkReal(-1.00000000000000))*(r00)*(x10421)*(x10423)))+(((IkReal(-1.00000000000000))*(x10418)*(x10420)))+(((x10421)*(x10422)))+(((x10418)*(x10419)))))), ((gconst26)*(((((IkReal(-1.00000000000000))*(cj5)*(x10419)*(x10421)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10418)*(x10423)))+(((IkReal(-1.00000000000000))*(r02)*(x10423)*(x10424)))+(((cj5)*(x10418)*(x10422)))+(((cj5)*(x10420)*(x10421)))+(((cj0)*(r12)*(x10424)))))));
33604 sj4array[0]=IKsin(j4array[0]);
33605 cj4array[0]=IKcos(j4array[0]);
33606 if( j4array[0] > IKPI )
33607 {
33608     j4array[0]-=IK2PI;
33609 }
33610 else if( j4array[0] < -IKPI )
33611 {    j4array[0]+=IK2PI;
33612 }
33613 j4valid[0] = true;
33614 for(int ij4 = 0; ij4 < 1; ++ij4)
33615 {
33616 if( !j4valid[ij4] )
33617 {
33618     continue;
33619 }
33620 _ij4[0] = ij4; _ij4[1] = -1;
33621 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
33622 {
33623 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
33624 {
33625     j4valid[iij4]=false; _ij4[1] = iij4; break; 
33626 }
33627 }
33628 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
33629 {
33630 IkReal evalcond[3];
33631 IkReal x10425=IKsin(j4);
33632 IkReal x10426=IKcos(j4);
33633 IkReal x10427=((r00)*(sj6));
33634 IkReal x10428=((cj6)*(r01));
33635 IkReal x10429=((IkReal(1.00000000000000))*(cj0));
33636 IkReal x10430=((IkReal(1.00000000000000))*(sj0));
33637 IkReal x10431=((r10)*(sj6));
33638 IkReal x10432=((sj5)*(x10425));
33639 IkReal x10433=((IkReal(1.00000000000000))*(cj6)*(r11));
33640 IkReal x10434=((cj5)*(x10425));
33641 IkReal x10435=((cj6)*(x10426));
33642 IkReal x10436=((sj0)*(x10434));
33643 IkReal x10437=((r01)*(sj6)*(x10426));
33644 IkReal x10438=((r11)*(sj6)*(x10426));
33645 evalcond[0]=((((r22)*(x10432)))+(((r20)*(sj6)*(x10434)))+(((cj6)*(r21)*(x10434)))+(cj1)+(((IkReal(-1.00000000000000))*(r20)*(x10435)))+(((r21)*(sj6)*(x10426))));
33646 evalcond[1]=((((IkReal(-1.00000000000000))*(r12)*(x10429)*(x10432)))+(((sj0)*(x10437)))+(((IkReal(-1.00000000000000))*(x10429)*(x10431)*(x10434)))+(((cj0)*(r10)*(x10435)))+(((r02)*(sj0)*(x10432)))+(((IkReal(-1.00000000000000))*(r00)*(x10430)*(x10435)))+(((x10427)*(x10436)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10429)*(x10434)))+(((x10428)*(x10436)))+(((IkReal(-1.00000000000000))*(x10429)*(x10438))));
33647 evalcond[2]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10430)*(x10434)))+(((IkReal(-1.00000000000000))*(x10430)*(x10438)))+(((IkReal(-1.00000000000000))*(x10429)*(x10437)))+(((IkReal(-1.00000000000000))*(sj1)))+(((r10)*(sj0)*(x10435)))+(((IkReal(-1.00000000000000))*(r12)*(x10430)*(x10432)))+(((cj0)*(r00)*(x10435)))+(((IkReal(-1.00000000000000))*(x10428)*(x10429)*(x10434)))+(((IkReal(-1.00000000000000))*(r02)*(x10429)*(x10432)))+(((IkReal(-1.00000000000000))*(x10427)*(x10429)*(x10434)))+(((IkReal(-1.00000000000000))*(x10430)*(x10431)*(x10434))));
33648 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
33649 {
33650 continue;
33651 }
33652 }
33653 
33654 {
33655 IkReal dummyeval[1];
33656 IkReal gconst30;
33657 gconst30=IKsign(sj1);
33658 dummyeval[0]=sj1;
33659 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
33660 {
33661 {
33662 IkReal dummyeval[1];
33663 dummyeval[0]=sj1;
33664 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
33665 {
33666 {
33667 IkReal dummyeval[1];
33668 dummyeval[0]=cj1;
33669 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
33670 {
33671 {
33672 IkReal evalcond[9];
33673 IkReal x10439=((IkReal(1.00000000000000))*(cj0));
33674 IkReal x10440=((cj4)*(sj6));
33675 IkReal x10441=((sj0)*(sj6));
33676 IkReal x10442=((cj5)*(sj4));
33677 IkReal x10443=((IkReal(0.374290000000000))*(sj5));
33678 IkReal x10444=((sj4)*(sj5));
33679 IkReal x10445=((cj0)*(cj6));
33680 IkReal x10446=((IkReal(0.0100000000000000))*(cj5));
33681 IkReal x10447=((cj4)*(sj5));
33682 IkReal x10448=((cj5)*(sj0));
33683 IkReal x10449=((IkReal(0.374290000000000))*(r02));
33684 IkReal x10450=((r20)*(sj6));
33685 IkReal x10451=((cj6)*(r21));
33686 IkReal x10452=((IkReal(1.00000000000000))*(sj0));
33687 IkReal x10453=((cj0)*(sj6));
33688 IkReal x10454=((cj4)*(cj6));
33689 IkReal x10455=((IkReal(0.374290000000000))*(r12));
33690 IkReal x10456=((cj0)*(cj5));
33691 IkReal x10457=((cj6)*(sj5));
33692 IkReal x10458=((cj6)*(r01));
33693 IkReal x10459=((r00)*(sj6));
33694 IkReal x10460=((IkReal(0.0100000000000000))*(sj5));
33695 IkReal x10461=((cj6)*(r11));
33696 IkReal x10462=((IkReal(1.00000000000000))*(r10));
33697 IkReal x10463=((r02)*(sj0));
33698 IkReal x10464=((cj6)*(sj4));
33699 IkReal x10465=((r12)*(x10452));
33700 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
33701 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x10454)))+(((r22)*(x10444)))+(((x10442)*(x10451)))+(((x10442)*(x10450)))+(((r21)*(x10440))));
33702 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(x10446)*(x10451)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x10460)))+(((x10443)*(x10450)))+(pz)+(((IkReal(-1.00000000000000))*(x10446)*(x10450)))+(((x10443)*(x10451))));
33703 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x10441)*(x10462)))+(((IkReal(-1.00000000000000))*(sj5)*(x10439)*(x10459)))+(((IkReal(-1.00000000000000))*(r01)*(x10439)*(x10457)))+(((r12)*(x10448)))+(((IkReal(-1.00000000000000))*(r11)*(x10452)*(x10457)))+(((r02)*(x10456))));
33704 evalcond[4]=((((cj4)*(r10)*(x10445)))+(((IkReal(-1.00000000000000))*(r00)*(x10452)*(x10454)))+(((x10444)*(x10463)))+(((r01)*(sj0)*(x10440)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x10439)*(x10442)))+(((sj0)*(x10442)*(x10458)))+(((IkReal(-1.00000000000000))*(r12)*(x10439)*(x10444)))+(((r00)*(x10441)*(x10442)))+(((IkReal(-1.00000000000000))*(x10439)*(x10442)*(x10461)))+(((IkReal(-1.00000000000000))*(r11)*(x10439)*(x10440))));
33705 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x10444)*(x10465)))+(((r10)*(sj0)*(x10454)))+(((IkReal(-1.00000000000000))*(x10439)*(x10442)*(x10458)))+(((IkReal(-1.00000000000000))*(r01)*(x10439)*(x10440)))+(((cj4)*(r00)*(x10445)))+(((IkReal(-1.00000000000000))*(x10442)*(x10452)*(x10461)))+(((IkReal(-1.00000000000000))*(r11)*(x10440)*(x10452)))+(((IkReal(-1.00000000000000))*(x10439)*(x10442)*(x10459)))+(((IkReal(-1.00000000000000))*(x10441)*(x10442)*(x10462)))+(((IkReal(-1.00000000000000))*(r02)*(x10439)*(x10444))));
33706 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r00)*(x10441)*(x10446)))+(((r10)*(x10446)*(x10453)))+(((IkReal(-1.00000000000000))*(r11)*(x10443)*(x10445)))+(((IkReal(-1.00000000000000))*(sj0)*(x10446)*(x10458)))+(((IkReal(-1.00000000000000))*(x10460)*(x10463)))+(((cj0)*(r12)*(x10460)))+(((sj0)*(x10443)*(x10458)))+(((IkReal(-1.00000000000000))*(py)*(x10439)))+(((r11)*(x10445)*(x10446)))+(((px)*(sj0)))+(((x10455)*(x10456)))+(((IkReal(-1.00000000000000))*(x10448)*(x10449)))+(((IkReal(-1.00000000000000))*(r10)*(x10443)*(x10453)))+(((r00)*(x10441)*(x10443))));
33707 evalcond[7]=((((IkReal(-1.00000000000000))*(r02)*(x10439)*(x10447)))+(((IkReal(-1.00000000000000))*(r10)*(x10452)*(x10464)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10439)*(x10454)))+(((IkReal(-1.00000000000000))*(r11)*(x10448)*(x10454)))+(((r01)*(sj4)*(x10453)))+(((IkReal(-1.00000000000000))*(r00)*(x10439)*(x10464)))+(((IkReal(-1.00000000000000))*(x10447)*(x10465)))+(((IkReal(-1.00000000000000))*(x10440)*(x10448)*(x10462)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10439)*(x10440)))+(((r11)*(sj4)*(x10441))));
33708 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x10439)))+(((IkReal(-1.00000000000000))*(py)*(x10452)))+(((r01)*(x10445)*(x10446)))+(((IkReal(-1.00000000000000))*(r00)*(x10443)*(x10453)))+(((sj0)*(x10446)*(x10461)))+(((IkReal(-1.00000000000000))*(r01)*(x10443)*(x10445)))+(((x10449)*(x10456)))+(((r00)*(x10446)*(x10453)))+(((cj0)*(r02)*(x10460)))+(((IkReal(-1.00000000000000))*(sj0)*(x10443)*(x10461)))+(((x10448)*(x10455)))+(((r12)*(sj0)*(x10460)))+(((r10)*(x10441)*(x10446)))+(((IkReal(-1.00000000000000))*(r10)*(x10441)*(x10443))));
33709 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
33710 {
33711 {
33712 IkReal j3array[1], cj3array[1], sj3array[1];
33713 bool j3valid[1]={false};
33714 _nj3 = 1;
33715 IkReal x10466=((r20)*(sj6));
33716 IkReal x10467=((cj4)*(cj5));
33717 IkReal x10468=((cj6)*(r21));
33718 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10467)*(x10468)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10466)*(x10467))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x10466)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10468))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10467)*(x10468)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10466)*(x10467)))))+IKsqr(((((sj5)*(x10466)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10468)))))-1) <= IKFAST_SINCOS_THRESH )
33719     continue;
33720 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10467)*(x10468)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10466)*(x10467)))), ((((sj5)*(x10466)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10468)))));
33721 sj3array[0]=IKsin(j3array[0]);
33722 cj3array[0]=IKcos(j3array[0]);
33723 if( j3array[0] > IKPI )
33724 {
33725     j3array[0]-=IK2PI;
33726 }
33727 else if( j3array[0] < -IKPI )
33728 {    j3array[0]+=IK2PI;
33729 }
33730 j3valid[0] = true;
33731 for(int ij3 = 0; ij3 < 1; ++ij3)
33732 {
33733 if( !j3valid[ij3] )
33734 {
33735     continue;
33736 }
33737 _ij3[0] = ij3; _ij3[1] = -1;
33738 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33739 {
33740 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33741 {
33742     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33743 }
33744 }
33745 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33746 {
33747 IkReal evalcond[4];
33748 IkReal x10469=IKsin(j3);
33749 IkReal x10470=((sj0)*(sj5));
33750 IkReal x10471=((r00)*(sj6));
33751 IkReal x10472=((cj6)*(r01));
33752 IkReal x10473=((cj5)*(sj0));
33753 IkReal x10474=((cj0)*(cj5));
33754 IkReal x10475=((cj6)*(sj4));
33755 IkReal x10476=((sj4)*(sj6));
33756 IkReal x10477=((cj0)*(r11));
33757 IkReal x10478=((cj4)*(cj6));
33758 IkReal x10479=((cj4)*(sj6));
33759 IkReal x10480=((IkReal(1.00000000000000))*(cj0));
33760 IkReal x10481=((cj4)*(sj5));
33761 IkReal x10482=((sj5)*(sj6));
33762 IkReal x10483=((cj6)*(sj5));
33763 IkReal x10484=((IkReal(1.00000000000000))*(IKcos(j3)));
33764 evalcond[0]=((((r21)*(x10483)))+(((r20)*(x10482)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10484))));
33765 evalcond[1]=((((cj5)*(r20)*(x10479)))+(((IkReal(-1.00000000000000))*(x10469)))+(((IkReal(-1.00000000000000))*(r21)*(x10476)))+(((r22)*(x10481)))+(((cj5)*(r21)*(x10478)))+(((r20)*(x10475))));
33766 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x10473)))+(((IkReal(-1.00000000000000))*(r10)*(x10480)*(x10482)))+(((r12)*(x10474)))+(((IkReal(-1.00000000000000))*(x10477)*(x10483)))+(((x10470)*(x10471)))+(((x10470)*(x10472)))+(x10469));
33767 evalcond[3]=((((r00)*(sj0)*(x10475)))+(((IkReal(-1.00000000000000))*(r12)*(x10480)*(x10481)))+(((cj4)*(x10471)*(x10473)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x10476)))+(((IkReal(-1.00000000000000))*(r10)*(x10474)*(x10479)))+(((cj4)*(r02)*(x10470)))+(((x10476)*(x10477)))+(((cj4)*(x10472)*(x10473)))+(((IkReal(-1.00000000000000))*(r10)*(x10475)*(x10480)))+(((IkReal(-1.00000000000000))*(x10484)))+(((IkReal(-1.00000000000000))*(r11)*(x10474)*(x10478))));
33768 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
33769 {
33770 continue;
33771 }
33772 }
33773 
33774 {
33775 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33776 vinfos[0].jointtype = 1;
33777 vinfos[0].foffset = j0;
33778 vinfos[0].indices[0] = _ij0[0];
33779 vinfos[0].indices[1] = _ij0[1];
33780 vinfos[0].maxsolutions = _nj0;
33781 vinfos[1].jointtype = 1;
33782 vinfos[1].foffset = j1;
33783 vinfos[1].indices[0] = _ij1[0];
33784 vinfos[1].indices[1] = _ij1[1];
33785 vinfos[1].maxsolutions = _nj1;
33786 vinfos[2].jointtype = 1;
33787 vinfos[2].foffset = j2;
33788 vinfos[2].indices[0] = _ij2[0];
33789 vinfos[2].indices[1] = _ij2[1];
33790 vinfos[2].maxsolutions = _nj2;
33791 vinfos[3].jointtype = 1;
33792 vinfos[3].foffset = j3;
33793 vinfos[3].indices[0] = _ij3[0];
33794 vinfos[3].indices[1] = _ij3[1];
33795 vinfos[3].maxsolutions = _nj3;
33796 vinfos[4].jointtype = 1;
33797 vinfos[4].foffset = j4;
33798 vinfos[4].indices[0] = _ij4[0];
33799 vinfos[4].indices[1] = _ij4[1];
33800 vinfos[4].maxsolutions = _nj4;
33801 vinfos[5].jointtype = 1;
33802 vinfos[5].foffset = j5;
33803 vinfos[5].indices[0] = _ij5[0];
33804 vinfos[5].indices[1] = _ij5[1];
33805 vinfos[5].maxsolutions = _nj5;
33806 vinfos[6].jointtype = 1;
33807 vinfos[6].foffset = j6;
33808 vinfos[6].indices[0] = _ij6[0];
33809 vinfos[6].indices[1] = _ij6[1];
33810 vinfos[6].maxsolutions = _nj6;
33811 std::vector<int> vfree(0);
33812 solutions.AddSolution(vinfos,vfree);
33813 }
33814 }
33815 }
33816 
33817 } else
33818 {
33819 IkReal x10485=((IkReal(1.00000000000000))*(cj0));
33820 IkReal x10486=((cj4)*(sj6));
33821 IkReal x10487=((sj0)*(sj6));
33822 IkReal x10488=((cj5)*(sj4));
33823 IkReal x10489=((IkReal(0.374290000000000))*(sj5));
33824 IkReal x10490=((sj4)*(sj5));
33825 IkReal x10491=((cj0)*(cj6));
33826 IkReal x10492=((IkReal(0.0100000000000000))*(cj5));
33827 IkReal x10493=((cj4)*(sj5));
33828 IkReal x10494=((cj5)*(sj0));
33829 IkReal x10495=((IkReal(0.374290000000000))*(r02));
33830 IkReal x10496=((r20)*(sj6));
33831 IkReal x10497=((cj6)*(r21));
33832 IkReal x10498=((IkReal(1.00000000000000))*(sj0));
33833 IkReal x10499=((cj0)*(sj6));
33834 IkReal x10500=((cj4)*(cj6));
33835 IkReal x10501=((IkReal(0.374290000000000))*(r12));
33836 IkReal x10502=((cj0)*(cj5));
33837 IkReal x10503=((cj6)*(sj5));
33838 IkReal x10504=((cj6)*(r01));
33839 IkReal x10505=((r00)*(sj6));
33840 IkReal x10506=((IkReal(0.0100000000000000))*(sj5));
33841 IkReal x10507=((cj6)*(r11));
33842 IkReal x10508=((IkReal(1.00000000000000))*(r10));
33843 IkReal x10509=((r02)*(sj0));
33844 IkReal x10510=((cj6)*(sj4));
33845 IkReal x10511=((r12)*(x10498));
33846 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
33847 evalcond[1]=((((x10488)*(x10497)))+(((x10488)*(x10496)))+(((IkReal(-1.00000000000000))*(r20)*(x10500)))+(((r22)*(x10490)))+(((r21)*(x10486))));
33848 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x10489)*(x10497)))+(((IkReal(-1.00000000000000))*(x10492)*(x10496)))+(((IkReal(-1.00000000000000))*(x10492)*(x10497)))+(((x10489)*(x10496)))+(((IkReal(-1.00000000000000))*(r22)*(x10506))));
33849 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x10485)*(x10505)))+(((r02)*(x10502)))+(((IkReal(-1.00000000000000))*(sj5)*(x10487)*(x10508)))+(((r12)*(x10494)))+(((IkReal(-1.00000000000000))*(r11)*(x10498)*(x10503)))+(((IkReal(-1.00000000000000))*(r01)*(x10485)*(x10503))));
33850 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x10485)*(x10490)))+(((IkReal(-1.00000000000000))*(r00)*(x10498)*(x10500)))+(((r01)*(sj0)*(x10486)))+(((IkReal(-1.00000000000000))*(r11)*(x10485)*(x10486)))+(((x10490)*(x10509)))+(((r00)*(x10487)*(x10488)))+(((cj4)*(r10)*(x10491)))+(((sj0)*(x10488)*(x10504)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x10485)*(x10488)))+(((IkReal(-1.00000000000000))*(x10485)*(x10488)*(x10507))));
33851 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x10486)*(x10498)))+(((IkReal(-1.00000000000000))*(x10485)*(x10488)*(x10504)))+(((IkReal(-1.00000000000000))*(x10485)*(x10488)*(x10505)))+(((IkReal(-1.00000000000000))*(x10490)*(x10511)))+(((IkReal(-1.00000000000000))*(x10488)*(x10498)*(x10507)))+(((IkReal(-1.00000000000000))*(r01)*(x10485)*(x10486)))+(((IkReal(-1.00000000000000))*(r02)*(x10485)*(x10490)))+(((cj4)*(r00)*(x10491)))+(((IkReal(-1.00000000000000))*(x10487)*(x10488)*(x10508)))+(((r10)*(sj0)*(x10500))));
33852 evalcond[6]=((IkReal(-0.0690000000000000))+(((r00)*(x10487)*(x10489)))+(((IkReal(-1.00000000000000))*(sj0)*(x10492)*(x10504)))+(((IkReal(-1.00000000000000))*(r00)*(x10487)*(x10492)))+(((r10)*(x10492)*(x10499)))+(((IkReal(-1.00000000000000))*(r10)*(x10489)*(x10499)))+(((IkReal(-1.00000000000000))*(x10494)*(x10495)))+(((IkReal(-1.00000000000000))*(py)*(x10485)))+(((r11)*(x10491)*(x10492)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x10506)*(x10509)))+(((IkReal(-1.00000000000000))*(r11)*(x10489)*(x10491)))+(((x10501)*(x10502)))+(((cj0)*(r12)*(x10506)))+(((sj0)*(x10489)*(x10504))));
33853 evalcond[7]=((((IkReal(-1.00000000000000))*(x10493)*(x10511)))+(((r11)*(sj4)*(x10487)))+(((IkReal(-1.00000000000000))*(r00)*(x10485)*(x10510)))+(((IkReal(-1.00000000000000))*(r10)*(x10498)*(x10510)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x10485)*(x10486)))+(((IkReal(-1.00000000000000))*(r11)*(x10494)*(x10500)))+(((IkReal(-1.00000000000000))*(r02)*(x10485)*(x10493)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x10485)*(x10500)))+(((IkReal(-1.00000000000000))*(x10486)*(x10494)*(x10508)))+(((r01)*(sj4)*(x10499))));
33854 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x10487)*(x10489)))+(((r10)*(x10487)*(x10492)))+(((IkReal(-1.00000000000000))*(sj0)*(x10489)*(x10507)))+(((IkReal(-1.00000000000000))*(r01)*(x10489)*(x10491)))+(((sj0)*(x10492)*(x10507)))+(((x10494)*(x10501)))+(((IkReal(-1.00000000000000))*(py)*(x10498)))+(((r12)*(sj0)*(x10506)))+(((IkReal(-1.00000000000000))*(r00)*(x10489)*(x10499)))+(((IkReal(-1.00000000000000))*(px)*(x10485)))+(((r01)*(x10491)*(x10492)))+(((cj0)*(r02)*(x10506)))+(((r00)*(x10492)*(x10499)))+(((x10495)*(x10502))));
33855 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
33856 {
33857 {
33858 IkReal j3array[1], cj3array[1], sj3array[1];
33859 bool j3valid[1]={false};
33860 _nj3 = 1;
33861 IkReal x10512=((IkReal(1.00000000000000))*(sj5));
33862 IkReal x10513=((cj6)*(r21));
33863 IkReal x10514=((r20)*(sj6));
33864 IkReal x10515=((IkReal(1.00000000000000))*(cj4)*(cj5));
33865 if( IKabs(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10512)))+(((IkReal(-1.00000000000000))*(x10514)*(x10515)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x10513)*(x10515)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x10512)*(x10513)))+(((IkReal(-1.00000000000000))*(x10512)*(x10514)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10512)))+(((IkReal(-1.00000000000000))*(x10514)*(x10515)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x10513)*(x10515)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x10512)*(x10513)))+(((IkReal(-1.00000000000000))*(x10512)*(x10514)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
33866     continue;
33867 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x10512)))+(((IkReal(-1.00000000000000))*(x10514)*(x10515)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x10513)*(x10515)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x10512)*(x10513)))+(((IkReal(-1.00000000000000))*(x10512)*(x10514)))+(((cj5)*(r22)))));
33868 sj3array[0]=IKsin(j3array[0]);
33869 cj3array[0]=IKcos(j3array[0]);
33870 if( j3array[0] > IKPI )
33871 {
33872     j3array[0]-=IK2PI;
33873 }
33874 else if( j3array[0] < -IKPI )
33875 {    j3array[0]+=IK2PI;
33876 }
33877 j3valid[0] = true;
33878 for(int ij3 = 0; ij3 < 1; ++ij3)
33879 {
33880 if( !j3valid[ij3] )
33881 {
33882     continue;
33883 }
33884 _ij3[0] = ij3; _ij3[1] = -1;
33885 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
33886 {
33887 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
33888 {
33889     j3valid[iij3]=false; _ij3[1] = iij3; break; 
33890 }
33891 }
33892 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
33893 {
33894 IkReal evalcond[4];
33895 IkReal x10516=IKsin(j3);
33896 IkReal x10517=IKcos(j3);
33897 IkReal x10518=((sj0)*(sj5));
33898 IkReal x10519=((r00)*(sj6));
33899 IkReal x10520=((cj6)*(r01));
33900 IkReal x10521=((cj0)*(cj5));
33901 IkReal x10522=((IkReal(1.00000000000000))*(cj5));
33902 IkReal x10523=((cj4)*(cj5));
33903 IkReal x10524=((cj6)*(sj4));
33904 IkReal x10525=((sj4)*(sj6));
33905 IkReal x10526=((cj0)*(r11));
33906 IkReal x10527=((IkReal(1.00000000000000))*(cj4));
33907 IkReal x10528=((cj6)*(r21));
33908 IkReal x10529=((r20)*(sj6));
33909 IkReal x10530=((cj0)*(sj5));
33910 IkReal x10531=((r10)*(sj6));
33911 evalcond[0]=((((sj5)*(x10528)))+(x10517)+(((sj5)*(x10529)))+(((IkReal(-1.00000000000000))*(r22)*(x10522))));
33912 evalcond[1]=((((r20)*(x10524)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x10525)))+(x10516)+(((x10523)*(x10529)))+(((x10523)*(x10528))));
33913 evalcond[2]=((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x10526)))+(((r12)*(x10521)))+(((x10518)*(x10519)))+(((IkReal(-1.00000000000000))*(x10530)*(x10531)))+(x10516)+(((x10518)*(x10520)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x10522))));
33914 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r10)*(x10524)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10521)*(x10527)))+(((cj4)*(r02)*(x10518)))+(((IkReal(-1.00000000000000))*(r12)*(x10527)*(x10530)))+(((x10525)*(x10526)))+(((sj0)*(x10519)*(x10523)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x10525)))+(((IkReal(-1.00000000000000))*(x10517)))+(((IkReal(-1.00000000000000))*(x10521)*(x10527)*(x10531)))+(((sj0)*(x10520)*(x10523)))+(((r00)*(sj0)*(x10524))));
33915 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
33916 {
33917 continue;
33918 }
33919 }
33920 
33921 {
33922 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
33923 vinfos[0].jointtype = 1;
33924 vinfos[0].foffset = j0;
33925 vinfos[0].indices[0] = _ij0[0];
33926 vinfos[0].indices[1] = _ij0[1];
33927 vinfos[0].maxsolutions = _nj0;
33928 vinfos[1].jointtype = 1;
33929 vinfos[1].foffset = j1;
33930 vinfos[1].indices[0] = _ij1[0];
33931 vinfos[1].indices[1] = _ij1[1];
33932 vinfos[1].maxsolutions = _nj1;
33933 vinfos[2].jointtype = 1;
33934 vinfos[2].foffset = j2;
33935 vinfos[2].indices[0] = _ij2[0];
33936 vinfos[2].indices[1] = _ij2[1];
33937 vinfos[2].maxsolutions = _nj2;
33938 vinfos[3].jointtype = 1;
33939 vinfos[3].foffset = j3;
33940 vinfos[3].indices[0] = _ij3[0];
33941 vinfos[3].indices[1] = _ij3[1];
33942 vinfos[3].maxsolutions = _nj3;
33943 vinfos[4].jointtype = 1;
33944 vinfos[4].foffset = j4;
33945 vinfos[4].indices[0] = _ij4[0];
33946 vinfos[4].indices[1] = _ij4[1];
33947 vinfos[4].maxsolutions = _nj4;
33948 vinfos[5].jointtype = 1;
33949 vinfos[5].foffset = j5;
33950 vinfos[5].indices[0] = _ij5[0];
33951 vinfos[5].indices[1] = _ij5[1];
33952 vinfos[5].maxsolutions = _nj5;
33953 vinfos[6].jointtype = 1;
33954 vinfos[6].foffset = j6;
33955 vinfos[6].indices[0] = _ij6[0];
33956 vinfos[6].indices[1] = _ij6[1];
33957 vinfos[6].maxsolutions = _nj6;
33958 std::vector<int> vfree(0);
33959 solutions.AddSolution(vinfos,vfree);
33960 }
33961 }
33962 }
33963 
33964 } else
33965 {
33966 IkReal x10532=((IkReal(1.00000000000000))*(cj0));
33967 IkReal x10533=((cj4)*(sj6));
33968 IkReal x10534=((sj0)*(sj4));
33969 IkReal x10535=((cj5)*(sj6));
33970 IkReal x10536=((sj4)*(sj5));
33971 IkReal x10537=((r12)*(sj5));
33972 IkReal x10538=((IkReal(0.374290000000000))*(cj5));
33973 IkReal x10539=((r02)*(sj0));
33974 IkReal x10540=((r20)*(sj4));
33975 IkReal x10541=((IkReal(1.00000000000000))*(sj0));
33976 IkReal x10542=((IkReal(1.00000000000000))*(cj5));
33977 IkReal x10543=((cj0)*(r10));
33978 IkReal x10544=((cj4)*(cj6));
33979 IkReal x10545=((r00)*(sj0));
33980 IkReal x10546=((cj6)*(r21));
33981 IkReal x10547=((IkReal(0.374290000000000))*(sj5));
33982 IkReal x10548=((cj0)*(r00));
33983 IkReal x10549=((IkReal(0.0100000000000000))*(sj5));
33984 IkReal x10550=((cj0)*(r02));
33985 IkReal x10551=((cj5)*(sj4));
33986 IkReal x10552=((cj6)*(r01));
33987 IkReal x10553=((cj6)*(r11));
33988 IkReal x10554=((r01)*(sj0));
33989 IkReal x10555=((r10)*(sj0));
33990 IkReal x10556=((IkReal(0.0100000000000000))*(cj5)*(cj6));
33991 IkReal x10557=((sj6)*(x10547));
33992 IkReal x10558=((cj0)*(cj6)*(x10547));
33993 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
33994 evalcond[1]=((((sj5)*(x10546)))+(((IkReal(-1.00000000000000))*(r22)*(x10542)))+(((r20)*(sj5)*(sj6))));
33995 evalcond[2]=((IkReal(1.00000000000000))+(((r21)*(x10533)))+(((IkReal(-1.00000000000000))*(r20)*(x10544)))+(((x10535)*(x10540)))+(((x10546)*(x10551)))+(((r22)*(x10536))));
33996 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x10538)))+(((x10546)*(x10547)))+(((IkReal(-0.0100000000000000))*(cj5)*(x10546)))+(((r20)*(x10557)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x10549)))+(((IkReal(-0.0100000000000000))*(r20)*(x10535))));
33997 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x10533)))+(((cj6)*(x10540)))+(((cj5)*(r21)*(x10544))));
33998 evalcond[5]=((((r02)*(sj5)*(x10534)))+(((cj5)*(x10534)*(x10552)))+(((x10543)*(x10544)))+(((x10533)*(x10554)))+(((IkReal(-1.00000000000000))*(x10532)*(x10551)*(x10553)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x10532)*(x10535)))+(((IkReal(-1.00000000000000))*(r11)*(x10532)*(x10533)))+(((r00)*(x10534)*(x10535)))+(((IkReal(-1.00000000000000))*(r12)*(x10532)*(x10536)))+(((IkReal(-1.00000000000000))*(r00)*(x10541)*(x10544))));
33999 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x10532)*(x10536)))+(((IkReal(-1.00000000000000))*(r10)*(x10534)*(x10535)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x10532)*(x10535)))+(((IkReal(-1.00000000000000))*(x10532)*(x10551)*(x10552)))+(((IkReal(-1.00000000000000))*(r11)*(x10533)*(x10541)))+(((IkReal(-1.00000000000000))*(x10534)*(x10537)))+(((IkReal(-1.00000000000000))*(r01)*(x10532)*(x10533)))+(((x10544)*(x10555)))+(((x10544)*(x10548)))+(((IkReal(-1.00000000000000))*(x10534)*(x10542)*(x10553))));
34000 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10553)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x10552)))+(((IkReal(-1.00000000000000))*(x10543)*(x10557)))+(((IkReal(0.0100000000000000))*(x10535)*(x10543)))+(((IkReal(-1.00000000000000))*(py)*(x10532)))+(((IkReal(-0.0100000000000000))*(x10535)*(x10545)))+(((IkReal(-1.00000000000000))*(cj0)*(x10547)*(x10553)))+(((cj0)*(r12)*(x10538)))+(((x10545)*(x10557)))+(((IkReal(-1.00000000000000))*(x10538)*(x10539)))+(((IkReal(0.0100000000000000))*(cj0)*(x10537)))+(((sj0)*(x10547)*(x10552)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x10539)*(x10549))));
34001 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(x10548)*(x10557)))+(((IkReal(-1.00000000000000))*(px)*(x10532)))+(((IkReal(0.0100000000000000))*(sj0)*(x10537)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10552)))+(((IkReal(-1.00000000000000))*(py)*(x10541)))+(((r12)*(sj0)*(x10538)))+(((IkReal(0.0100000000000000))*(x10535)*(x10548)))+(((IkReal(-1.00000000000000))*(x10555)*(x10557)))+(((IkReal(0.0100000000000000))*(x10535)*(x10555)))+(((x10549)*(x10550)))+(((x10538)*(x10550)))+(((IkReal(-1.00000000000000))*(sj0)*(x10547)*(x10553)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x10553)))+(((IkReal(-1.00000000000000))*(cj0)*(x10547)*(x10552))));
34002 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
34003 {
34004 {
34005 IkReal j3array[1], cj3array[1], sj3array[1];
34006 bool j3valid[1]={false};
34007 _nj3 = 1;
34008 IkReal x10559=((cj5)*(r02));
34009 IkReal x10560=((cj0)*(sj5));
34010 IkReal x10561=((r10)*(sj6));
34011 IkReal x10562=((IkReal(1.00000000000000))*(cj6));
34012 IkReal x10563=((sj0)*(sj5));
34013 IkReal x10564=((cj5)*(r12));
34014 IkReal x10565=((IkReal(1.00000000000000))*(r00)*(sj6));
34015 if( IKabs(((((x10560)*(x10561)))+(((IkReal(-1.00000000000000))*(r01)*(x10562)*(x10563)))+(((IkReal(-1.00000000000000))*(cj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10563)*(x10565)))+(((cj6)*(r11)*(x10560)))+(((sj0)*(x10559))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x10561)*(x10563)))+(((cj0)*(x10559)))+(((IkReal(-1.00000000000000))*(r01)*(x10560)*(x10562)))+(((sj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10560)*(x10565)))+(((IkReal(-1.00000000000000))*(r11)*(x10562)*(x10563))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x10560)*(x10561)))+(((IkReal(-1.00000000000000))*(r01)*(x10562)*(x10563)))+(((IkReal(-1.00000000000000))*(cj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10563)*(x10565)))+(((cj6)*(r11)*(x10560)))+(((sj0)*(x10559)))))+IKsqr(((((IkReal(-1.00000000000000))*(x10561)*(x10563)))+(((cj0)*(x10559)))+(((IkReal(-1.00000000000000))*(r01)*(x10560)*(x10562)))+(((sj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10560)*(x10565)))+(((IkReal(-1.00000000000000))*(r11)*(x10562)*(x10563)))))-1) <= IKFAST_SINCOS_THRESH )
34016     continue;
34017 j3array[0]=IKatan2(((((x10560)*(x10561)))+(((IkReal(-1.00000000000000))*(r01)*(x10562)*(x10563)))+(((IkReal(-1.00000000000000))*(cj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10563)*(x10565)))+(((cj6)*(r11)*(x10560)))+(((sj0)*(x10559)))), ((((IkReal(-1.00000000000000))*(x10561)*(x10563)))+(((cj0)*(x10559)))+(((IkReal(-1.00000000000000))*(r01)*(x10560)*(x10562)))+(((sj0)*(x10564)))+(((IkReal(-1.00000000000000))*(x10560)*(x10565)))+(((IkReal(-1.00000000000000))*(r11)*(x10562)*(x10563)))));
34018 sj3array[0]=IKsin(j3array[0]);
34019 cj3array[0]=IKcos(j3array[0]);
34020 if( j3array[0] > IKPI )
34021 {
34022     j3array[0]-=IK2PI;
34023 }
34024 else if( j3array[0] < -IKPI )
34025 {    j3array[0]+=IK2PI;
34026 }
34027 j3valid[0] = true;
34028 for(int ij3 = 0; ij3 < 1; ++ij3)
34029 {
34030 if( !j3valid[ij3] )
34031 {
34032     continue;
34033 }
34034 _ij3[0] = ij3; _ij3[1] = -1;
34035 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34036 {
34037 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34038 {
34039     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34040 }
34041 }
34042 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34043 {
34044 IkReal evalcond[4];
34045 IkReal x10566=IKsin(j3);
34046 IkReal x10567=((sj0)*(sj5));
34047 IkReal x10568=((r00)*(sj6));
34048 IkReal x10569=((IkReal(1.00000000000000))*(cj4));
34049 IkReal x10570=((cj6)*(sj0));
34050 IkReal x10571=((r00)*(sj4));
34051 IkReal x10572=((cj0)*(cj5));
34052 IkReal x10573=((cj6)*(r01));
34053 IkReal x10574=((cj5)*(sj0));
34054 IkReal x10575=((cj0)*(sj5));
34055 IkReal x10576=((cj6)*(r11));
34056 IkReal x10577=((r10)*(sj6));
34057 IkReal x10578=((r10)*(sj4));
34058 IkReal x10579=((IkReal(1.00000000000000))*(IKcos(j3)));
34059 IkReal x10580=((cj0)*(sj4)*(sj6));
34060 IkReal x10581=((sj0)*(sj4)*(sj6));
34061 IkReal x10582=((IkReal(1.00000000000000))*(cj0)*(cj6));
34062 evalcond[0]=((((IkReal(-1.00000000000000))*(r02)*(x10574)))+(((r12)*(x10572)))+(((x10567)*(x10573)))+(x10566)+(((x10567)*(x10568)))+(((IkReal(-1.00000000000000))*(x10575)*(x10576)))+(((IkReal(-1.00000000000000))*(x10575)*(x10577))));
34063 evalcond[1]=((((r12)*(x10574)))+(((IkReal(-1.00000000000000))*(x10568)*(x10575)))+(((IkReal(-1.00000000000000))*(x10567)*(x10576)))+(((IkReal(-1.00000000000000))*(x10579)))+(((IkReal(-1.00000000000000))*(x10573)*(x10575)))+(((IkReal(-1.00000000000000))*(x10567)*(x10577)))+(((r02)*(x10572))));
34064 evalcond[2]=((((x10570)*(x10571)))+(((IkReal(-1.00000000000000))*(x10578)*(x10582)))+(((IkReal(-1.00000000000000))*(x10579)))+(((IkReal(-1.00000000000000))*(r12)*(x10569)*(x10575)))+(((IkReal(-1.00000000000000))*(x10569)*(x10572)*(x10576)))+(((cj4)*(cj5)*(r01)*(x10570)))+(((IkReal(-1.00000000000000))*(r01)*(x10581)))+(((r11)*(x10580)))+(((IkReal(-1.00000000000000))*(x10569)*(x10572)*(x10577)))+(((cj4)*(x10568)*(x10574)))+(((cj4)*(r02)*(x10567))));
34065 evalcond[3]=((((r01)*(x10580)))+(((IkReal(-1.00000000000000))*(r12)*(x10567)*(x10569)))+(((IkReal(-1.00000000000000))*(x10569)*(x10572)*(x10573)))+(((IkReal(-1.00000000000000))*(x10569)*(x10574)*(x10577)))+(((IkReal(-1.00000000000000))*(x10566)))+(((IkReal(-1.00000000000000))*(x10568)*(x10569)*(x10572)))+(((r11)*(x10581)))+(((IkReal(-1.00000000000000))*(r02)*(x10569)*(x10575)))+(((IkReal(-1.00000000000000))*(x10570)*(x10578)))+(((IkReal(-1.00000000000000))*(x10571)*(x10582)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x10569)*(x10570))));
34066 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
34067 {
34068 continue;
34069 }
34070 }
34071 
34072 {
34073 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34074 vinfos[0].jointtype = 1;
34075 vinfos[0].foffset = j0;
34076 vinfos[0].indices[0] = _ij0[0];
34077 vinfos[0].indices[1] = _ij0[1];
34078 vinfos[0].maxsolutions = _nj0;
34079 vinfos[1].jointtype = 1;
34080 vinfos[1].foffset = j1;
34081 vinfos[1].indices[0] = _ij1[0];
34082 vinfos[1].indices[1] = _ij1[1];
34083 vinfos[1].maxsolutions = _nj1;
34084 vinfos[2].jointtype = 1;
34085 vinfos[2].foffset = j2;
34086 vinfos[2].indices[0] = _ij2[0];
34087 vinfos[2].indices[1] = _ij2[1];
34088 vinfos[2].maxsolutions = _nj2;
34089 vinfos[3].jointtype = 1;
34090 vinfos[3].foffset = j3;
34091 vinfos[3].indices[0] = _ij3[0];
34092 vinfos[3].indices[1] = _ij3[1];
34093 vinfos[3].maxsolutions = _nj3;
34094 vinfos[4].jointtype = 1;
34095 vinfos[4].foffset = j4;
34096 vinfos[4].indices[0] = _ij4[0];
34097 vinfos[4].indices[1] = _ij4[1];
34098 vinfos[4].maxsolutions = _nj4;
34099 vinfos[5].jointtype = 1;
34100 vinfos[5].foffset = j5;
34101 vinfos[5].indices[0] = _ij5[0];
34102 vinfos[5].indices[1] = _ij5[1];
34103 vinfos[5].maxsolutions = _nj5;
34104 vinfos[6].jointtype = 1;
34105 vinfos[6].foffset = j6;
34106 vinfos[6].indices[0] = _ij6[0];
34107 vinfos[6].indices[1] = _ij6[1];
34108 vinfos[6].maxsolutions = _nj6;
34109 std::vector<int> vfree(0);
34110 solutions.AddSolution(vinfos,vfree);
34111 }
34112 }
34113 }
34114 
34115 } else
34116 {
34117 IkReal x10583=((IkReal(1.00000000000000))*(cj0));
34118 IkReal x10584=((cj4)*(sj6));
34119 IkReal x10585=((sj0)*(sj4));
34120 IkReal x10586=((cj5)*(sj6));
34121 IkReal x10587=((sj4)*(sj5));
34122 IkReal x10588=((r12)*(sj5));
34123 IkReal x10589=((IkReal(0.374290000000000))*(cj5));
34124 IkReal x10590=((r02)*(sj0));
34125 IkReal x10591=((r20)*(sj4));
34126 IkReal x10592=((IkReal(1.00000000000000))*(sj0));
34127 IkReal x10593=((IkReal(1.00000000000000))*(cj5));
34128 IkReal x10594=((cj0)*(r10));
34129 IkReal x10595=((cj4)*(cj6));
34130 IkReal x10596=((r00)*(sj0));
34131 IkReal x10597=((cj6)*(r21));
34132 IkReal x10598=((IkReal(0.374290000000000))*(sj5));
34133 IkReal x10599=((cj0)*(r00));
34134 IkReal x10600=((IkReal(0.0100000000000000))*(sj5));
34135 IkReal x10601=((cj0)*(r02));
34136 IkReal x10602=((cj5)*(sj4));
34137 IkReal x10603=((cj6)*(r01));
34138 IkReal x10604=((cj6)*(r11));
34139 IkReal x10605=((r01)*(sj0));
34140 IkReal x10606=((r10)*(sj0));
34141 IkReal x10607=((IkReal(0.0100000000000000))*(cj5)*(cj6));
34142 IkReal x10608=((sj6)*(x10598));
34143 IkReal x10609=((cj0)*(cj6)*(x10598));
34144 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
34145 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x10593)))+(((sj5)*(x10597)))+(((r20)*(sj5)*(sj6))));
34146 evalcond[2]=((IkReal(-1.00000000000000))+(((x10586)*(x10591)))+(((r21)*(x10584)))+(((r22)*(x10587)))+(((IkReal(-1.00000000000000))*(r20)*(x10595)))+(((x10597)*(x10602))));
34147 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x10597)))+(((r20)*(x10608)))+(((IkReal(-1.00000000000000))*(r22)*(x10589)))+(((IkReal(-1.00000000000000))*(r22)*(x10600)))+(((IkReal(-0.0100000000000000))*(r20)*(x10586)))+(pz)+(((x10597)*(x10598))));
34148 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x10595)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x10584)))+(((cj6)*(x10591))));
34149 evalcond[5]=((((x10584)*(x10605)))+(((IkReal(-1.00000000000000))*(r00)*(x10592)*(x10595)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x10583)*(x10586)))+(((x10594)*(x10595)))+(((r00)*(x10585)*(x10586)))+(((IkReal(-1.00000000000000))*(r11)*(x10583)*(x10584)))+(((r02)*(sj5)*(x10585)))+(((IkReal(-1.00000000000000))*(r12)*(x10583)*(x10587)))+(((cj5)*(x10585)*(x10603)))+(((IkReal(-1.00000000000000))*(x10583)*(x10602)*(x10604))));
34150 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x10584)*(x10592)))+(((IkReal(-1.00000000000000))*(x10583)*(x10602)*(x10603)))+(((IkReal(-1.00000000000000))*(x10585)*(x10588)))+(((IkReal(-1.00000000000000))*(r02)*(x10583)*(x10587)))+(((x10595)*(x10606)))+(((IkReal(-1.00000000000000))*(x10585)*(x10593)*(x10604)))+(((IkReal(-1.00000000000000))*(r01)*(x10583)*(x10584)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x10583)*(x10586)))+(((x10595)*(x10599)))+(((IkReal(-1.00000000000000))*(r10)*(x10585)*(x10586))));
34151 evalcond[7]=((IkReal(-0.0690000000000000))+(((x10596)*(x10608)))+(((sj0)*(x10598)*(x10603)))+(((IkReal(0.0100000000000000))*(x10586)*(x10594)))+(((IkReal(-1.00000000000000))*(x10590)*(x10600)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10604)))+(((IkReal(0.0100000000000000))*(cj0)*(x10588)))+(((IkReal(-0.0100000000000000))*(x10586)*(x10596)))+(((IkReal(-1.00000000000000))*(py)*(x10583)))+(((IkReal(-1.00000000000000))*(x10594)*(x10608)))+(((IkReal(-1.00000000000000))*(cj0)*(x10598)*(x10604)))+(((cj0)*(r12)*(x10589)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x10589)*(x10590)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x10603))));
34152 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(x10586)*(x10606)))+(((IkReal(-1.00000000000000))*(x10606)*(x10608)))+(((IkReal(-1.00000000000000))*(cj0)*(x10598)*(x10603)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x10603)))+(((IkReal(-1.00000000000000))*(x10599)*(x10608)))+(((x10589)*(x10601)))+(((IkReal(0.0100000000000000))*(sj0)*(x10588)))+(((IkReal(-1.00000000000000))*(px)*(x10583)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x10604)))+(((r12)*(sj0)*(x10589)))+(((IkReal(-1.00000000000000))*(py)*(x10592)))+(((IkReal(-1.00000000000000))*(sj0)*(x10598)*(x10604)))+(((x10600)*(x10601)))+(((IkReal(0.0100000000000000))*(x10586)*(x10599))));
34153 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
34154 {
34155 {
34156 IkReal j3array[1], cj3array[1], sj3array[1];
34157 bool j3valid[1]={false};
34158 _nj3 = 1;
34159 IkReal x10610=((IkReal(1.00000000000000))*(cj5));
34160 IkReal x10611=((r10)*(sj5)*(sj6));
34161 IkReal x10612=((cj6)*(sj0)*(sj5));
34162 IkReal x10613=((r00)*(sj5)*(sj6));
34163 IkReal x10614=((cj0)*(cj6)*(sj5));
34164 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10610)))+(((cj0)*(x10611)))+(((IkReal(-1.00000000000000))*(r01)*(x10612)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x10614)))+(((IkReal(-1.00000000000000))*(sj0)*(x10613))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10610)))+(((cj0)*(x10613)))+(((sj0)*(x10611)))+(((r11)*(x10612)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10610)))+(((r01)*(x10614))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10610)))+(((cj0)*(x10611)))+(((IkReal(-1.00000000000000))*(r01)*(x10612)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x10614)))+(((IkReal(-1.00000000000000))*(sj0)*(x10613)))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10610)))+(((cj0)*(x10613)))+(((sj0)*(x10611)))+(((r11)*(x10612)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10610)))+(((r01)*(x10614)))))-1) <= IKFAST_SINCOS_THRESH )
34165     continue;
34166 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10610)))+(((cj0)*(x10611)))+(((IkReal(-1.00000000000000))*(r01)*(x10612)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x10614)))+(((IkReal(-1.00000000000000))*(sj0)*(x10613)))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10610)))+(((cj0)*(x10613)))+(((sj0)*(x10611)))+(((r11)*(x10612)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10610)))+(((r01)*(x10614)))));
34167 sj3array[0]=IKsin(j3array[0]);
34168 cj3array[0]=IKcos(j3array[0]);
34169 if( j3array[0] > IKPI )
34170 {
34171     j3array[0]-=IK2PI;
34172 }
34173 else if( j3array[0] < -IKPI )
34174 {    j3array[0]+=IK2PI;
34175 }
34176 j3valid[0] = true;
34177 for(int ij3 = 0; ij3 < 1; ++ij3)
34178 {
34179 if( !j3valid[ij3] )
34180 {
34181     continue;
34182 }
34183 _ij3[0] = ij3; _ij3[1] = -1;
34184 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34185 {
34186 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34187 {
34188     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34189 }
34190 }
34191 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34192 {
34193 IkReal evalcond[4];
34194 IkReal x10615=IKcos(j3);
34195 IkReal x10616=IKsin(j3);
34196 IkReal x10617=((sj0)*(sj5));
34197 IkReal x10618=((r00)*(sj6));
34198 IkReal x10619=((IkReal(1.00000000000000))*(cj4));
34199 IkReal x10620=((cj6)*(sj0));
34200 IkReal x10621=((r00)*(sj4));
34201 IkReal x10622=((cj0)*(cj5));
34202 IkReal x10623=((cj6)*(r01));
34203 IkReal x10624=((cj5)*(sj0));
34204 IkReal x10625=((cj0)*(sj5));
34205 IkReal x10626=((cj6)*(r11));
34206 IkReal x10627=((r10)*(sj6));
34207 IkReal x10628=((r10)*(sj4));
34208 IkReal x10629=((cj0)*(sj4)*(sj6));
34209 IkReal x10630=((sj0)*(sj4)*(sj6));
34210 IkReal x10631=((IkReal(1.00000000000000))*(cj0)*(cj6));
34211 evalcond[0]=((((IkReal(-1.00000000000000))*(x10625)*(x10627)))+(((x10617)*(x10618)))+(((IkReal(-1.00000000000000))*(r02)*(x10624)))+(((IkReal(-1.00000000000000))*(x10625)*(x10626)))+(x10616)+(((x10617)*(x10623)))+(((r12)*(x10622))));
34212 evalcond[1]=((((IkReal(-1.00000000000000))*(x10618)*(x10625)))+(((IkReal(-1.00000000000000))*(x10623)*(x10625)))+(((r02)*(x10622)))+(((IkReal(-1.00000000000000))*(x10617)*(x10627)))+(((r12)*(x10624)))+(x10615)+(((IkReal(-1.00000000000000))*(x10617)*(x10626))));
34213 evalcond[2]=((((IkReal(-1.00000000000000))*(x10628)*(x10631)))+(((IkReal(-1.00000000000000))*(r12)*(x10619)*(x10625)))+(((r11)*(x10629)))+(((cj4)*(cj5)*(r01)*(x10620)))+(((cj4)*(x10618)*(x10624)))+(((IkReal(-1.00000000000000))*(x10615)))+(((IkReal(-1.00000000000000))*(x10619)*(x10622)*(x10626)))+(((cj4)*(r02)*(x10617)))+(((IkReal(-1.00000000000000))*(x10619)*(x10622)*(x10627)))+(((IkReal(-1.00000000000000))*(r01)*(x10630)))+(((x10620)*(x10621))));
34214 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x10619)*(x10620)))+(((IkReal(-1.00000000000000))*(x10620)*(x10628)))+(((r11)*(x10630)))+(((IkReal(-1.00000000000000))*(x10619)*(x10624)*(x10627)))+(x10616)+(((r01)*(x10629)))+(((IkReal(-1.00000000000000))*(x10621)*(x10631)))+(((IkReal(-1.00000000000000))*(x10619)*(x10622)*(x10623)))+(((IkReal(-1.00000000000000))*(r02)*(x10619)*(x10625)))+(((IkReal(-1.00000000000000))*(x10618)*(x10619)*(x10622)))+(((IkReal(-1.00000000000000))*(r12)*(x10617)*(x10619))));
34215 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
34216 {
34217 continue;
34218 }
34219 }
34220 
34221 {
34222 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34223 vinfos[0].jointtype = 1;
34224 vinfos[0].foffset = j0;
34225 vinfos[0].indices[0] = _ij0[0];
34226 vinfos[0].indices[1] = _ij0[1];
34227 vinfos[0].maxsolutions = _nj0;
34228 vinfos[1].jointtype = 1;
34229 vinfos[1].foffset = j1;
34230 vinfos[1].indices[0] = _ij1[0];
34231 vinfos[1].indices[1] = _ij1[1];
34232 vinfos[1].maxsolutions = _nj1;
34233 vinfos[2].jointtype = 1;
34234 vinfos[2].foffset = j2;
34235 vinfos[2].indices[0] = _ij2[0];
34236 vinfos[2].indices[1] = _ij2[1];
34237 vinfos[2].maxsolutions = _nj2;
34238 vinfos[3].jointtype = 1;
34239 vinfos[3].foffset = j3;
34240 vinfos[3].indices[0] = _ij3[0];
34241 vinfos[3].indices[1] = _ij3[1];
34242 vinfos[3].maxsolutions = _nj3;
34243 vinfos[4].jointtype = 1;
34244 vinfos[4].foffset = j4;
34245 vinfos[4].indices[0] = _ij4[0];
34246 vinfos[4].indices[1] = _ij4[1];
34247 vinfos[4].maxsolutions = _nj4;
34248 vinfos[5].jointtype = 1;
34249 vinfos[5].foffset = j5;
34250 vinfos[5].indices[0] = _ij5[0];
34251 vinfos[5].indices[1] = _ij5[1];
34252 vinfos[5].maxsolutions = _nj5;
34253 vinfos[6].jointtype = 1;
34254 vinfos[6].foffset = j6;
34255 vinfos[6].indices[0] = _ij6[0];
34256 vinfos[6].indices[1] = _ij6[1];
34257 vinfos[6].maxsolutions = _nj6;
34258 std::vector<int> vfree(0);
34259 solutions.AddSolution(vinfos,vfree);
34260 }
34261 }
34262 }
34263 
34264 } else
34265 {
34266 if( 1 )
34267 {
34268 continue;
34269 
34270 } else
34271 {
34272 }
34273 }
34274 }
34275 }
34276 }
34277 }
34278 
34279 } else
34280 {
34281 {
34282 IkReal j3array[1], cj3array[1], sj3array[1];
34283 bool j3valid[1]={false};
34284 _nj3 = 1;
34285 IkReal x10632=((cj5)*(r02));
34286 IkReal x10633=((cj0)*(sj5));
34287 IkReal x10634=((r10)*(sj6));
34288 IkReal x10635=((IkReal(1.00000000000000))*(cj6));
34289 IkReal x10636=((sj0)*(sj5));
34290 IkReal x10637=((cj5)*(r12));
34291 IkReal x10638=((IkReal(1.00000000000000))*(r00)*(sj6));
34292 if( IKabs(((((IkReal(-1.00000000000000))*(cj0)*(x10637)))+(((IkReal(-1.00000000000000))*(x10636)*(x10638)))+(((IkReal(-1.00000000000000))*(r01)*(x10635)*(x10636)))+(((sj0)*(x10632)))+(((x10633)*(x10634)))+(((cj6)*(r11)*(x10633))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x10633)*(x10635)))+(((sj0)*(x10637)))+(((IkReal(-1.00000000000000))*(r11)*(x10635)*(x10636)))+(((IkReal(-1.00000000000000))*(x10633)*(x10638)))+(((IkReal(-1.00000000000000))*(x10634)*(x10636)))+(((cj0)*(x10632))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(x10637)))+(((IkReal(-1.00000000000000))*(x10636)*(x10638)))+(((IkReal(-1.00000000000000))*(r01)*(x10635)*(x10636)))+(((sj0)*(x10632)))+(((x10633)*(x10634)))+(((cj6)*(r11)*(x10633)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x10633)*(x10635)))+(((sj0)*(x10637)))+(((IkReal(-1.00000000000000))*(r11)*(x10635)*(x10636)))+(((IkReal(-1.00000000000000))*(x10633)*(x10638)))+(((IkReal(-1.00000000000000))*(x10634)*(x10636)))+(((cj0)*(x10632)))))))-1) <= IKFAST_SINCOS_THRESH )
34293     continue;
34294 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj0)*(x10637)))+(((IkReal(-1.00000000000000))*(x10636)*(x10638)))+(((IkReal(-1.00000000000000))*(r01)*(x10635)*(x10636)))+(((sj0)*(x10632)))+(((x10633)*(x10634)))+(((cj6)*(r11)*(x10633)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x10633)*(x10635)))+(((sj0)*(x10637)))+(((IkReal(-1.00000000000000))*(r11)*(x10635)*(x10636)))+(((IkReal(-1.00000000000000))*(x10633)*(x10638)))+(((IkReal(-1.00000000000000))*(x10634)*(x10636)))+(((cj0)*(x10632)))))));
34295 sj3array[0]=IKsin(j3array[0]);
34296 cj3array[0]=IKcos(j3array[0]);
34297 if( j3array[0] > IKPI )
34298 {
34299     j3array[0]-=IK2PI;
34300 }
34301 else if( j3array[0] < -IKPI )
34302 {    j3array[0]+=IK2PI;
34303 }
34304 j3valid[0] = true;
34305 for(int ij3 = 0; ij3 < 1; ++ij3)
34306 {
34307 if( !j3valid[ij3] )
34308 {
34309     continue;
34310 }
34311 _ij3[0] = ij3; _ij3[1] = -1;
34312 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34313 {
34314 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34315 {
34316     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34317 }
34318 }
34319 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34320 {
34321 IkReal evalcond[6];
34322 IkReal x10639=IKsin(j3);
34323 IkReal x10640=IKcos(j3);
34324 IkReal x10641=((sj0)*(sj5));
34325 IkReal x10642=((r00)*(sj6));
34326 IkReal x10643=((IkReal(1.00000000000000))*(cj4));
34327 IkReal x10644=((cj6)*(r01));
34328 IkReal x10645=((cj0)*(cj5));
34329 IkReal x10646=((cj5)*(sj0));
34330 IkReal x10647=((cj6)*(r11));
34331 IkReal x10648=((cj0)*(sj5));
34332 IkReal x10649=((IkReal(1.00000000000000))*(cj1));
34333 IkReal x10650=((cj6)*(sj4));
34334 IkReal x10651=((IkReal(1.00000000000000))*(sj1));
34335 IkReal x10652=((cj4)*(cj5));
34336 IkReal x10653=((cj6)*(r21));
34337 IkReal x10654=((r20)*(sj6));
34338 IkReal x10655=((r10)*(sj6));
34339 IkReal x10656=((IkReal(1.00000000000000))*(cj0));
34340 IkReal x10657=((cj0)*(sj4)*(sj6));
34341 IkReal x10658=((sj0)*(sj4)*(sj6));
34342 evalcond[0]=((((sj5)*(x10654)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10653)))+(((IkReal(-1.00000000000000))*(x10640)*(x10651))));
34343 evalcond[1]=((((IkReal(-1.00000000000000))*(x10639)*(x10651)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x10652)*(x10654)))+(((r20)*(x10650)))+(((x10652)*(x10653))));
34344 evalcond[2]=((((IkReal(-1.00000000000000))*(x10648)*(x10655)))+(((IkReal(-1.00000000000000))*(x10647)*(x10648)))+(x10639)+(((x10641)*(x10644)))+(((x10641)*(x10642)))+(((r12)*(x10645)))+(((IkReal(-1.00000000000000))*(r02)*(x10646))));
34345 evalcond[3]=((((IkReal(-1.00000000000000))*(x10641)*(x10655)))+(((IkReal(-1.00000000000000))*(x10641)*(x10647)))+(((r12)*(x10646)))+(((IkReal(-1.00000000000000))*(x10642)*(x10648)))+(((IkReal(-1.00000000000000))*(x10640)*(x10649)))+(((r02)*(x10645)))+(((IkReal(-1.00000000000000))*(x10644)*(x10648))));
34346 evalcond[4]=((((cj4)*(x10644)*(x10646)))+(((r11)*(x10657)))+(((IkReal(-1.00000000000000))*(r10)*(x10650)*(x10656)))+(((IkReal(-1.00000000000000))*(r01)*(x10658)))+(((IkReal(-1.00000000000000))*(x10640)))+(((IkReal(-1.00000000000000))*(x10643)*(x10645)*(x10647)))+(((cj4)*(x10642)*(x10646)))+(((cj4)*(r02)*(x10641)))+(((IkReal(-1.00000000000000))*(x10643)*(x10645)*(x10655)))+(((r00)*(sj0)*(x10650)))+(((IkReal(-1.00000000000000))*(r12)*(x10643)*(x10648))));
34347 evalcond[5]=((((IkReal(-1.00000000000000))*(x10639)*(x10649)))+(((IkReal(-1.00000000000000))*(x10643)*(x10646)*(x10655)))+(((IkReal(-1.00000000000000))*(x10643)*(x10646)*(x10647)))+(((IkReal(-1.00000000000000))*(r02)*(x10643)*(x10648)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10650)))+(((IkReal(-1.00000000000000))*(r12)*(x10641)*(x10643)))+(((r11)*(x10658)))+(((IkReal(-1.00000000000000))*(r00)*(x10650)*(x10656)))+(((r01)*(x10657)))+(((IkReal(-1.00000000000000))*(x10643)*(x10644)*(x10645)))+(((IkReal(-1.00000000000000))*(x10642)*(x10643)*(x10645))));
34348 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
34349 {
34350 continue;
34351 }
34352 }
34353 
34354 {
34355 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34356 vinfos[0].jointtype = 1;
34357 vinfos[0].foffset = j0;
34358 vinfos[0].indices[0] = _ij0[0];
34359 vinfos[0].indices[1] = _ij0[1];
34360 vinfos[0].maxsolutions = _nj0;
34361 vinfos[1].jointtype = 1;
34362 vinfos[1].foffset = j1;
34363 vinfos[1].indices[0] = _ij1[0];
34364 vinfos[1].indices[1] = _ij1[1];
34365 vinfos[1].maxsolutions = _nj1;
34366 vinfos[2].jointtype = 1;
34367 vinfos[2].foffset = j2;
34368 vinfos[2].indices[0] = _ij2[0];
34369 vinfos[2].indices[1] = _ij2[1];
34370 vinfos[2].maxsolutions = _nj2;
34371 vinfos[3].jointtype = 1;
34372 vinfos[3].foffset = j3;
34373 vinfos[3].indices[0] = _ij3[0];
34374 vinfos[3].indices[1] = _ij3[1];
34375 vinfos[3].maxsolutions = _nj3;
34376 vinfos[4].jointtype = 1;
34377 vinfos[4].foffset = j4;
34378 vinfos[4].indices[0] = _ij4[0];
34379 vinfos[4].indices[1] = _ij4[1];
34380 vinfos[4].maxsolutions = _nj4;
34381 vinfos[5].jointtype = 1;
34382 vinfos[5].foffset = j5;
34383 vinfos[5].indices[0] = _ij5[0];
34384 vinfos[5].indices[1] = _ij5[1];
34385 vinfos[5].maxsolutions = _nj5;
34386 vinfos[6].jointtype = 1;
34387 vinfos[6].foffset = j6;
34388 vinfos[6].indices[0] = _ij6[0];
34389 vinfos[6].indices[1] = _ij6[1];
34390 vinfos[6].maxsolutions = _nj6;
34391 std::vector<int> vfree(0);
34392 solutions.AddSolution(vinfos,vfree);
34393 }
34394 }
34395 }
34396 
34397 }
34398 
34399 }
34400 
34401 } else
34402 {
34403 {
34404 IkReal j3array[1], cj3array[1], sj3array[1];
34405 bool j3valid[1]={false};
34406 _nj3 = 1;
34407 IkReal x10659=((sj5)*(sj6));
34408 IkReal x10660=((IkReal(1.00000000000000))*(sj0));
34409 IkReal x10661=((cj6)*(sj5));
34410 IkReal x10662=((IkReal(1.00000000000000))*(cj5));
34411 if( IKabs(((((cj0)*(r10)*(x10659)))+(((IkReal(-1.00000000000000))*(r01)*(x10660)*(x10661)))+(((cj0)*(r11)*(x10661)))+(((IkReal(-1.00000000000000))*(r00)*(x10659)*(x10660)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10662))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10662)))+(((r20)*(x10659)))+(((r21)*(x10661))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r10)*(x10659)))+(((IkReal(-1.00000000000000))*(r01)*(x10660)*(x10661)))+(((cj0)*(r11)*(x10661)))+(((IkReal(-1.00000000000000))*(r00)*(x10659)*(x10660)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10662)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10662)))+(((r20)*(x10659)))+(((r21)*(x10661)))))))-1) <= IKFAST_SINCOS_THRESH )
34412     continue;
34413 j3array[0]=IKatan2(((((cj0)*(r10)*(x10659)))+(((IkReal(-1.00000000000000))*(r01)*(x10660)*(x10661)))+(((cj0)*(r11)*(x10661)))+(((IkReal(-1.00000000000000))*(r00)*(x10659)*(x10660)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x10662)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x10662)))+(((r20)*(x10659)))+(((r21)*(x10661)))))));
34414 sj3array[0]=IKsin(j3array[0]);
34415 cj3array[0]=IKcos(j3array[0]);
34416 if( j3array[0] > IKPI )
34417 {
34418     j3array[0]-=IK2PI;
34419 }
34420 else if( j3array[0] < -IKPI )
34421 {    j3array[0]+=IK2PI;
34422 }
34423 j3valid[0] = true;
34424 for(int ij3 = 0; ij3 < 1; ++ij3)
34425 {
34426 if( !j3valid[ij3] )
34427 {
34428     continue;
34429 }
34430 _ij3[0] = ij3; _ij3[1] = -1;
34431 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34432 {
34433 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34434 {
34435     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34436 }
34437 }
34438 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34439 {
34440 IkReal evalcond[6];
34441 IkReal x10663=IKsin(j3);
34442 IkReal x10664=IKcos(j3);
34443 IkReal x10665=((sj0)*(sj5));
34444 IkReal x10666=((r00)*(sj6));
34445 IkReal x10667=((IkReal(1.00000000000000))*(cj4));
34446 IkReal x10668=((cj6)*(r01));
34447 IkReal x10669=((cj0)*(cj5));
34448 IkReal x10670=((cj5)*(sj0));
34449 IkReal x10671=((cj6)*(r11));
34450 IkReal x10672=((cj0)*(sj5));
34451 IkReal x10673=((IkReal(1.00000000000000))*(cj1));
34452 IkReal x10674=((cj6)*(sj4));
34453 IkReal x10675=((IkReal(1.00000000000000))*(sj1));
34454 IkReal x10676=((cj4)*(cj5));
34455 IkReal x10677=((cj6)*(r21));
34456 IkReal x10678=((r20)*(sj6));
34457 IkReal x10679=((r10)*(sj6));
34458 IkReal x10680=((IkReal(1.00000000000000))*(cj0));
34459 IkReal x10681=((cj0)*(sj4)*(sj6));
34460 IkReal x10682=((sj0)*(sj4)*(sj6));
34461 evalcond[0]=((((sj5)*(x10678)))+(((IkReal(-1.00000000000000))*(x10664)*(x10675)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10677))));
34462 evalcond[1]=((((IkReal(-1.00000000000000))*(x10663)*(x10675)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x10676)*(x10677)))+(((r20)*(x10674)))+(((x10676)*(x10678))));
34463 evalcond[2]=((((IkReal(-1.00000000000000))*(x10671)*(x10672)))+(((x10665)*(x10668)))+(((r12)*(x10669)))+(((IkReal(-1.00000000000000))*(x10672)*(x10679)))+(((IkReal(-1.00000000000000))*(r02)*(x10670)))+(x10663)+(((x10665)*(x10666))));
34464 evalcond[3]=((((IkReal(-1.00000000000000))*(x10664)*(x10673)))+(((IkReal(-1.00000000000000))*(x10666)*(x10672)))+(((r12)*(x10670)))+(((IkReal(-1.00000000000000))*(x10668)*(x10672)))+(((IkReal(-1.00000000000000))*(x10665)*(x10679)))+(((r02)*(x10669)))+(((IkReal(-1.00000000000000))*(x10665)*(x10671))));
34465 evalcond[4]=((((cj4)*(x10666)*(x10670)))+(((IkReal(-1.00000000000000))*(x10667)*(x10669)*(x10671)))+(((IkReal(-1.00000000000000))*(r12)*(x10667)*(x10672)))+(((IkReal(-1.00000000000000))*(r10)*(x10674)*(x10680)))+(((cj4)*(r02)*(x10665)))+(((r11)*(x10681)))+(((IkReal(-1.00000000000000))*(x10664)))+(((IkReal(-1.00000000000000))*(r01)*(x10682)))+(((IkReal(-1.00000000000000))*(x10667)*(x10669)*(x10679)))+(((cj4)*(x10668)*(x10670)))+(((r00)*(sj0)*(x10674))));
34466 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x10674)*(x10680)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10674)))+(((r01)*(x10681)))+(((IkReal(-1.00000000000000))*(x10667)*(x10670)*(x10671)))+(((IkReal(-1.00000000000000))*(r02)*(x10667)*(x10672)))+(((IkReal(-1.00000000000000))*(r12)*(x10665)*(x10667)))+(((IkReal(-1.00000000000000))*(x10666)*(x10667)*(x10669)))+(((IkReal(-1.00000000000000))*(x10667)*(x10670)*(x10679)))+(((IkReal(-1.00000000000000))*(x10667)*(x10668)*(x10669)))+(((IkReal(-1.00000000000000))*(x10663)*(x10673)))+(((r11)*(x10682))));
34467 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
34468 {
34469 continue;
34470 }
34471 }
34472 
34473 {
34474 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34475 vinfos[0].jointtype = 1;
34476 vinfos[0].foffset = j0;
34477 vinfos[0].indices[0] = _ij0[0];
34478 vinfos[0].indices[1] = _ij0[1];
34479 vinfos[0].maxsolutions = _nj0;
34480 vinfos[1].jointtype = 1;
34481 vinfos[1].foffset = j1;
34482 vinfos[1].indices[0] = _ij1[0];
34483 vinfos[1].indices[1] = _ij1[1];
34484 vinfos[1].maxsolutions = _nj1;
34485 vinfos[2].jointtype = 1;
34486 vinfos[2].foffset = j2;
34487 vinfos[2].indices[0] = _ij2[0];
34488 vinfos[2].indices[1] = _ij2[1];
34489 vinfos[2].maxsolutions = _nj2;
34490 vinfos[3].jointtype = 1;
34491 vinfos[3].foffset = j3;
34492 vinfos[3].indices[0] = _ij3[0];
34493 vinfos[3].indices[1] = _ij3[1];
34494 vinfos[3].maxsolutions = _nj3;
34495 vinfos[4].jointtype = 1;
34496 vinfos[4].foffset = j4;
34497 vinfos[4].indices[0] = _ij4[0];
34498 vinfos[4].indices[1] = _ij4[1];
34499 vinfos[4].maxsolutions = _nj4;
34500 vinfos[5].jointtype = 1;
34501 vinfos[5].foffset = j5;
34502 vinfos[5].indices[0] = _ij5[0];
34503 vinfos[5].indices[1] = _ij5[1];
34504 vinfos[5].maxsolutions = _nj5;
34505 vinfos[6].jointtype = 1;
34506 vinfos[6].foffset = j6;
34507 vinfos[6].indices[0] = _ij6[0];
34508 vinfos[6].indices[1] = _ij6[1];
34509 vinfos[6].maxsolutions = _nj6;
34510 std::vector<int> vfree(0);
34511 solutions.AddSolution(vinfos,vfree);
34512 }
34513 }
34514 }
34515 
34516 }
34517 
34518 }
34519 
34520 } else
34521 {
34522 {
34523 IkReal j3array[1], cj3array[1], sj3array[1];
34524 bool j3valid[1]={false};
34525 _nj3 = 1;
34526 IkReal x10683=((r20)*(sj6));
34527 IkReal x10684=((cj4)*(cj5));
34528 IkReal x10685=((cj6)*(r21));
34529 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10683)*(x10684)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10684)*(x10685))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((sj5)*(x10685)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10683))))))) < IKFAST_ATAN2_MAGTHRESH )
34530     continue;
34531 j3array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x10683)*(x10684)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x10684)*(x10685)))))), ((gconst30)*(((((sj5)*(x10685)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10683)))))));
34532 sj3array[0]=IKsin(j3array[0]);
34533 cj3array[0]=IKcos(j3array[0]);
34534 if( j3array[0] > IKPI )
34535 {
34536     j3array[0]-=IK2PI;
34537 }
34538 else if( j3array[0] < -IKPI )
34539 {    j3array[0]+=IK2PI;
34540 }
34541 j3valid[0] = true;
34542 for(int ij3 = 0; ij3 < 1; ++ij3)
34543 {
34544 if( !j3valid[ij3] )
34545 {
34546     continue;
34547 }
34548 _ij3[0] = ij3; _ij3[1] = -1;
34549 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34550 {
34551 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34552 {
34553     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34554 }
34555 }
34556 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34557 {
34558 IkReal evalcond[6];
34559 IkReal x10686=IKsin(j3);
34560 IkReal x10687=IKcos(j3);
34561 IkReal x10688=((sj0)*(sj5));
34562 IkReal x10689=((r00)*(sj6));
34563 IkReal x10690=((IkReal(1.00000000000000))*(cj4));
34564 IkReal x10691=((cj6)*(r01));
34565 IkReal x10692=((cj0)*(cj5));
34566 IkReal x10693=((cj5)*(sj0));
34567 IkReal x10694=((cj6)*(r11));
34568 IkReal x10695=((cj0)*(sj5));
34569 IkReal x10696=((IkReal(1.00000000000000))*(cj1));
34570 IkReal x10697=((cj6)*(sj4));
34571 IkReal x10698=((IkReal(1.00000000000000))*(sj1));
34572 IkReal x10699=((cj4)*(cj5));
34573 IkReal x10700=((cj6)*(r21));
34574 IkReal x10701=((r20)*(sj6));
34575 IkReal x10702=((r10)*(sj6));
34576 IkReal x10703=((IkReal(1.00000000000000))*(cj0));
34577 IkReal x10704=((cj0)*(sj4)*(sj6));
34578 IkReal x10705=((sj0)*(sj4)*(sj6));
34579 evalcond[0]=((((IkReal(-1.00000000000000))*(x10687)*(x10698)))+(((sj5)*(x10700)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10701))));
34580 evalcond[1]=((((x10699)*(x10700)))+(((r20)*(x10697)))+(((x10699)*(x10701)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x10686)*(x10698)))+(((cj4)*(r22)*(sj5))));
34581 evalcond[2]=((((IkReal(-1.00000000000000))*(x10695)*(x10702)))+(((IkReal(-1.00000000000000))*(x10694)*(x10695)))+(((IkReal(-1.00000000000000))*(r02)*(x10693)))+(x10686)+(((x10688)*(x10691)))+(((x10688)*(x10689)))+(((r12)*(x10692))));
34582 evalcond[3]=((((r12)*(x10693)))+(((IkReal(-1.00000000000000))*(x10689)*(x10695)))+(((IkReal(-1.00000000000000))*(x10687)*(x10696)))+(((IkReal(-1.00000000000000))*(x10688)*(x10694)))+(((IkReal(-1.00000000000000))*(x10691)*(x10695)))+(((IkReal(-1.00000000000000))*(x10688)*(x10702)))+(((r02)*(x10692))));
34583 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x10705)))+(((r00)*(sj0)*(x10697)))+(((r11)*(x10704)))+(((cj4)*(x10691)*(x10693)))+(((IkReal(-1.00000000000000))*(x10690)*(x10692)*(x10702)))+(((cj4)*(x10689)*(x10693)))+(((cj4)*(r02)*(x10688)))+(((IkReal(-1.00000000000000))*(x10687)))+(((IkReal(-1.00000000000000))*(r10)*(x10697)*(x10703)))+(((IkReal(-1.00000000000000))*(r12)*(x10690)*(x10695)))+(((IkReal(-1.00000000000000))*(x10690)*(x10692)*(x10694))));
34584 evalcond[5]=((((IkReal(-1.00000000000000))*(x10690)*(x10691)*(x10692)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10697)))+(((r01)*(x10704)))+(((IkReal(-1.00000000000000))*(x10689)*(x10690)*(x10692)))+(((IkReal(-1.00000000000000))*(r02)*(x10690)*(x10695)))+(((IkReal(-1.00000000000000))*(x10690)*(x10693)*(x10694)))+(((r11)*(x10705)))+(((IkReal(-1.00000000000000))*(x10686)*(x10696)))+(((IkReal(-1.00000000000000))*(r12)*(x10688)*(x10690)))+(((IkReal(-1.00000000000000))*(x10690)*(x10693)*(x10702)))+(((IkReal(-1.00000000000000))*(r00)*(x10697)*(x10703))));
34585 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
34586 {
34587 continue;
34588 }
34589 }
34590 
34591 {
34592 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34593 vinfos[0].jointtype = 1;
34594 vinfos[0].foffset = j0;
34595 vinfos[0].indices[0] = _ij0[0];
34596 vinfos[0].indices[1] = _ij0[1];
34597 vinfos[0].maxsolutions = _nj0;
34598 vinfos[1].jointtype = 1;
34599 vinfos[1].foffset = j1;
34600 vinfos[1].indices[0] = _ij1[0];
34601 vinfos[1].indices[1] = _ij1[1];
34602 vinfos[1].maxsolutions = _nj1;
34603 vinfos[2].jointtype = 1;
34604 vinfos[2].foffset = j2;
34605 vinfos[2].indices[0] = _ij2[0];
34606 vinfos[2].indices[1] = _ij2[1];
34607 vinfos[2].maxsolutions = _nj2;
34608 vinfos[3].jointtype = 1;
34609 vinfos[3].foffset = j3;
34610 vinfos[3].indices[0] = _ij3[0];
34611 vinfos[3].indices[1] = _ij3[1];
34612 vinfos[3].maxsolutions = _nj3;
34613 vinfos[4].jointtype = 1;
34614 vinfos[4].foffset = j4;
34615 vinfos[4].indices[0] = _ij4[0];
34616 vinfos[4].indices[1] = _ij4[1];
34617 vinfos[4].maxsolutions = _nj4;
34618 vinfos[5].jointtype = 1;
34619 vinfos[5].foffset = j5;
34620 vinfos[5].indices[0] = _ij5[0];
34621 vinfos[5].indices[1] = _ij5[1];
34622 vinfos[5].maxsolutions = _nj5;
34623 vinfos[6].jointtype = 1;
34624 vinfos[6].foffset = j6;
34625 vinfos[6].indices[0] = _ij6[0];
34626 vinfos[6].indices[1] = _ij6[1];
34627 vinfos[6].maxsolutions = _nj6;
34628 std::vector<int> vfree(0);
34629 solutions.AddSolution(vinfos,vfree);
34630 }
34631 }
34632 }
34633 
34634 }
34635 
34636 }
34637 }
34638 }
34639 
34640 }
34641 
34642 }
34643 
34644 } else
34645 {
34646 if( 1 )
34647 {
34648 continue;
34649 
34650 } else
34651 {
34652 }
34653 }
34654 }
34655 }
34656 
34657 } else
34658 {
34659 {
34660 IkReal j3array[1], cj3array[1], sj3array[1];
34661 bool j3valid[1]={false};
34662 _nj3 = 1;
34663 IkReal x10706=(cj1)*(cj1);
34664 IkReal x10707=(sj1)*(sj1);
34665 IkReal x10708=((r00)*(sj6));
34666 IkReal x10709=((cj6)*(r01));
34667 IkReal x10710=((IkReal(1.00000000000000))*(cj1));
34668 IkReal x10711=((cj5)*(r22));
34669 IkReal x10712=((sj5)*(sj6));
34670 IkReal x10713=((r10)*(sj0));
34671 IkReal x10714=((cj1)*(cj5));
34672 IkReal x10715=((cj0)*(r02));
34673 IkReal x10716=((r12)*(sj0));
34674 IkReal x10717=((IkReal(1.00000000000000))*(sj1));
34675 IkReal x10718=((cj6)*(sj5));
34676 IkReal x10719=((cj0)*(sj5));
34677 IkReal x10720=((r11)*(sj0));
34678 IkReal x10721=((sj1)*(x10719));
34679 if( IKabs(((((IKabs(((((cj2)*(x10706)))+(((cj2)*(x10707))))) != 0)?((IkReal)1/(((((cj2)*(x10706)))+(((cj2)*(x10707)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10710)*(x10711)))+(((cj1)*(r20)*(x10712)))+(((sj1)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(cj5)*(x10716)*(x10717)))+(((cj1)*(r21)*(x10718)))+(((sj1)*(x10718)*(x10720)))+(((x10709)*(x10721)))+(((IkReal(-1.00000000000000))*(cj5)*(x10715)*(x10717)))+(((x10708)*(x10721))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x10707)+(x10706))) != 0)?((IkReal)1/(((x10707)+(x10706)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10709)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10708)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10710)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(x10710)*(x10718)*(x10720)))+(((IkReal(-1.00000000000000))*(x10711)*(x10717)))+(((r21)*(sj1)*(x10718)))+(((x10714)*(x10716)))+(((x10714)*(x10715)))+(((r20)*(sj1)*(x10712))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x10706)))+(((cj2)*(x10707))))) != 0)?((IkReal)1/(((((cj2)*(x10706)))+(((cj2)*(x10707)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10710)*(x10711)))+(((cj1)*(r20)*(x10712)))+(((sj1)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(cj5)*(x10716)*(x10717)))+(((cj1)*(r21)*(x10718)))+(((sj1)*(x10718)*(x10720)))+(((x10709)*(x10721)))+(((IkReal(-1.00000000000000))*(cj5)*(x10715)*(x10717)))+(((x10708)*(x10721)))))))+IKsqr(((((IKabs(((x10707)+(x10706))) != 0)?((IkReal)1/(((x10707)+(x10706)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10709)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10708)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10710)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(x10710)*(x10718)*(x10720)))+(((IkReal(-1.00000000000000))*(x10711)*(x10717)))+(((r21)*(sj1)*(x10718)))+(((x10714)*(x10716)))+(((x10714)*(x10715)))+(((r20)*(sj1)*(x10712)))))))-1) <= IKFAST_SINCOS_THRESH )
34680     continue;
34681 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x10706)))+(((cj2)*(x10707))))) != 0)?((IkReal)1/(((((cj2)*(x10706)))+(((cj2)*(x10707)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10710)*(x10711)))+(((cj1)*(r20)*(x10712)))+(((sj1)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(cj5)*(x10716)*(x10717)))+(((cj1)*(r21)*(x10718)))+(((sj1)*(x10718)*(x10720)))+(((x10709)*(x10721)))+(((IkReal(-1.00000000000000))*(cj5)*(x10715)*(x10717)))+(((x10708)*(x10721)))))), ((((IKabs(((x10707)+(x10706))) != 0)?((IkReal)1/(((x10707)+(x10706)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x10709)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10708)*(x10710)*(x10719)))+(((IkReal(-1.00000000000000))*(x10710)*(x10712)*(x10713)))+(((IkReal(-1.00000000000000))*(x10710)*(x10718)*(x10720)))+(((IkReal(-1.00000000000000))*(x10711)*(x10717)))+(((r21)*(sj1)*(x10718)))+(((x10714)*(x10716)))+(((x10714)*(x10715)))+(((r20)*(sj1)*(x10712)))))));
34682 sj3array[0]=IKsin(j3array[0]);
34683 cj3array[0]=IKcos(j3array[0]);
34684 if( j3array[0] > IKPI )
34685 {
34686     j3array[0]-=IK2PI;
34687 }
34688 else if( j3array[0] < -IKPI )
34689 {    j3array[0]+=IK2PI;
34690 }
34691 j3valid[0] = true;
34692 for(int ij3 = 0; ij3 < 1; ++ij3)
34693 {
34694 if( !j3valid[ij3] )
34695 {
34696     continue;
34697 }
34698 _ij3[0] = ij3; _ij3[1] = -1;
34699 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
34700 {
34701 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
34702 {
34703     j3valid[iij3]=false; _ij3[1] = iij3; break; 
34704 }
34705 }
34706 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
34707 {
34708 IkReal evalcond[3];
34709 IkReal x10722=IKsin(j3);
34710 IkReal x10723=IKcos(j3);
34711 IkReal x10724=((sj5)*(sj6));
34712 IkReal x10725=((cj0)*(cj5));
34713 IkReal x10726=((IkReal(1.00000000000000))*(cj0));
34714 IkReal x10727=((IkReal(1.00000000000000))*(sj0));
34715 IkReal x10728=((IkReal(1.00000000000000))*(x10723));
34716 IkReal x10729=((IkReal(1.00000000000000))*(x10722));
34717 IkReal x10730=((cj6)*(r01)*(sj5));
34718 IkReal x10731=((cj6)*(r11)*(sj5));
34719 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x10728)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj1)*(cj2)*(x10729)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x10724))));
34720 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)*(x10729)))+(((sj0)*(x10730)))+(((IkReal(-1.00000000000000))*(x10726)*(x10731)))+(((r00)*(sj0)*(x10724)))+(((IkReal(-1.00000000000000))*(cj5)*(r02)*(x10727)))+(((r12)*(x10725)))+(((IkReal(-1.00000000000000))*(r10)*(x10724)*(x10726))));
34721 evalcond[2]=((((IkReal(-1.00000000000000))*(x10727)*(x10731)))+(((IkReal(-1.00000000000000))*(x10726)*(x10730)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r00)*(x10724)*(x10726)))+(((IkReal(-1.00000000000000))*(r10)*(x10724)*(x10727)))+(((cj2)*(sj1)*(x10722)))+(((r02)*(x10725)))+(((IkReal(-1.00000000000000))*(cj1)*(x10728))));
34722 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
34723 {
34724 continue;
34725 }
34726 }
34727 
34728 {
34729 IkReal dummyeval[1];
34730 IkReal gconst2;
34731 IkReal x10732=(r21)*(r21);
34732 IkReal x10733=(cj5)*(cj5);
34733 IkReal x10734=(sj6)*(sj6);
34734 IkReal x10735=(cj6)*(cj6);
34735 IkReal x10736=(r20)*(r20);
34736 IkReal x10737=((cj6)*(r21));
34737 IkReal x10738=((IkReal(2.00000000000000))*(r20)*(sj6));
34738 IkReal x10739=((cj5)*(r22)*(sj5));
34739 IkReal x10740=((IkReal(1.00000000000000))*(x10734));
34740 IkReal x10741=((IkReal(1.00000000000000))*(x10735));
34741 gconst2=IKsign(((((IkReal(-1.00000000000000))*(x10736)*(x10741)))+(((IkReal(-1.00000000000000))*(x10733)*(x10736)*(x10740)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x10733)*(x10737)*(x10738)))+(((x10737)*(x10738)))+(((IkReal(-2.00000000000000))*(x10737)*(x10739)))+(((IkReal(-1.00000000000000))*(x10732)*(x10740)))+(((IkReal(-1.00000000000000))*(x10732)*(x10733)*(x10741)))+(((IkReal(-1.00000000000000))*(x10738)*(x10739)))));
34742 IkReal x10742=(r21)*(r21);
34743 IkReal x10743=(cj5)*(cj5);
34744 IkReal x10744=(sj6)*(sj6);
34745 IkReal x10745=(cj6)*(cj6);
34746 IkReal x10746=(r20)*(r20);
34747 IkReal x10747=((cj6)*(r21));
34748 IkReal x10748=((IkReal(2.00000000000000))*(r20)*(sj6));
34749 IkReal x10749=((cj5)*(r22)*(sj5));
34750 IkReal x10750=((IkReal(1.00000000000000))*(x10744));
34751 IkReal x10751=((IkReal(1.00000000000000))*(x10745));
34752 dummyeval[0]=((((IkReal(-1.00000000000000))*(x10742)*(x10743)*(x10751)))+(((IkReal(-1.00000000000000))*(x10743)*(x10746)*(x10750)))+(((IkReal(-1.00000000000000))*((r22)*(r22))*((sj5)*(sj5))))+(((IkReal(-1.00000000000000))*(x10743)*(x10747)*(x10748)))+(((IkReal(-1.00000000000000))*(x10746)*(x10751)))+(((IkReal(-1.00000000000000))*(x10748)*(x10749)))+(((x10747)*(x10748)))+(((IkReal(-1.00000000000000))*(x10742)*(x10750)))+(((IkReal(-2.00000000000000))*(x10747)*(x10749))));
34753 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
34754 {
34755 {
34756 IkReal dummyeval[1];
34757 IkReal gconst3;
34758 IkReal x10752=(cj6)*(cj6);
34759 IkReal x10753=(sj6)*(sj6);
34760 IkReal x10754=((IkReal(1.00000000000000))*(r21));
34761 IkReal x10755=((cj6)*(r20));
34762 IkReal x10756=((r22)*(sj5));
34763 IkReal x10757=((r01)*(sj0));
34764 IkReal x10758=((r00)*(sj0));
34765 IkReal x10759=((cj0)*(r10));
34766 IkReal x10760=((r02)*(sj0)*(sj5));
34767 IkReal x10761=((cj5)*(x10752));
34768 IkReal x10762=((cj0)*(r12)*(sj5));
34769 IkReal x10763=((IkReal(1.00000000000000))*(cj0)*(r11));
34770 IkReal x10764=((cj5)*(x10753));
34771 IkReal x10765=((r20)*(x10764));
34772 gconst3=IKsign(((((x10757)*(x10765)))+(((IkReal(-1.00000000000000))*(x10754)*(x10758)*(x10764)))+(((IkReal(-1.00000000000000))*(x10763)*(x10765)))+(((IkReal(-1.00000000000000))*(sj6)*(x10756)*(x10763)))+(((IkReal(-1.00000000000000))*(r20)*(x10761)*(x10763)))+(((sj6)*(x10756)*(x10757)))+(((IkReal(-1.00000000000000))*(x10755)*(x10762)))+(((r20)*(x10757)*(x10761)))+(((r21)*(sj6)*(x10762)))+(((IkReal(-1.00000000000000))*(x10754)*(x10758)*(x10761)))+(((IkReal(-1.00000000000000))*(cj6)*(x10756)*(x10758)))+(((cj6)*(x10756)*(x10759)))+(((x10755)*(x10760)))+(((IkReal(-1.00000000000000))*(sj6)*(x10754)*(x10760)))+(((r21)*(x10759)*(x10761)))+(((r21)*(x10759)*(x10764)))));
34773 IkReal x10766=(cj6)*(cj6);
34774 IkReal x10767=(sj6)*(sj6);
34775 IkReal x10768=((IkReal(1.00000000000000))*(r21));
34776 IkReal x10769=((cj6)*(r20));
34777 IkReal x10770=((r22)*(sj5));
34778 IkReal x10771=((r01)*(sj0));
34779 IkReal x10772=((r00)*(sj0));
34780 IkReal x10773=((cj0)*(r10));
34781 IkReal x10774=((r02)*(sj0)*(sj5));
34782 IkReal x10775=((cj5)*(x10766));
34783 IkReal x10776=((cj0)*(r12)*(sj5));
34784 IkReal x10777=((IkReal(1.00000000000000))*(cj0)*(r11));
34785 IkReal x10778=((cj5)*(x10767));
34786 IkReal x10779=((r20)*(x10778));
34787 dummyeval[0]=((((IkReal(-1.00000000000000))*(sj6)*(x10770)*(x10777)))+(((IkReal(-1.00000000000000))*(x10777)*(x10779)))+(((r21)*(sj6)*(x10776)))+(((r21)*(x10773)*(x10778)))+(((IkReal(-1.00000000000000))*(cj6)*(x10770)*(x10772)))+(((r20)*(x10771)*(x10775)))+(((IkReal(-1.00000000000000))*(x10768)*(x10772)*(x10778)))+(((cj6)*(x10770)*(x10773)))+(((sj6)*(x10770)*(x10771)))+(((IkReal(-1.00000000000000))*(sj6)*(x10768)*(x10774)))+(((IkReal(-1.00000000000000))*(x10769)*(x10776)))+(((r21)*(x10773)*(x10775)))+(((IkReal(-1.00000000000000))*(x10768)*(x10772)*(x10775)))+(((x10771)*(x10779)))+(((x10769)*(x10774)))+(((IkReal(-1.00000000000000))*(r20)*(x10775)*(x10777))));
34788 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
34789 {
34790 continue;
34791 
34792 } else
34793 {
34794 {
34795 IkReal j4array[1], cj4array[1], sj4array[1];
34796 bool j4valid[1]={false};
34797 _nj4 = 1;
34798 IkReal x10780=((cj5)*(sj6));
34799 IkReal x10781=((cj2)*(r21));
34800 IkReal x10782=((cj5)*(cj6));
34801 IkReal x10783=((IkReal(1.00000000000000))*(cj2)*(r20));
34802 IkReal x10784=((cj0)*(cj1)*(sj2));
34803 IkReal x10785=((IkReal(1.00000000000000))*(cj1)*(sj0)*(sj2));
34804 IkReal x10786=((r10)*(x10784));
34805 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(cj6)*(r00)*(x10785)))+(((cj6)*(x10786)))+(((cj1)*(r01)*(sj0)*(sj2)*(sj6)))+(((sj6)*(x10781)))+(((IkReal(-1.00000000000000))*(cj6)*(x10783)))+(((IkReal(-1.00000000000000))*(r11)*(sj6)*(x10784))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((r11)*(x10782)*(x10784)))+(((r12)*(sj5)*(x10784)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x10785)))+(((x10780)*(x10786)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x10781)*(x10782)))+(((IkReal(-1.00000000000000))*(r00)*(x10780)*(x10785)))+(((IkReal(-1.00000000000000))*(r01)*(x10782)*(x10785)))+(((IkReal(-1.00000000000000))*(x10780)*(x10783))))))) < IKFAST_ATAN2_MAGTHRESH )
34806     continue;
34807 j4array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(cj6)*(r00)*(x10785)))+(((cj6)*(x10786)))+(((cj1)*(r01)*(sj0)*(sj2)*(sj6)))+(((sj6)*(x10781)))+(((IkReal(-1.00000000000000))*(cj6)*(x10783)))+(((IkReal(-1.00000000000000))*(r11)*(sj6)*(x10784)))))), ((gconst3)*(((((r11)*(x10782)*(x10784)))+(((r12)*(sj5)*(x10784)))+(((IkReal(-1.00000000000000))*(r02)*(sj5)*(x10785)))+(((x10780)*(x10786)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x10781)*(x10782)))+(((IkReal(-1.00000000000000))*(r00)*(x10780)*(x10785)))+(((IkReal(-1.00000000000000))*(r01)*(x10782)*(x10785)))+(((IkReal(-1.00000000000000))*(x10780)*(x10783)))))));
34808 sj4array[0]=IKsin(j4array[0]);
34809 cj4array[0]=IKcos(j4array[0]);
34810 if( j4array[0] > IKPI )
34811 {
34812     j4array[0]-=IK2PI;
34813 }
34814 else if( j4array[0] < -IKPI )
34815 {    j4array[0]+=IK2PI;
34816 }
34817 j4valid[0] = true;
34818 for(int ij4 = 0; ij4 < 1; ++ij4)
34819 {
34820 if( !j4valid[ij4] )
34821 {
34822     continue;
34823 }
34824 _ij4[0] = ij4; _ij4[1] = -1;
34825 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
34826 {
34827 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
34828 {
34829     j4valid[iij4]=false; _ij4[1] = iij4; break; 
34830 }
34831 }
34832 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
34833 {
34834 IkReal evalcond[6];
34835 IkReal x10787=IKsin(j4);
34836 IkReal x10788=IKcos(j4);
34837 IkReal x10789=((r00)*(sj6));
34838 IkReal x10790=((IkReal(1.00000000000000))*(r12));
34839 IkReal x10791=((IkReal(1.00000000000000))*(cj6));
34840 IkReal x10792=((cj6)*(r01));
34841 IkReal x10793=((IkReal(1.00000000000000))*(cj1));
34842 IkReal x10794=((cj2)*(cj3));
34843 IkReal x10795=((IkReal(1.00000000000000))*(sj1));
34844 IkReal x10796=((r11)*(sj6));
34845 IkReal x10797=((r01)*(sj6));
34846 IkReal x10798=((IkReal(1.00000000000000))*(cj5));
34847 IkReal x10799=((r10)*(sj6));
34848 IkReal x10800=((cj5)*(r11));
34849 IkReal x10801=((cj6)*(r00));
34850 IkReal x10802=((r21)*(sj6));
34851 IkReal x10803=((r02)*(sj5));
34852 IkReal x10804=((cj6)*(r10));
34853 IkReal x10805=((cj5)*(sj6));
34854 IkReal x10806=((cj5)*(r01));
34855 IkReal x10807=((sj5)*(x10787));
34856 IkReal x10808=((cj0)*(x10788));
34857 IkReal x10809=((cj0)*(x10787));
34858 IkReal x10810=((sj0)*(x10788));
34859 IkReal x10811=((sj0)*(x10787));
34860 IkReal x10812=((r20)*(x10788));
34861 IkReal x10813=((cj5)*(cj6)*(r21));
34862 IkReal x10814=((r20)*(x10787));
34863 IkReal x10815=((cj5)*(x10811));
34864 evalcond[0]=((((x10787)*(x10813)))+(((x10788)*(x10802)))+(((IkReal(-1.00000000000000))*(sj2)*(x10793)))+(((r22)*(x10807)))+(((x10805)*(x10814)))+(((IkReal(-1.00000000000000))*(x10791)*(x10812))));
34865 evalcond[1]=((((x10788)*(x10813)))+(((cj1)*(x10794)))+(((r22)*(sj5)*(x10788)))+(((x10805)*(x10812)))+(((IkReal(-1.00000000000000))*(sj3)*(x10795)))+(((cj6)*(x10814)))+(((IkReal(-1.00000000000000))*(x10787)*(x10802))));
34866 evalcond[2]=((((IkReal(-1.00000000000000))*(x10791)*(x10800)*(x10809)))+(((IkReal(-1.00000000000000))*(x10798)*(x10799)*(x10809)))+(((x10803)*(x10811)))+(((IkReal(-1.00000000000000))*(x10796)*(x10808)))+(((x10804)*(x10808)))+(((IkReal(-1.00000000000000))*(cj0)*(x10790)*(x10807)))+(((x10797)*(x10810)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x10791)*(x10810)))+(((x10792)*(x10815)))+(((x10789)*(x10815))));
34867 evalcond[3]=((((cj5)*(x10789)*(x10810)))+(((IkReal(-1.00000000000000))*(sj5)*(x10790)*(x10808)))+(((x10801)*(x10811)))+(((IkReal(-1.00000000000000))*(x10797)*(x10811)))+(((cj5)*(x10792)*(x10810)))+(((x10796)*(x10809)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(r10)*(x10791)*(x10809)))+(((IkReal(-1.00000000000000))*(x10798)*(x10799)*(x10808)))+(((x10803)*(x10810)))+(((IkReal(-1.00000000000000))*(x10791)*(x10800)*(x10808))));
34868 evalcond[4]=((((IkReal(-1.00000000000000))*(sj0)*(x10790)*(x10807)))+(((IkReal(-1.00000000000000))*(x10797)*(x10808)))+(((IkReal(-1.00000000000000))*(x10791)*(x10800)*(x10811)))+(((IkReal(-1.00000000000000))*(x10798)*(x10799)*(x10811)))+(((IkReal(-1.00000000000000))*(x10796)*(x10810)))+(((sj1)*(sj2)))+(((x10801)*(x10808)))+(((IkReal(-1.00000000000000))*(x10803)*(x10809)))+(((IkReal(-1.00000000000000))*(x10789)*(x10798)*(x10809)))+(((IkReal(-1.00000000000000))*(x10791)*(x10806)*(x10809)))+(((x10804)*(x10810))));
34869 evalcond[5]=((((IkReal(-1.00000000000000))*(x10791)*(x10800)*(x10810)))+(((IkReal(-1.00000000000000))*(x10789)*(x10798)*(x10808)))+(((x10797)*(x10809)))+(((IkReal(-1.00000000000000))*(sj3)*(x10793)))+(((x10796)*(x10811)))+(((IkReal(-1.00000000000000))*(x10803)*(x10808)))+(((IkReal(-1.00000000000000))*(r00)*(x10791)*(x10809)))+(((IkReal(-1.00000000000000))*(x10791)*(x10806)*(x10808)))+(((IkReal(-1.00000000000000))*(sj5)*(x10790)*(x10810)))+(((IkReal(-1.00000000000000))*(r10)*(x10791)*(x10811)))+(((IkReal(-1.00000000000000))*(x10794)*(x10795)))+(((IkReal(-1.00000000000000))*(x10798)*(x10799)*(x10810))));
34870 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
34871 {
34872 continue;
34873 }
34874 }
34875 
34876 {
34877 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
34878 vinfos[0].jointtype = 1;
34879 vinfos[0].foffset = j0;
34880 vinfos[0].indices[0] = _ij0[0];
34881 vinfos[0].indices[1] = _ij0[1];
34882 vinfos[0].maxsolutions = _nj0;
34883 vinfos[1].jointtype = 1;
34884 vinfos[1].foffset = j1;
34885 vinfos[1].indices[0] = _ij1[0];
34886 vinfos[1].indices[1] = _ij1[1];
34887 vinfos[1].maxsolutions = _nj1;
34888 vinfos[2].jointtype = 1;
34889 vinfos[2].foffset = j2;
34890 vinfos[2].indices[0] = _ij2[0];
34891 vinfos[2].indices[1] = _ij2[1];
34892 vinfos[2].maxsolutions = _nj2;
34893 vinfos[3].jointtype = 1;
34894 vinfos[3].foffset = j3;
34895 vinfos[3].indices[0] = _ij3[0];
34896 vinfos[3].indices[1] = _ij3[1];
34897 vinfos[3].maxsolutions = _nj3;
34898 vinfos[4].jointtype = 1;
34899 vinfos[4].foffset = j4;
34900 vinfos[4].indices[0] = _ij4[0];
34901 vinfos[4].indices[1] = _ij4[1];
34902 vinfos[4].maxsolutions = _nj4;
34903 vinfos[5].jointtype = 1;
34904 vinfos[5].foffset = j5;
34905 vinfos[5].indices[0] = _ij5[0];
34906 vinfos[5].indices[1] = _ij5[1];
34907 vinfos[5].maxsolutions = _nj5;
34908 vinfos[6].jointtype = 1;
34909 vinfos[6].foffset = j6;
34910 vinfos[6].indices[0] = _ij6[0];
34911 vinfos[6].indices[1] = _ij6[1];
34912 vinfos[6].maxsolutions = _nj6;
34913 std::vector<int> vfree(0);
34914 solutions.AddSolution(vinfos,vfree);
34915 }
34916 }
34917 }
34918 
34919 }
34920 
34921 }
34922 
34923 } else
34924 {
34925 {
34926 IkReal j4array[1], cj4array[1], sj4array[1];
34927 bool j4valid[1]={false};
34928 _nj4 = 1;
34929 IkReal x10816=((cj1)*(sj2));
34930 IkReal x10817=((cj6)*(r20));
34931 IkReal x10818=((sj1)*(sj3));
34932 IkReal x10819=((r21)*(sj6));
34933 IkReal x10820=((IkReal(1.00000000000000))*(cj5));
34934 IkReal x10821=((cj6)*(r21));
34935 IkReal x10822=((r20)*(sj6));
34936 IkReal x10823=((IkReal(1.00000000000000))*(r22)*(sj5));
34937 IkReal x10824=((cj1)*(cj2)*(cj3));
34938 if( IKabs(((gconst2)*(((((x10818)*(x10819)))+(((IkReal(-1.00000000000000))*(x10816)*(x10820)*(x10822)))+(((IkReal(-1.00000000000000))*(x10816)*(x10820)*(x10821)))+(((IkReal(-1.00000000000000))*(x10819)*(x10824)))+(((x10817)*(x10824)))+(((IkReal(-1.00000000000000))*(x10816)*(x10823)))+(((IkReal(-1.00000000000000))*(x10817)*(x10818))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x10818)*(x10820)*(x10822)))+(((cj5)*(x10821)*(x10824)))+(((IkReal(-1.00000000000000))*(x10816)*(x10819)))+(((r22)*(sj5)*(x10824)))+(((IkReal(-1.00000000000000))*(x10818)*(x10823)))+(((cj5)*(x10822)*(x10824)))+(((IkReal(-1.00000000000000))*(x10818)*(x10820)*(x10821)))+(((x10816)*(x10817))))))) < IKFAST_ATAN2_MAGTHRESH )
34939     continue;
34940 j4array[0]=IKatan2(((gconst2)*(((((x10818)*(x10819)))+(((IkReal(-1.00000000000000))*(x10816)*(x10820)*(x10822)))+(((IkReal(-1.00000000000000))*(x10816)*(x10820)*(x10821)))+(((IkReal(-1.00000000000000))*(x10819)*(x10824)))+(((x10817)*(x10824)))+(((IkReal(-1.00000000000000))*(x10816)*(x10823)))+(((IkReal(-1.00000000000000))*(x10817)*(x10818)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(x10818)*(x10820)*(x10822)))+(((cj5)*(x10821)*(x10824)))+(((IkReal(-1.00000000000000))*(x10816)*(x10819)))+(((r22)*(sj5)*(x10824)))+(((IkReal(-1.00000000000000))*(x10818)*(x10823)))+(((cj5)*(x10822)*(x10824)))+(((IkReal(-1.00000000000000))*(x10818)*(x10820)*(x10821)))+(((x10816)*(x10817)))))));
34941 sj4array[0]=IKsin(j4array[0]);
34942 cj4array[0]=IKcos(j4array[0]);
34943 if( j4array[0] > IKPI )
34944 {
34945     j4array[0]-=IK2PI;
34946 }
34947 else if( j4array[0] < -IKPI )
34948 {    j4array[0]+=IK2PI;
34949 }
34950 j4valid[0] = true;
34951 for(int ij4 = 0; ij4 < 1; ++ij4)
34952 {
34953 if( !j4valid[ij4] )
34954 {
34955     continue;
34956 }
34957 _ij4[0] = ij4; _ij4[1] = -1;
34958 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
34959 {
34960 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
34961 {
34962     j4valid[iij4]=false; _ij4[1] = iij4; break; 
34963 }
34964 }
34965 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
34966 {
34967 IkReal evalcond[6];
34968 IkReal x10825=IKsin(j4);
34969 IkReal x10826=IKcos(j4);
34970 IkReal x10827=((r00)*(sj6));
34971 IkReal x10828=((IkReal(1.00000000000000))*(r12));
34972 IkReal x10829=((IkReal(1.00000000000000))*(cj6));
34973 IkReal x10830=((cj6)*(r01));
34974 IkReal x10831=((IkReal(1.00000000000000))*(cj1));
34975 IkReal x10832=((cj2)*(cj3));
34976 IkReal x10833=((IkReal(1.00000000000000))*(sj1));
34977 IkReal x10834=((r11)*(sj6));
34978 IkReal x10835=((r01)*(sj6));
34979 IkReal x10836=((IkReal(1.00000000000000))*(cj5));
34980 IkReal x10837=((r10)*(sj6));
34981 IkReal x10838=((cj5)*(r11));
34982 IkReal x10839=((cj6)*(r00));
34983 IkReal x10840=((r21)*(sj6));
34984 IkReal x10841=((r02)*(sj5));
34985 IkReal x10842=((cj6)*(r10));
34986 IkReal x10843=((cj5)*(sj6));
34987 IkReal x10844=((cj5)*(r01));
34988 IkReal x10845=((sj5)*(x10825));
34989 IkReal x10846=((cj0)*(x10826));
34990 IkReal x10847=((cj0)*(x10825));
34991 IkReal x10848=((sj0)*(x10826));
34992 IkReal x10849=((sj0)*(x10825));
34993 IkReal x10850=((r20)*(x10826));
34994 IkReal x10851=((cj5)*(cj6)*(r21));
34995 IkReal x10852=((r20)*(x10825));
34996 IkReal x10853=((cj5)*(x10849));
34997 evalcond[0]=((((x10825)*(x10851)))+(((x10843)*(x10852)))+(((IkReal(-1.00000000000000))*(x10829)*(x10850)))+(((r22)*(x10845)))+(((x10826)*(x10840)))+(((IkReal(-1.00000000000000))*(sj2)*(x10831))));
34998 evalcond[1]=((((x10843)*(x10850)))+(((cj6)*(x10852)))+(((x10826)*(x10851)))+(((IkReal(-1.00000000000000))*(x10825)*(x10840)))+(((r22)*(sj5)*(x10826)))+(((cj1)*(x10832)))+(((IkReal(-1.00000000000000))*(sj3)*(x10833))));
34999 evalcond[2]=((((IkReal(-1.00000000000000))*(x10834)*(x10846)))+(((x10842)*(x10846)))+(((x10835)*(x10848)))+(((x10841)*(x10849)))+(((IkReal(-1.00000000000000))*(x10829)*(x10838)*(x10847)))+(((x10830)*(x10853)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x10829)*(x10848)))+(((IkReal(-1.00000000000000))*(x10836)*(x10837)*(x10847)))+(((x10827)*(x10853)))+(((IkReal(-1.00000000000000))*(cj0)*(x10828)*(x10845))));
35000 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x10829)*(x10847)))+(((IkReal(-1.00000000000000))*(x10829)*(x10838)*(x10846)))+(((x10839)*(x10849)))+(((cj5)*(x10830)*(x10848)))+(((IkReal(-1.00000000000000))*(x10836)*(x10837)*(x10846)))+(((x10834)*(x10847)))+(((cj3)*(sj2)))+(((IkReal(-1.00000000000000))*(x10835)*(x10849)))+(((x10841)*(x10848)))+(((cj5)*(x10827)*(x10848)))+(((IkReal(-1.00000000000000))*(sj5)*(x10828)*(x10846))));
35001 evalcond[4]=((((IkReal(-1.00000000000000))*(x10836)*(x10837)*(x10849)))+(((IkReal(-1.00000000000000))*(x10834)*(x10848)))+(((IkReal(-1.00000000000000))*(x10835)*(x10846)))+(((IkReal(-1.00000000000000))*(x10841)*(x10847)))+(((IkReal(-1.00000000000000))*(sj0)*(x10828)*(x10845)))+(((IkReal(-1.00000000000000))*(x10829)*(x10844)*(x10847)))+(((x10842)*(x10848)))+(((IkReal(-1.00000000000000))*(x10827)*(x10836)*(x10847)))+(((IkReal(-1.00000000000000))*(x10829)*(x10838)*(x10849)))+(((sj1)*(sj2)))+(((x10839)*(x10846))));
35002 evalcond[5]=((((x10834)*(x10849)))+(((IkReal(-1.00000000000000))*(x10829)*(x10838)*(x10848)))+(((IkReal(-1.00000000000000))*(x10836)*(x10837)*(x10848)))+(((IkReal(-1.00000000000000))*(r00)*(x10829)*(x10847)))+(((IkReal(-1.00000000000000))*(x10829)*(x10844)*(x10846)))+(((IkReal(-1.00000000000000))*(sj3)*(x10831)))+(((IkReal(-1.00000000000000))*(r10)*(x10829)*(x10849)))+(((IkReal(-1.00000000000000))*(x10832)*(x10833)))+(((IkReal(-1.00000000000000))*(x10827)*(x10836)*(x10846)))+(((IkReal(-1.00000000000000))*(sj5)*(x10828)*(x10848)))+(((IkReal(-1.00000000000000))*(x10841)*(x10846)))+(((x10835)*(x10847))));
35003 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
35004 {
35005 continue;
35006 }
35007 }
35008 
35009 {
35010 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35011 vinfos[0].jointtype = 1;
35012 vinfos[0].foffset = j0;
35013 vinfos[0].indices[0] = _ij0[0];
35014 vinfos[0].indices[1] = _ij0[1];
35015 vinfos[0].maxsolutions = _nj0;
35016 vinfos[1].jointtype = 1;
35017 vinfos[1].foffset = j1;
35018 vinfos[1].indices[0] = _ij1[0];
35019 vinfos[1].indices[1] = _ij1[1];
35020 vinfos[1].maxsolutions = _nj1;
35021 vinfos[2].jointtype = 1;
35022 vinfos[2].foffset = j2;
35023 vinfos[2].indices[0] = _ij2[0];
35024 vinfos[2].indices[1] = _ij2[1];
35025 vinfos[2].maxsolutions = _nj2;
35026 vinfos[3].jointtype = 1;
35027 vinfos[3].foffset = j3;
35028 vinfos[3].indices[0] = _ij3[0];
35029 vinfos[3].indices[1] = _ij3[1];
35030 vinfos[3].maxsolutions = _nj3;
35031 vinfos[4].jointtype = 1;
35032 vinfos[4].foffset = j4;
35033 vinfos[4].indices[0] = _ij4[0];
35034 vinfos[4].indices[1] = _ij4[1];
35035 vinfos[4].maxsolutions = _nj4;
35036 vinfos[5].jointtype = 1;
35037 vinfos[5].foffset = j5;
35038 vinfos[5].indices[0] = _ij5[0];
35039 vinfos[5].indices[1] = _ij5[1];
35040 vinfos[5].maxsolutions = _nj5;
35041 vinfos[6].jointtype = 1;
35042 vinfos[6].foffset = j6;
35043 vinfos[6].indices[0] = _ij6[0];
35044 vinfos[6].indices[1] = _ij6[1];
35045 vinfos[6].maxsolutions = _nj6;
35046 std::vector<int> vfree(0);
35047 solutions.AddSolution(vinfos,vfree);
35048 }
35049 }
35050 }
35051 
35052 }
35053 
35054 }
35055 }
35056 }
35057 
35058 }
35059 
35060 }
35061 
35062 } else
35063 {
35064 {
35065 IkReal j4array[1], cj4array[1], sj4array[1];
35066 bool j4valid[1]={false};
35067 _nj4 = 1;
35068 IkReal x10854=((cj0)*(r00));
35069 IkReal x10855=((r10)*(sj0));
35070 IkReal x10856=((cj0)*(r01));
35071 IkReal x10857=((IkReal(1.00000000000000))*(cj5));
35072 IkReal x10858=((r11)*(sj0));
35073 IkReal x10859=((sj2)*(sj5));
35074 IkReal x10860=((IkReal(1.00000000000000))*(cj1));
35075 IkReal x10861=((r20)*(sj1)*(sj2));
35076 IkReal x10862=((cj1)*(sj2)*(sj6));
35077 IkReal x10863=((r21)*(sj1)*(sj2));
35078 IkReal x10864=((cj6)*(sj2)*(x10860));
35079 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(sj6)*(x10863)))+(((x10858)*(x10862)))+(((IkReal(-1.00000000000000))*(x10854)*(x10864)))+(((x10856)*(x10862)))+(((cj6)*(x10861)))+(((IkReal(-1.00000000000000))*(x10855)*(x10864))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10859)*(x10860)))+(((IkReal(-1.00000000000000))*(x10854)*(x10857)*(x10862)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x10857)*(x10858)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x10856)*(x10857)))+(((cj5)*(sj6)*(x10861)))+(((r22)*(sj1)*(x10859)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10859)*(x10860)))+(((IkReal(-1.00000000000000))*(x10855)*(x10857)*(x10862)))+(((cj5)*(cj6)*(x10863))))))) < IKFAST_ATAN2_MAGTHRESH )
35080     continue;
35081 j4array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(sj6)*(x10863)))+(((x10858)*(x10862)))+(((IkReal(-1.00000000000000))*(x10854)*(x10864)))+(((x10856)*(x10862)))+(((cj6)*(x10861)))+(((IkReal(-1.00000000000000))*(x10855)*(x10864)))))), ((gconst1)*(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x10859)*(x10860)))+(((IkReal(-1.00000000000000))*(x10854)*(x10857)*(x10862)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x10857)*(x10858)))+(((IkReal(-1.00000000000000))*(cj1)*(cj6)*(sj2)*(x10856)*(x10857)))+(((cj5)*(sj6)*(x10861)))+(((r22)*(sj1)*(x10859)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x10859)*(x10860)))+(((IkReal(-1.00000000000000))*(x10855)*(x10857)*(x10862)))+(((cj5)*(cj6)*(x10863)))))));
35082 sj4array[0]=IKsin(j4array[0]);
35083 cj4array[0]=IKcos(j4array[0]);
35084 if( j4array[0] > IKPI )
35085 {
35086     j4array[0]-=IK2PI;
35087 }
35088 else if( j4array[0] < -IKPI )
35089 {    j4array[0]+=IK2PI;
35090 }
35091 j4valid[0] = true;
35092 for(int ij4 = 0; ij4 < 1; ++ij4)
35093 {
35094 if( !j4valid[ij4] )
35095 {
35096     continue;
35097 }
35098 _ij4[0] = ij4; _ij4[1] = -1;
35099 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
35100 {
35101 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
35102 {
35103     j4valid[iij4]=false; _ij4[1] = iij4; break; 
35104 }
35105 }
35106 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
35107 {
35108 IkReal evalcond[3];
35109 IkReal x10865=IKsin(j4);
35110 IkReal x10866=IKcos(j4);
35111 IkReal x10867=((r00)*(sj6));
35112 IkReal x10868=((cj6)*(r01));
35113 IkReal x10869=((IkReal(1.00000000000000))*(cj0));
35114 IkReal x10870=((IkReal(1.00000000000000))*(sj0));
35115 IkReal x10871=((r10)*(sj6));
35116 IkReal x10872=((sj5)*(x10865));
35117 IkReal x10873=((IkReal(1.00000000000000))*(cj6)*(r11));
35118 IkReal x10874=((cj5)*(x10865));
35119 IkReal x10875=((cj6)*(x10866));
35120 IkReal x10876=((sj0)*(x10874));
35121 IkReal x10877=((r01)*(sj6)*(x10866));
35122 IkReal x10878=((r11)*(sj6)*(x10866));
35123 evalcond[0]=((((IkReal(-1.00000000000000))*(r20)*(x10875)))+(((cj6)*(r21)*(x10874)))+(((IkReal(-1.00000000000000))*(cj1)*(sj2)))+(((r21)*(sj6)*(x10866)))+(((r20)*(sj6)*(x10874)))+(((r22)*(x10872))));
35124 evalcond[1]=((((IkReal(-1.00000000000000))*(x10869)*(x10878)))+(((cj0)*(r10)*(x10875)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10869)*(x10874)))+(((sj0)*(x10877)))+(((IkReal(-1.00000000000000))*(r12)*(x10869)*(x10872)))+(((x10868)*(x10876)))+(((IkReal(-1.00000000000000))*(x10869)*(x10871)*(x10874)))+(cj2)+(((r02)*(sj0)*(x10872)))+(((x10867)*(x10876)))+(((IkReal(-1.00000000000000))*(r00)*(x10870)*(x10875))));
35125 evalcond[2]=((((IkReal(-1.00000000000000))*(x10869)*(x10877)))+(((cj0)*(r00)*(x10875)))+(((IkReal(-1.00000000000000))*(r02)*(x10869)*(x10872)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x10870)*(x10874)))+(((IkReal(-1.00000000000000))*(x10870)*(x10878)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x10867)*(x10869)*(x10874)))+(((IkReal(-1.00000000000000))*(x10868)*(x10869)*(x10874)))+(((IkReal(-1.00000000000000))*(r12)*(x10870)*(x10872)))+(((IkReal(-1.00000000000000))*(x10870)*(x10871)*(x10874)))+(((r10)*(sj0)*(x10875))));
35126 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
35127 {
35128 continue;
35129 }
35130 }
35131 
35132 {
35133 IkReal dummyeval[1];
35134 IkReal gconst4;
35135 gconst4=IKsign((((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2))))));
35136 dummyeval[0]=(((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2)))));
35137 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35138 {
35139 {
35140 IkReal dummyeval[2];
35141 IkReal x10879=(cj1)*(cj1);
35142 IkReal x10880=(sj1)*(sj1);
35143 dummyeval[0]=((((cj2)*(x10880)))+(((cj2)*(x10879))));
35144 dummyeval[1]=((x10879)+(x10880));
35145 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
35146 {
35147 {
35148 IkReal dummyeval[2];
35149 dummyeval[0]=sj2;
35150 dummyeval[1]=sj1;
35151 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
35152 {
35153 {
35154 IkReal evalcond[9];
35155 IkReal x10881=((cj5)*(sj4));
35156 IkReal x10882=((IkReal(1.00000000000000))*(sj6));
35157 IkReal x10883=((r10)*(sj0));
35158 IkReal x10884=((sj4)*(sj5));
35159 IkReal x10885=((cj4)*(cj5));
35160 IkReal x10886=((IkReal(1.00000000000000))*(r02));
35161 IkReal x10887=((IkReal(0.374290000000000))*(cj0));
35162 IkReal x10888=((cj5)*(r12));
35163 IkReal x10889=((cj6)*(sj5));
35164 IkReal x10890=((cj0)*(r11));
35165 IkReal x10891=((cj5)*(sj0));
35166 IkReal x10892=((r20)*(sj6));
35167 IkReal x10893=((IkReal(1.00000000000000))*(sj0));
35168 IkReal x10894=((IkReal(1.00000000000000))*(cj6));
35169 IkReal x10895=((IkReal(0.0100000000000000))*(cj5));
35170 IkReal x10896=((IkReal(0.0100000000000000))*(sj5));
35171 IkReal x10897=((sj5)*(sj6));
35172 IkReal x10898=((cj0)*(r10));
35173 IkReal x10899=((cj4)*(cj6));
35174 IkReal x10900=((cj0)*(r01));
35175 IkReal x10901=((cj0)*(r00));
35176 IkReal x10902=((cj6)*(r21));
35177 IkReal x10903=((IkReal(0.374290000000000))*(sj0));
35178 IkReal x10904=((IkReal(0.374290000000000))*(sj5));
35179 IkReal x10905=((cj6)*(r11));
35180 IkReal x10906=((sj0)*(sj4));
35181 IkReal x10907=((cj4)*(sj5));
35182 IkReal x10908=((cj4)*(sj6));
35183 IkReal x10909=((IkReal(1.00000000000000))*(cj0));
35184 IkReal x10910=((r02)*(sj0));
35185 IkReal x10911=((r00)*(sj0)*(sj6));
35186 IkReal x10912=((cj6)*(r01)*(sj0));
35187 IkReal x10913=((r00)*(x10899));
35188 IkReal x10914=((r12)*(x10909));
35189 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
35190 evalcond[1]=((((r21)*(x10908)))+(((x10881)*(x10902)))+(((r22)*(x10884)))+(((x10881)*(x10892)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x10894))));
35191 evalcond[2]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(0.374290000000000))*(r21)*(x10889)))+(((IkReal(-1.00000000000000))*(r22)*(x10896)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x10892)*(x10904)))+(((IkReal(-1.00000000000000))*(x10892)*(x10895)))+(pz)+(((IkReal(-1.00000000000000))*(x10895)*(x10902)))+(((IkReal(0.0690000000000000))*(cj1))));
35192 evalcond[3]=((((IkReal(-1.00000000000000))*(x10886)*(x10891)))+(((r00)*(sj0)*(x10897)))+(((r01)*(sj0)*(x10889)))+(((IkReal(-1.00000000000000))*(x10889)*(x10890)))+(((IkReal(-1.00000000000000))*(sj5)*(x10882)*(x10898)))+(((cj0)*(x10888))));
35193 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x10881)*(x10890)*(x10894)))+(((x10898)*(x10899)))+(((IkReal(-1.00000000000000))*(x10884)*(x10914)))+(((x10881)*(x10911)))+(((r01)*(sj0)*(x10908)))+(((IkReal(-1.00000000000000))*(x10893)*(x10913)))+(((IkReal(-1.00000000000000))*(x10881)*(x10882)*(x10898)))+(((IkReal(-1.00000000000000))*(cj4)*(x10882)*(x10890)))+(((x10884)*(x10910)))+(((x10881)*(x10912))));
35194 evalcond[5]=((((IkReal(-1.00000000000000))*(x10882)*(x10885)*(x10898)))+(((IkReal(-1.00000000000000))*(x10885)*(x10890)*(x10894)))+(((sj4)*(sj6)*(x10890)))+(((IkReal(-1.00000000000000))*(sj4)*(x10894)*(x10898)))+(((IkReal(-1.00000000000000))*(r01)*(x10882)*(x10906)))+(((x10907)*(x10910)))+(((x10885)*(x10912)))+(((x10885)*(x10911)))+(((cj6)*(r00)*(x10906)))+(((IkReal(-1.00000000000000))*(x10907)*(x10914))));
35195 evalcond[6]=((((IkReal(-1.00000000000000))*(r12)*(x10884)*(x10893)))+(((IkReal(-1.00000000000000))*(x10881)*(x10893)*(x10905)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x10882)))+(((IkReal(-1.00000000000000))*(x10881)*(x10882)*(x10883)))+(((IkReal(-1.00000000000000))*(cj0)*(x10884)*(x10886)))+(((IkReal(-1.00000000000000))*(x10881)*(x10894)*(x10900)))+(((IkReal(-1.00000000000000))*(x10881)*(x10882)*(x10901)))+(((x10899)*(x10901)))+(((x10883)*(x10899)))+(((IkReal(-1.00000000000000))*(cj4)*(x10882)*(x10900))));
35196 evalcond[7]=((((IkReal(-0.374290000000000))*(r02)*(x10891)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x10891)))+(((IkReal(-1.00000000000000))*(x10896)*(x10910)))+(((IkReal(-1.00000000000000))*(r11)*(x10887)*(x10889)))+(((sj6)*(x10895)*(x10898)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x10891)))+(((IkReal(-1.00000000000000))*(py)*(x10909)))+(((r00)*(x10897)*(x10903)))+(((cj6)*(x10890)*(x10895)))+(((IkReal(-1.00000000000000))*(r10)*(x10887)*(x10897)))+(((x10887)*(x10888)))+(((r01)*(x10889)*(x10903)))+(((px)*(sj0)))+(((cj0)*(r12)*(x10896))));
35197 evalcond[8]=((IkReal(0.0690000000000000))+(((cj0)*(r02)*(x10896)))+(((IkReal(-0.0690000000000000))*(sj1)))+(((x10888)*(x10903)))+(((r12)*(sj0)*(x10896)))+(((IkReal(-1.00000000000000))*(py)*(x10893)))+(((IkReal(-0.374290000000000))*(x10883)*(x10897)))+(((IkReal(-1.00000000000000))*(r01)*(x10887)*(x10889)))+(((sj6)*(x10883)*(x10895)))+(((cj6)*(x10895)*(x10900)))+(((cj5)*(r02)*(x10887)))+(((IkReal(-1.00000000000000))*(px)*(x10909)))+(((IkReal(-1.00000000000000))*(r11)*(x10889)*(x10903)))+(((IkReal(0.0100000000000000))*(x10891)*(x10905)))+(((IkReal(-1.00000000000000))*(r00)*(x10887)*(x10897)))+(((sj6)*(x10895)*(x10901)))+(((IkReal(0.364420000000000))*(cj1))));
35198 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
35199 {
35200 {
35201 IkReal dummyeval[1];
35202 IkReal gconst5;
35203 gconst5=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
35204 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
35205 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35206 {
35207 {
35208 IkReal dummyeval[1];
35209 IkReal gconst6;
35210 gconst6=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
35211 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
35212 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35213 {
35214 continue;
35215 
35216 } else
35217 {
35218 {
35219 IkReal j3array[1], cj3array[1], sj3array[1];
35220 bool j3valid[1]={false};
35221 _nj3 = 1;
35222 IkReal x10915=((sj5)*(sj6));
35223 IkReal x10916=((IkReal(1.00000000000000))*(sj0));
35224 IkReal x10917=((cj5)*(r12));
35225 IkReal x10918=((cj0)*(r00));
35226 IkReal x10919=((cj0)*(cj1));
35227 IkReal x10920=((cj6)*(sj5));
35228 IkReal x10921=((cj5)*(r02));
35229 IkReal x10922=((IkReal(1.00000000000000))*(cj1));
35230 IkReal x10923=((sj0)*(sj1));
35231 IkReal x10924=((cj0)*(sj1));
35232 IkReal x10925=((cj5)*(r22));
35233 if( IKabs(((gconst6)*(((((r10)*(x10915)*(x10923)))+(((IkReal(-1.00000000000000))*(sj1)*(x10916)*(x10917)))+(((sj1)*(x10915)*(x10918)))+(((cj1)*(r21)*(x10920)))+(((r11)*(x10920)*(x10923)))+(((cj1)*(r20)*(x10915)))+(((IkReal(-1.00000000000000))*(x10921)*(x10924)))+(((IkReal(-1.00000000000000))*(x10922)*(x10925)))+(((r01)*(x10920)*(x10924))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((r21)*(sj1)*(x10920)))+(((x10919)*(x10921)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x10916)*(x10920)))+(((r20)*(sj1)*(x10915)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x10915)*(x10916)))+(((cj1)*(sj0)*(x10917)))+(((IkReal(-1.00000000000000))*(r01)*(x10919)*(x10920)))+(((IkReal(-1.00000000000000))*(sj1)*(x10925)))+(((IkReal(-1.00000000000000))*(x10915)*(x10918)*(x10922))))))) < IKFAST_ATAN2_MAGTHRESH )
35234     continue;
35235 j3array[0]=IKatan2(((gconst6)*(((((r10)*(x10915)*(x10923)))+(((IkReal(-1.00000000000000))*(sj1)*(x10916)*(x10917)))+(((sj1)*(x10915)*(x10918)))+(((cj1)*(r21)*(x10920)))+(((r11)*(x10920)*(x10923)))+(((cj1)*(r20)*(x10915)))+(((IkReal(-1.00000000000000))*(x10921)*(x10924)))+(((IkReal(-1.00000000000000))*(x10922)*(x10925)))+(((r01)*(x10920)*(x10924)))))), ((gconst6)*(((((r21)*(sj1)*(x10920)))+(((x10919)*(x10921)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x10916)*(x10920)))+(((r20)*(sj1)*(x10915)))+(((IkReal(-1.00000000000000))*(cj1)*(r10)*(x10915)*(x10916)))+(((cj1)*(sj0)*(x10917)))+(((IkReal(-1.00000000000000))*(r01)*(x10919)*(x10920)))+(((IkReal(-1.00000000000000))*(sj1)*(x10925)))+(((IkReal(-1.00000000000000))*(x10915)*(x10918)*(x10922)))))));
35236 sj3array[0]=IKsin(j3array[0]);
35237 cj3array[0]=IKcos(j3array[0]);
35238 if( j3array[0] > IKPI )
35239 {
35240     j3array[0]-=IK2PI;
35241 }
35242 else if( j3array[0] < -IKPI )
35243 {    j3array[0]+=IK2PI;
35244 }
35245 j3valid[0] = true;
35246 for(int ij3 = 0; ij3 < 1; ++ij3)
35247 {
35248 if( !j3valid[ij3] )
35249 {
35250     continue;
35251 }
35252 _ij3[0] = ij3; _ij3[1] = -1;
35253 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
35254 {
35255 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
35256 {
35257     j3valid[iij3]=false; _ij3[1] = iij3; break; 
35258 }
35259 }
35260 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
35261 {
35262 IkReal evalcond[4];
35263 IkReal x10926=IKcos(j3);
35264 IkReal x10927=IKsin(j3);
35265 IkReal x10928=((IkReal(1.00000000000000))*(cj4));
35266 IkReal x10929=((sj0)*(sj5));
35267 IkReal x10930=((cj0)*(cj5));
35268 IkReal x10931=((cj6)*(r01));
35269 IkReal x10932=((r00)*(sj6));
35270 IkReal x10933=((cj6)*(r11));
35271 IkReal x10934=((cj5)*(sj0));
35272 IkReal x10935=((cj6)*(sj4));
35273 IkReal x10936=((sj4)*(sj6));
35274 IkReal x10937=((cj4)*(cj5));
35275 IkReal x10938=((cj6)*(r21));
35276 IkReal x10939=((r20)*(sj6));
35277 IkReal x10940=((r10)*(sj6));
35278 IkReal x10941=((cj1)*(x10926));
35279 IkReal x10942=((IkReal(1.00000000000000))*(cj0)*(sj5));
35280 IkReal x10943=((IkReal(1.00000000000000))*(x10927));
35281 IkReal x10944=((IkReal(1.00000000000000))*(sj1)*(x10926));
35282 IkReal x10945=((cj1)*(x10943));
35283 IkReal x10946=((x10945)+(x10944));
35284 evalcond[0]=((((sj5)*(x10939)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x10946)))+(((sj5)*(x10938))));
35285 evalcond[1]=((x10941)+(((x10937)*(x10939)))+(((r20)*(x10935)))+(((IkReal(-1.00000000000000))*(sj1)*(x10943)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x10936)))+(((x10937)*(x10938))));
35286 evalcond[2]=((((r02)*(x10930)))+(((IkReal(-1.00000000000000))*(x10929)*(x10933)))+(((sj1)*(x10927)))+(((IkReal(-1.00000000000000))*(x10931)*(x10942)))+(((IkReal(-1.00000000000000))*(x10932)*(x10942)))+(((IkReal(-1.00000000000000))*(x10929)*(x10940)))+(((IkReal(-1.00000000000000))*(x10941)))+(((r12)*(x10934))));
35287 evalcond[3]=((((IkReal(-1.00000000000000))*(x10928)*(x10930)*(x10931)))+(((IkReal(-1.00000000000000))*(x10928)*(x10934)*(x10940)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x10928)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10935)))+(((cj0)*(r01)*(x10936)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x10935)))+(((IkReal(-1.00000000000000))*(x10946)))+(((IkReal(-1.00000000000000))*(x10928)*(x10930)*(x10932)))+(((IkReal(-1.00000000000000))*(x10928)*(x10933)*(x10934)))+(((r11)*(sj0)*(x10936)))+(((IkReal(-1.00000000000000))*(r12)*(x10928)*(x10929))));
35288 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
35289 {
35290 continue;
35291 }
35292 }
35293 
35294 {
35295 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35296 vinfos[0].jointtype = 1;
35297 vinfos[0].foffset = j0;
35298 vinfos[0].indices[0] = _ij0[0];
35299 vinfos[0].indices[1] = _ij0[1];
35300 vinfos[0].maxsolutions = _nj0;
35301 vinfos[1].jointtype = 1;
35302 vinfos[1].foffset = j1;
35303 vinfos[1].indices[0] = _ij1[0];
35304 vinfos[1].indices[1] = _ij1[1];
35305 vinfos[1].maxsolutions = _nj1;
35306 vinfos[2].jointtype = 1;
35307 vinfos[2].foffset = j2;
35308 vinfos[2].indices[0] = _ij2[0];
35309 vinfos[2].indices[1] = _ij2[1];
35310 vinfos[2].maxsolutions = _nj2;
35311 vinfos[3].jointtype = 1;
35312 vinfos[3].foffset = j3;
35313 vinfos[3].indices[0] = _ij3[0];
35314 vinfos[3].indices[1] = _ij3[1];
35315 vinfos[3].maxsolutions = _nj3;
35316 vinfos[4].jointtype = 1;
35317 vinfos[4].foffset = j4;
35318 vinfos[4].indices[0] = _ij4[0];
35319 vinfos[4].indices[1] = _ij4[1];
35320 vinfos[4].maxsolutions = _nj4;
35321 vinfos[5].jointtype = 1;
35322 vinfos[5].foffset = j5;
35323 vinfos[5].indices[0] = _ij5[0];
35324 vinfos[5].indices[1] = _ij5[1];
35325 vinfos[5].maxsolutions = _nj5;
35326 vinfos[6].jointtype = 1;
35327 vinfos[6].foffset = j6;
35328 vinfos[6].indices[0] = _ij6[0];
35329 vinfos[6].indices[1] = _ij6[1];
35330 vinfos[6].maxsolutions = _nj6;
35331 std::vector<int> vfree(0);
35332 solutions.AddSolution(vinfos,vfree);
35333 }
35334 }
35335 }
35336 
35337 }
35338 
35339 }
35340 
35341 } else
35342 {
35343 {
35344 IkReal j3array[1], cj3array[1], sj3array[1];
35345 bool j3valid[1]={false};
35346 _nj3 = 1;
35347 IkReal x10947=((sj1)*(sj5));
35348 IkReal x10948=((r20)*(sj6));
35349 IkReal x10949=((cj4)*(r22));
35350 IkReal x10950=((IkReal(1.00000000000000))*(cj1));
35351 IkReal x10951=((cj5)*(sj1));
35352 IkReal x10952=((cj6)*(r21));
35353 IkReal x10953=((cj1)*(sj5));
35354 IkReal x10954=((cj4)*(cj5));
35355 IkReal x10955=((cj6)*(r20)*(sj4));
35356 IkReal x10956=((r21)*(sj4)*(sj6));
35357 if( IKabs(((gconst5)*(((((x10952)*(x10953)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x10950)))+(((cj4)*(x10951)*(x10952)))+(((x10948)*(x10953)))+(((x10947)*(x10949)))+(((sj1)*(x10955)))+(((cj4)*(x10948)*(x10951)))+(((IkReal(-1.00000000000000))*(sj1)*(x10956))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(x10950)*(x10952)*(x10954)))+(((x10947)*(x10948)))+(((x10947)*(x10952)))+(((IkReal(-1.00000000000000))*(x10950)*(x10955)))+(((IkReal(-1.00000000000000))*(x10948)*(x10950)*(x10954)))+(((IkReal(-1.00000000000000))*(sj5)*(x10949)*(x10950)))+(((cj1)*(x10956)))+(((IkReal(-1.00000000000000))*(r22)*(x10951))))))) < IKFAST_ATAN2_MAGTHRESH )
35358     continue;
35359 j3array[0]=IKatan2(((gconst5)*(((((x10952)*(x10953)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x10950)))+(((cj4)*(x10951)*(x10952)))+(((x10948)*(x10953)))+(((x10947)*(x10949)))+(((sj1)*(x10955)))+(((cj4)*(x10948)*(x10951)))+(((IkReal(-1.00000000000000))*(sj1)*(x10956)))))), ((gconst5)*(((((IkReal(-1.00000000000000))*(x10950)*(x10952)*(x10954)))+(((x10947)*(x10948)))+(((x10947)*(x10952)))+(((IkReal(-1.00000000000000))*(x10950)*(x10955)))+(((IkReal(-1.00000000000000))*(x10948)*(x10950)*(x10954)))+(((IkReal(-1.00000000000000))*(sj5)*(x10949)*(x10950)))+(((cj1)*(x10956)))+(((IkReal(-1.00000000000000))*(r22)*(x10951)))))));
35360 sj3array[0]=IKsin(j3array[0]);
35361 cj3array[0]=IKcos(j3array[0]);
35362 if( j3array[0] > IKPI )
35363 {
35364     j3array[0]-=IK2PI;
35365 }
35366 else if( j3array[0] < -IKPI )
35367 {    j3array[0]+=IK2PI;
35368 }
35369 j3valid[0] = true;
35370 for(int ij3 = 0; ij3 < 1; ++ij3)
35371 {
35372 if( !j3valid[ij3] )
35373 {
35374     continue;
35375 }
35376 _ij3[0] = ij3; _ij3[1] = -1;
35377 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
35378 {
35379 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
35380 {
35381     j3valid[iij3]=false; _ij3[1] = iij3; break; 
35382 }
35383 }
35384 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
35385 {
35386 IkReal evalcond[4];
35387 IkReal x10957=IKcos(j3);
35388 IkReal x10958=IKsin(j3);
35389 IkReal x10959=((IkReal(1.00000000000000))*(cj4));
35390 IkReal x10960=((sj0)*(sj5));
35391 IkReal x10961=((cj0)*(cj5));
35392 IkReal x10962=((cj6)*(r01));
35393 IkReal x10963=((r00)*(sj6));
35394 IkReal x10964=((cj6)*(r11));
35395 IkReal x10965=((cj5)*(sj0));
35396 IkReal x10966=((cj6)*(sj4));
35397 IkReal x10967=((sj4)*(sj6));
35398 IkReal x10968=((cj4)*(cj5));
35399 IkReal x10969=((cj6)*(r21));
35400 IkReal x10970=((r20)*(sj6));
35401 IkReal x10971=((r10)*(sj6));
35402 IkReal x10972=((cj1)*(x10957));
35403 IkReal x10973=((IkReal(1.00000000000000))*(cj0)*(sj5));
35404 IkReal x10974=((IkReal(1.00000000000000))*(x10958));
35405 IkReal x10975=((IkReal(1.00000000000000))*(sj1)*(x10957));
35406 IkReal x10976=((cj1)*(x10974));
35407 IkReal x10977=((x10976)+(x10975));
35408 evalcond[0]=((((IkReal(-1.00000000000000))*(x10977)))+(((sj5)*(x10969)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x10970))));
35409 evalcond[1]=((((r20)*(x10966)))+(((x10968)*(x10969)))+(((IkReal(-1.00000000000000))*(sj1)*(x10974)))+(((x10968)*(x10970)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x10967)))+(x10972));
35410 evalcond[2]=((((IkReal(-1.00000000000000))*(x10972)))+(((r12)*(x10965)))+(((IkReal(-1.00000000000000))*(x10963)*(x10973)))+(((IkReal(-1.00000000000000))*(x10962)*(x10973)))+(((r02)*(x10961)))+(((IkReal(-1.00000000000000))*(x10960)*(x10964)))+(((sj1)*(x10958)))+(((IkReal(-1.00000000000000))*(x10960)*(x10971))));
35411 evalcond[3]=((((IkReal(-1.00000000000000))*(x10977)))+(((IkReal(-1.00000000000000))*(x10959)*(x10961)*(x10963)))+(((IkReal(-1.00000000000000))*(x10959)*(x10964)*(x10965)))+(((IkReal(-1.00000000000000))*(x10959)*(x10961)*(x10962)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x10966)))+(((r11)*(sj0)*(x10967)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x10966)))+(((IkReal(-1.00000000000000))*(r12)*(x10959)*(x10960)))+(((IkReal(-1.00000000000000))*(x10959)*(x10965)*(x10971)))+(((cj0)*(r01)*(x10967)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x10959))));
35412 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
35413 {
35414 continue;
35415 }
35416 }
35417 
35418 {
35419 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35420 vinfos[0].jointtype = 1;
35421 vinfos[0].foffset = j0;
35422 vinfos[0].indices[0] = _ij0[0];
35423 vinfos[0].indices[1] = _ij0[1];
35424 vinfos[0].maxsolutions = _nj0;
35425 vinfos[1].jointtype = 1;
35426 vinfos[1].foffset = j1;
35427 vinfos[1].indices[0] = _ij1[0];
35428 vinfos[1].indices[1] = _ij1[1];
35429 vinfos[1].maxsolutions = _nj1;
35430 vinfos[2].jointtype = 1;
35431 vinfos[2].foffset = j2;
35432 vinfos[2].indices[0] = _ij2[0];
35433 vinfos[2].indices[1] = _ij2[1];
35434 vinfos[2].maxsolutions = _nj2;
35435 vinfos[3].jointtype = 1;
35436 vinfos[3].foffset = j3;
35437 vinfos[3].indices[0] = _ij3[0];
35438 vinfos[3].indices[1] = _ij3[1];
35439 vinfos[3].maxsolutions = _nj3;
35440 vinfos[4].jointtype = 1;
35441 vinfos[4].foffset = j4;
35442 vinfos[4].indices[0] = _ij4[0];
35443 vinfos[4].indices[1] = _ij4[1];
35444 vinfos[4].maxsolutions = _nj4;
35445 vinfos[5].jointtype = 1;
35446 vinfos[5].foffset = j5;
35447 vinfos[5].indices[0] = _ij5[0];
35448 vinfos[5].indices[1] = _ij5[1];
35449 vinfos[5].maxsolutions = _nj5;
35450 vinfos[6].jointtype = 1;
35451 vinfos[6].foffset = j6;
35452 vinfos[6].indices[0] = _ij6[0];
35453 vinfos[6].indices[1] = _ij6[1];
35454 vinfos[6].maxsolutions = _nj6;
35455 std::vector<int> vfree(0);
35456 solutions.AddSolution(vinfos,vfree);
35457 }
35458 }
35459 }
35460 
35461 }
35462 
35463 }
35464 
35465 } else
35466 {
35467 IkReal x10978=((cj5)*(sj4));
35468 IkReal x10979=((IkReal(1.00000000000000))*(sj6));
35469 IkReal x10980=((r10)*(sj0));
35470 IkReal x10981=((sj4)*(sj5));
35471 IkReal x10982=((cj4)*(cj5));
35472 IkReal x10983=((IkReal(1.00000000000000))*(r02));
35473 IkReal x10984=((IkReal(0.374290000000000))*(cj0));
35474 IkReal x10985=((cj5)*(r12));
35475 IkReal x10986=((cj6)*(sj5));
35476 IkReal x10987=((cj0)*(r11));
35477 IkReal x10988=((cj5)*(sj0));
35478 IkReal x10989=((r20)*(sj6));
35479 IkReal x10990=((IkReal(1.00000000000000))*(sj0));
35480 IkReal x10991=((IkReal(1.00000000000000))*(cj6));
35481 IkReal x10992=((IkReal(0.0100000000000000))*(cj5));
35482 IkReal x10993=((IkReal(0.0100000000000000))*(sj5));
35483 IkReal x10994=((sj5)*(sj6));
35484 IkReal x10995=((cj0)*(r10));
35485 IkReal x10996=((cj4)*(cj6));
35486 IkReal x10997=((cj0)*(r01));
35487 IkReal x10998=((cj0)*(r00));
35488 IkReal x10999=((cj6)*(r21));
35489 IkReal x11000=((IkReal(0.374290000000000))*(sj0));
35490 IkReal x11001=((IkReal(0.374290000000000))*(sj5));
35491 IkReal x11002=((cj6)*(r11));
35492 IkReal x11003=((sj0)*(sj4));
35493 IkReal x11004=((cj4)*(sj5));
35494 IkReal x11005=((cj4)*(sj6));
35495 IkReal x11006=((IkReal(1.00000000000000))*(cj0));
35496 IkReal x11007=((r02)*(sj0));
35497 IkReal x11008=((r00)*(sj0)*(sj6));
35498 IkReal x11009=((cj6)*(r01)*(sj0));
35499 IkReal x11010=((r00)*(x10996));
35500 IkReal x11011=((r12)*(x11006));
35501 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
35502 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(r20)*(x10991)))+(((x10978)*(x10989)))+(((r21)*(x11005)))+(((r22)*(x10981)))+(((x10978)*(x10999))));
35503 evalcond[2]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.0690000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(r22)*(x10993)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(0.374290000000000))*(r21)*(x10986)))+(((IkReal(-1.00000000000000))*(x10992)*(x10999)))+(((x10989)*(x11001)))+(((IkReal(-1.00000000000000))*(x10989)*(x10992))));
35504 evalcond[3]=((((cj0)*(x10985)))+(((r01)*(sj0)*(x10986)))+(((r00)*(sj0)*(x10994)))+(((IkReal(-1.00000000000000))*(sj5)*(x10979)*(x10995)))+(((IkReal(-1.00000000000000))*(x10986)*(x10987)))+(((IkReal(-1.00000000000000))*(x10983)*(x10988))));
35505 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(x10979)*(x10987)))+(((x10981)*(x11007)))+(((IkReal(-1.00000000000000))*(x10981)*(x11011)))+(((x10995)*(x10996)))+(((IkReal(-1.00000000000000))*(x10990)*(x11010)))+(((x10978)*(x11008)))+(((r01)*(sj0)*(x11005)))+(((x10978)*(x11009)))+(((IkReal(-1.00000000000000))*(x10978)*(x10987)*(x10991)))+(((IkReal(-1.00000000000000))*(x10978)*(x10979)*(x10995))));
35506 evalcond[5]=((((IkReal(-1.00000000000000))*(x11004)*(x11011)))+(((x10982)*(x11008)))+(((IkReal(-1.00000000000000))*(r01)*(x10979)*(x11003)))+(((IkReal(-1.00000000000000))*(x10982)*(x10987)*(x10991)))+(((IkReal(-1.00000000000000))*(sj4)*(x10991)*(x10995)))+(((sj4)*(sj6)*(x10987)))+(((x10982)*(x11009)))+(((x11004)*(x11007)))+(((cj6)*(r00)*(x11003)))+(((IkReal(-1.00000000000000))*(x10979)*(x10982)*(x10995))));
35507 evalcond[6]=((((x10996)*(x10998)))+(((IkReal(-1.00000000000000))*(x10978)*(x10991)*(x10997)))+(((IkReal(-1.00000000000000))*(x10978)*(x10979)*(x10980)))+(((IkReal(-1.00000000000000))*(cj0)*(x10981)*(x10983)))+(((IkReal(-1.00000000000000))*(x10978)*(x10990)*(x11002)))+(((IkReal(-1.00000000000000))*(cj4)*(x10979)*(x10997)))+(((x10980)*(x10996)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x10979)))+(((IkReal(-1.00000000000000))*(r12)*(x10981)*(x10990)))+(((IkReal(-1.00000000000000))*(x10978)*(x10979)*(x10998))));
35508 evalcond[7]=((((IkReal(-0.374290000000000))*(r02)*(x10988)))+(((r00)*(x10994)*(x11000)))+(((IkReal(-1.00000000000000))*(x10993)*(x11007)))+(((cj6)*(x10987)*(x10992)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x10988)))+(((r01)*(x10986)*(x11000)))+(((IkReal(-1.00000000000000))*(r11)*(x10984)*(x10986)))+(((x10984)*(x10985)))+(((sj6)*(x10992)*(x10995)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x10988)))+(((cj0)*(r12)*(x10993)))+(((IkReal(-1.00000000000000))*(r10)*(x10984)*(x10994)))+(((IkReal(-1.00000000000000))*(py)*(x11006))));
35509 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x10984)*(x10986)))+(((IkReal(-1.00000000000000))*(px)*(x11006)))+(((IkReal(0.0100000000000000))*(x10988)*(x11002)))+(((IkReal(-1.00000000000000))*(r00)*(x10984)*(x10994)))+(((IkReal(0.0690000000000000))*(sj1)))+(((cj0)*(r02)*(x10993)))+(((cj6)*(x10992)*(x10997)))+(((IkReal(-1.00000000000000))*(py)*(x10990)))+(((sj6)*(x10980)*(x10992)))+(((r12)*(sj0)*(x10993)))+(((cj5)*(r02)*(x10984)))+(((IkReal(-0.374290000000000))*(x10980)*(x10994)))+(((x10985)*(x11000)))+(((sj6)*(x10992)*(x10998)))+(((IkReal(-1.00000000000000))*(r11)*(x10986)*(x11000)))+(((IkReal(0.364420000000000))*(cj1))));
35510 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
35511 {
35512 {
35513 IkReal dummyeval[1];
35514 IkReal gconst7;
35515 gconst7=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
35516 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
35517 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35518 {
35519 {
35520 IkReal dummyeval[1];
35521 IkReal gconst8;
35522 gconst8=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
35523 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
35524 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35525 {
35526 continue;
35527 
35528 } else
35529 {
35530 {
35531 IkReal j3array[1], cj3array[1], sj3array[1];
35532 bool j3valid[1]={false};
35533 _nj3 = 1;
35534 IkReal x11012=((IkReal(1.00000000000000))*(sj0));
35535 IkReal x11013=((cj6)*(r21));
35536 IkReal x11014=((cj0)*(r00));
35537 IkReal x11015=((cj5)*(sj1));
35538 IkReal x11016=((r12)*(sj0));
35539 IkReal x11017=((cj1)*(cj5));
35540 IkReal x11018=((cj0)*(r02));
35541 IkReal x11019=((sj1)*(sj5));
35542 IkReal x11020=((cj6)*(r11));
35543 IkReal x11021=((cj1)*(sj5));
35544 IkReal x11022=((sj6)*(x11019));
35545 IkReal x11023=((IkReal(1.00000000000000))*(x11021));
35546 IkReal x11024=((cj0)*(cj6)*(r01));
35547 if( IKabs(((gconst8)*(((((IkReal(-1.00000000000000))*(r20)*(sj6)*(x11023)))+(((IkReal(-1.00000000000000))*(x11019)*(x11024)))+(((x11015)*(x11018)))+(((IkReal(-1.00000000000000))*(x11014)*(x11022)))+(((IkReal(-1.00000000000000))*(x11013)*(x11023)))+(((IkReal(-1.00000000000000))*(r10)*(x11012)*(x11022)))+(((IkReal(-1.00000000000000))*(x11012)*(x11019)*(x11020)))+(((r22)*(x11017)))+(((x11015)*(x11016))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((IkReal(-1.00000000000000))*(x11012)*(x11020)*(x11021)))+(((x11016)*(x11017)))+(((r20)*(x11022)))+(((IkReal(-1.00000000000000))*(sj6)*(x11014)*(x11023)))+(((x11013)*(x11019)))+(((x11017)*(x11018)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11012)*(x11021)))+(((IkReal(-1.00000000000000))*(r22)*(x11015)))+(((IkReal(-1.00000000000000))*(x11023)*(x11024))))))) < IKFAST_ATAN2_MAGTHRESH )
35548     continue;
35549 j3array[0]=IKatan2(((gconst8)*(((((IkReal(-1.00000000000000))*(r20)*(sj6)*(x11023)))+(((IkReal(-1.00000000000000))*(x11019)*(x11024)))+(((x11015)*(x11018)))+(((IkReal(-1.00000000000000))*(x11014)*(x11022)))+(((IkReal(-1.00000000000000))*(x11013)*(x11023)))+(((IkReal(-1.00000000000000))*(r10)*(x11012)*(x11022)))+(((IkReal(-1.00000000000000))*(x11012)*(x11019)*(x11020)))+(((r22)*(x11017)))+(((x11015)*(x11016)))))), ((gconst8)*(((((IkReal(-1.00000000000000))*(x11012)*(x11020)*(x11021)))+(((x11016)*(x11017)))+(((r20)*(x11022)))+(((IkReal(-1.00000000000000))*(sj6)*(x11014)*(x11023)))+(((x11013)*(x11019)))+(((x11017)*(x11018)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11012)*(x11021)))+(((IkReal(-1.00000000000000))*(r22)*(x11015)))+(((IkReal(-1.00000000000000))*(x11023)*(x11024)))))));
35550 sj3array[0]=IKsin(j3array[0]);
35551 cj3array[0]=IKcos(j3array[0]);
35552 if( j3array[0] > IKPI )
35553 {
35554     j3array[0]-=IK2PI;
35555 }
35556 else if( j3array[0] < -IKPI )
35557 {    j3array[0]+=IK2PI;
35558 }
35559 j3valid[0] = true;
35560 for(int ij3 = 0; ij3 < 1; ++ij3)
35561 {
35562 if( !j3valid[ij3] )
35563 {
35564     continue;
35565 }
35566 _ij3[0] = ij3; _ij3[1] = -1;
35567 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
35568 {
35569 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
35570 {
35571     j3valid[iij3]=false; _ij3[1] = iij3; break; 
35572 }
35573 }
35574 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
35575 {
35576 IkReal evalcond[4];
35577 IkReal x11025=IKsin(j3);
35578 IkReal x11026=IKcos(j3);
35579 IkReal x11027=((IkReal(1.00000000000000))*(cj4));
35580 IkReal x11028=((sj0)*(sj5));
35581 IkReal x11029=((cj0)*(cj5));
35582 IkReal x11030=((cj6)*(r01));
35583 IkReal x11031=((r00)*(sj6));
35584 IkReal x11032=((cj6)*(r11));
35585 IkReal x11033=((cj5)*(sj0));
35586 IkReal x11034=((cj6)*(sj4));
35587 IkReal x11035=((sj4)*(sj6));
35588 IkReal x11036=((cj4)*(cj5));
35589 IkReal x11037=((cj6)*(r21));
35590 IkReal x11038=((r20)*(sj6));
35591 IkReal x11039=((r10)*(sj6));
35592 IkReal x11040=((cj1)*(x11025));
35593 IkReal x11041=((IkReal(1.00000000000000))*(cj0)*(sj5));
35594 IkReal x11042=((IkReal(1.00000000000000))*(x11026));
35595 IkReal x11043=((IkReal(1.00000000000000))*(sj1)*(x11025));
35596 IkReal x11044=((cj1)*(x11042));
35597 IkReal x11045=((x11044)+(x11043));
35598 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x11042)))+(((sj5)*(x11037)))+(((sj5)*(x11038)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x11040));
35599 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x11035)))+(((r20)*(x11034)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x11045)))+(((x11036)*(x11037)))+(((x11036)*(x11038))));
35600 evalcond[2]=((((IkReal(-1.00000000000000))*(x11028)*(x11039)))+(((r02)*(x11029)))+(((IkReal(-1.00000000000000))*(x11028)*(x11032)))+(((r12)*(x11033)))+(((IkReal(-1.00000000000000))*(x11045)))+(((IkReal(-1.00000000000000))*(x11031)*(x11041)))+(((IkReal(-1.00000000000000))*(x11030)*(x11041))));
35601 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x11027)*(x11028)))+(((sj1)*(x11026)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11034)))+(((IkReal(-1.00000000000000))*(x11027)*(x11029)*(x11030)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11034)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11027)))+(((IkReal(-1.00000000000000))*(x11027)*(x11032)*(x11033)))+(((IkReal(-1.00000000000000))*(x11040)))+(((IkReal(-1.00000000000000))*(x11027)*(x11033)*(x11039)))+(((IkReal(-1.00000000000000))*(x11027)*(x11029)*(x11031)))+(((r11)*(sj0)*(x11035)))+(((cj0)*(r01)*(x11035))));
35602 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
35603 {
35604 continue;
35605 }
35606 }
35607 
35608 {
35609 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35610 vinfos[0].jointtype = 1;
35611 vinfos[0].foffset = j0;
35612 vinfos[0].indices[0] = _ij0[0];
35613 vinfos[0].indices[1] = _ij0[1];
35614 vinfos[0].maxsolutions = _nj0;
35615 vinfos[1].jointtype = 1;
35616 vinfos[1].foffset = j1;
35617 vinfos[1].indices[0] = _ij1[0];
35618 vinfos[1].indices[1] = _ij1[1];
35619 vinfos[1].maxsolutions = _nj1;
35620 vinfos[2].jointtype = 1;
35621 vinfos[2].foffset = j2;
35622 vinfos[2].indices[0] = _ij2[0];
35623 vinfos[2].indices[1] = _ij2[1];
35624 vinfos[2].maxsolutions = _nj2;
35625 vinfos[3].jointtype = 1;
35626 vinfos[3].foffset = j3;
35627 vinfos[3].indices[0] = _ij3[0];
35628 vinfos[3].indices[1] = _ij3[1];
35629 vinfos[3].maxsolutions = _nj3;
35630 vinfos[4].jointtype = 1;
35631 vinfos[4].foffset = j4;
35632 vinfos[4].indices[0] = _ij4[0];
35633 vinfos[4].indices[1] = _ij4[1];
35634 vinfos[4].maxsolutions = _nj4;
35635 vinfos[5].jointtype = 1;
35636 vinfos[5].foffset = j5;
35637 vinfos[5].indices[0] = _ij5[0];
35638 vinfos[5].indices[1] = _ij5[1];
35639 vinfos[5].maxsolutions = _nj5;
35640 vinfos[6].jointtype = 1;
35641 vinfos[6].foffset = j6;
35642 vinfos[6].indices[0] = _ij6[0];
35643 vinfos[6].indices[1] = _ij6[1];
35644 vinfos[6].maxsolutions = _nj6;
35645 std::vector<int> vfree(0);
35646 solutions.AddSolution(vinfos,vfree);
35647 }
35648 }
35649 }
35650 
35651 }
35652 
35653 }
35654 
35655 } else
35656 {
35657 {
35658 IkReal j3array[1], cj3array[1], sj3array[1];
35659 bool j3valid[1]={false};
35660 _nj3 = 1;
35661 IkReal x11046=((sj1)*(sj6));
35662 IkReal x11047=((r20)*(sj5));
35663 IkReal x11048=((IkReal(1.00000000000000))*(r21));
35664 IkReal x11049=((cj1)*(cj6));
35665 IkReal x11050=((r20)*(sj4));
35666 IkReal x11051=((cj6)*(sj1));
35667 IkReal x11052=((cj4)*(cj5));
35668 IkReal x11053=((cj1)*(sj6));
35669 IkReal x11054=((cj5)*(r22));
35670 IkReal x11055=((cj4)*(r22)*(sj5));
35671 if( IKabs(((gconst7)*(((((r20)*(x11046)*(x11052)))+(((sj1)*(x11055)))+(((r21)*(x11051)*(x11052)))+(((IkReal(-1.00000000000000))*(sj4)*(x11046)*(x11048)))+(((IkReal(-1.00000000000000))*(sj5)*(x11048)*(x11049)))+(((cj1)*(x11054)))+(((x11050)*(x11051)))+(((IkReal(-1.00000000000000))*(x11047)*(x11053))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((r21)*(x11049)*(x11052)))+(((x11049)*(x11050)))+(((x11046)*(x11047)))+(((cj1)*(x11055)))+(((r21)*(sj5)*(x11051)))+(((IkReal(-1.00000000000000))*(sj1)*(x11054)))+(((IkReal(-1.00000000000000))*(sj4)*(x11048)*(x11053)))+(((r20)*(x11052)*(x11053))))))) < IKFAST_ATAN2_MAGTHRESH )
35672     continue;
35673 j3array[0]=IKatan2(((gconst7)*(((((r20)*(x11046)*(x11052)))+(((sj1)*(x11055)))+(((r21)*(x11051)*(x11052)))+(((IkReal(-1.00000000000000))*(sj4)*(x11046)*(x11048)))+(((IkReal(-1.00000000000000))*(sj5)*(x11048)*(x11049)))+(((cj1)*(x11054)))+(((x11050)*(x11051)))+(((IkReal(-1.00000000000000))*(x11047)*(x11053)))))), ((gconst7)*(((((r21)*(x11049)*(x11052)))+(((x11049)*(x11050)))+(((x11046)*(x11047)))+(((cj1)*(x11055)))+(((r21)*(sj5)*(x11051)))+(((IkReal(-1.00000000000000))*(sj1)*(x11054)))+(((IkReal(-1.00000000000000))*(sj4)*(x11048)*(x11053)))+(((r20)*(x11052)*(x11053)))))));
35674 sj3array[0]=IKsin(j3array[0]);
35675 cj3array[0]=IKcos(j3array[0]);
35676 if( j3array[0] > IKPI )
35677 {
35678     j3array[0]-=IK2PI;
35679 }
35680 else if( j3array[0] < -IKPI )
35681 {    j3array[0]+=IK2PI;
35682 }
35683 j3valid[0] = true;
35684 for(int ij3 = 0; ij3 < 1; ++ij3)
35685 {
35686 if( !j3valid[ij3] )
35687 {
35688     continue;
35689 }
35690 _ij3[0] = ij3; _ij3[1] = -1;
35691 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
35692 {
35693 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
35694 {
35695     j3valid[iij3]=false; _ij3[1] = iij3; break; 
35696 }
35697 }
35698 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
35699 {
35700 IkReal evalcond[4];
35701 IkReal x11056=IKsin(j3);
35702 IkReal x11057=IKcos(j3);
35703 IkReal x11058=((IkReal(1.00000000000000))*(cj4));
35704 IkReal x11059=((sj0)*(sj5));
35705 IkReal x11060=((cj0)*(cj5));
35706 IkReal x11061=((cj6)*(r01));
35707 IkReal x11062=((r00)*(sj6));
35708 IkReal x11063=((cj6)*(r11));
35709 IkReal x11064=((cj5)*(sj0));
35710 IkReal x11065=((cj6)*(sj4));
35711 IkReal x11066=((sj4)*(sj6));
35712 IkReal x11067=((cj4)*(cj5));
35713 IkReal x11068=((cj6)*(r21));
35714 IkReal x11069=((r20)*(sj6));
35715 IkReal x11070=((r10)*(sj6));
35716 IkReal x11071=((cj1)*(x11056));
35717 IkReal x11072=((IkReal(1.00000000000000))*(cj0)*(sj5));
35718 IkReal x11073=((IkReal(1.00000000000000))*(x11057));
35719 IkReal x11074=((IkReal(1.00000000000000))*(sj1)*(x11056));
35720 IkReal x11075=((cj1)*(x11073));
35721 IkReal x11076=((x11074)+(x11075));
35722 evalcond[0]=((x11071)+(((sj5)*(x11068)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11069)))+(((IkReal(-1.00000000000000))*(sj1)*(x11073))));
35723 evalcond[1]=((((x11067)*(x11069)))+(((IkReal(-1.00000000000000))*(x11076)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x11065)))+(((x11067)*(x11068)))+(((IkReal(-1.00000000000000))*(r21)*(x11066))));
35724 evalcond[2]=((((IkReal(-1.00000000000000))*(x11061)*(x11072)))+(((IkReal(-1.00000000000000))*(x11062)*(x11072)))+(((IkReal(-1.00000000000000))*(x11059)*(x11063)))+(((IkReal(-1.00000000000000))*(x11076)))+(((r02)*(x11060)))+(((IkReal(-1.00000000000000))*(x11059)*(x11070)))+(((r12)*(x11064))));
35725 evalcond[3]=((((IkReal(-1.00000000000000))*(x11058)*(x11063)*(x11064)))+(((IkReal(-1.00000000000000))*(x11058)*(x11064)*(x11070)))+(((cj0)*(r01)*(x11066)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11065)))+(((r11)*(sj0)*(x11066)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11058)))+(((IkReal(-1.00000000000000))*(x11058)*(x11060)*(x11062)))+(((IkReal(-1.00000000000000))*(x11058)*(x11060)*(x11061)))+(((IkReal(-1.00000000000000))*(r12)*(x11058)*(x11059)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11065)))+(((sj1)*(x11057)))+(((IkReal(-1.00000000000000))*(x11071))));
35726 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
35727 {
35728 continue;
35729 }
35730 }
35731 
35732 {
35733 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35734 vinfos[0].jointtype = 1;
35735 vinfos[0].foffset = j0;
35736 vinfos[0].indices[0] = _ij0[0];
35737 vinfos[0].indices[1] = _ij0[1];
35738 vinfos[0].maxsolutions = _nj0;
35739 vinfos[1].jointtype = 1;
35740 vinfos[1].foffset = j1;
35741 vinfos[1].indices[0] = _ij1[0];
35742 vinfos[1].indices[1] = _ij1[1];
35743 vinfos[1].maxsolutions = _nj1;
35744 vinfos[2].jointtype = 1;
35745 vinfos[2].foffset = j2;
35746 vinfos[2].indices[0] = _ij2[0];
35747 vinfos[2].indices[1] = _ij2[1];
35748 vinfos[2].maxsolutions = _nj2;
35749 vinfos[3].jointtype = 1;
35750 vinfos[3].foffset = j3;
35751 vinfos[3].indices[0] = _ij3[0];
35752 vinfos[3].indices[1] = _ij3[1];
35753 vinfos[3].maxsolutions = _nj3;
35754 vinfos[4].jointtype = 1;
35755 vinfos[4].foffset = j4;
35756 vinfos[4].indices[0] = _ij4[0];
35757 vinfos[4].indices[1] = _ij4[1];
35758 vinfos[4].maxsolutions = _nj4;
35759 vinfos[5].jointtype = 1;
35760 vinfos[5].foffset = j5;
35761 vinfos[5].indices[0] = _ij5[0];
35762 vinfos[5].indices[1] = _ij5[1];
35763 vinfos[5].maxsolutions = _nj5;
35764 vinfos[6].jointtype = 1;
35765 vinfos[6].foffset = j6;
35766 vinfos[6].indices[0] = _ij6[0];
35767 vinfos[6].indices[1] = _ij6[1];
35768 vinfos[6].maxsolutions = _nj6;
35769 std::vector<int> vfree(0);
35770 solutions.AddSolution(vinfos,vfree);
35771 }
35772 }
35773 }
35774 
35775 }
35776 
35777 }
35778 
35779 } else
35780 {
35781 IkReal x11077=((IkReal(1.00000000000000))*(cj0));
35782 IkReal x11078=((cj4)*(sj6));
35783 IkReal x11079=((sj0)*(sj4));
35784 IkReal x11080=((cj5)*(sj6));
35785 IkReal x11081=((sj4)*(sj5));
35786 IkReal x11082=((r12)*(sj5));
35787 IkReal x11083=((IkReal(0.374290000000000))*(cj5));
35788 IkReal x11084=((r02)*(sj0));
35789 IkReal x11085=((cj6)*(r21));
35790 IkReal x11086=((IkReal(0.0100000000000000))*(cj5));
35791 IkReal x11087=((IkReal(1.00000000000000))*(sj0));
35792 IkReal x11088=((cj0)*(r10));
35793 IkReal x11089=((cj4)*(cj6));
35794 IkReal x11090=((r00)*(sj0));
35795 IkReal x11091=((IkReal(0.374290000000000))*(sj5));
35796 IkReal x11092=((cj0)*(r00));
35797 IkReal x11093=((IkReal(0.0100000000000000))*(sj5));
35798 IkReal x11094=((cj0)*(r02));
35799 IkReal x11095=((cj5)*(sj4));
35800 IkReal x11096=((cj6)*(r01));
35801 IkReal x11097=((cj6)*(r11));
35802 IkReal x11098=((r10)*(sj0));
35803 IkReal x11099=((sj6)*(x11091));
35804 IkReal x11100=((cj0)*(cj6)*(x11091));
35805 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
35806 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)))+(((r21)*(x11078)))+(((r22)*(x11081)))+(((r20)*(sj4)*(x11080)))+(((x11085)*(x11095)))+(((IkReal(-1.00000000000000))*(r20)*(x11089))));
35807 evalcond[2]=((((r20)*(x11099)))+(((IkReal(-1.00000000000000))*(r22)*(x11083)))+(((IkReal(-0.0100000000000000))*(r20)*(x11080)))+(pz)+(((IkReal(0.0690000000000000))*(cj2)))+(((x11085)*(x11091)))+(((IkReal(-1.00000000000000))*(r22)*(x11093)))+(((IkReal(-1.00000000000000))*(x11085)*(x11086))));
35808 evalcond[3]=((((cj5)*(x11079)*(x11096)))+(((IkReal(-1.00000000000000))*(r12)*(x11077)*(x11081)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11077)*(x11080)))+(((r02)*(sj5)*(x11079)))+(((IkReal(-1.00000000000000))*(r11)*(x11077)*(x11078)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x11087)*(x11089)))+(((r01)*(sj0)*(x11078)))+(((r00)*(x11079)*(x11080)))+(((IkReal(-1.00000000000000))*(x11077)*(x11095)*(x11097)))+(((x11088)*(x11089))));
35809 evalcond[4]=((((IkReal(-1.00000000000000))*(x11077)*(x11095)*(x11096)))+(((IkReal(-1.00000000000000))*(r11)*(x11078)*(x11087)))+(((IkReal(-1.00000000000000))*(r10)*(x11079)*(x11080)))+(((IkReal(-1.00000000000000))*(r02)*(x11077)*(x11081)))+(((x11089)*(x11098)))+(((x11089)*(x11092)))+(((IkReal(-1.00000000000000))*(x11079)*(x11082)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11077)*(x11080)))+(((IkReal(-1.00000000000000))*(r01)*(x11077)*(x11078)))+(((IkReal(-1.00000000000000))*(cj5)*(x11079)*(x11097))));
35810 evalcond[5]=((((cj0)*(x11086)*(x11097)))+(((IkReal(-1.00000000000000))*(x11083)*(x11084)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(0.0100000000000000))*(cj0)*(x11082)))+(((IkReal(-1.00000000000000))*(sj0)*(x11086)*(x11096)))+(((cj0)*(r12)*(x11083)))+(((IkReal(-1.00000000000000))*(x11084)*(x11093)))+(((IkReal(-1.00000000000000))*(x11088)*(x11099)))+(((IkReal(-1.00000000000000))*(cj0)*(x11091)*(x11097)))+(((IkReal(0.0100000000000000))*(x11080)*(x11088)))+(((x11090)*(x11099)))+(((IkReal(-0.0100000000000000))*(x11080)*(x11090)))+(((px)*(sj0)))+(((sj0)*(x11091)*(x11096)))+(((IkReal(-1.00000000000000))*(py)*(x11077))));
35811 evalcond[6]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(py)*(x11087)))+(((IkReal(-1.00000000000000))*(x11092)*(x11099)))+(((sj0)*(x11086)*(x11097)))+(((r12)*(sj0)*(x11083)))+(((x11083)*(x11094)))+(((x11093)*(x11094)))+(((IkReal(-1.00000000000000))*(px)*(x11077)))+(((IkReal(-1.00000000000000))*(sj0)*(x11091)*(x11097)))+(((IkReal(0.0100000000000000))*(x11080)*(x11098)))+(((IkReal(0.0100000000000000))*(sj0)*(x11082)))+(((cj0)*(x11086)*(x11096)))+(((IkReal(-1.00000000000000))*(cj0)*(x11091)*(x11096)))+(((IkReal(-1.00000000000000))*(x11098)*(x11099)))+(((IkReal(0.0100000000000000))*(x11080)*(x11092))));
35812 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
35813 {
35814 {
35815 IkReal dummyeval[1];
35816 IkReal gconst9;
35817 gconst9=IKsign(cj2);
35818 dummyeval[0]=cj2;
35819 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35820 {
35821 {
35822 IkReal dummyeval[1];
35823 dummyeval[0]=cj2;
35824 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35825 {
35826 {
35827 IkReal dummyeval[1];
35828 dummyeval[0]=sj2;
35829 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
35830 {
35831 {
35832 IkReal evalcond[9];
35833 IkReal x11101=((cj5)*(sj4));
35834 IkReal x11102=((IkReal(1.00000000000000))*(sj6));
35835 IkReal x11103=((r10)*(sj0));
35836 IkReal x11104=((sj4)*(sj5));
35837 IkReal x11105=((cj5)*(cj6));
35838 IkReal x11106=((r01)*(sj0));
35839 IkReal x11107=((IkReal(1.00000000000000))*(r02));
35840 IkReal x11108=((IkReal(0.374290000000000))*(cj0));
35841 IkReal x11109=((cj5)*(r12));
35842 IkReal x11110=((cj6)*(sj5));
35843 IkReal x11111=((cj0)*(r11));
35844 IkReal x11112=((cj5)*(sj0));
35845 IkReal x11113=((r20)*(sj6));
35846 IkReal x11114=((IkReal(1.00000000000000))*(sj0));
35847 IkReal x11115=((cj4)*(cj5));
35848 IkReal x11116=((IkReal(1.00000000000000))*(cj6));
35849 IkReal x11117=((IkReal(0.0100000000000000))*(sj5));
35850 IkReal x11118=((sj5)*(sj6));
35851 IkReal x11119=((cj0)*(r10));
35852 IkReal x11120=((cj4)*(cj6));
35853 IkReal x11121=((cj0)*(r01));
35854 IkReal x11122=((IkReal(1.00000000000000))*(cj4));
35855 IkReal x11123=((cj0)*(r00));
35856 IkReal x11124=((IkReal(0.374290000000000))*(sj0));
35857 IkReal x11125=((cj0)*(r12));
35858 IkReal x11126=((IkReal(0.374290000000000))*(sj5));
35859 IkReal x11127=((cj4)*(sj6));
35860 IkReal x11128=((IkReal(1.00000000000000))*(cj0));
35861 IkReal x11129=((r02)*(sj0));
35862 IkReal x11130=((IkReal(0.0100000000000000))*(cj5));
35863 IkReal x11131=((r11)*(sj0));
35864 IkReal x11132=((r00)*(sj0)*(sj6));
35865 IkReal x11133=((r00)*(x11120));
35866 IkReal x11134=((sj6)*(x11130));
35867 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
35868 evalcond[1]=((((r21)*(x11127)))+(((r22)*(x11104)))+(((x11101)*(x11113)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x11116)))+(((cj6)*(r21)*(x11101))));
35869 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x11113)*(x11130)))+(((x11113)*(x11126)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(0.374290000000000))*(r21)*(x11110)))+(pz)+(((IkReal(-0.0100000000000000))*(r21)*(x11105)))+(((IkReal(-1.00000000000000))*(r22)*(x11117))));
35870 evalcond[3]=((((x11106)*(x11110)))+(((IkReal(-1.00000000000000))*(sj5)*(x11102)*(x11119)))+(((cj0)*(x11109)))+(((r00)*(sj0)*(x11118)))+(((IkReal(-1.00000000000000))*(x11107)*(x11112)))+(((IkReal(-1.00000000000000))*(x11110)*(x11111))));
35871 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x11101)*(x11111)*(x11116)))+(((IkReal(-1.00000000000000))*(x11101)*(x11102)*(x11119)))+(((x11119)*(x11120)))+(((IkReal(-1.00000000000000))*(cj4)*(x11102)*(x11111)))+(((IkReal(-1.00000000000000))*(x11114)*(x11133)))+(((x11101)*(x11132)))+(((x11104)*(x11129)))+(((cj6)*(x11101)*(x11106)))+(((x11106)*(x11127)))+(((IkReal(-1.00000000000000))*(x11104)*(x11125))));
35872 evalcond[5]=((((cj4)*(x11105)*(x11106)))+(((cj4)*(sj5)*(x11129)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x11116)*(x11119)))+(((IkReal(-1.00000000000000))*(sj5)*(x11122)*(x11125)))+(((IkReal(-1.00000000000000))*(x11105)*(x11111)*(x11122)))+(((sj4)*(sj6)*(x11111)))+(((r00)*(x11112)*(x11127)))+(((IkReal(-1.00000000000000))*(sj4)*(x11102)*(x11106)))+(((IkReal(-1.00000000000000))*(x11102)*(x11115)*(x11119))));
35873 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x11102)*(x11121)))+(((IkReal(-1.00000000000000))*(x11101)*(x11116)*(x11121)))+(((IkReal(-1.00000000000000))*(cj0)*(x11104)*(x11107)))+(((IkReal(-1.00000000000000))*(x11101)*(x11102)*(x11103)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x11101)*(x11114)))+(((IkReal(-1.00000000000000))*(r12)*(x11104)*(x11114)))+(((IkReal(-1.00000000000000))*(cj4)*(x11102)*(x11131)))+(((x11103)*(x11120)))+(((x11120)*(x11123)))+(((IkReal(-1.00000000000000))*(x11101)*(x11102)*(x11123))));
35874 evalcond[7]=((((x11117)*(x11125)))+(((IkReal(-1.00000000000000))*(x11117)*(x11129)))+(((IkReal(0.0100000000000000))*(x11105)*(x11111)))+(((x11119)*(x11134)))+(((IkReal(-1.00000000000000))*(r10)*(x11108)*(x11118)))+(((x11108)*(x11109)))+(((IkReal(-1.00000000000000))*(r11)*(x11108)*(x11110)))+(((IkReal(-0.0100000000000000))*(x11105)*(x11106)))+(((r00)*(x11118)*(x11124)))+(((IkReal(0.374290000000000))*(x11106)*(x11110)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x11112)))+(((IkReal(-1.00000000000000))*(py)*(x11128)))+(((IkReal(-0.374290000000000))*(r02)*(x11112))));
35875 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(x11105)*(x11121)))+(((r12)*(sj0)*(x11117)))+(((IkReal(-1.00000000000000))*(r00)*(x11108)*(x11118)))+(((IkReal(-1.00000000000000))*(r11)*(x11110)*(x11124)))+(((IkReal(-1.00000000000000))*(px)*(x11128)))+(((x11123)*(x11134)))+(((x11103)*(x11134)))+(((IkReal(-1.00000000000000))*(r01)*(x11108)*(x11110)))+(((cj5)*(r02)*(x11108)))+(((IkReal(0.0100000000000000))*(x11105)*(x11131)))+(((x11109)*(x11124)))+(((cj0)*(r02)*(x11117)))+(((IkReal(-0.374290000000000))*(x11103)*(x11118)))+(((IkReal(-1.00000000000000))*(py)*(x11114))));
35876 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
35877 {
35878 {
35879 IkReal j3array[1], cj3array[1], sj3array[1];
35880 bool j3valid[1]={false};
35881 _nj3 = 1;
35882 IkReal x11135=((IkReal(1.00000000000000))*(cj4));
35883 IkReal x11136=((cj6)*(r21));
35884 IkReal x11137=((r20)*(sj6));
35885 if( IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11136)))+(((sj5)*(x11137))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11135)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11136)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11137)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11136)))+(((sj5)*(x11137)))))+IKsqr(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11135)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11136)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11137)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
35886     continue;
35887 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11136)))+(((sj5)*(x11137)))), ((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11135)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11136)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x11135)*(x11137)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
35888 sj3array[0]=IKsin(j3array[0]);
35889 cj3array[0]=IKcos(j3array[0]);
35890 if( j3array[0] > IKPI )
35891 {
35892     j3array[0]-=IK2PI;
35893 }
35894 else if( j3array[0] < -IKPI )
35895 {    j3array[0]+=IK2PI;
35896 }
35897 j3valid[0] = true;
35898 for(int ij3 = 0; ij3 < 1; ++ij3)
35899 {
35900 if( !j3valid[ij3] )
35901 {
35902     continue;
35903 }
35904 _ij3[0] = ij3; _ij3[1] = -1;
35905 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
35906 {
35907 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
35908 {
35909     j3valid[iij3]=false; _ij3[1] = iij3; break; 
35910 }
35911 }
35912 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
35913 {
35914 IkReal evalcond[4];
35915 IkReal x11138=IKcos(j3);
35916 IkReal x11139=((IkReal(1.00000000000000))*(cj4));
35917 IkReal x11140=((sj0)*(sj5));
35918 IkReal x11141=((cj0)*(cj5));
35919 IkReal x11142=((cj6)*(r01));
35920 IkReal x11143=((r00)*(sj6));
35921 IkReal x11144=((cj6)*(r11));
35922 IkReal x11145=((cj5)*(sj0));
35923 IkReal x11146=((cj6)*(sj4));
35924 IkReal x11147=((sj4)*(sj6));
35925 IkReal x11148=((cj4)*(cj5));
35926 IkReal x11149=((cj6)*(r21));
35927 IkReal x11150=((r20)*(sj6));
35928 IkReal x11151=((r10)*(sj6));
35929 IkReal x11152=((IkReal(1.00000000000000))*(IKsin(j3)));
35930 IkReal x11153=((IkReal(1.00000000000000))*(cj0)*(sj5));
35931 evalcond[0]=((((IkReal(-1.00000000000000))*(x11152)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11149)))+(((sj5)*(x11150))));
35932 evalcond[1]=((((x11148)*(x11149)))+(((x11148)*(x11150)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x11146)))+(((IkReal(-1.00000000000000))*(r21)*(x11147)))+(x11138));
35933 evalcond[2]=((((IkReal(-1.00000000000000))*(x11138)))+(((r02)*(x11141)))+(((IkReal(-1.00000000000000))*(x11140)*(x11144)))+(((IkReal(-1.00000000000000))*(x11142)*(x11153)))+(((r12)*(x11145)))+(((IkReal(-1.00000000000000))*(x11143)*(x11153)))+(((IkReal(-1.00000000000000))*(x11140)*(x11151))));
35934 evalcond[3]=((((IkReal(-1.00000000000000))*(x11139)*(x11141)*(x11142)))+(((IkReal(-1.00000000000000))*(x11139)*(x11141)*(x11143)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11146)))+(((IkReal(-1.00000000000000))*(x11152)))+(((r11)*(sj0)*(x11147)))+(((cj0)*(r01)*(x11147)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11139)))+(((IkReal(-1.00000000000000))*(x11139)*(x11145)*(x11151)))+(((IkReal(-1.00000000000000))*(r12)*(x11139)*(x11140)))+(((IkReal(-1.00000000000000))*(x11139)*(x11144)*(x11145)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11146))));
35935 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
35936 {
35937 continue;
35938 }
35939 }
35940 
35941 {
35942 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
35943 vinfos[0].jointtype = 1;
35944 vinfos[0].foffset = j0;
35945 vinfos[0].indices[0] = _ij0[0];
35946 vinfos[0].indices[1] = _ij0[1];
35947 vinfos[0].maxsolutions = _nj0;
35948 vinfos[1].jointtype = 1;
35949 vinfos[1].foffset = j1;
35950 vinfos[1].indices[0] = _ij1[0];
35951 vinfos[1].indices[1] = _ij1[1];
35952 vinfos[1].maxsolutions = _nj1;
35953 vinfos[2].jointtype = 1;
35954 vinfos[2].foffset = j2;
35955 vinfos[2].indices[0] = _ij2[0];
35956 vinfos[2].indices[1] = _ij2[1];
35957 vinfos[2].maxsolutions = _nj2;
35958 vinfos[3].jointtype = 1;
35959 vinfos[3].foffset = j3;
35960 vinfos[3].indices[0] = _ij3[0];
35961 vinfos[3].indices[1] = _ij3[1];
35962 vinfos[3].maxsolutions = _nj3;
35963 vinfos[4].jointtype = 1;
35964 vinfos[4].foffset = j4;
35965 vinfos[4].indices[0] = _ij4[0];
35966 vinfos[4].indices[1] = _ij4[1];
35967 vinfos[4].maxsolutions = _nj4;
35968 vinfos[5].jointtype = 1;
35969 vinfos[5].foffset = j5;
35970 vinfos[5].indices[0] = _ij5[0];
35971 vinfos[5].indices[1] = _ij5[1];
35972 vinfos[5].maxsolutions = _nj5;
35973 vinfos[6].jointtype = 1;
35974 vinfos[6].foffset = j6;
35975 vinfos[6].indices[0] = _ij6[0];
35976 vinfos[6].indices[1] = _ij6[1];
35977 vinfos[6].maxsolutions = _nj6;
35978 std::vector<int> vfree(0);
35979 solutions.AddSolution(vinfos,vfree);
35980 }
35981 }
35982 }
35983 
35984 } else
35985 {
35986 IkReal x11154=((cj5)*(sj4));
35987 IkReal x11155=((IkReal(1.00000000000000))*(sj6));
35988 IkReal x11156=((r10)*(sj0));
35989 IkReal x11157=((sj4)*(sj5));
35990 IkReal x11158=((cj5)*(cj6));
35991 IkReal x11159=((r01)*(sj0));
35992 IkReal x11160=((IkReal(1.00000000000000))*(r02));
35993 IkReal x11161=((IkReal(0.374290000000000))*(cj0));
35994 IkReal x11162=((cj5)*(r12));
35995 IkReal x11163=((cj6)*(sj5));
35996 IkReal x11164=((cj0)*(r11));
35997 IkReal x11165=((cj5)*(sj0));
35998 IkReal x11166=((r20)*(sj6));
35999 IkReal x11167=((IkReal(1.00000000000000))*(sj0));
36000 IkReal x11168=((cj4)*(cj5));
36001 IkReal x11169=((IkReal(1.00000000000000))*(cj6));
36002 IkReal x11170=((IkReal(0.0100000000000000))*(sj5));
36003 IkReal x11171=((sj5)*(sj6));
36004 IkReal x11172=((cj0)*(r10));
36005 IkReal x11173=((cj4)*(cj6));
36006 IkReal x11174=((cj0)*(r01));
36007 IkReal x11175=((IkReal(1.00000000000000))*(cj4));
36008 IkReal x11176=((cj0)*(r00));
36009 IkReal x11177=((IkReal(0.374290000000000))*(sj0));
36010 IkReal x11178=((cj0)*(r12));
36011 IkReal x11179=((IkReal(0.374290000000000))*(sj5));
36012 IkReal x11180=((cj4)*(sj6));
36013 IkReal x11181=((IkReal(1.00000000000000))*(cj0));
36014 IkReal x11182=((r02)*(sj0));
36015 IkReal x11183=((IkReal(0.0100000000000000))*(cj5));
36016 IkReal x11184=((r11)*(sj0));
36017 IkReal x11185=((r00)*(sj0)*(sj6));
36018 IkReal x11186=((r00)*(x11173));
36019 IkReal x11187=((sj6)*(x11183));
36020 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
36021 evalcond[1]=((((x11154)*(x11166)))+(((r22)*(x11157)))+(((cj6)*(r21)*(x11154)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x11169)))+(((r21)*(x11180))));
36022 evalcond[2]=((IkReal(-0.0690000000000000))+(((x11166)*(x11179)))+(((IkReal(-0.0100000000000000))*(r21)*(x11158)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(0.374290000000000))*(r21)*(x11163)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x11170)))+(((IkReal(-1.00000000000000))*(x11166)*(x11183))));
36023 evalcond[3]=((((cj0)*(x11162)))+(((IkReal(-1.00000000000000))*(sj5)*(x11155)*(x11172)))+(((r00)*(sj0)*(x11171)))+(((IkReal(-1.00000000000000))*(x11163)*(x11164)))+(((IkReal(-1.00000000000000))*(x11160)*(x11165)))+(((x11159)*(x11163))));
36024 evalcond[4]=((IkReal(-1.00000000000000))+(((cj6)*(x11154)*(x11159)))+(((IkReal(-1.00000000000000))*(x11154)*(x11155)*(x11172)))+(((IkReal(-1.00000000000000))*(cj4)*(x11155)*(x11164)))+(((x11172)*(x11173)))+(((x11159)*(x11180)))+(((x11154)*(x11185)))+(((x11157)*(x11182)))+(((IkReal(-1.00000000000000))*(x11167)*(x11186)))+(((IkReal(-1.00000000000000))*(x11157)*(x11178)))+(((IkReal(-1.00000000000000))*(x11154)*(x11164)*(x11169))));
36025 evalcond[5]=((((IkReal(-1.00000000000000))*(x11158)*(x11164)*(x11175)))+(((cj4)*(sj5)*(x11182)))+(((IkReal(-1.00000000000000))*(sj5)*(x11175)*(x11178)))+(((sj4)*(sj6)*(x11164)))+(((cj4)*(x11158)*(x11159)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x11155)*(x11168)*(x11172)))+(((r00)*(x11165)*(x11180)))+(((IkReal(-1.00000000000000))*(sj4)*(x11155)*(x11159)))+(((IkReal(-1.00000000000000))*(sj4)*(x11169)*(x11172))));
36026 evalcond[6]=((((x11173)*(x11176)))+(((IkReal(-1.00000000000000))*(x11154)*(x11155)*(x11156)))+(((IkReal(-1.00000000000000))*(cj4)*(x11155)*(x11174)))+(((IkReal(-1.00000000000000))*(cj4)*(x11155)*(x11184)))+(((x11156)*(x11173)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x11154)*(x11167)))+(((IkReal(-1.00000000000000))*(cj0)*(x11157)*(x11160)))+(((IkReal(-1.00000000000000))*(x11154)*(x11155)*(x11176)))+(((IkReal(-1.00000000000000))*(r12)*(x11157)*(x11167)))+(((IkReal(-1.00000000000000))*(x11154)*(x11169)*(x11174))));
36027 evalcond[7]=((((IkReal(-1.00000000000000))*(x11170)*(x11182)))+(((x11172)*(x11187)))+(((x11161)*(x11162)))+(((x11170)*(x11178)))+(((IkReal(-0.0100000000000000))*(x11158)*(x11159)))+(((IkReal(-0.374290000000000))*(r02)*(x11165)))+(((IkReal(0.0100000000000000))*(x11158)*(x11164)))+(((IkReal(-1.00000000000000))*(r11)*(x11161)*(x11163)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x11165)))+(((IkReal(0.374290000000000))*(x11159)*(x11163)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x11181)))+(((r00)*(x11171)*(x11177)))+(((IkReal(-1.00000000000000))*(r10)*(x11161)*(x11171))));
36028 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(r00)*(x11161)*(x11171)))+(((cj0)*(r02)*(x11170)))+(((IkReal(0.0100000000000000))*(x11158)*(x11174)))+(((IkReal(-1.00000000000000))*(px)*(x11181)))+(((cj5)*(r02)*(x11161)))+(((IkReal(-1.00000000000000))*(r01)*(x11161)*(x11163)))+(((IkReal(-1.00000000000000))*(py)*(x11167)))+(((r12)*(sj0)*(x11170)))+(((x11176)*(x11187)))+(((x11162)*(x11177)))+(((x11156)*(x11187)))+(((IkReal(-1.00000000000000))*(r11)*(x11163)*(x11177)))+(((IkReal(-0.374290000000000))*(x11156)*(x11171)))+(((IkReal(0.0100000000000000))*(x11158)*(x11184))));
36029 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
36030 {
36031 {
36032 IkReal j3array[1], cj3array[1], sj3array[1];
36033 bool j3valid[1]={false};
36034 _nj3 = 1;
36035 IkReal x11188=((IkReal(1.00000000000000))*(r21));
36036 IkReal x11189=((cj4)*(cj5));
36037 IkReal x11190=((r20)*(sj6));
36038 if( IKabs(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11188)))+(((IkReal(-1.00000000000000))*(sj5)*(x11190)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r21)*(x11189)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11188)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x11189)*(x11190))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11188)))+(((IkReal(-1.00000000000000))*(sj5)*(x11190)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r21)*(x11189)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11188)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x11189)*(x11190)))))-1) <= IKFAST_SINCOS_THRESH )
36039     continue;
36040 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11188)))+(((IkReal(-1.00000000000000))*(sj5)*(x11190)))+(((cj5)*(r22)))), ((((cj6)*(r21)*(x11189)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11188)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x11189)*(x11190)))));
36041 sj3array[0]=IKsin(j3array[0]);
36042 cj3array[0]=IKcos(j3array[0]);
36043 if( j3array[0] > IKPI )
36044 {
36045     j3array[0]-=IK2PI;
36046 }
36047 else if( j3array[0] < -IKPI )
36048 {    j3array[0]+=IK2PI;
36049 }
36050 j3valid[0] = true;
36051 for(int ij3 = 0; ij3 < 1; ++ij3)
36052 {
36053 if( !j3valid[ij3] )
36054 {
36055     continue;
36056 }
36057 _ij3[0] = ij3; _ij3[1] = -1;
36058 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36059 {
36060 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36061 {
36062     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36063 }
36064 }
36065 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36066 {
36067 IkReal evalcond[4];
36068 IkReal x11191=IKsin(j3);
36069 IkReal x11192=((IkReal(1.00000000000000))*(cj4));
36070 IkReal x11193=((sj0)*(sj5));
36071 IkReal x11194=((cj0)*(cj5));
36072 IkReal x11195=((cj6)*(r01));
36073 IkReal x11196=((r00)*(sj6));
36074 IkReal x11197=((cj6)*(r11));
36075 IkReal x11198=((cj5)*(sj0));
36076 IkReal x11199=((cj6)*(sj4));
36077 IkReal x11200=((sj4)*(sj6));
36078 IkReal x11201=((cj4)*(cj5));
36079 IkReal x11202=((cj6)*(r21));
36080 IkReal x11203=((r20)*(sj6));
36081 IkReal x11204=((r10)*(sj6));
36082 IkReal x11205=((IkReal(1.00000000000000))*(IKcos(j3)));
36083 IkReal x11206=((IkReal(1.00000000000000))*(cj0)*(sj5));
36084 evalcond[0]=((x11191)+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11202)))+(((sj5)*(x11203))));
36085 evalcond[1]=((((r20)*(x11199)))+(((x11201)*(x11202)))+(((IkReal(-1.00000000000000))*(x11205)))+(((cj4)*(r22)*(sj5)))+(((x11201)*(x11203)))+(((IkReal(-1.00000000000000))*(r21)*(x11200))));
36086 evalcond[2]=((((IkReal(-1.00000000000000))*(x11196)*(x11206)))+(((IkReal(-1.00000000000000))*(x11205)))+(((IkReal(-1.00000000000000))*(x11195)*(x11206)))+(((IkReal(-1.00000000000000))*(x11193)*(x11204)))+(((IkReal(-1.00000000000000))*(x11193)*(x11197)))+(((r02)*(x11194)))+(((r12)*(x11198))));
36087 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11199)))+(((cj0)*(r01)*(x11200)))+(((IkReal(-1.00000000000000))*(x11192)*(x11197)*(x11198)))+(((IkReal(-1.00000000000000))*(x11192)*(x11194)*(x11196)))+(((r11)*(sj0)*(x11200)))+(((IkReal(-1.00000000000000))*(x11191)))+(((IkReal(-1.00000000000000))*(r12)*(x11192)*(x11193)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11199)))+(((IkReal(-1.00000000000000))*(x11192)*(x11194)*(x11195)))+(((IkReal(-1.00000000000000))*(x11192)*(x11198)*(x11204)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11192))));
36088 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
36089 {
36090 continue;
36091 }
36092 }
36093 
36094 {
36095 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36096 vinfos[0].jointtype = 1;
36097 vinfos[0].foffset = j0;
36098 vinfos[0].indices[0] = _ij0[0];
36099 vinfos[0].indices[1] = _ij0[1];
36100 vinfos[0].maxsolutions = _nj0;
36101 vinfos[1].jointtype = 1;
36102 vinfos[1].foffset = j1;
36103 vinfos[1].indices[0] = _ij1[0];
36104 vinfos[1].indices[1] = _ij1[1];
36105 vinfos[1].maxsolutions = _nj1;
36106 vinfos[2].jointtype = 1;
36107 vinfos[2].foffset = j2;
36108 vinfos[2].indices[0] = _ij2[0];
36109 vinfos[2].indices[1] = _ij2[1];
36110 vinfos[2].maxsolutions = _nj2;
36111 vinfos[3].jointtype = 1;
36112 vinfos[3].foffset = j3;
36113 vinfos[3].indices[0] = _ij3[0];
36114 vinfos[3].indices[1] = _ij3[1];
36115 vinfos[3].maxsolutions = _nj3;
36116 vinfos[4].jointtype = 1;
36117 vinfos[4].foffset = j4;
36118 vinfos[4].indices[0] = _ij4[0];
36119 vinfos[4].indices[1] = _ij4[1];
36120 vinfos[4].maxsolutions = _nj4;
36121 vinfos[5].jointtype = 1;
36122 vinfos[5].foffset = j5;
36123 vinfos[5].indices[0] = _ij5[0];
36124 vinfos[5].indices[1] = _ij5[1];
36125 vinfos[5].maxsolutions = _nj5;
36126 vinfos[6].jointtype = 1;
36127 vinfos[6].foffset = j6;
36128 vinfos[6].indices[0] = _ij6[0];
36129 vinfos[6].indices[1] = _ij6[1];
36130 vinfos[6].maxsolutions = _nj6;
36131 std::vector<int> vfree(0);
36132 solutions.AddSolution(vinfos,vfree);
36133 }
36134 }
36135 }
36136 
36137 } else
36138 {
36139 IkReal x11207=((IkReal(1.00000000000000))*(cj0));
36140 IkReal x11208=((cj4)*(sj6));
36141 IkReal x11209=((sj0)*(sj4));
36142 IkReal x11210=((cj5)*(sj6));
36143 IkReal x11211=((sj4)*(sj5));
36144 IkReal x11212=((r12)*(sj5));
36145 IkReal x11213=((IkReal(0.374290000000000))*(cj5));
36146 IkReal x11214=((r02)*(sj0));
36147 IkReal x11215=((r20)*(sj4));
36148 IkReal x11216=((IkReal(1.00000000000000))*(sj0));
36149 IkReal x11217=((IkReal(1.00000000000000))*(cj5));
36150 IkReal x11218=((cj0)*(r10));
36151 IkReal x11219=((cj4)*(cj6));
36152 IkReal x11220=((r00)*(sj0));
36153 IkReal x11221=((cj6)*(r21));
36154 IkReal x11222=((IkReal(0.374290000000000))*(sj5));
36155 IkReal x11223=((cj0)*(r00));
36156 IkReal x11224=((IkReal(0.0100000000000000))*(sj5));
36157 IkReal x11225=((cj0)*(r02));
36158 IkReal x11226=((cj5)*(sj4));
36159 IkReal x11227=((cj6)*(r01));
36160 IkReal x11228=((cj6)*(r11));
36161 IkReal x11229=((r01)*(sj0));
36162 IkReal x11230=((r10)*(sj0));
36163 IkReal x11231=((IkReal(0.0100000000000000))*(cj5)*(cj6));
36164 IkReal x11232=((sj6)*(x11222));
36165 IkReal x11233=((cj0)*(cj6)*(x11222));
36166 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
36167 evalcond[1]=((((sj5)*(x11221)))+(((IkReal(-1.00000000000000))*(r22)*(x11217)))+(((r20)*(sj5)*(sj6))));
36168 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x11211)))+(((x11221)*(x11226)))+(((x11210)*(x11215)))+(((IkReal(-1.00000000000000))*(r20)*(x11219)))+(((r21)*(x11208))));
36169 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x11210)))+(((IkReal(-1.00000000000000))*(r22)*(x11213)))+(((x11221)*(x11222)))+(((r20)*(x11232)))+(((IkReal(-1.00000000000000))*(r22)*(x11224)))+(pz)+(((IkReal(-0.0100000000000000))*(cj5)*(x11221))));
36170 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x11208)))+(((cj5)*(r21)*(x11219)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x11215))));
36171 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x11207)*(x11211)))+(((IkReal(-1.00000000000000))*(x11207)*(x11226)*(x11228)))+(((r00)*(x11209)*(x11210)))+(((cj5)*(x11209)*(x11227)))+(((IkReal(-1.00000000000000))*(r11)*(x11207)*(x11208)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11207)*(x11210)))+(((x11218)*(x11219)))+(((IkReal(-1.00000000000000))*(r00)*(x11216)*(x11219)))+(((x11208)*(x11229)))+(((r02)*(sj5)*(x11209))));
36172 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11207)*(x11210)))+(((IkReal(-1.00000000000000))*(r02)*(x11207)*(x11211)))+(((x11219)*(x11223)))+(((IkReal(-1.00000000000000))*(x11209)*(x11212)))+(((IkReal(-1.00000000000000))*(r10)*(x11209)*(x11210)))+(((IkReal(-1.00000000000000))*(x11207)*(x11226)*(x11227)))+(((x11219)*(x11230)))+(((IkReal(-1.00000000000000))*(x11209)*(x11217)*(x11228)))+(((IkReal(-1.00000000000000))*(r01)*(x11207)*(x11208)))+(((IkReal(-1.00000000000000))*(r11)*(x11208)*(x11216))));
36173 evalcond[7]=((IkReal(0.0690000000000000))+(((cj0)*(r12)*(x11213)))+(((IkReal(-1.00000000000000))*(py)*(x11207)))+(((IkReal(0.0100000000000000))*(x11210)*(x11218)))+(((IkReal(-1.00000000000000))*(x11214)*(x11224)))+(((x11220)*(x11232)))+(((IkReal(-1.00000000000000))*(cj0)*(x11222)*(x11228)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11228)))+(((IkReal(0.0100000000000000))*(cj0)*(x11212)))+(((IkReal(-1.00000000000000))*(x11218)*(x11232)))+(((sj0)*(x11222)*(x11227)))+(((IkReal(-1.00000000000000))*(x11213)*(x11214)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11227)))+(((IkReal(-0.0100000000000000))*(x11210)*(x11220))));
36174 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11228)))+(((IkReal(-1.00000000000000))*(x11223)*(x11232)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11227)))+(((IkReal(0.0100000000000000))*(x11210)*(x11223)))+(((IkReal(-1.00000000000000))*(cj0)*(x11222)*(x11227)))+(((x11213)*(x11225)))+(((IkReal(0.0100000000000000))*(x11210)*(x11230)))+(((IkReal(0.0100000000000000))*(sj0)*(x11212)))+(((IkReal(-1.00000000000000))*(py)*(x11216)))+(((IkReal(-1.00000000000000))*(sj0)*(x11222)*(x11228)))+(((x11224)*(x11225)))+(((r12)*(sj0)*(x11213)))+(((IkReal(-1.00000000000000))*(x11230)*(x11232)))+(((IkReal(-1.00000000000000))*(px)*(x11207))));
36175 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
36176 {
36177 {
36178 IkReal j3array[1], cj3array[1], sj3array[1];
36179 bool j3valid[1]={false};
36180 _nj3 = 1;
36181 IkReal x11234=((cj0)*(cj5));
36182 IkReal x11235=((IkReal(1.00000000000000))*(cj0));
36183 IkReal x11236=((cj6)*(r11));
36184 IkReal x11237=((r10)*(sj6));
36185 IkReal x11238=((cj5)*(sj0));
36186 IkReal x11239=((r00)*(sj5)*(sj6));
36187 IkReal x11240=((cj6)*(r01)*(sj5));
36188 IkReal x11241=((IkReal(1.00000000000000))*(sj0)*(sj5));
36189 if( IKabs(((((sj0)*(x11240)))+(((IkReal(-1.00000000000000))*(r02)*(x11238)))+(((sj0)*(x11239)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11237)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11236)))+(((r12)*(x11234))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x11237)*(x11241)))+(((IkReal(-1.00000000000000))*(x11236)*(x11241)))+(((r02)*(x11234)))+(((IkReal(-1.00000000000000))*(x11235)*(x11240)))+(((r12)*(x11238)))+(((IkReal(-1.00000000000000))*(x11235)*(x11239))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x11240)))+(((IkReal(-1.00000000000000))*(r02)*(x11238)))+(((sj0)*(x11239)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11237)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11236)))+(((r12)*(x11234)))))+IKsqr(((((IkReal(-1.00000000000000))*(x11237)*(x11241)))+(((IkReal(-1.00000000000000))*(x11236)*(x11241)))+(((r02)*(x11234)))+(((IkReal(-1.00000000000000))*(x11235)*(x11240)))+(((r12)*(x11238)))+(((IkReal(-1.00000000000000))*(x11235)*(x11239)))))-1) <= IKFAST_SINCOS_THRESH )
36190     continue;
36191 j3array[0]=IKatan2(((((sj0)*(x11240)))+(((IkReal(-1.00000000000000))*(r02)*(x11238)))+(((sj0)*(x11239)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11237)))+(((IkReal(-1.00000000000000))*(sj5)*(x11235)*(x11236)))+(((r12)*(x11234)))), ((((IkReal(-1.00000000000000))*(x11237)*(x11241)))+(((IkReal(-1.00000000000000))*(x11236)*(x11241)))+(((r02)*(x11234)))+(((IkReal(-1.00000000000000))*(x11235)*(x11240)))+(((r12)*(x11238)))+(((IkReal(-1.00000000000000))*(x11235)*(x11239)))));
36192 sj3array[0]=IKsin(j3array[0]);
36193 cj3array[0]=IKcos(j3array[0]);
36194 if( j3array[0] > IKPI )
36195 {
36196     j3array[0]-=IK2PI;
36197 }
36198 else if( j3array[0] < -IKPI )
36199 {    j3array[0]+=IK2PI;
36200 }
36201 j3valid[0] = true;
36202 for(int ij3 = 0; ij3 < 1; ++ij3)
36203 {
36204 if( !j3valid[ij3] )
36205 {
36206     continue;
36207 }
36208 _ij3[0] = ij3; _ij3[1] = -1;
36209 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36210 {
36211 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36212 {
36213     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36214 }
36215 }
36216 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36217 {
36218 IkReal evalcond[4];
36219 IkReal x11242=IKcos(j3);
36220 IkReal x11243=((sj0)*(sj5));
36221 IkReal x11244=((r00)*(sj6));
36222 IkReal x11245=((cj6)*(sj0));
36223 IkReal x11246=((IkReal(1.00000000000000))*(cj4));
36224 IkReal x11247=((r00)*(sj4));
36225 IkReal x11248=((cj0)*(cj5));
36226 IkReal x11249=((cj5)*(sj0));
36227 IkReal x11250=((cj6)*(r11));
36228 IkReal x11251=((r10)*(sj6));
36229 IkReal x11252=((cj0)*(sj5));
36230 IkReal x11253=((r10)*(sj4));
36231 IkReal x11254=((IkReal(1.00000000000000))*(IKsin(j3)));
36232 IkReal x11255=((cj4)*(cj5)*(r01));
36233 IkReal x11256=((IkReal(1.00000000000000))*(cj0)*(cj6));
36234 IkReal x11257=((cj0)*(sj4)*(sj6));
36235 IkReal x11258=((sj0)*(sj4)*(sj6));
36236 evalcond[0]=((((cj6)*(r01)*(x11243)))+(((x11243)*(x11244)))+(((IkReal(-1.00000000000000))*(r02)*(x11249)))+(((IkReal(-1.00000000000000))*(x11254)))+(((IkReal(-1.00000000000000))*(x11250)*(x11252)))+(((IkReal(-1.00000000000000))*(x11251)*(x11252)))+(((r12)*(x11248))));
36237 evalcond[1]=((((r12)*(x11249)))+(((r02)*(x11248)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x11252)))+(((IkReal(-1.00000000000000))*(x11242)))+(((IkReal(-1.00000000000000))*(x11243)*(x11250)))+(((IkReal(-1.00000000000000))*(x11243)*(x11251)))+(((IkReal(-1.00000000000000))*(x11244)*(x11252))));
36238 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x11258)))+(((r11)*(x11257)))+(((cj4)*(r02)*(x11243)))+(((IkReal(-1.00000000000000))*(x11246)*(x11248)*(x11251)))+(((IkReal(-1.00000000000000))*(r12)*(x11246)*(x11252)))+(((IkReal(-1.00000000000000))*(x11253)*(x11256)))+(x11242)+(((IkReal(-1.00000000000000))*(x11246)*(x11248)*(x11250)))+(((cj4)*(x11244)*(x11249)))+(((x11245)*(x11255)))+(((x11245)*(x11247))));
36239 evalcond[3]=((((IkReal(-1.00000000000000))*(x11245)*(x11253)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x11245)*(x11246)))+(((IkReal(-1.00000000000000))*(x11244)*(x11246)*(x11248)))+(((r01)*(x11257)))+(((IkReal(-1.00000000000000))*(x11254)))+(((IkReal(-1.00000000000000))*(x11246)*(x11249)*(x11251)))+(((r11)*(x11258)))+(((IkReal(-1.00000000000000))*(x11247)*(x11256)))+(((IkReal(-1.00000000000000))*(r12)*(x11243)*(x11246)))+(((IkReal(-1.00000000000000))*(r02)*(x11246)*(x11252)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x11246)*(x11248))));
36240 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
36241 {
36242 continue;
36243 }
36244 }
36245 
36246 {
36247 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36248 vinfos[0].jointtype = 1;
36249 vinfos[0].foffset = j0;
36250 vinfos[0].indices[0] = _ij0[0];
36251 vinfos[0].indices[1] = _ij0[1];
36252 vinfos[0].maxsolutions = _nj0;
36253 vinfos[1].jointtype = 1;
36254 vinfos[1].foffset = j1;
36255 vinfos[1].indices[0] = _ij1[0];
36256 vinfos[1].indices[1] = _ij1[1];
36257 vinfos[1].maxsolutions = _nj1;
36258 vinfos[2].jointtype = 1;
36259 vinfos[2].foffset = j2;
36260 vinfos[2].indices[0] = _ij2[0];
36261 vinfos[2].indices[1] = _ij2[1];
36262 vinfos[2].maxsolutions = _nj2;
36263 vinfos[3].jointtype = 1;
36264 vinfos[3].foffset = j3;
36265 vinfos[3].indices[0] = _ij3[0];
36266 vinfos[3].indices[1] = _ij3[1];
36267 vinfos[3].maxsolutions = _nj3;
36268 vinfos[4].jointtype = 1;
36269 vinfos[4].foffset = j4;
36270 vinfos[4].indices[0] = _ij4[0];
36271 vinfos[4].indices[1] = _ij4[1];
36272 vinfos[4].maxsolutions = _nj4;
36273 vinfos[5].jointtype = 1;
36274 vinfos[5].foffset = j5;
36275 vinfos[5].indices[0] = _ij5[0];
36276 vinfos[5].indices[1] = _ij5[1];
36277 vinfos[5].maxsolutions = _nj5;
36278 vinfos[6].jointtype = 1;
36279 vinfos[6].foffset = j6;
36280 vinfos[6].indices[0] = _ij6[0];
36281 vinfos[6].indices[1] = _ij6[1];
36282 vinfos[6].maxsolutions = _nj6;
36283 std::vector<int> vfree(0);
36284 solutions.AddSolution(vinfos,vfree);
36285 }
36286 }
36287 }
36288 
36289 } else
36290 {
36291 IkReal x11259=((IkReal(1.00000000000000))*(cj0));
36292 IkReal x11260=((cj4)*(sj6));
36293 IkReal x11261=((sj0)*(sj4));
36294 IkReal x11262=((cj5)*(sj6));
36295 IkReal x11263=((sj4)*(sj5));
36296 IkReal x11264=((r12)*(sj5));
36297 IkReal x11265=((IkReal(0.374290000000000))*(cj5));
36298 IkReal x11266=((r02)*(sj0));
36299 IkReal x11267=((r20)*(sj4));
36300 IkReal x11268=((IkReal(1.00000000000000))*(sj0));
36301 IkReal x11269=((IkReal(1.00000000000000))*(cj5));
36302 IkReal x11270=((cj0)*(r10));
36303 IkReal x11271=((cj4)*(cj6));
36304 IkReal x11272=((r00)*(sj0));
36305 IkReal x11273=((cj6)*(r21));
36306 IkReal x11274=((IkReal(0.374290000000000))*(sj5));
36307 IkReal x11275=((cj0)*(r00));
36308 IkReal x11276=((IkReal(0.0100000000000000))*(sj5));
36309 IkReal x11277=((cj0)*(r02));
36310 IkReal x11278=((cj5)*(sj4));
36311 IkReal x11279=((cj6)*(r01));
36312 IkReal x11280=((cj6)*(r11));
36313 IkReal x11281=((r01)*(sj0));
36314 IkReal x11282=((r10)*(sj0));
36315 IkReal x11283=((IkReal(0.0100000000000000))*(cj5)*(cj6));
36316 IkReal x11284=((sj6)*(x11274));
36317 IkReal x11285=((cj0)*(cj6)*(x11274));
36318 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
36319 evalcond[1]=((((r20)*(sj5)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(x11269)))+(((sj5)*(x11273))));
36320 evalcond[2]=((IkReal(1.00000000000000))+(((x11273)*(x11278)))+(((r21)*(x11260)))+(((IkReal(-1.00000000000000))*(r20)*(x11271)))+(((r22)*(x11263)))+(((x11262)*(x11267))));
36321 evalcond[3]=((((IkReal(-0.0100000000000000))*(r20)*(x11262)))+(((x11273)*(x11274)))+(((IkReal(-0.0100000000000000))*(cj5)*(x11273)))+(((IkReal(-1.00000000000000))*(r22)*(x11265)))+(((IkReal(-1.00000000000000))*(r22)*(x11276)))+(pz)+(((r20)*(x11284))));
36322 evalcond[4]=((((cj6)*(x11267)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x11271)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r20)*(x11260))));
36323 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x11259)*(x11263)))+(((cj5)*(x11261)*(x11279)))+(((x11270)*(x11271)))+(((IkReal(-1.00000000000000))*(r11)*(x11259)*(x11260)))+(((r02)*(sj5)*(x11261)))+(((r00)*(x11261)*(x11262)))+(((IkReal(-1.00000000000000))*(r00)*(x11268)*(x11271)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11259)*(x11262)))+(((IkReal(-1.00000000000000))*(x11259)*(x11278)*(x11280)))+(((x11260)*(x11281))));
36324 evalcond[6]=((((x11271)*(x11275)))+(((IkReal(-1.00000000000000))*(r02)*(x11259)*(x11263)))+(((IkReal(-1.00000000000000))*(x11261)*(x11269)*(x11280)))+(((IkReal(-1.00000000000000))*(x11261)*(x11264)))+(((IkReal(-1.00000000000000))*(r11)*(x11260)*(x11268)))+(((IkReal(-1.00000000000000))*(r01)*(x11259)*(x11260)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11259)*(x11262)))+(((IkReal(-1.00000000000000))*(r10)*(x11261)*(x11262)))+(((x11271)*(x11282)))+(((IkReal(-1.00000000000000))*(x11259)*(x11278)*(x11279))));
36325 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(0.0100000000000000))*(x11262)*(x11270)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11279)))+(((IkReal(-1.00000000000000))*(x11265)*(x11266)))+(((IkReal(-0.0100000000000000))*(x11262)*(x11272)))+(((cj0)*(r12)*(x11265)))+(((IkReal(-1.00000000000000))*(cj0)*(x11274)*(x11280)))+(((IkReal(0.0100000000000000))*(cj0)*(x11264)))+(((IkReal(-1.00000000000000))*(x11270)*(x11284)))+(((IkReal(-1.00000000000000))*(x11266)*(x11276)))+(((sj0)*(x11274)*(x11279)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11280)))+(((px)*(sj0)))+(((x11272)*(x11284)))+(((IkReal(-1.00000000000000))*(py)*(x11259))));
36326 evalcond[8]=((IkReal(0.433420000000000))+(((x11276)*(x11277)))+(((IkReal(-1.00000000000000))*(cj0)*(x11274)*(x11279)))+(((IkReal(-1.00000000000000))*(py)*(x11268)))+(((IkReal(-1.00000000000000))*(sj0)*(x11274)*(x11280)))+(((IkReal(-1.00000000000000))*(x11275)*(x11284)))+(((IkReal(0.0100000000000000))*(x11262)*(x11282)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11280)))+(((IkReal(-1.00000000000000))*(px)*(x11259)))+(((IkReal(0.0100000000000000))*(sj0)*(x11264)))+(((IkReal(0.0100000000000000))*(x11262)*(x11275)))+(((IkReal(-1.00000000000000))*(x11282)*(x11284)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11279)))+(((x11265)*(x11277)))+(((r12)*(sj0)*(x11265))));
36327 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
36328 {
36329 {
36330 IkReal j3array[1], cj3array[1], sj3array[1];
36331 bool j3valid[1]={false};
36332 _nj3 = 1;
36333 IkReal x11286=((cj5)*(r02));
36334 IkReal x11287=((cj0)*(sj5));
36335 IkReal x11288=((r10)*(sj6));
36336 IkReal x11289=((IkReal(1.00000000000000))*(cj6));
36337 IkReal x11290=((sj0)*(sj5));
36338 IkReal x11291=((cj5)*(r12));
36339 IkReal x11292=((IkReal(1.00000000000000))*(r00)*(sj6));
36340 if( IKabs(((((x11287)*(x11288)))+(((IkReal(-1.00000000000000))*(r01)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(cj0)*(x11291)))+(((cj6)*(r11)*(x11287)))+(((sj0)*(x11286)))+(((IkReal(-1.00000000000000))*(x11290)*(x11292))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj0)*(x11291)))+(((IkReal(-1.00000000000000))*(r11)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(x11287)*(x11292)))+(((IkReal(-1.00000000000000))*(r01)*(x11287)*(x11289)))+(((IkReal(-1.00000000000000))*(x11288)*(x11290)))+(((cj0)*(x11286))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x11287)*(x11288)))+(((IkReal(-1.00000000000000))*(r01)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(cj0)*(x11291)))+(((cj6)*(r11)*(x11287)))+(((sj0)*(x11286)))+(((IkReal(-1.00000000000000))*(x11290)*(x11292)))))+IKsqr(((((sj0)*(x11291)))+(((IkReal(-1.00000000000000))*(r11)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(x11287)*(x11292)))+(((IkReal(-1.00000000000000))*(r01)*(x11287)*(x11289)))+(((IkReal(-1.00000000000000))*(x11288)*(x11290)))+(((cj0)*(x11286)))))-1) <= IKFAST_SINCOS_THRESH )
36341     continue;
36342 j3array[0]=IKatan2(((((x11287)*(x11288)))+(((IkReal(-1.00000000000000))*(r01)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(cj0)*(x11291)))+(((cj6)*(r11)*(x11287)))+(((sj0)*(x11286)))+(((IkReal(-1.00000000000000))*(x11290)*(x11292)))), ((((sj0)*(x11291)))+(((IkReal(-1.00000000000000))*(r11)*(x11289)*(x11290)))+(((IkReal(-1.00000000000000))*(x11287)*(x11292)))+(((IkReal(-1.00000000000000))*(r01)*(x11287)*(x11289)))+(((IkReal(-1.00000000000000))*(x11288)*(x11290)))+(((cj0)*(x11286)))));
36343 sj3array[0]=IKsin(j3array[0]);
36344 cj3array[0]=IKcos(j3array[0]);
36345 if( j3array[0] > IKPI )
36346 {
36347     j3array[0]-=IK2PI;
36348 }
36349 else if( j3array[0] < -IKPI )
36350 {    j3array[0]+=IK2PI;
36351 }
36352 j3valid[0] = true;
36353 for(int ij3 = 0; ij3 < 1; ++ij3)
36354 {
36355 if( !j3valid[ij3] )
36356 {
36357     continue;
36358 }
36359 _ij3[0] = ij3; _ij3[1] = -1;
36360 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36361 {
36362 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36363 {
36364     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36365 }
36366 }
36367 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36368 {
36369 IkReal evalcond[4];
36370 IkReal x11293=IKsin(j3);
36371 IkReal x11294=((sj0)*(sj5));
36372 IkReal x11295=((r00)*(sj6));
36373 IkReal x11296=((IkReal(1.00000000000000))*(cj4));
36374 IkReal x11297=((cj6)*(sj0));
36375 IkReal x11298=((r00)*(sj4));
36376 IkReal x11299=((cj0)*(cj5));
36377 IkReal x11300=((cj6)*(r01));
36378 IkReal x11301=((cj5)*(sj0));
36379 IkReal x11302=((cj0)*(sj5));
36380 IkReal x11303=((cj6)*(r11));
36381 IkReal x11304=((r10)*(sj6));
36382 IkReal x11305=((r10)*(sj4));
36383 IkReal x11306=((IkReal(1.00000000000000))*(IKcos(j3)));
36384 IkReal x11307=((cj0)*(sj4)*(sj6));
36385 IkReal x11308=((sj0)*(sj4)*(sj6));
36386 IkReal x11309=((IkReal(1.00000000000000))*(cj0)*(cj6));
36387 evalcond[0]=((((x11294)*(x11300)))+(((IkReal(-1.00000000000000))*(x11302)*(x11303)))+(((r12)*(x11299)))+(((IkReal(-1.00000000000000))*(x11302)*(x11304)))+(((x11294)*(x11295)))+(x11293)+(((IkReal(-1.00000000000000))*(r02)*(x11301))));
36388 evalcond[1]=((((IkReal(-1.00000000000000))*(x11294)*(x11304)))+(((IkReal(-1.00000000000000))*(x11300)*(x11302)))+(((IkReal(-1.00000000000000))*(x11295)*(x11302)))+(((IkReal(-1.00000000000000))*(x11294)*(x11303)))+(((r02)*(x11299)))+(((r12)*(x11301)))+(((IkReal(-1.00000000000000))*(x11306))));
36389 evalcond[2]=((((cj4)*(r02)*(x11294)))+(((cj4)*(x11295)*(x11301)))+(((IkReal(-1.00000000000000))*(x11296)*(x11299)*(x11303)))+(((cj4)*(cj5)*(r01)*(x11297)))+(((IkReal(-1.00000000000000))*(x11305)*(x11309)))+(((IkReal(-1.00000000000000))*(x11296)*(x11299)*(x11304)))+(((IkReal(-1.00000000000000))*(r12)*(x11296)*(x11302)))+(((IkReal(-1.00000000000000))*(r01)*(x11308)))+(((r11)*(x11307)))+(((IkReal(-1.00000000000000))*(x11306)))+(((x11297)*(x11298))));
36390 evalcond[3]=((((r11)*(x11308)))+(((IkReal(-1.00000000000000))*(x11297)*(x11305)))+(((r01)*(x11307)))+(((IkReal(-1.00000000000000))*(x11298)*(x11309)))+(((IkReal(-1.00000000000000))*(x11293)))+(((IkReal(-1.00000000000000))*(x11296)*(x11299)*(x11300)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x11296)*(x11297)))+(((IkReal(-1.00000000000000))*(x11296)*(x11301)*(x11304)))+(((IkReal(-1.00000000000000))*(x11295)*(x11296)*(x11299)))+(((IkReal(-1.00000000000000))*(r02)*(x11296)*(x11302)))+(((IkReal(-1.00000000000000))*(r12)*(x11294)*(x11296))));
36391 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
36392 {
36393 continue;
36394 }
36395 }
36396 
36397 {
36398 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36399 vinfos[0].jointtype = 1;
36400 vinfos[0].foffset = j0;
36401 vinfos[0].indices[0] = _ij0[0];
36402 vinfos[0].indices[1] = _ij0[1];
36403 vinfos[0].maxsolutions = _nj0;
36404 vinfos[1].jointtype = 1;
36405 vinfos[1].foffset = j1;
36406 vinfos[1].indices[0] = _ij1[0];
36407 vinfos[1].indices[1] = _ij1[1];
36408 vinfos[1].maxsolutions = _nj1;
36409 vinfos[2].jointtype = 1;
36410 vinfos[2].foffset = j2;
36411 vinfos[2].indices[0] = _ij2[0];
36412 vinfos[2].indices[1] = _ij2[1];
36413 vinfos[2].maxsolutions = _nj2;
36414 vinfos[3].jointtype = 1;
36415 vinfos[3].foffset = j3;
36416 vinfos[3].indices[0] = _ij3[0];
36417 vinfos[3].indices[1] = _ij3[1];
36418 vinfos[3].maxsolutions = _nj3;
36419 vinfos[4].jointtype = 1;
36420 vinfos[4].foffset = j4;
36421 vinfos[4].indices[0] = _ij4[0];
36422 vinfos[4].indices[1] = _ij4[1];
36423 vinfos[4].maxsolutions = _nj4;
36424 vinfos[5].jointtype = 1;
36425 vinfos[5].foffset = j5;
36426 vinfos[5].indices[0] = _ij5[0];
36427 vinfos[5].indices[1] = _ij5[1];
36428 vinfos[5].maxsolutions = _nj5;
36429 vinfos[6].jointtype = 1;
36430 vinfos[6].foffset = j6;
36431 vinfos[6].indices[0] = _ij6[0];
36432 vinfos[6].indices[1] = _ij6[1];
36433 vinfos[6].maxsolutions = _nj6;
36434 std::vector<int> vfree(0);
36435 solutions.AddSolution(vinfos,vfree);
36436 }
36437 }
36438 }
36439 
36440 } else
36441 {
36442 if( 1 )
36443 {
36444 continue;
36445 
36446 } else
36447 {
36448 }
36449 }
36450 }
36451 }
36452 }
36453 }
36454 
36455 } else
36456 {
36457 {
36458 IkReal j3array[1], cj3array[1], sj3array[1];
36459 bool j3valid[1]={false};
36460 _nj3 = 1;
36461 IkReal x11310=((cj0)*(cj5));
36462 IkReal x11311=((IkReal(1.00000000000000))*(cj0));
36463 IkReal x11312=((cj6)*(r11));
36464 IkReal x11313=((r10)*(sj6));
36465 IkReal x11314=((cj5)*(sj0));
36466 IkReal x11315=((r00)*(sj5)*(sj6));
36467 IkReal x11316=((cj6)*(r01)*(sj5));
36468 IkReal x11317=((IkReal(1.00000000000000))*(sj0)*(sj5));
36469 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x11310)))+(((IkReal(-1.00000000000000))*(r02)*(x11314)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11312)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11313)))+(((sj0)*(x11315)))+(((sj0)*(x11316))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x11312)*(x11317)))+(((r02)*(x11310)))+(((IkReal(-1.00000000000000))*(x11313)*(x11317)))+(((IkReal(-1.00000000000000))*(x11311)*(x11315)))+(((IkReal(-1.00000000000000))*(x11311)*(x11316)))+(((r12)*(x11314))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x11310)))+(((IkReal(-1.00000000000000))*(r02)*(x11314)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11312)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11313)))+(((sj0)*(x11315)))+(((sj0)*(x11316)))))))+IKsqr(((((IkReal(-1.00000000000000))*(x11312)*(x11317)))+(((r02)*(x11310)))+(((IkReal(-1.00000000000000))*(x11313)*(x11317)))+(((IkReal(-1.00000000000000))*(x11311)*(x11315)))+(((IkReal(-1.00000000000000))*(x11311)*(x11316)))+(((r12)*(x11314)))))-1) <= IKFAST_SINCOS_THRESH )
36470     continue;
36471 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x11310)))+(((IkReal(-1.00000000000000))*(r02)*(x11314)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11312)))+(((IkReal(-1.00000000000000))*(sj5)*(x11311)*(x11313)))+(((sj0)*(x11315)))+(((sj0)*(x11316)))))), ((((IkReal(-1.00000000000000))*(x11312)*(x11317)))+(((r02)*(x11310)))+(((IkReal(-1.00000000000000))*(x11313)*(x11317)))+(((IkReal(-1.00000000000000))*(x11311)*(x11315)))+(((IkReal(-1.00000000000000))*(x11311)*(x11316)))+(((r12)*(x11314)))));
36472 sj3array[0]=IKsin(j3array[0]);
36473 cj3array[0]=IKcos(j3array[0]);
36474 if( j3array[0] > IKPI )
36475 {
36476     j3array[0]-=IK2PI;
36477 }
36478 else if( j3array[0] < -IKPI )
36479 {    j3array[0]+=IK2PI;
36480 }
36481 j3valid[0] = true;
36482 for(int ij3 = 0; ij3 < 1; ++ij3)
36483 {
36484 if( !j3valid[ij3] )
36485 {
36486     continue;
36487 }
36488 _ij3[0] = ij3; _ij3[1] = -1;
36489 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36490 {
36491 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36492 {
36493     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36494 }
36495 }
36496 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36497 {
36498 IkReal evalcond[6];
36499 IkReal x11318=IKsin(j3);
36500 IkReal x11319=IKcos(j3);
36501 IkReal x11320=((sj0)*(sj5));
36502 IkReal x11321=((r00)*(sj6));
36503 IkReal x11322=((IkReal(1.00000000000000))*(cj4));
36504 IkReal x11323=((cj6)*(r01));
36505 IkReal x11324=((cj0)*(cj5));
36506 IkReal x11325=((cj5)*(sj0));
36507 IkReal x11326=((cj6)*(r11));
36508 IkReal x11327=((cj0)*(sj5));
36509 IkReal x11328=((cj6)*(sj4));
36510 IkReal x11329=((cj4)*(cj5));
36511 IkReal x11330=((cj6)*(r21));
36512 IkReal x11331=((r20)*(sj6));
36513 IkReal x11332=((r10)*(sj6));
36514 IkReal x11333=((IkReal(1.00000000000000))*(cj0));
36515 IkReal x11334=((IkReal(1.00000000000000))*(x11318));
36516 IkReal x11335=((cj0)*(sj4)*(sj6));
36517 IkReal x11336=((sj0)*(sj4)*(sj6));
36518 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x11334)))+(((sj5)*(x11331)))+(((sj5)*(x11330)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
36519 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x11328)))+(((x11329)*(x11331)))+(((cj2)*(x11319)))+(((x11329)*(x11330))));
36520 evalcond[2]=((((x11320)*(x11323)))+(((x11320)*(x11321)))+(((r12)*(x11324)))+(((IkReal(-1.00000000000000))*(sj2)*(x11334)))+(((IkReal(-1.00000000000000))*(r02)*(x11325)))+(((IkReal(-1.00000000000000))*(x11326)*(x11327)))+(((IkReal(-1.00000000000000))*(x11327)*(x11332))));
36521 evalcond[3]=((((r12)*(x11325)))+(((IkReal(-1.00000000000000))*(x11320)*(x11326)))+(((IkReal(-1.00000000000000))*(x11320)*(x11332)))+(((IkReal(-1.00000000000000))*(x11321)*(x11327)))+(((IkReal(-1.00000000000000))*(x11323)*(x11327)))+(((r02)*(x11324)))+(((IkReal(-1.00000000000000))*(x11319))));
36522 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x11328)*(x11333)))+(((IkReal(-1.00000000000000))*(r01)*(x11336)))+(((r11)*(x11335)))+(((cj4)*(r02)*(x11320)))+(((r00)*(sj0)*(x11328)))+(((IkReal(-1.00000000000000))*(x11322)*(x11324)*(x11332)))+(((IkReal(-1.00000000000000))*(r12)*(x11322)*(x11327)))+(((sj2)*(x11319)))+(((cj4)*(x11321)*(x11325)))+(((IkReal(-1.00000000000000))*(x11322)*(x11324)*(x11326)))+(((cj4)*(x11323)*(x11325))));
36523 evalcond[5]=((((IkReal(-1.00000000000000))*(x11322)*(x11325)*(x11332)))+(((IkReal(-1.00000000000000))*(r02)*(x11322)*(x11327)))+(((IkReal(-1.00000000000000))*(x11322)*(x11323)*(x11324)))+(((r11)*(x11336)))+(((IkReal(-1.00000000000000))*(x11322)*(x11325)*(x11326)))+(((IkReal(-1.00000000000000))*(r12)*(x11320)*(x11322)))+(((r01)*(x11335)))+(((IkReal(-1.00000000000000))*(x11334)))+(((IkReal(-1.00000000000000))*(r00)*(x11328)*(x11333)))+(((IkReal(-1.00000000000000))*(x11321)*(x11322)*(x11324)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11328))));
36524 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
36525 {
36526 continue;
36527 }
36528 }
36529 
36530 {
36531 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36532 vinfos[0].jointtype = 1;
36533 vinfos[0].foffset = j0;
36534 vinfos[0].indices[0] = _ij0[0];
36535 vinfos[0].indices[1] = _ij0[1];
36536 vinfos[0].maxsolutions = _nj0;
36537 vinfos[1].jointtype = 1;
36538 vinfos[1].foffset = j1;
36539 vinfos[1].indices[0] = _ij1[0];
36540 vinfos[1].indices[1] = _ij1[1];
36541 vinfos[1].maxsolutions = _nj1;
36542 vinfos[2].jointtype = 1;
36543 vinfos[2].foffset = j2;
36544 vinfos[2].indices[0] = _ij2[0];
36545 vinfos[2].indices[1] = _ij2[1];
36546 vinfos[2].maxsolutions = _nj2;
36547 vinfos[3].jointtype = 1;
36548 vinfos[3].foffset = j3;
36549 vinfos[3].indices[0] = _ij3[0];
36550 vinfos[3].indices[1] = _ij3[1];
36551 vinfos[3].maxsolutions = _nj3;
36552 vinfos[4].jointtype = 1;
36553 vinfos[4].foffset = j4;
36554 vinfos[4].indices[0] = _ij4[0];
36555 vinfos[4].indices[1] = _ij4[1];
36556 vinfos[4].maxsolutions = _nj4;
36557 vinfos[5].jointtype = 1;
36558 vinfos[5].foffset = j5;
36559 vinfos[5].indices[0] = _ij5[0];
36560 vinfos[5].indices[1] = _ij5[1];
36561 vinfos[5].maxsolutions = _nj5;
36562 vinfos[6].jointtype = 1;
36563 vinfos[6].foffset = j6;
36564 vinfos[6].indices[0] = _ij6[0];
36565 vinfos[6].indices[1] = _ij6[1];
36566 vinfos[6].maxsolutions = _nj6;
36567 std::vector<int> vfree(0);
36568 solutions.AddSolution(vinfos,vfree);
36569 }
36570 }
36571 }
36572 
36573 }
36574 
36575 }
36576 
36577 } else
36578 {
36579 {
36580 IkReal j3array[1], cj3array[1], sj3array[1];
36581 bool j3valid[1]={false};
36582 _nj3 = 1;
36583 IkReal x11337=((sj5)*(sj6));
36584 IkReal x11338=((IkReal(1.00000000000000))*(cj6)*(sj5));
36585 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x11337)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11337)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x11338)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11337)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x11338))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x11337)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11337)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x11338)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11337)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x11338)))))-1) <= IKFAST_SINCOS_THRESH )
36586     continue;
36587 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((r20)*(x11337)))+(((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))), ((((cj0)*(cj5)*(r02)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11337)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x11338)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11337)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x11338)))));
36588 sj3array[0]=IKsin(j3array[0]);
36589 cj3array[0]=IKcos(j3array[0]);
36590 if( j3array[0] > IKPI )
36591 {
36592     j3array[0]-=IK2PI;
36593 }
36594 else if( j3array[0] < -IKPI )
36595 {    j3array[0]+=IK2PI;
36596 }
36597 j3valid[0] = true;
36598 for(int ij3 = 0; ij3 < 1; ++ij3)
36599 {
36600 if( !j3valid[ij3] )
36601 {
36602     continue;
36603 }
36604 _ij3[0] = ij3; _ij3[1] = -1;
36605 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36606 {
36607 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36608 {
36609     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36610 }
36611 }
36612 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36613 {
36614 IkReal evalcond[6];
36615 IkReal x11339=IKsin(j3);
36616 IkReal x11340=IKcos(j3);
36617 IkReal x11341=((sj0)*(sj5));
36618 IkReal x11342=((r00)*(sj6));
36619 IkReal x11343=((IkReal(1.00000000000000))*(cj4));
36620 IkReal x11344=((cj6)*(r01));
36621 IkReal x11345=((cj0)*(cj5));
36622 IkReal x11346=((cj5)*(sj0));
36623 IkReal x11347=((cj6)*(r11));
36624 IkReal x11348=((cj0)*(sj5));
36625 IkReal x11349=((cj6)*(sj4));
36626 IkReal x11350=((cj4)*(cj5));
36627 IkReal x11351=((cj6)*(r21));
36628 IkReal x11352=((r20)*(sj6));
36629 IkReal x11353=((r10)*(sj6));
36630 IkReal x11354=((IkReal(1.00000000000000))*(cj0));
36631 IkReal x11355=((IkReal(1.00000000000000))*(x11339));
36632 IkReal x11356=((cj0)*(sj4)*(sj6));
36633 IkReal x11357=((sj0)*(sj4)*(sj6));
36634 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x11355)))+(((sj5)*(x11351)))+(((sj5)*(x11352))));
36635 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11350)*(x11352)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x11349)))+(((x11350)*(x11351)))+(((cj2)*(x11340))));
36636 evalcond[2]=((((x11341)*(x11342)))+(((r12)*(x11345)))+(((IkReal(-1.00000000000000))*(x11347)*(x11348)))+(((IkReal(-1.00000000000000))*(r02)*(x11346)))+(((IkReal(-1.00000000000000))*(sj2)*(x11355)))+(((x11341)*(x11344)))+(((IkReal(-1.00000000000000))*(x11348)*(x11353))));
36637 evalcond[3]=((((IkReal(-1.00000000000000))*(x11342)*(x11348)))+(((IkReal(-1.00000000000000))*(x11340)))+(((IkReal(-1.00000000000000))*(x11341)*(x11353)))+(((IkReal(-1.00000000000000))*(x11344)*(x11348)))+(((IkReal(-1.00000000000000))*(x11341)*(x11347)))+(((r12)*(x11346)))+(((r02)*(x11345))));
36638 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x11349)*(x11354)))+(((IkReal(-1.00000000000000))*(x11343)*(x11345)*(x11347)))+(((cj4)*(x11344)*(x11346)))+(((cj4)*(r02)*(x11341)))+(((sj2)*(x11340)))+(((IkReal(-1.00000000000000))*(x11343)*(x11345)*(x11353)))+(((IkReal(-1.00000000000000))*(r01)*(x11357)))+(((r00)*(sj0)*(x11349)))+(((r11)*(x11356)))+(((cj4)*(x11342)*(x11346)))+(((IkReal(-1.00000000000000))*(r12)*(x11343)*(x11348))));
36639 evalcond[5]=((((IkReal(-1.00000000000000))*(x11343)*(x11346)*(x11347)))+(((IkReal(-1.00000000000000))*(x11355)))+(((r01)*(x11356)))+(((IkReal(-1.00000000000000))*(x11343)*(x11344)*(x11345)))+(((IkReal(-1.00000000000000))*(r12)*(x11341)*(x11343)))+(((IkReal(-1.00000000000000))*(r02)*(x11343)*(x11348)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11349)))+(((IkReal(-1.00000000000000))*(x11343)*(x11346)*(x11353)))+(((IkReal(-1.00000000000000))*(x11342)*(x11343)*(x11345)))+(((r11)*(x11357)))+(((IkReal(-1.00000000000000))*(r00)*(x11349)*(x11354))));
36640 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
36641 {
36642 continue;
36643 }
36644 }
36645 
36646 {
36647 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36648 vinfos[0].jointtype = 1;
36649 vinfos[0].foffset = j0;
36650 vinfos[0].indices[0] = _ij0[0];
36651 vinfos[0].indices[1] = _ij0[1];
36652 vinfos[0].maxsolutions = _nj0;
36653 vinfos[1].jointtype = 1;
36654 vinfos[1].foffset = j1;
36655 vinfos[1].indices[0] = _ij1[0];
36656 vinfos[1].indices[1] = _ij1[1];
36657 vinfos[1].maxsolutions = _nj1;
36658 vinfos[2].jointtype = 1;
36659 vinfos[2].foffset = j2;
36660 vinfos[2].indices[0] = _ij2[0];
36661 vinfos[2].indices[1] = _ij2[1];
36662 vinfos[2].maxsolutions = _nj2;
36663 vinfos[3].jointtype = 1;
36664 vinfos[3].foffset = j3;
36665 vinfos[3].indices[0] = _ij3[0];
36666 vinfos[3].indices[1] = _ij3[1];
36667 vinfos[3].maxsolutions = _nj3;
36668 vinfos[4].jointtype = 1;
36669 vinfos[4].foffset = j4;
36670 vinfos[4].indices[0] = _ij4[0];
36671 vinfos[4].indices[1] = _ij4[1];
36672 vinfos[4].maxsolutions = _nj4;
36673 vinfos[5].jointtype = 1;
36674 vinfos[5].foffset = j5;
36675 vinfos[5].indices[0] = _ij5[0];
36676 vinfos[5].indices[1] = _ij5[1];
36677 vinfos[5].maxsolutions = _nj5;
36678 vinfos[6].jointtype = 1;
36679 vinfos[6].foffset = j6;
36680 vinfos[6].indices[0] = _ij6[0];
36681 vinfos[6].indices[1] = _ij6[1];
36682 vinfos[6].maxsolutions = _nj6;
36683 std::vector<int> vfree(0);
36684 solutions.AddSolution(vinfos,vfree);
36685 }
36686 }
36687 }
36688 
36689 }
36690 
36691 }
36692 
36693 } else
36694 {
36695 {
36696 IkReal j3array[1], cj3array[1], sj3array[1];
36697 bool j3valid[1]={false};
36698 _nj3 = 1;
36699 IkReal x11358=((IkReal(1.00000000000000))*(cj4));
36700 IkReal x11359=((cj6)*(r21));
36701 IkReal x11360=((r20)*(sj6));
36702 if( IKabs(((gconst9)*(((((sj5)*(x11360)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11359))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x11358)*(x11360)))+(((IkReal(-1.00000000000000))*(cj5)*(x11358)*(x11359)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11358)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
36703     continue;
36704 j3array[0]=IKatan2(((gconst9)*(((((sj5)*(x11360)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11359)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x11358)*(x11360)))+(((IkReal(-1.00000000000000))*(cj5)*(x11358)*(x11359)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11358)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
36705 sj3array[0]=IKsin(j3array[0]);
36706 cj3array[0]=IKcos(j3array[0]);
36707 if( j3array[0] > IKPI )
36708 {
36709     j3array[0]-=IK2PI;
36710 }
36711 else if( j3array[0] < -IKPI )
36712 {    j3array[0]+=IK2PI;
36713 }
36714 j3valid[0] = true;
36715 for(int ij3 = 0; ij3 < 1; ++ij3)
36716 {
36717 if( !j3valid[ij3] )
36718 {
36719     continue;
36720 }
36721 _ij3[0] = ij3; _ij3[1] = -1;
36722 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36723 {
36724 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36725 {
36726     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36727 }
36728 }
36729 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36730 {
36731 IkReal evalcond[6];
36732 IkReal x11361=IKsin(j3);
36733 IkReal x11362=IKcos(j3);
36734 IkReal x11363=((sj0)*(sj5));
36735 IkReal x11364=((r00)*(sj6));
36736 IkReal x11365=((IkReal(1.00000000000000))*(cj4));
36737 IkReal x11366=((cj6)*(r01));
36738 IkReal x11367=((cj0)*(cj5));
36739 IkReal x11368=((cj5)*(sj0));
36740 IkReal x11369=((cj6)*(r11));
36741 IkReal x11370=((cj0)*(sj5));
36742 IkReal x11371=((cj6)*(sj4));
36743 IkReal x11372=((cj4)*(cj5));
36744 IkReal x11373=((cj6)*(r21));
36745 IkReal x11374=((r20)*(sj6));
36746 IkReal x11375=((r10)*(sj6));
36747 IkReal x11376=((IkReal(1.00000000000000))*(cj0));
36748 IkReal x11377=((IkReal(1.00000000000000))*(x11361));
36749 IkReal x11378=((cj0)*(sj4)*(sj6));
36750 IkReal x11379=((sj0)*(sj4)*(sj6));
36751 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x11377)))+(((sj5)*(x11374)))+(((sj5)*(x11373))));
36752 evalcond[1]=((((x11372)*(x11374)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x11362)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x11371)))+(((x11372)*(x11373))));
36753 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x11377)))+(((r12)*(x11367)))+(((IkReal(-1.00000000000000))*(x11370)*(x11375)))+(((x11363)*(x11366)))+(((x11363)*(x11364)))+(((IkReal(-1.00000000000000))*(x11369)*(x11370)))+(((IkReal(-1.00000000000000))*(r02)*(x11368))));
36754 evalcond[3]=((((IkReal(-1.00000000000000))*(x11363)*(x11369)))+(((IkReal(-1.00000000000000))*(x11362)))+(((IkReal(-1.00000000000000))*(x11366)*(x11370)))+(((r02)*(x11367)))+(((r12)*(x11368)))+(((IkReal(-1.00000000000000))*(x11363)*(x11375)))+(((IkReal(-1.00000000000000))*(x11364)*(x11370))));
36755 evalcond[4]=((((IkReal(-1.00000000000000))*(x11365)*(x11367)*(x11369)))+(((r11)*(x11378)))+(((IkReal(-1.00000000000000))*(x11365)*(x11367)*(x11375)))+(((IkReal(-1.00000000000000))*(r01)*(x11379)))+(((cj4)*(x11364)*(x11368)))+(((cj4)*(r02)*(x11363)))+(((r00)*(sj0)*(x11371)))+(((sj2)*(x11362)))+(((IkReal(-1.00000000000000))*(r12)*(x11365)*(x11370)))+(((cj4)*(x11366)*(x11368)))+(((IkReal(-1.00000000000000))*(r10)*(x11371)*(x11376))));
36756 evalcond[5]=((((IkReal(-1.00000000000000))*(x11365)*(x11368)*(x11369)))+(((IkReal(-1.00000000000000))*(r02)*(x11365)*(x11370)))+(((IkReal(-1.00000000000000))*(r12)*(x11363)*(x11365)))+(((r11)*(x11379)))+(((IkReal(-1.00000000000000))*(x11365)*(x11368)*(x11375)))+(((IkReal(-1.00000000000000))*(x11364)*(x11365)*(x11367)))+(((IkReal(-1.00000000000000))*(x11377)))+(((r01)*(x11378)))+(((IkReal(-1.00000000000000))*(x11365)*(x11366)*(x11367)))+(((IkReal(-1.00000000000000))*(r00)*(x11371)*(x11376)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11371))));
36757 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
36758 {
36759 continue;
36760 }
36761 }
36762 
36763 {
36764 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36765 vinfos[0].jointtype = 1;
36766 vinfos[0].foffset = j0;
36767 vinfos[0].indices[0] = _ij0[0];
36768 vinfos[0].indices[1] = _ij0[1];
36769 vinfos[0].maxsolutions = _nj0;
36770 vinfos[1].jointtype = 1;
36771 vinfos[1].foffset = j1;
36772 vinfos[1].indices[0] = _ij1[0];
36773 vinfos[1].indices[1] = _ij1[1];
36774 vinfos[1].maxsolutions = _nj1;
36775 vinfos[2].jointtype = 1;
36776 vinfos[2].foffset = j2;
36777 vinfos[2].indices[0] = _ij2[0];
36778 vinfos[2].indices[1] = _ij2[1];
36779 vinfos[2].maxsolutions = _nj2;
36780 vinfos[3].jointtype = 1;
36781 vinfos[3].foffset = j3;
36782 vinfos[3].indices[0] = _ij3[0];
36783 vinfos[3].indices[1] = _ij3[1];
36784 vinfos[3].maxsolutions = _nj3;
36785 vinfos[4].jointtype = 1;
36786 vinfos[4].foffset = j4;
36787 vinfos[4].indices[0] = _ij4[0];
36788 vinfos[4].indices[1] = _ij4[1];
36789 vinfos[4].maxsolutions = _nj4;
36790 vinfos[5].jointtype = 1;
36791 vinfos[5].foffset = j5;
36792 vinfos[5].indices[0] = _ij5[0];
36793 vinfos[5].indices[1] = _ij5[1];
36794 vinfos[5].maxsolutions = _nj5;
36795 vinfos[6].jointtype = 1;
36796 vinfos[6].foffset = j6;
36797 vinfos[6].indices[0] = _ij6[0];
36798 vinfos[6].indices[1] = _ij6[1];
36799 vinfos[6].maxsolutions = _nj6;
36800 std::vector<int> vfree(0);
36801 solutions.AddSolution(vinfos,vfree);
36802 }
36803 }
36804 }
36805 
36806 }
36807 
36808 }
36809 
36810 } else
36811 {
36812 IkReal x11380=((IkReal(1.00000000000000))*(cj0));
36813 IkReal x11381=((cj4)*(sj6));
36814 IkReal x11382=((sj0)*(sj4));
36815 IkReal x11383=((cj5)*(sj6));
36816 IkReal x11384=((sj4)*(sj5));
36817 IkReal x11385=((r12)*(sj5));
36818 IkReal x11386=((IkReal(0.374290000000000))*(cj5));
36819 IkReal x11387=((r02)*(sj0));
36820 IkReal x11388=((IkReal(1.00000000000000))*(sj0));
36821 IkReal x11389=((cj0)*(r10));
36822 IkReal x11390=((cj4)*(cj6));
36823 IkReal x11391=((r00)*(sj0));
36824 IkReal x11392=((cj6)*(r21));
36825 IkReal x11393=((IkReal(0.374290000000000))*(sj5));
36826 IkReal x11394=((cj0)*(r00));
36827 IkReal x11395=((IkReal(0.0100000000000000))*(sj5));
36828 IkReal x11396=((cj0)*(r02));
36829 IkReal x11397=((cj5)*(sj4));
36830 IkReal x11398=((cj6)*(r01));
36831 IkReal x11399=((cj6)*(r11));
36832 IkReal x11400=((r01)*(sj0));
36833 IkReal x11401=((r10)*(sj0));
36834 IkReal x11402=((IkReal(0.0100000000000000))*(cj5)*(cj6));
36835 IkReal x11403=((sj6)*(x11393));
36836 IkReal x11404=((cj0)*(cj6)*(x11393));
36837 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
36838 evalcond[1]=((((x11392)*(x11397)))+(((r22)*(x11384)))+(sj2)+(((r21)*(x11381)))+(((r20)*(sj4)*(x11383)))+(((IkReal(-1.00000000000000))*(r20)*(x11390))));
36839 evalcond[2]=((((x11392)*(x11393)))+(((IkReal(-0.0100000000000000))*(cj5)*(x11392)))+(((IkReal(-0.0690000000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(r22)*(x11386)))+(((IkReal(-0.0100000000000000))*(r20)*(x11383)))+(pz)+(((r20)*(x11403)))+(((IkReal(-1.00000000000000))*(r22)*(x11395))));
36840 evalcond[3]=((((r00)*(x11382)*(x11383)))+(((IkReal(-1.00000000000000))*(x11380)*(x11397)*(x11399)))+(((x11389)*(x11390)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11380)*(x11383)))+(((IkReal(-1.00000000000000))*(r12)*(x11380)*(x11384)))+(((IkReal(-1.00000000000000))*(r11)*(x11380)*(x11381)))+(((x11381)*(x11400)))+(((r02)*(sj5)*(x11382)))+(((cj5)*(x11382)*(x11398)))+(cj2)+(((IkReal(-1.00000000000000))*(r00)*(x11388)*(x11390))));
36841 evalcond[4]=((((x11390)*(x11394)))+(((x11390)*(x11401)))+(((IkReal(-1.00000000000000))*(r10)*(x11382)*(x11383)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11380)*(x11383)))+(((IkReal(-1.00000000000000))*(r02)*(x11380)*(x11384)))+(((IkReal(-1.00000000000000))*(x11382)*(x11385)))+(((IkReal(-1.00000000000000))*(cj5)*(x11382)*(x11399)))+(((IkReal(-1.00000000000000))*(r11)*(x11381)*(x11388)))+(((IkReal(-1.00000000000000))*(x11380)*(x11397)*(x11398)))+(((IkReal(-1.00000000000000))*(r01)*(x11380)*(x11381))));
36842 evalcond[5]=((((IkReal(-1.00000000000000))*(x11389)*(x11403)))+(((IkReal(0.0100000000000000))*(x11383)*(x11389)))+(((IkReal(-1.00000000000000))*(py)*(x11380)))+(((IkReal(-0.0100000000000000))*(x11383)*(x11391)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11399)))+(((cj0)*(r12)*(x11386)))+(((IkReal(0.0100000000000000))*(cj0)*(x11385)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(cj0)*(x11393)*(x11399)))+(((x11391)*(x11403)))+(((sj0)*(x11393)*(x11398)))+(((IkReal(-1.00000000000000))*(x11387)*(x11395)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x11386)*(x11387)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11398))));
36843 evalcond[6]=((IkReal(-0.295420000000000))+(((r12)*(sj0)*(x11386)))+(((IkReal(-1.00000000000000))*(x11401)*(x11403)))+(((IkReal(0.0100000000000000))*(x11383)*(x11394)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11398)))+(((IkReal(0.0100000000000000))*(x11383)*(x11401)))+(((IkReal(-1.00000000000000))*(px)*(x11380)))+(((x11395)*(x11396)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11399)))+(((IkReal(-1.00000000000000))*(x11394)*(x11403)))+(((x11386)*(x11396)))+(((IkReal(-1.00000000000000))*(cj0)*(x11393)*(x11398)))+(((IkReal(-1.00000000000000))*(py)*(x11388)))+(((IkReal(0.0100000000000000))*(sj0)*(x11385)))+(((IkReal(-1.00000000000000))*(sj0)*(x11393)*(x11399))));
36844 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
36845 {
36846 {
36847 IkReal dummyeval[1];
36848 IkReal gconst10;
36849 gconst10=IKsign(cj2);
36850 dummyeval[0]=cj2;
36851 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
36852 {
36853 {
36854 IkReal dummyeval[1];
36855 dummyeval[0]=cj2;
36856 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
36857 {
36858 {
36859 IkReal dummyeval[1];
36860 dummyeval[0]=sj2;
36861 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
36862 {
36863 {
36864 IkReal evalcond[9];
36865 IkReal x11405=((cj5)*(sj4));
36866 IkReal x11406=((IkReal(1.00000000000000))*(sj6));
36867 IkReal x11407=((r10)*(sj0));
36868 IkReal x11408=((sj4)*(sj5));
36869 IkReal x11409=((cj5)*(cj6));
36870 IkReal x11410=((r01)*(sj0));
36871 IkReal x11411=((IkReal(1.00000000000000))*(r02));
36872 IkReal x11412=((IkReal(0.374290000000000))*(cj0));
36873 IkReal x11413=((cj5)*(r12));
36874 IkReal x11414=((cj6)*(sj5));
36875 IkReal x11415=((cj0)*(r11));
36876 IkReal x11416=((cj5)*(sj0));
36877 IkReal x11417=((r20)*(sj6));
36878 IkReal x11418=((IkReal(1.00000000000000))*(sj0));
36879 IkReal x11419=((cj4)*(cj5));
36880 IkReal x11420=((IkReal(1.00000000000000))*(cj6));
36881 IkReal x11421=((IkReal(0.0100000000000000))*(sj5));
36882 IkReal x11422=((sj5)*(sj6));
36883 IkReal x11423=((cj0)*(r10));
36884 IkReal x11424=((cj4)*(cj6));
36885 IkReal x11425=((cj0)*(r01));
36886 IkReal x11426=((IkReal(1.00000000000000))*(cj4));
36887 IkReal x11427=((cj0)*(r00));
36888 IkReal x11428=((IkReal(0.374290000000000))*(sj0));
36889 IkReal x11429=((cj0)*(r12));
36890 IkReal x11430=((IkReal(0.374290000000000))*(sj5));
36891 IkReal x11431=((cj4)*(sj6));
36892 IkReal x11432=((IkReal(1.00000000000000))*(cj0));
36893 IkReal x11433=((r02)*(sj0));
36894 IkReal x11434=((IkReal(0.0100000000000000))*(cj5));
36895 IkReal x11435=((r11)*(sj0));
36896 IkReal x11436=((r00)*(sj0)*(sj6));
36897 IkReal x11437=((r00)*(x11424));
36898 IkReal x11438=((sj6)*(x11434));
36899 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
36900 evalcond[1]=((((cj6)*(r21)*(x11405)))+(((r22)*(x11408)))+(((r21)*(x11431)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x11420)))+(((x11405)*(x11417))));
36901 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x11414)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x11417)*(x11430)))+(((IkReal(-1.00000000000000))*(r22)*(x11421)))+(((IkReal(-0.0100000000000000))*(r21)*(x11409)))+(pz)+(((IkReal(-1.00000000000000))*(x11417)*(x11434))));
36902 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x11406)*(x11423)))+(((IkReal(-1.00000000000000))*(x11411)*(x11416)))+(((IkReal(-1.00000000000000))*(x11414)*(x11415)))+(((r00)*(sj0)*(x11422)))+(((x11410)*(x11414)))+(((cj0)*(x11413))));
36903 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x11418)*(x11437)))+(((IkReal(-1.00000000000000))*(x11405)*(x11415)*(x11420)))+(((x11405)*(x11436)))+(((IkReal(-1.00000000000000))*(x11408)*(x11429)))+(((IkReal(-1.00000000000000))*(x11405)*(x11406)*(x11423)))+(((IkReal(-1.00000000000000))*(cj4)*(x11406)*(x11415)))+(((x11408)*(x11433)))+(((x11423)*(x11424)))+(((x11410)*(x11431)))+(((cj6)*(x11405)*(x11410))));
36904 evalcond[5]=((((IkReal(-1.00000000000000))*(x11406)*(x11419)*(x11423)))+(((cj4)*(sj5)*(x11433)))+(((IkReal(-1.00000000000000))*(sj4)*(x11420)*(x11423)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(x11409)*(x11410)))+(((IkReal(-1.00000000000000))*(sj4)*(x11406)*(x11410)))+(((r00)*(x11416)*(x11431)))+(((IkReal(-1.00000000000000))*(x11409)*(x11415)*(x11426)))+(((sj4)*(sj6)*(x11415)))+(((IkReal(-1.00000000000000))*(sj5)*(x11426)*(x11429))));
36905 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x11406)*(x11435)))+(((x11424)*(x11427)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x11405)*(x11418)))+(((IkReal(-1.00000000000000))*(r12)*(x11408)*(x11418)))+(((x11407)*(x11424)))+(((IkReal(-1.00000000000000))*(cj0)*(x11408)*(x11411)))+(((IkReal(-1.00000000000000))*(x11405)*(x11406)*(x11427)))+(((IkReal(-1.00000000000000))*(x11405)*(x11406)*(x11407)))+(((IkReal(-1.00000000000000))*(cj4)*(x11406)*(x11425)))+(((IkReal(-1.00000000000000))*(x11405)*(x11420)*(x11425))));
36906 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x11412)*(x11414)))+(((x11423)*(x11438)))+(((IkReal(0.374290000000000))*(x11410)*(x11414)))+(((IkReal(-1.00000000000000))*(r10)*(x11412)*(x11422)))+(((IkReal(-0.0100000000000000))*(x11409)*(x11410)))+(((r00)*(x11422)*(x11428)))+(((IkReal(-1.00000000000000))*(x11421)*(x11433)))+(((IkReal(-0.374290000000000))*(r02)*(x11416)))+(((IkReal(0.0100000000000000))*(x11409)*(x11415)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x11416)))+(((px)*(sj0)))+(((x11412)*(x11413)))+(((x11421)*(x11429)))+(((IkReal(-1.00000000000000))*(py)*(x11432))));
36907 evalcond[8]=((IkReal(-0.295420000000000))+(((x11427)*(x11438)))+(((IkReal(-1.00000000000000))*(r11)*(x11414)*(x11428)))+(((IkReal(-1.00000000000000))*(py)*(x11418)))+(((cj0)*(r02)*(x11421)))+(((IkReal(0.0100000000000000))*(x11409)*(x11425)))+(((IkReal(-1.00000000000000))*(r00)*(x11412)*(x11422)))+(((r12)*(sj0)*(x11421)))+(((x11413)*(x11428)))+(((IkReal(0.0100000000000000))*(x11409)*(x11435)))+(((IkReal(-1.00000000000000))*(px)*(x11432)))+(((cj5)*(r02)*(x11412)))+(((x11407)*(x11438)))+(((IkReal(-0.374290000000000))*(x11407)*(x11422)))+(((IkReal(-1.00000000000000))*(r01)*(x11412)*(x11414))));
36908 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
36909 {
36910 {
36911 IkReal j3array[1], cj3array[1], sj3array[1];
36912 bool j3valid[1]={false};
36913 _nj3 = 1;
36914 IkReal x11439=((IkReal(1.00000000000000))*(r21));
36915 IkReal x11440=((cj4)*(cj5));
36916 IkReal x11441=((r20)*(sj6));
36917 if( IKabs(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11439)))+(((IkReal(-1.00000000000000))*(sj5)*(x11441)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r21)*(x11440)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11439)))+(((x11440)*(x11441))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11439)))+(((IkReal(-1.00000000000000))*(sj5)*(x11441)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r21)*(x11440)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11439)))+(((x11440)*(x11441)))))-1) <= IKFAST_SINCOS_THRESH )
36918     continue;
36919 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11439)))+(((IkReal(-1.00000000000000))*(sj5)*(x11441)))+(((cj5)*(r22)))), ((((cj6)*(r21)*(x11440)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11439)))+(((x11440)*(x11441)))));
36920 sj3array[0]=IKsin(j3array[0]);
36921 cj3array[0]=IKcos(j3array[0]);
36922 if( j3array[0] > IKPI )
36923 {
36924     j3array[0]-=IK2PI;
36925 }
36926 else if( j3array[0] < -IKPI )
36927 {    j3array[0]+=IK2PI;
36928 }
36929 j3valid[0] = true;
36930 for(int ij3 = 0; ij3 < 1; ++ij3)
36931 {
36932 if( !j3valid[ij3] )
36933 {
36934     continue;
36935 }
36936 _ij3[0] = ij3; _ij3[1] = -1;
36937 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
36938 {
36939 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
36940 {
36941     j3valid[iij3]=false; _ij3[1] = iij3; break; 
36942 }
36943 }
36944 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
36945 {
36946 IkReal evalcond[4];
36947 IkReal x11442=IKcos(j3);
36948 IkReal x11443=IKsin(j3);
36949 IkReal x11444=((IkReal(1.00000000000000))*(cj4));
36950 IkReal x11445=((sj0)*(sj5));
36951 IkReal x11446=((cj0)*(cj5));
36952 IkReal x11447=((cj6)*(r01));
36953 IkReal x11448=((r00)*(sj6));
36954 IkReal x11449=((cj6)*(r11));
36955 IkReal x11450=((cj5)*(sj0));
36956 IkReal x11451=((cj6)*(sj4));
36957 IkReal x11452=((sj4)*(sj6));
36958 IkReal x11453=((cj4)*(cj5));
36959 IkReal x11454=((cj6)*(r21));
36960 IkReal x11455=((r20)*(sj6));
36961 IkReal x11456=((r10)*(sj6));
36962 IkReal x11457=((IkReal(1.00000000000000))*(cj0)*(sj5));
36963 evalcond[0]=((((sj5)*(x11454)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11455)))+(x11443));
36964 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x11452)))+(((IkReal(-1.00000000000000))*(x11442)))+(((cj4)*(r22)*(sj5)))+(((x11453)*(x11454)))+(((r20)*(x11451)))+(((x11453)*(x11455))));
36965 evalcond[2]=((((r02)*(x11446)))+(((IkReal(-1.00000000000000))*(x11447)*(x11457)))+(((IkReal(-1.00000000000000))*(x11445)*(x11449)))+(((IkReal(-1.00000000000000))*(x11448)*(x11457)))+(((r12)*(x11450)))+(x11442)+(((IkReal(-1.00000000000000))*(x11445)*(x11456))));
36966 evalcond[3]=((((IkReal(-1.00000000000000))*(x11444)*(x11446)*(x11447)))+(((cj0)*(r01)*(x11452)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11451)))+(((IkReal(-1.00000000000000))*(x11444)*(x11446)*(x11448)))+(((IkReal(-1.00000000000000))*(x11444)*(x11449)*(x11450)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11451)))+(((IkReal(-1.00000000000000))*(x11444)*(x11450)*(x11456)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11444)))+(((IkReal(-1.00000000000000))*(r12)*(x11444)*(x11445)))+(((r11)*(sj0)*(x11452)))+(x11443));
36967 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
36968 {
36969 continue;
36970 }
36971 }
36972 
36973 {
36974 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
36975 vinfos[0].jointtype = 1;
36976 vinfos[0].foffset = j0;
36977 vinfos[0].indices[0] = _ij0[0];
36978 vinfos[0].indices[1] = _ij0[1];
36979 vinfos[0].maxsolutions = _nj0;
36980 vinfos[1].jointtype = 1;
36981 vinfos[1].foffset = j1;
36982 vinfos[1].indices[0] = _ij1[0];
36983 vinfos[1].indices[1] = _ij1[1];
36984 vinfos[1].maxsolutions = _nj1;
36985 vinfos[2].jointtype = 1;
36986 vinfos[2].foffset = j2;
36987 vinfos[2].indices[0] = _ij2[0];
36988 vinfos[2].indices[1] = _ij2[1];
36989 vinfos[2].maxsolutions = _nj2;
36990 vinfos[3].jointtype = 1;
36991 vinfos[3].foffset = j3;
36992 vinfos[3].indices[0] = _ij3[0];
36993 vinfos[3].indices[1] = _ij3[1];
36994 vinfos[3].maxsolutions = _nj3;
36995 vinfos[4].jointtype = 1;
36996 vinfos[4].foffset = j4;
36997 vinfos[4].indices[0] = _ij4[0];
36998 vinfos[4].indices[1] = _ij4[1];
36999 vinfos[4].maxsolutions = _nj4;
37000 vinfos[5].jointtype = 1;
37001 vinfos[5].foffset = j5;
37002 vinfos[5].indices[0] = _ij5[0];
37003 vinfos[5].indices[1] = _ij5[1];
37004 vinfos[5].maxsolutions = _nj5;
37005 vinfos[6].jointtype = 1;
37006 vinfos[6].foffset = j6;
37007 vinfos[6].indices[0] = _ij6[0];
37008 vinfos[6].indices[1] = _ij6[1];
37009 vinfos[6].maxsolutions = _nj6;
37010 std::vector<int> vfree(0);
37011 solutions.AddSolution(vinfos,vfree);
37012 }
37013 }
37014 }
37015 
37016 } else
37017 {
37018 IkReal x11458=((cj5)*(sj4));
37019 IkReal x11459=((IkReal(1.00000000000000))*(sj6));
37020 IkReal x11460=((r10)*(sj0));
37021 IkReal x11461=((sj4)*(sj5));
37022 IkReal x11462=((cj5)*(cj6));
37023 IkReal x11463=((r01)*(sj0));
37024 IkReal x11464=((IkReal(1.00000000000000))*(r02));
37025 IkReal x11465=((IkReal(0.374290000000000))*(cj0));
37026 IkReal x11466=((cj5)*(r12));
37027 IkReal x11467=((cj6)*(sj5));
37028 IkReal x11468=((cj0)*(r11));
37029 IkReal x11469=((cj5)*(sj0));
37030 IkReal x11470=((r20)*(sj6));
37031 IkReal x11471=((IkReal(1.00000000000000))*(sj0));
37032 IkReal x11472=((cj4)*(cj5));
37033 IkReal x11473=((IkReal(1.00000000000000))*(cj6));
37034 IkReal x11474=((IkReal(0.0100000000000000))*(sj5));
37035 IkReal x11475=((sj5)*(sj6));
37036 IkReal x11476=((cj0)*(r10));
37037 IkReal x11477=((cj4)*(cj6));
37038 IkReal x11478=((cj0)*(r01));
37039 IkReal x11479=((IkReal(1.00000000000000))*(cj4));
37040 IkReal x11480=((cj0)*(r00));
37041 IkReal x11481=((IkReal(0.374290000000000))*(sj0));
37042 IkReal x11482=((cj0)*(r12));
37043 IkReal x11483=((IkReal(0.374290000000000))*(sj5));
37044 IkReal x11484=((cj4)*(sj6));
37045 IkReal x11485=((IkReal(1.00000000000000))*(cj0));
37046 IkReal x11486=((r02)*(sj0));
37047 IkReal x11487=((IkReal(0.0100000000000000))*(cj5));
37048 IkReal x11488=((r11)*(sj0));
37049 IkReal x11489=((r00)*(sj0)*(sj6));
37050 IkReal x11490=((r00)*(x11477));
37051 IkReal x11491=((sj6)*(x11487));
37052 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
37053 evalcond[1]=((((cj6)*(r21)*(x11458)))+(((r21)*(x11484)))+(((x11458)*(x11470)))+(((r22)*(x11461)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x11473))));
37054 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(0.374290000000000))*(r21)*(x11467)))+(((x11470)*(x11483)))+(((IkReal(-1.00000000000000))*(r22)*(x11474)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x11470)*(x11487)))+(((IkReal(-0.0100000000000000))*(r21)*(x11462))));
37055 evalcond[3]=((((IkReal(-1.00000000000000))*(x11464)*(x11469)))+(((IkReal(-1.00000000000000))*(x11467)*(x11468)))+(((x11463)*(x11467)))+(((IkReal(-1.00000000000000))*(sj5)*(x11459)*(x11476)))+(((cj0)*(x11466)))+(((r00)*(sj0)*(x11475))));
37056 evalcond[4]=((IkReal(-1.00000000000000))+(((x11461)*(x11486)))+(((IkReal(-1.00000000000000))*(x11461)*(x11482)))+(((x11463)*(x11484)))+(((cj6)*(x11458)*(x11463)))+(((IkReal(-1.00000000000000))*(cj4)*(x11459)*(x11468)))+(((IkReal(-1.00000000000000))*(x11458)*(x11459)*(x11476)))+(((IkReal(-1.00000000000000))*(x11471)*(x11490)))+(((x11458)*(x11489)))+(((x11476)*(x11477)))+(((IkReal(-1.00000000000000))*(x11458)*(x11468)*(x11473))));
37057 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x11459)*(x11463)))+(((r00)*(x11469)*(x11484)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((IkReal(-1.00000000000000))*(x11462)*(x11468)*(x11479)))+(((cj4)*(sj5)*(x11486)))+(((IkReal(-1.00000000000000))*(sj5)*(x11479)*(x11482)))+(((sj4)*(sj6)*(x11468)))+(((IkReal(-1.00000000000000))*(x11459)*(x11472)*(x11476)))+(((cj4)*(x11462)*(x11463)))+(((IkReal(-1.00000000000000))*(sj4)*(x11473)*(x11476))));
37058 evalcond[6]=((((x11477)*(x11480)))+(((IkReal(-1.00000000000000))*(x11458)*(x11473)*(x11478)))+(((x11460)*(x11477)))+(((IkReal(-1.00000000000000))*(x11458)*(x11459)*(x11460)))+(((IkReal(-1.00000000000000))*(x11458)*(x11459)*(x11480)))+(((IkReal(-1.00000000000000))*(cj0)*(x11461)*(x11464)))+(((IkReal(-1.00000000000000))*(r12)*(x11461)*(x11471)))+(((IkReal(-1.00000000000000))*(cj4)*(x11459)*(x11488)))+(((IkReal(-1.00000000000000))*(cj4)*(x11459)*(x11478)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x11458)*(x11471))));
37059 evalcond[7]=((((IkReal(-1.00000000000000))*(x11474)*(x11486)))+(((x11474)*(x11482)))+(((IkReal(-1.00000000000000))*(py)*(x11485)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x11469)))+(((IkReal(-1.00000000000000))*(r11)*(x11465)*(x11467)))+(((IkReal(-0.374290000000000))*(r02)*(x11469)))+(((IkReal(-1.00000000000000))*(r10)*(x11465)*(x11475)))+(((IkReal(0.374290000000000))*(x11463)*(x11467)))+(((IkReal(0.0100000000000000))*(x11462)*(x11468)))+(((x11465)*(x11466)))+(((px)*(sj0)))+(((x11476)*(x11491)))+(((r00)*(x11475)*(x11481)))+(((IkReal(-0.0100000000000000))*(x11462)*(x11463))));
37060 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(r01)*(x11465)*(x11467)))+(((cj0)*(r02)*(x11474)))+(((cj5)*(r02)*(x11465)))+(((IkReal(-1.00000000000000))*(px)*(x11485)))+(((x11460)*(x11491)))+(((IkReal(0.0100000000000000))*(x11462)*(x11478)))+(((r12)*(sj0)*(x11474)))+(((IkReal(-1.00000000000000))*(py)*(x11471)))+(((IkReal(-1.00000000000000))*(r00)*(x11465)*(x11475)))+(((x11466)*(x11481)))+(((IkReal(-1.00000000000000))*(r11)*(x11467)*(x11481)))+(((IkReal(0.0100000000000000))*(x11462)*(x11488)))+(((IkReal(-0.374290000000000))*(x11460)*(x11475)))+(((x11480)*(x11491))));
37061 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
37062 {
37063 {
37064 IkReal j3array[1], cj3array[1], sj3array[1];
37065 bool j3valid[1]={false};
37066 _nj3 = 1;
37067 IkReal x11492=((IkReal(1.00000000000000))*(cj4));
37068 IkReal x11493=((cj6)*(r21));
37069 IkReal x11494=((r20)*(sj6));
37070 if( IKabs(((((sj5)*(x11493)))+(((sj5)*(x11494)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11493)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11492)))+(((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x11493)))+(((sj5)*(x11494)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11493)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11492)))+(((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
37071     continue;
37072 j3array[0]=IKatan2(((((sj5)*(x11493)))+(((sj5)*(x11494)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11493)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x11492)))+(((IkReal(-1.00000000000000))*(cj5)*(x11492)*(x11494)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
37073 sj3array[0]=IKsin(j3array[0]);
37074 cj3array[0]=IKcos(j3array[0]);
37075 if( j3array[0] > IKPI )
37076 {
37077     j3array[0]-=IK2PI;
37078 }
37079 else if( j3array[0] < -IKPI )
37080 {    j3array[0]+=IK2PI;
37081 }
37082 j3valid[0] = true;
37083 for(int ij3 = 0; ij3 < 1; ++ij3)
37084 {
37085 if( !j3valid[ij3] )
37086 {
37087     continue;
37088 }
37089 _ij3[0] = ij3; _ij3[1] = -1;
37090 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37091 {
37092 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37093 {
37094     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37095 }
37096 }
37097 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37098 {
37099 IkReal evalcond[4];
37100 IkReal x11495=IKcos(j3);
37101 IkReal x11496=IKsin(j3);
37102 IkReal x11497=((IkReal(1.00000000000000))*(cj4));
37103 IkReal x11498=((sj0)*(sj5));
37104 IkReal x11499=((cj0)*(cj5));
37105 IkReal x11500=((cj6)*(r01));
37106 IkReal x11501=((r00)*(sj6));
37107 IkReal x11502=((cj6)*(r11));
37108 IkReal x11503=((cj5)*(sj0));
37109 IkReal x11504=((cj6)*(sj4));
37110 IkReal x11505=((sj4)*(sj6));
37111 IkReal x11506=((cj4)*(cj5));
37112 IkReal x11507=((cj6)*(r21));
37113 IkReal x11508=((r20)*(sj6));
37114 IkReal x11509=((r10)*(sj6));
37115 IkReal x11510=((IkReal(1.00000000000000))*(cj0)*(sj5));
37116 evalcond[0]=((((sj5)*(x11507)))+(((IkReal(-1.00000000000000))*(x11496)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11508))));
37117 evalcond[1]=((((cj4)*(r22)*(sj5)))+(((x11506)*(x11507)))+(((IkReal(-1.00000000000000))*(r21)*(x11505)))+(x11495)+(((r20)*(x11504)))+(((x11506)*(x11508))));
37118 evalcond[2]=((((IkReal(-1.00000000000000))*(x11498)*(x11509)))+(((r12)*(x11503)))+(((IkReal(-1.00000000000000))*(x11500)*(x11510)))+(((IkReal(-1.00000000000000))*(x11501)*(x11510)))+(((IkReal(-1.00000000000000))*(x11498)*(x11502)))+(((r02)*(x11499)))+(x11495));
37119 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x11497)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11504)))+(((r11)*(sj0)*(x11505)))+(((IkReal(-1.00000000000000))*(x11497)*(x11499)*(x11500)))+(((IkReal(-1.00000000000000))*(r12)*(x11497)*(x11498)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x11504)))+(((IkReal(-1.00000000000000))*(x11497)*(x11502)*(x11503)))+(((cj0)*(r01)*(x11505)))+(((IkReal(-1.00000000000000))*(x11497)*(x11499)*(x11501)))+(x11496)+(((IkReal(-1.00000000000000))*(x11497)*(x11503)*(x11509))));
37120 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
37121 {
37122 continue;
37123 }
37124 }
37125 
37126 {
37127 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37128 vinfos[0].jointtype = 1;
37129 vinfos[0].foffset = j0;
37130 vinfos[0].indices[0] = _ij0[0];
37131 vinfos[0].indices[1] = _ij0[1];
37132 vinfos[0].maxsolutions = _nj0;
37133 vinfos[1].jointtype = 1;
37134 vinfos[1].foffset = j1;
37135 vinfos[1].indices[0] = _ij1[0];
37136 vinfos[1].indices[1] = _ij1[1];
37137 vinfos[1].maxsolutions = _nj1;
37138 vinfos[2].jointtype = 1;
37139 vinfos[2].foffset = j2;
37140 vinfos[2].indices[0] = _ij2[0];
37141 vinfos[2].indices[1] = _ij2[1];
37142 vinfos[2].maxsolutions = _nj2;
37143 vinfos[3].jointtype = 1;
37144 vinfos[3].foffset = j3;
37145 vinfos[3].indices[0] = _ij3[0];
37146 vinfos[3].indices[1] = _ij3[1];
37147 vinfos[3].maxsolutions = _nj3;
37148 vinfos[4].jointtype = 1;
37149 vinfos[4].foffset = j4;
37150 vinfos[4].indices[0] = _ij4[0];
37151 vinfos[4].indices[1] = _ij4[1];
37152 vinfos[4].maxsolutions = _nj4;
37153 vinfos[5].jointtype = 1;
37154 vinfos[5].foffset = j5;
37155 vinfos[5].indices[0] = _ij5[0];
37156 vinfos[5].indices[1] = _ij5[1];
37157 vinfos[5].maxsolutions = _nj5;
37158 vinfos[6].jointtype = 1;
37159 vinfos[6].foffset = j6;
37160 vinfos[6].indices[0] = _ij6[0];
37161 vinfos[6].indices[1] = _ij6[1];
37162 vinfos[6].maxsolutions = _nj6;
37163 std::vector<int> vfree(0);
37164 solutions.AddSolution(vinfos,vfree);
37165 }
37166 }
37167 }
37168 
37169 } else
37170 {
37171 IkReal x11511=((IkReal(1.00000000000000))*(cj0));
37172 IkReal x11512=((cj4)*(sj6));
37173 IkReal x11513=((sj0)*(sj4));
37174 IkReal x11514=((cj5)*(sj6));
37175 IkReal x11515=((sj4)*(sj5));
37176 IkReal x11516=((r12)*(sj5));
37177 IkReal x11517=((IkReal(0.374290000000000))*(cj5));
37178 IkReal x11518=((r02)*(sj0));
37179 IkReal x11519=((r20)*(sj4));
37180 IkReal x11520=((IkReal(1.00000000000000))*(sj0));
37181 IkReal x11521=((IkReal(1.00000000000000))*(cj5));
37182 IkReal x11522=((cj0)*(r10));
37183 IkReal x11523=((cj4)*(cj6));
37184 IkReal x11524=((r00)*(sj0));
37185 IkReal x11525=((cj6)*(r21));
37186 IkReal x11526=((IkReal(0.374290000000000))*(sj5));
37187 IkReal x11527=((cj0)*(r00));
37188 IkReal x11528=((IkReal(0.0100000000000000))*(sj5));
37189 IkReal x11529=((cj0)*(r02));
37190 IkReal x11530=((cj5)*(sj4));
37191 IkReal x11531=((cj6)*(r01));
37192 IkReal x11532=((cj6)*(r11));
37193 IkReal x11533=((r01)*(sj0));
37194 IkReal x11534=((r10)*(sj0));
37195 IkReal x11535=((IkReal(0.0100000000000000))*(cj5)*(cj6));
37196 IkReal x11536=((sj6)*(x11526));
37197 IkReal x11537=((cj0)*(cj6)*(x11526));
37198 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
37199 evalcond[1]=((((sj5)*(x11525)))+(((IkReal(-1.00000000000000))*(r22)*(x11521)))+(((r20)*(sj5)*(sj6))));
37200 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x11523)))+(((x11514)*(x11519)))+(((r21)*(x11512)))+(((r22)*(x11515)))+(((x11525)*(x11530))));
37201 evalcond[3]=((((x11525)*(x11526)))+(((r20)*(x11536)))+(((IkReal(-0.0100000000000000))*(r20)*(x11514)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x11517)))+(((IkReal(-0.0100000000000000))*(cj5)*(x11525)))+(((IkReal(-1.00000000000000))*(r22)*(x11528))));
37202 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x11523)))+(((cj6)*(x11519)))+(((cj5)*(r20)*(x11512))));
37203 evalcond[5]=((((cj5)*(x11513)*(x11531)))+(((x11512)*(x11533)))+(((IkReal(-1.00000000000000))*(r12)*(x11511)*(x11515)))+(((r02)*(sj5)*(x11513)))+(((IkReal(-1.00000000000000))*(x11511)*(x11530)*(x11532)))+(((x11522)*(x11523)))+(((r00)*(x11513)*(x11514)))+(((IkReal(-1.00000000000000))*(r11)*(x11511)*(x11512)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11511)*(x11514)))+(((IkReal(-1.00000000000000))*(r00)*(x11520)*(x11523))));
37204 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11511)*(x11514)))+(((IkReal(-1.00000000000000))*(x11513)*(x11516)))+(((IkReal(-1.00000000000000))*(r10)*(x11513)*(x11514)))+(((x11523)*(x11527)))+(((IkReal(-1.00000000000000))*(x11511)*(x11530)*(x11531)))+(((IkReal(-1.00000000000000))*(x11513)*(x11521)*(x11532)))+(((IkReal(-1.00000000000000))*(r11)*(x11512)*(x11520)))+(((x11523)*(x11534)))+(((IkReal(-1.00000000000000))*(r02)*(x11511)*(x11515)))+(((IkReal(-1.00000000000000))*(r01)*(x11511)*(x11512))));
37205 evalcond[7]=((IkReal(0.0690000000000000))+(((x11524)*(x11536)))+(((IkReal(0.0100000000000000))*(cj0)*(x11516)))+(((IkReal(-1.00000000000000))*(x11522)*(x11536)))+(((IkReal(-1.00000000000000))*(py)*(x11511)))+(((sj0)*(x11526)*(x11531)))+(((IkReal(0.0100000000000000))*(x11514)*(x11522)))+(((IkReal(-1.00000000000000))*(x11518)*(x11528)))+(((px)*(sj0)))+(((cj0)*(r12)*(x11517)))+(((IkReal(-0.0100000000000000))*(x11514)*(x11524)))+(((IkReal(-1.00000000000000))*(cj0)*(x11526)*(x11532)))+(((IkReal(-1.00000000000000))*(x11517)*(x11518)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11531)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11532))));
37206 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(-1.00000000000000))*(x11534)*(x11536)))+(((IkReal(-1.00000000000000))*(x11527)*(x11536)))+(((IkReal(0.0100000000000000))*(x11514)*(x11527)))+(((x11528)*(x11529)))+(((IkReal(-1.00000000000000))*(cj0)*(x11526)*(x11531)))+(((IkReal(-1.00000000000000))*(sj0)*(x11526)*(x11532)))+(((IkReal(-1.00000000000000))*(px)*(x11511)))+(((IkReal(0.0100000000000000))*(sj0)*(x11516)))+(((x11517)*(x11529)))+(((IkReal(0.0100000000000000))*(x11514)*(x11534)))+(((IkReal(-1.00000000000000))*(py)*(x11520)))+(((r12)*(sj0)*(x11517)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11532)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11531))));
37207 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
37208 {
37209 {
37210 IkReal j3array[1], cj3array[1], sj3array[1];
37211 bool j3valid[1]={false};
37212 _nj3 = 1;
37213 IkReal x11538=((sj0)*(sj5));
37214 IkReal x11539=((r00)*(sj6));
37215 IkReal x11540=((IkReal(1.00000000000000))*(cj5));
37216 IkReal x11541=((cj6)*(r11));
37217 IkReal x11542=((cj6)*(r01));
37218 IkReal x11543=((r10)*(sj6));
37219 IkReal x11544=((cj0)*(sj5));
37220 if( IKabs(((((IkReal(-1.00000000000000))*(x11541)*(x11544)))+(((IkReal(-1.00000000000000))*(x11543)*(x11544)))+(((x11538)*(x11542)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11540)))+(((x11538)*(x11539))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x11538)*(x11541)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11540)))+(((x11538)*(x11543)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11540)))+(((x11542)*(x11544)))+(((x11539)*(x11544))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x11541)*(x11544)))+(((IkReal(-1.00000000000000))*(x11543)*(x11544)))+(((x11538)*(x11542)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11540)))+(((x11538)*(x11539)))))+IKsqr(((((x11538)*(x11541)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11540)))+(((x11538)*(x11543)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11540)))+(((x11542)*(x11544)))+(((x11539)*(x11544)))))-1) <= IKFAST_SINCOS_THRESH )
37221     continue;
37222 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x11541)*(x11544)))+(((IkReal(-1.00000000000000))*(x11543)*(x11544)))+(((x11538)*(x11542)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11540)))+(((x11538)*(x11539)))), ((((x11538)*(x11541)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11540)))+(((x11538)*(x11543)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11540)))+(((x11542)*(x11544)))+(((x11539)*(x11544)))));
37223 sj3array[0]=IKsin(j3array[0]);
37224 cj3array[0]=IKcos(j3array[0]);
37225 if( j3array[0] > IKPI )
37226 {
37227     j3array[0]-=IK2PI;
37228 }
37229 else if( j3array[0] < -IKPI )
37230 {    j3array[0]+=IK2PI;
37231 }
37232 j3valid[0] = true;
37233 for(int ij3 = 0; ij3 < 1; ++ij3)
37234 {
37235 if( !j3valid[ij3] )
37236 {
37237     continue;
37238 }
37239 _ij3[0] = ij3; _ij3[1] = -1;
37240 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37241 {
37242 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37243 {
37244     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37245 }
37246 }
37247 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37248 {
37249 IkReal evalcond[4];
37250 IkReal x11545=IKcos(j3);
37251 IkReal x11546=IKsin(j3);
37252 IkReal x11547=((sj0)*(sj5));
37253 IkReal x11548=((r00)*(sj6));
37254 IkReal x11549=((cj6)*(sj0));
37255 IkReal x11550=((IkReal(1.00000000000000))*(cj4));
37256 IkReal x11551=((r00)*(sj4));
37257 IkReal x11552=((cj0)*(cj5));
37258 IkReal x11553=((cj5)*(sj0));
37259 IkReal x11554=((cj6)*(r11));
37260 IkReal x11555=((r10)*(sj6));
37261 IkReal x11556=((cj0)*(sj5));
37262 IkReal x11557=((r10)*(sj4));
37263 IkReal x11558=((cj4)*(cj5)*(r01));
37264 IkReal x11559=((IkReal(1.00000000000000))*(cj0)*(cj6));
37265 IkReal x11560=((cj0)*(sj4)*(sj6));
37266 IkReal x11561=((sj0)*(sj4)*(sj6));
37267 evalcond[0]=((((r12)*(x11552)))+(((cj6)*(r01)*(x11547)))+(((x11547)*(x11548)))+(((IkReal(-1.00000000000000))*(x11546)))+(((IkReal(-1.00000000000000))*(r02)*(x11553)))+(((IkReal(-1.00000000000000))*(x11555)*(x11556)))+(((IkReal(-1.00000000000000))*(x11554)*(x11556))));
37268 evalcond[1]=((((IkReal(-1.00000000000000))*(x11548)*(x11556)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x11556)))+(((IkReal(-1.00000000000000))*(x11547)*(x11554)))+(x11545)+(((IkReal(-1.00000000000000))*(x11547)*(x11555)))+(((r12)*(x11553)))+(((r02)*(x11552))));
37269 evalcond[2]=((((cj4)*(x11548)*(x11553)))+(((IkReal(-1.00000000000000))*(r12)*(x11550)*(x11556)))+(((x11549)*(x11551)))+(((IkReal(-1.00000000000000))*(x11550)*(x11552)*(x11555)))+(((r11)*(x11560)))+(x11545)+(((IkReal(-1.00000000000000))*(r01)*(x11561)))+(((IkReal(-1.00000000000000))*(x11557)*(x11559)))+(((cj4)*(r02)*(x11547)))+(((x11549)*(x11558)))+(((IkReal(-1.00000000000000))*(x11550)*(x11552)*(x11554))));
37270 evalcond[3]=((((IkReal(-1.00000000000000))*(r02)*(x11550)*(x11556)))+(((r11)*(x11561)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x11550)*(x11552)))+(((IkReal(-1.00000000000000))*(x11549)*(x11557)))+(x11546)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x11549)*(x11550)))+(((IkReal(-1.00000000000000))*(x11550)*(x11553)*(x11555)))+(((r01)*(x11560)))+(((IkReal(-1.00000000000000))*(x11548)*(x11550)*(x11552)))+(((IkReal(-1.00000000000000))*(r12)*(x11547)*(x11550)))+(((IkReal(-1.00000000000000))*(x11551)*(x11559))));
37271 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
37272 {
37273 continue;
37274 }
37275 }
37276 
37277 {
37278 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37279 vinfos[0].jointtype = 1;
37280 vinfos[0].foffset = j0;
37281 vinfos[0].indices[0] = _ij0[0];
37282 vinfos[0].indices[1] = _ij0[1];
37283 vinfos[0].maxsolutions = _nj0;
37284 vinfos[1].jointtype = 1;
37285 vinfos[1].foffset = j1;
37286 vinfos[1].indices[0] = _ij1[0];
37287 vinfos[1].indices[1] = _ij1[1];
37288 vinfos[1].maxsolutions = _nj1;
37289 vinfos[2].jointtype = 1;
37290 vinfos[2].foffset = j2;
37291 vinfos[2].indices[0] = _ij2[0];
37292 vinfos[2].indices[1] = _ij2[1];
37293 vinfos[2].maxsolutions = _nj2;
37294 vinfos[3].jointtype = 1;
37295 vinfos[3].foffset = j3;
37296 vinfos[3].indices[0] = _ij3[0];
37297 vinfos[3].indices[1] = _ij3[1];
37298 vinfos[3].maxsolutions = _nj3;
37299 vinfos[4].jointtype = 1;
37300 vinfos[4].foffset = j4;
37301 vinfos[4].indices[0] = _ij4[0];
37302 vinfos[4].indices[1] = _ij4[1];
37303 vinfos[4].maxsolutions = _nj4;
37304 vinfos[5].jointtype = 1;
37305 vinfos[5].foffset = j5;
37306 vinfos[5].indices[0] = _ij5[0];
37307 vinfos[5].indices[1] = _ij5[1];
37308 vinfos[5].maxsolutions = _nj5;
37309 vinfos[6].jointtype = 1;
37310 vinfos[6].foffset = j6;
37311 vinfos[6].indices[0] = _ij6[0];
37312 vinfos[6].indices[1] = _ij6[1];
37313 vinfos[6].maxsolutions = _nj6;
37314 std::vector<int> vfree(0);
37315 solutions.AddSolution(vinfos,vfree);
37316 }
37317 }
37318 }
37319 
37320 } else
37321 {
37322 IkReal x11562=((IkReal(1.00000000000000))*(cj0));
37323 IkReal x11563=((cj4)*(sj6));
37324 IkReal x11564=((sj0)*(sj4));
37325 IkReal x11565=((cj5)*(sj6));
37326 IkReal x11566=((sj4)*(sj5));
37327 IkReal x11567=((r12)*(sj5));
37328 IkReal x11568=((IkReal(0.374290000000000))*(cj5));
37329 IkReal x11569=((r02)*(sj0));
37330 IkReal x11570=((r20)*(sj4));
37331 IkReal x11571=((IkReal(1.00000000000000))*(sj0));
37332 IkReal x11572=((IkReal(1.00000000000000))*(cj5));
37333 IkReal x11573=((cj0)*(r10));
37334 IkReal x11574=((cj4)*(cj6));
37335 IkReal x11575=((r00)*(sj0));
37336 IkReal x11576=((cj6)*(r21));
37337 IkReal x11577=((IkReal(0.374290000000000))*(sj5));
37338 IkReal x11578=((cj0)*(r00));
37339 IkReal x11579=((IkReal(0.0100000000000000))*(sj5));
37340 IkReal x11580=((cj0)*(r02));
37341 IkReal x11581=((cj5)*(sj4));
37342 IkReal x11582=((cj6)*(r01));
37343 IkReal x11583=((cj6)*(r11));
37344 IkReal x11584=((r01)*(sj0));
37345 IkReal x11585=((r10)*(sj0));
37346 IkReal x11586=((IkReal(0.0100000000000000))*(cj5)*(cj6));
37347 IkReal x11587=((sj6)*(x11577));
37348 IkReal x11588=((cj0)*(cj6)*(x11577));
37349 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
37350 evalcond[1]=((((sj5)*(x11576)))+(((IkReal(-1.00000000000000))*(r22)*(x11572)))+(((r20)*(sj5)*(sj6))));
37351 evalcond[2]=((IkReal(-1.00000000000000))+(((r21)*(x11563)))+(((IkReal(-1.00000000000000))*(r20)*(x11574)))+(((x11565)*(x11570)))+(((r22)*(x11566)))+(((x11576)*(x11581))));
37352 evalcond[3]=((((IkReal(-0.0100000000000000))*(cj5)*(x11576)))+(((IkReal(-1.00000000000000))*(r22)*(x11579)))+(((IkReal(-1.00000000000000))*(r22)*(x11568)))+(((x11576)*(x11577)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x11565)))+(((r20)*(x11587))));
37353 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x11563)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x11570)))+(((cj5)*(r21)*(x11574))));
37354 evalcond[5]=((((x11573)*(x11574)))+(((r00)*(x11564)*(x11565)))+(((IkReal(-1.00000000000000))*(r12)*(x11562)*(x11566)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11562)*(x11565)))+(((cj5)*(x11564)*(x11582)))+(((x11563)*(x11584)))+(((IkReal(-1.00000000000000))*(r11)*(x11562)*(x11563)))+(((IkReal(-1.00000000000000))*(x11562)*(x11581)*(x11583)))+(((r02)*(sj5)*(x11564)))+(((IkReal(-1.00000000000000))*(r00)*(x11571)*(x11574))));
37355 evalcond[6]=((((x11574)*(x11585)))+(((IkReal(-1.00000000000000))*(r11)*(x11563)*(x11571)))+(((IkReal(-1.00000000000000))*(x11564)*(x11572)*(x11583)))+(((x11574)*(x11578)))+(((IkReal(-1.00000000000000))*(r10)*(x11564)*(x11565)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11562)*(x11565)))+(((IkReal(-1.00000000000000))*(r01)*(x11562)*(x11563)))+(((IkReal(-1.00000000000000))*(x11564)*(x11567)))+(((IkReal(-1.00000000000000))*(r02)*(x11562)*(x11566)))+(((IkReal(-1.00000000000000))*(x11562)*(x11581)*(x11582))));
37356 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x11573)*(x11587)))+(((sj0)*(x11577)*(x11582)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11583)))+(((IkReal(-1.00000000000000))*(x11568)*(x11569)))+(((IkReal(0.0100000000000000))*(x11565)*(x11573)))+(((IkReal(-1.00000000000000))*(cj0)*(x11577)*(x11583)))+(((IkReal(-0.0100000000000000))*(x11565)*(x11575)))+(((cj0)*(r12)*(x11568)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11582)))+(((IkReal(-1.00000000000000))*(x11569)*(x11579)))+(((IkReal(0.0100000000000000))*(cj0)*(x11567)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x11562)))+(((x11575)*(x11587))));
37357 evalcond[8]=((IkReal(-0.295420000000000))+(((x11568)*(x11580)))+(((IkReal(-1.00000000000000))*(cj0)*(x11577)*(x11582)))+(((IkReal(-1.00000000000000))*(px)*(x11562)))+(((IkReal(-1.00000000000000))*(sj0)*(x11577)*(x11583)))+(((IkReal(-1.00000000000000))*(x11585)*(x11587)))+(((IkReal(0.0100000000000000))*(x11565)*(x11578)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11582)))+(((r12)*(sj0)*(x11568)))+(((IkReal(-1.00000000000000))*(x11578)*(x11587)))+(((IkReal(0.0100000000000000))*(sj0)*(x11567)))+(((x11579)*(x11580)))+(((IkReal(-1.00000000000000))*(py)*(x11571)))+(((IkReal(0.0100000000000000))*(x11565)*(x11585)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11583))));
37358 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
37359 {
37360 {
37361 IkReal j3array[1], cj3array[1], sj3array[1];
37362 bool j3valid[1]={false};
37363 _nj3 = 1;
37364 IkReal x11589=((IkReal(1.00000000000000))*(cj5));
37365 IkReal x11590=((r10)*(sj5)*(sj6));
37366 IkReal x11591=((cj6)*(sj0)*(sj5));
37367 IkReal x11592=((r00)*(sj5)*(sj6));
37368 IkReal x11593=((cj0)*(cj6)*(sj5));
37369 if( IKabs(((((IkReal(-1.00000000000000))*(r01)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x11589)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x11593)))+(((cj0)*(x11590)))+(((IkReal(-1.00000000000000))*(sj0)*(x11592))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(x11592)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11589)))+(((sj0)*(x11590)))+(((r01)*(x11593)))+(((r11)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11589))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r01)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x11589)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x11593)))+(((cj0)*(x11590)))+(((IkReal(-1.00000000000000))*(sj0)*(x11592)))))+IKsqr(((((cj0)*(x11592)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11589)))+(((sj0)*(x11590)))+(((r01)*(x11593)))+(((r11)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11589)))))-1) <= IKFAST_SINCOS_THRESH )
37370     continue;
37371 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r01)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x11589)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x11593)))+(((cj0)*(x11590)))+(((IkReal(-1.00000000000000))*(sj0)*(x11592)))), ((((cj0)*(x11592)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11589)))+(((sj0)*(x11590)))+(((r01)*(x11593)))+(((r11)*(x11591)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11589)))));
37372 sj3array[0]=IKsin(j3array[0]);
37373 cj3array[0]=IKcos(j3array[0]);
37374 if( j3array[0] > IKPI )
37375 {
37376     j3array[0]-=IK2PI;
37377 }
37378 else if( j3array[0] < -IKPI )
37379 {    j3array[0]+=IK2PI;
37380 }
37381 j3valid[0] = true;
37382 for(int ij3 = 0; ij3 < 1; ++ij3)
37383 {
37384 if( !j3valid[ij3] )
37385 {
37386     continue;
37387 }
37388 _ij3[0] = ij3; _ij3[1] = -1;
37389 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37390 {
37391 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37392 {
37393     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37394 }
37395 }
37396 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37397 {
37398 IkReal evalcond[4];
37399 IkReal x11594=IKcos(j3);
37400 IkReal x11595=IKsin(j3);
37401 IkReal x11596=((sj0)*(sj5));
37402 IkReal x11597=((r00)*(sj6));
37403 IkReal x11598=((IkReal(1.00000000000000))*(cj4));
37404 IkReal x11599=((cj6)*(sj0));
37405 IkReal x11600=((r00)*(sj4));
37406 IkReal x11601=((cj0)*(cj5));
37407 IkReal x11602=((cj6)*(r01));
37408 IkReal x11603=((cj5)*(sj0));
37409 IkReal x11604=((cj0)*(sj5));
37410 IkReal x11605=((cj6)*(r11));
37411 IkReal x11606=((r10)*(sj6));
37412 IkReal x11607=((r10)*(sj4));
37413 IkReal x11608=((cj0)*(sj4)*(sj6));
37414 IkReal x11609=((sj0)*(sj4)*(sj6));
37415 IkReal x11610=((IkReal(1.00000000000000))*(cj0)*(cj6));
37416 evalcond[0]=((x11595)+(((r12)*(x11601)))+(((x11596)*(x11602)))+(((IkReal(-1.00000000000000))*(x11604)*(x11605)))+(((IkReal(-1.00000000000000))*(x11604)*(x11606)))+(((IkReal(-1.00000000000000))*(r02)*(x11603)))+(((x11596)*(x11597))));
37417 evalcond[1]=((x11594)+(((IkReal(-1.00000000000000))*(x11602)*(x11604)))+(((r02)*(x11601)))+(((IkReal(-1.00000000000000))*(x11597)*(x11604)))+(((IkReal(-1.00000000000000))*(x11596)*(x11605)))+(((r12)*(x11603)))+(((IkReal(-1.00000000000000))*(x11596)*(x11606))));
37418 evalcond[2]=((((cj4)*(x11597)*(x11603)))+(((cj4)*(cj5)*(r01)*(x11599)))+(((IkReal(-1.00000000000000))*(x11607)*(x11610)))+(((IkReal(-1.00000000000000))*(r12)*(x11598)*(x11604)))+(((x11599)*(x11600)))+(((IkReal(-1.00000000000000))*(x11594)))+(((IkReal(-1.00000000000000))*(x11598)*(x11601)*(x11606)))+(((IkReal(-1.00000000000000))*(r01)*(x11609)))+(((r11)*(x11608)))+(((IkReal(-1.00000000000000))*(x11598)*(x11601)*(x11605)))+(((cj4)*(r02)*(x11596))));
37419 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x11598)*(x11599)))+(x11595)+(((IkReal(-1.00000000000000))*(x11600)*(x11610)))+(((IkReal(-1.00000000000000))*(x11598)*(x11603)*(x11606)))+(((IkReal(-1.00000000000000))*(x11597)*(x11598)*(x11601)))+(((IkReal(-1.00000000000000))*(r02)*(x11598)*(x11604)))+(((IkReal(-1.00000000000000))*(r12)*(x11596)*(x11598)))+(((r11)*(x11609)))+(((IkReal(-1.00000000000000))*(x11599)*(x11607)))+(((IkReal(-1.00000000000000))*(x11598)*(x11601)*(x11602)))+(((r01)*(x11608))));
37420 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
37421 {
37422 continue;
37423 }
37424 }
37425 
37426 {
37427 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37428 vinfos[0].jointtype = 1;
37429 vinfos[0].foffset = j0;
37430 vinfos[0].indices[0] = _ij0[0];
37431 vinfos[0].indices[1] = _ij0[1];
37432 vinfos[0].maxsolutions = _nj0;
37433 vinfos[1].jointtype = 1;
37434 vinfos[1].foffset = j1;
37435 vinfos[1].indices[0] = _ij1[0];
37436 vinfos[1].indices[1] = _ij1[1];
37437 vinfos[1].maxsolutions = _nj1;
37438 vinfos[2].jointtype = 1;
37439 vinfos[2].foffset = j2;
37440 vinfos[2].indices[0] = _ij2[0];
37441 vinfos[2].indices[1] = _ij2[1];
37442 vinfos[2].maxsolutions = _nj2;
37443 vinfos[3].jointtype = 1;
37444 vinfos[3].foffset = j3;
37445 vinfos[3].indices[0] = _ij3[0];
37446 vinfos[3].indices[1] = _ij3[1];
37447 vinfos[3].maxsolutions = _nj3;
37448 vinfos[4].jointtype = 1;
37449 vinfos[4].foffset = j4;
37450 vinfos[4].indices[0] = _ij4[0];
37451 vinfos[4].indices[1] = _ij4[1];
37452 vinfos[4].maxsolutions = _nj4;
37453 vinfos[5].jointtype = 1;
37454 vinfos[5].foffset = j5;
37455 vinfos[5].indices[0] = _ij5[0];
37456 vinfos[5].indices[1] = _ij5[1];
37457 vinfos[5].maxsolutions = _nj5;
37458 vinfos[6].jointtype = 1;
37459 vinfos[6].foffset = j6;
37460 vinfos[6].indices[0] = _ij6[0];
37461 vinfos[6].indices[1] = _ij6[1];
37462 vinfos[6].maxsolutions = _nj6;
37463 std::vector<int> vfree(0);
37464 solutions.AddSolution(vinfos,vfree);
37465 }
37466 }
37467 }
37468 
37469 } else
37470 {
37471 if( 1 )
37472 {
37473 continue;
37474 
37475 } else
37476 {
37477 }
37478 }
37479 }
37480 }
37481 }
37482 }
37483 
37484 } else
37485 {
37486 {
37487 IkReal j3array[1], cj3array[1], sj3array[1];
37488 bool j3valid[1]={false};
37489 _nj3 = 1;
37490 IkReal x11611=((sj0)*(sj5));
37491 IkReal x11612=((r00)*(sj6));
37492 IkReal x11613=((IkReal(1.00000000000000))*(cj5));
37493 IkReal x11614=((cj6)*(r11));
37494 IkReal x11615=((cj6)*(r01));
37495 IkReal x11616=((cj0)*(sj5));
37496 IkReal x11617=((r10)*(sj6));
37497 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11613)))+(((IkReal(-1.00000000000000))*(x11614)*(x11616)))+(((x11611)*(x11615)))+(((cj0)*(cj5)*(r12)))+(((x11611)*(x11612)))+(((IkReal(-1.00000000000000))*(x11616)*(x11617))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((x11615)*(x11616)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11613)))+(((x11611)*(x11614)))+(((x11611)*(x11617)))+(((x11612)*(x11616)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11613))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11613)))+(((IkReal(-1.00000000000000))*(x11614)*(x11616)))+(((x11611)*(x11615)))+(((cj0)*(cj5)*(r12)))+(((x11611)*(x11612)))+(((IkReal(-1.00000000000000))*(x11616)*(x11617)))))))+IKsqr(((((x11615)*(x11616)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11613)))+(((x11611)*(x11614)))+(((x11611)*(x11617)))+(((x11612)*(x11616)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11613)))))-1) <= IKFAST_SINCOS_THRESH )
37498     continue;
37499 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11613)))+(((IkReal(-1.00000000000000))*(x11614)*(x11616)))+(((x11611)*(x11615)))+(((cj0)*(cj5)*(r12)))+(((x11611)*(x11612)))+(((IkReal(-1.00000000000000))*(x11616)*(x11617)))))), ((((x11615)*(x11616)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11613)))+(((x11611)*(x11614)))+(((x11611)*(x11617)))+(((x11612)*(x11616)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11613)))));
37500 sj3array[0]=IKsin(j3array[0]);
37501 cj3array[0]=IKcos(j3array[0]);
37502 if( j3array[0] > IKPI )
37503 {
37504     j3array[0]-=IK2PI;
37505 }
37506 else if( j3array[0] < -IKPI )
37507 {    j3array[0]+=IK2PI;
37508 }
37509 j3valid[0] = true;
37510 for(int ij3 = 0; ij3 < 1; ++ij3)
37511 {
37512 if( !j3valid[ij3] )
37513 {
37514     continue;
37515 }
37516 _ij3[0] = ij3; _ij3[1] = -1;
37517 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37518 {
37519 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37520 {
37521     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37522 }
37523 }
37524 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37525 {
37526 IkReal evalcond[6];
37527 IkReal x11618=IKsin(j3);
37528 IkReal x11619=IKcos(j3);
37529 IkReal x11620=((sj0)*(sj5));
37530 IkReal x11621=((r00)*(sj6));
37531 IkReal x11622=((IkReal(1.00000000000000))*(cj4));
37532 IkReal x11623=((cj6)*(r01));
37533 IkReal x11624=((cj0)*(cj5));
37534 IkReal x11625=((cj5)*(sj0));
37535 IkReal x11626=((cj6)*(r11));
37536 IkReal x11627=((cj6)*(sj4));
37537 IkReal x11628=((cj0)*(sj5));
37538 IkReal x11629=((cj4)*(cj5));
37539 IkReal x11630=((cj6)*(r21));
37540 IkReal x11631=((r20)*(sj6));
37541 IkReal x11632=((r10)*(sj6));
37542 IkReal x11633=((IkReal(1.00000000000000))*(cj0));
37543 IkReal x11634=((cj0)*(sj4)*(sj6));
37544 IkReal x11635=((sj0)*(sj4)*(sj6));
37545 evalcond[0]=((((sj5)*(x11631)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11630)))+(((cj2)*(x11618))));
37546 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11629)*(x11631)))+(((x11629)*(x11630)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x11619)))+(((r20)*(x11627))));
37547 evalcond[2]=((((x11620)*(x11623)))+(((IkReal(-1.00000000000000))*(r02)*(x11625)))+(((r12)*(x11624)))+(((IkReal(-1.00000000000000))*(sj2)*(x11618)))+(((x11620)*(x11621)))+(((IkReal(-1.00000000000000))*(x11628)*(x11632)))+(((IkReal(-1.00000000000000))*(x11626)*(x11628))));
37548 evalcond[3]=((((IkReal(-1.00000000000000))*(x11623)*(x11628)))+(((IkReal(-1.00000000000000))*(x11621)*(x11628)))+(((IkReal(-1.00000000000000))*(x11620)*(x11626)))+(((r12)*(x11625)))+(((r02)*(x11624)))+(((IkReal(-1.00000000000000))*(x11620)*(x11632)))+(x11619));
37549 evalcond[4]=((((cj4)*(x11621)*(x11625)))+(((cj4)*(r02)*(x11620)))+(((IkReal(-1.00000000000000))*(r12)*(x11622)*(x11628)))+(((IkReal(-1.00000000000000))*(x11622)*(x11624)*(x11632)))+(((IkReal(-1.00000000000000))*(r01)*(x11635)))+(((sj2)*(x11619)))+(((cj4)*(x11623)*(x11625)))+(((IkReal(-1.00000000000000))*(r10)*(x11627)*(x11633)))+(((r11)*(x11634)))+(((r00)*(sj0)*(x11627)))+(((IkReal(-1.00000000000000))*(x11622)*(x11624)*(x11626))));
37550 evalcond[5]=((((IkReal(-1.00000000000000))*(x11621)*(x11622)*(x11624)))+(((IkReal(-1.00000000000000))*(r00)*(x11627)*(x11633)))+(((IkReal(-1.00000000000000))*(x11622)*(x11625)*(x11632)))+(((r01)*(x11634)))+(((IkReal(-1.00000000000000))*(r12)*(x11620)*(x11622)))+(((IkReal(-1.00000000000000))*(x11622)*(x11625)*(x11626)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11627)))+(((r11)*(x11635)))+(((IkReal(-1.00000000000000))*(x11622)*(x11623)*(x11624)))+(((IkReal(-1.00000000000000))*(r02)*(x11622)*(x11628)))+(x11618));
37551 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
37552 {
37553 continue;
37554 }
37555 }
37556 
37557 {
37558 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37559 vinfos[0].jointtype = 1;
37560 vinfos[0].foffset = j0;
37561 vinfos[0].indices[0] = _ij0[0];
37562 vinfos[0].indices[1] = _ij0[1];
37563 vinfos[0].maxsolutions = _nj0;
37564 vinfos[1].jointtype = 1;
37565 vinfos[1].foffset = j1;
37566 vinfos[1].indices[0] = _ij1[0];
37567 vinfos[1].indices[1] = _ij1[1];
37568 vinfos[1].maxsolutions = _nj1;
37569 vinfos[2].jointtype = 1;
37570 vinfos[2].foffset = j2;
37571 vinfos[2].indices[0] = _ij2[0];
37572 vinfos[2].indices[1] = _ij2[1];
37573 vinfos[2].maxsolutions = _nj2;
37574 vinfos[3].jointtype = 1;
37575 vinfos[3].foffset = j3;
37576 vinfos[3].indices[0] = _ij3[0];
37577 vinfos[3].indices[1] = _ij3[1];
37578 vinfos[3].maxsolutions = _nj3;
37579 vinfos[4].jointtype = 1;
37580 vinfos[4].foffset = j4;
37581 vinfos[4].indices[0] = _ij4[0];
37582 vinfos[4].indices[1] = _ij4[1];
37583 vinfos[4].maxsolutions = _nj4;
37584 vinfos[5].jointtype = 1;
37585 vinfos[5].foffset = j5;
37586 vinfos[5].indices[0] = _ij5[0];
37587 vinfos[5].indices[1] = _ij5[1];
37588 vinfos[5].maxsolutions = _nj5;
37589 vinfos[6].jointtype = 1;
37590 vinfos[6].foffset = j6;
37591 vinfos[6].indices[0] = _ij6[0];
37592 vinfos[6].indices[1] = _ij6[1];
37593 vinfos[6].maxsolutions = _nj6;
37594 std::vector<int> vfree(0);
37595 solutions.AddSolution(vinfos,vfree);
37596 }
37597 }
37598 }
37599 
37600 }
37601 
37602 }
37603 
37604 } else
37605 {
37606 {
37607 IkReal j3array[1], cj3array[1], sj3array[1];
37608 bool j3valid[1]={false};
37609 _nj3 = 1;
37610 IkReal x11636=((cj6)*(sj5));
37611 IkReal x11637=((IkReal(1.00000000000000))*(cj5));
37612 IkReal x11638=((sj5)*(sj6));
37613 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x11638)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r21)*(x11636))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(r01)*(x11636)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11637)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11637)))+(((r11)*(sj0)*(x11636)))+(((r10)*(sj0)*(x11638)))+(((cj0)*(r00)*(x11638))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x11638)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r21)*(x11636)))))))+IKsqr(((((cj0)*(r01)*(x11636)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11637)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11637)))+(((r11)*(sj0)*(x11636)))+(((r10)*(sj0)*(x11638)))+(((cj0)*(r00)*(x11638)))))-1) <= IKFAST_SINCOS_THRESH )
37614     continue;
37615 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r20)*(x11638)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r21)*(x11636)))))), ((((cj0)*(r01)*(x11636)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x11637)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x11637)))+(((r11)*(sj0)*(x11636)))+(((r10)*(sj0)*(x11638)))+(((cj0)*(r00)*(x11638)))));
37616 sj3array[0]=IKsin(j3array[0]);
37617 cj3array[0]=IKcos(j3array[0]);
37618 if( j3array[0] > IKPI )
37619 {
37620     j3array[0]-=IK2PI;
37621 }
37622 else if( j3array[0] < -IKPI )
37623 {    j3array[0]+=IK2PI;
37624 }
37625 j3valid[0] = true;
37626 for(int ij3 = 0; ij3 < 1; ++ij3)
37627 {
37628 if( !j3valid[ij3] )
37629 {
37630     continue;
37631 }
37632 _ij3[0] = ij3; _ij3[1] = -1;
37633 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37634 {
37635 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37636 {
37637     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37638 }
37639 }
37640 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37641 {
37642 IkReal evalcond[6];
37643 IkReal x11639=IKsin(j3);
37644 IkReal x11640=IKcos(j3);
37645 IkReal x11641=((sj0)*(sj5));
37646 IkReal x11642=((r00)*(sj6));
37647 IkReal x11643=((IkReal(1.00000000000000))*(cj4));
37648 IkReal x11644=((cj6)*(r01));
37649 IkReal x11645=((cj0)*(cj5));
37650 IkReal x11646=((cj5)*(sj0));
37651 IkReal x11647=((cj6)*(r11));
37652 IkReal x11648=((cj6)*(sj4));
37653 IkReal x11649=((cj0)*(sj5));
37654 IkReal x11650=((cj4)*(cj5));
37655 IkReal x11651=((cj6)*(r21));
37656 IkReal x11652=((r20)*(sj6));
37657 IkReal x11653=((r10)*(sj6));
37658 IkReal x11654=((IkReal(1.00000000000000))*(cj0));
37659 IkReal x11655=((cj0)*(sj4)*(sj6));
37660 IkReal x11656=((sj0)*(sj4)*(sj6));
37661 evalcond[0]=((((sj5)*(x11651)))+(((sj5)*(x11652)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x11639))));
37662 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x11640)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((r20)*(x11648)))+(((cj4)*(r22)*(sj5)))+(((x11650)*(x11651)))+(((x11650)*(x11652))));
37663 evalcond[2]=((((r12)*(x11645)))+(((IkReal(-1.00000000000000))*(x11647)*(x11649)))+(((IkReal(-1.00000000000000))*(x11649)*(x11653)))+(((IkReal(-1.00000000000000))*(r02)*(x11646)))+(((x11641)*(x11642)))+(((x11641)*(x11644)))+(((IkReal(-1.00000000000000))*(sj2)*(x11639))));
37664 evalcond[3]=((((r12)*(x11646)))+(((IkReal(-1.00000000000000))*(x11642)*(x11649)))+(((IkReal(-1.00000000000000))*(x11641)*(x11653)))+(((IkReal(-1.00000000000000))*(x11644)*(x11649)))+(((IkReal(-1.00000000000000))*(x11641)*(x11647)))+(x11640)+(((r02)*(x11645))));
37665 evalcond[4]=((((IkReal(-1.00000000000000))*(x11643)*(x11645)*(x11647)))+(((cj4)*(x11642)*(x11646)))+(((cj4)*(x11644)*(x11646)))+(((IkReal(-1.00000000000000))*(r12)*(x11643)*(x11649)))+(((cj4)*(r02)*(x11641)))+(((IkReal(-1.00000000000000))*(r01)*(x11656)))+(((sj2)*(x11640)))+(((IkReal(-1.00000000000000))*(r10)*(x11648)*(x11654)))+(((r11)*(x11655)))+(((IkReal(-1.00000000000000))*(x11643)*(x11645)*(x11653)))+(((r00)*(sj0)*(x11648))));
37666 evalcond[5]=((((IkReal(-1.00000000000000))*(x11643)*(x11646)*(x11653)))+(((IkReal(-1.00000000000000))*(r00)*(x11648)*(x11654)))+(((IkReal(-1.00000000000000))*(r02)*(x11643)*(x11649)))+(x11639)+(((IkReal(-1.00000000000000))*(x11642)*(x11643)*(x11645)))+(((r11)*(x11656)))+(((IkReal(-1.00000000000000))*(x11643)*(x11646)*(x11647)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11648)))+(((IkReal(-1.00000000000000))*(x11643)*(x11644)*(x11645)))+(((IkReal(-1.00000000000000))*(r12)*(x11641)*(x11643)))+(((r01)*(x11655))));
37667 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
37668 {
37669 continue;
37670 }
37671 }
37672 
37673 {
37674 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37675 vinfos[0].jointtype = 1;
37676 vinfos[0].foffset = j0;
37677 vinfos[0].indices[0] = _ij0[0];
37678 vinfos[0].indices[1] = _ij0[1];
37679 vinfos[0].maxsolutions = _nj0;
37680 vinfos[1].jointtype = 1;
37681 vinfos[1].foffset = j1;
37682 vinfos[1].indices[0] = _ij1[0];
37683 vinfos[1].indices[1] = _ij1[1];
37684 vinfos[1].maxsolutions = _nj1;
37685 vinfos[2].jointtype = 1;
37686 vinfos[2].foffset = j2;
37687 vinfos[2].indices[0] = _ij2[0];
37688 vinfos[2].indices[1] = _ij2[1];
37689 vinfos[2].maxsolutions = _nj2;
37690 vinfos[3].jointtype = 1;
37691 vinfos[3].foffset = j3;
37692 vinfos[3].indices[0] = _ij3[0];
37693 vinfos[3].indices[1] = _ij3[1];
37694 vinfos[3].maxsolutions = _nj3;
37695 vinfos[4].jointtype = 1;
37696 vinfos[4].foffset = j4;
37697 vinfos[4].indices[0] = _ij4[0];
37698 vinfos[4].indices[1] = _ij4[1];
37699 vinfos[4].maxsolutions = _nj4;
37700 vinfos[5].jointtype = 1;
37701 vinfos[5].foffset = j5;
37702 vinfos[5].indices[0] = _ij5[0];
37703 vinfos[5].indices[1] = _ij5[1];
37704 vinfos[5].maxsolutions = _nj5;
37705 vinfos[6].jointtype = 1;
37706 vinfos[6].foffset = j6;
37707 vinfos[6].indices[0] = _ij6[0];
37708 vinfos[6].indices[1] = _ij6[1];
37709 vinfos[6].maxsolutions = _nj6;
37710 std::vector<int> vfree(0);
37711 solutions.AddSolution(vinfos,vfree);
37712 }
37713 }
37714 }
37715 
37716 }
37717 
37718 }
37719 
37720 } else
37721 {
37722 {
37723 IkReal j3array[1], cj3array[1], sj3array[1];
37724 bool j3valid[1]={false};
37725 _nj3 = 1;
37726 IkReal x11657=((IkReal(1.00000000000000))*(r21));
37727 IkReal x11658=((cj4)*(cj5));
37728 IkReal x11659=((r20)*(sj6));
37729 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(sj5)*(x11659)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11657)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((cj6)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11657)))+(((cj4)*(r22)*(sj5)))+(((x11658)*(x11659)))+(((cj6)*(r21)*(x11658))))))) < IKFAST_ATAN2_MAGTHRESH )
37730     continue;
37731 j3array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(sj5)*(x11659)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11657)))+(((cj5)*(r22)))))), ((gconst10)*(((((cj6)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x11657)))+(((cj4)*(r22)*(sj5)))+(((x11658)*(x11659)))+(((cj6)*(r21)*(x11658)))))));
37732 sj3array[0]=IKsin(j3array[0]);
37733 cj3array[0]=IKcos(j3array[0]);
37734 if( j3array[0] > IKPI )
37735 {
37736     j3array[0]-=IK2PI;
37737 }
37738 else if( j3array[0] < -IKPI )
37739 {    j3array[0]+=IK2PI;
37740 }
37741 j3valid[0] = true;
37742 for(int ij3 = 0; ij3 < 1; ++ij3)
37743 {
37744 if( !j3valid[ij3] )
37745 {
37746     continue;
37747 }
37748 _ij3[0] = ij3; _ij3[1] = -1;
37749 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37750 {
37751 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37752 {
37753     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37754 }
37755 }
37756 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37757 {
37758 IkReal evalcond[6];
37759 IkReal x11660=IKsin(j3);
37760 IkReal x11661=IKcos(j3);
37761 IkReal x11662=((sj0)*(sj5));
37762 IkReal x11663=((r00)*(sj6));
37763 IkReal x11664=((IkReal(1.00000000000000))*(cj4));
37764 IkReal x11665=((cj6)*(r01));
37765 IkReal x11666=((cj0)*(cj5));
37766 IkReal x11667=((cj5)*(sj0));
37767 IkReal x11668=((cj6)*(r11));
37768 IkReal x11669=((cj6)*(sj4));
37769 IkReal x11670=((cj0)*(sj5));
37770 IkReal x11671=((cj4)*(cj5));
37771 IkReal x11672=((cj6)*(r21));
37772 IkReal x11673=((r20)*(sj6));
37773 IkReal x11674=((r10)*(sj6));
37774 IkReal x11675=((IkReal(1.00000000000000))*(cj0));
37775 IkReal x11676=((cj0)*(sj4)*(sj6));
37776 IkReal x11677=((sj0)*(sj4)*(sj6));
37777 evalcond[0]=((((sj5)*(x11673)))+(((sj5)*(x11672)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x11660))));
37778 evalcond[1]=((((x11671)*(x11673)))+(((r20)*(x11669)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x11661)))+(((x11671)*(x11672))));
37779 evalcond[2]=((((x11662)*(x11663)))+(((IkReal(-1.00000000000000))*(x11670)*(x11674)))+(((x11662)*(x11665)))+(((IkReal(-1.00000000000000))*(x11668)*(x11670)))+(((r12)*(x11666)))+(((IkReal(-1.00000000000000))*(r02)*(x11667)))+(((IkReal(-1.00000000000000))*(sj2)*(x11660))));
37780 evalcond[3]=((x11661)+(((IkReal(-1.00000000000000))*(x11663)*(x11670)))+(((r12)*(x11667)))+(((IkReal(-1.00000000000000))*(x11662)*(x11668)))+(((IkReal(-1.00000000000000))*(x11665)*(x11670)))+(((IkReal(-1.00000000000000))*(x11662)*(x11674)))+(((r02)*(x11666))));
37781 evalcond[4]=((((cj4)*(r02)*(x11662)))+(((r00)*(sj0)*(x11669)))+(((cj4)*(x11665)*(x11667)))+(((sj2)*(x11661)))+(((cj4)*(x11663)*(x11667)))+(((IkReal(-1.00000000000000))*(x11664)*(x11666)*(x11674)))+(((IkReal(-1.00000000000000))*(r01)*(x11677)))+(((IkReal(-1.00000000000000))*(r10)*(x11669)*(x11675)))+(((r11)*(x11676)))+(((IkReal(-1.00000000000000))*(x11664)*(x11666)*(x11668)))+(((IkReal(-1.00000000000000))*(r12)*(x11664)*(x11670))));
37782 evalcond[5]=((((r01)*(x11676)))+(((IkReal(-1.00000000000000))*(x11664)*(x11667)*(x11668)))+(x11660)+(((IkReal(-1.00000000000000))*(x11663)*(x11664)*(x11666)))+(((IkReal(-1.00000000000000))*(r12)*(x11662)*(x11664)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x11669)))+(((r11)*(x11677)))+(((IkReal(-1.00000000000000))*(x11664)*(x11665)*(x11666)))+(((IkReal(-1.00000000000000))*(r00)*(x11669)*(x11675)))+(((IkReal(-1.00000000000000))*(x11664)*(x11667)*(x11674)))+(((IkReal(-1.00000000000000))*(r02)*(x11664)*(x11670))));
37783 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
37784 {
37785 continue;
37786 }
37787 }
37788 
37789 {
37790 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37791 vinfos[0].jointtype = 1;
37792 vinfos[0].foffset = j0;
37793 vinfos[0].indices[0] = _ij0[0];
37794 vinfos[0].indices[1] = _ij0[1];
37795 vinfos[0].maxsolutions = _nj0;
37796 vinfos[1].jointtype = 1;
37797 vinfos[1].foffset = j1;
37798 vinfos[1].indices[0] = _ij1[0];
37799 vinfos[1].indices[1] = _ij1[1];
37800 vinfos[1].maxsolutions = _nj1;
37801 vinfos[2].jointtype = 1;
37802 vinfos[2].foffset = j2;
37803 vinfos[2].indices[0] = _ij2[0];
37804 vinfos[2].indices[1] = _ij2[1];
37805 vinfos[2].maxsolutions = _nj2;
37806 vinfos[3].jointtype = 1;
37807 vinfos[3].foffset = j3;
37808 vinfos[3].indices[0] = _ij3[0];
37809 vinfos[3].indices[1] = _ij3[1];
37810 vinfos[3].maxsolutions = _nj3;
37811 vinfos[4].jointtype = 1;
37812 vinfos[4].foffset = j4;
37813 vinfos[4].indices[0] = _ij4[0];
37814 vinfos[4].indices[1] = _ij4[1];
37815 vinfos[4].maxsolutions = _nj4;
37816 vinfos[5].jointtype = 1;
37817 vinfos[5].foffset = j5;
37818 vinfos[5].indices[0] = _ij5[0];
37819 vinfos[5].indices[1] = _ij5[1];
37820 vinfos[5].maxsolutions = _nj5;
37821 vinfos[6].jointtype = 1;
37822 vinfos[6].foffset = j6;
37823 vinfos[6].indices[0] = _ij6[0];
37824 vinfos[6].indices[1] = _ij6[1];
37825 vinfos[6].maxsolutions = _nj6;
37826 std::vector<int> vfree(0);
37827 solutions.AddSolution(vinfos,vfree);
37828 }
37829 }
37830 }
37831 
37832 }
37833 
37834 }
37835 
37836 } else
37837 {
37838 IkReal x11678=((IkReal(1.00000000000000))*(cj0));
37839 IkReal x11679=((cj4)*(sj6));
37840 IkReal x11680=((sj0)*(sj4));
37841 IkReal x11681=((cj5)*(sj6));
37842 IkReal x11682=((sj4)*(sj5));
37843 IkReal x11683=((r12)*(sj5));
37844 IkReal x11684=((IkReal(0.374290000000000))*(cj5));
37845 IkReal x11685=((r02)*(sj0));
37846 IkReal x11686=((IkReal(1.00000000000000))*(sj0));
37847 IkReal x11687=((cj0)*(r10));
37848 IkReal x11688=((cj4)*(cj6));
37849 IkReal x11689=((r00)*(sj0));
37850 IkReal x11690=((cj6)*(r21));
37851 IkReal x11691=((IkReal(0.374290000000000))*(sj5));
37852 IkReal x11692=((IkReal(0.0100000000000000))*(sj5));
37853 IkReal x11693=((cj0)*(r02));
37854 IkReal x11694=((cj5)*(sj4));
37855 IkReal x11695=((cj6)*(r01));
37856 IkReal x11696=((cj0)*(r00));
37857 IkReal x11697=((cj6)*(r11));
37858 IkReal x11698=((r01)*(sj0));
37859 IkReal x11699=((r10)*(sj0));
37860 IkReal x11700=((IkReal(0.0100000000000000))*(cj5)*(cj6));
37861 IkReal x11701=((sj6)*(x11691));
37862 IkReal x11702=((cj0)*(cj6)*(x11691));
37863 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
37864 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x11688)))+(((x11690)*(x11694)))+(((r20)*(sj4)*(x11681)))+(((IkReal(-1.00000000000000))*(cj1)))+(((r21)*(x11679)))+(((r22)*(x11682))));
37865 evalcond[2]=((((IkReal(-0.0100000000000000))*(r20)*(x11681)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x11692)))+(((IkReal(-1.00000000000000))*(r22)*(x11684)))+(((r20)*(x11701)))+(((IkReal(-0.0100000000000000))*(cj5)*(x11690)))+(((x11690)*(x11691)))+(pz));
37866 evalcond[3]=((((IkReal(-1.00000000000000))*(x11678)*(x11694)*(x11697)))+(((IkReal(-1.00000000000000))*(r11)*(x11678)*(x11679)))+(((IkReal(-1.00000000000000))*(r00)*(x11686)*(x11688)))+(((r00)*(x11680)*(x11681)))+(((r02)*(sj5)*(x11680)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11678)*(x11681)))+(((x11687)*(x11688)))+(((IkReal(-1.00000000000000))*(r12)*(x11678)*(x11682)))+(((x11679)*(x11698)))+(((cj5)*(x11680)*(x11695))));
37867 evalcond[4]=((((IkReal(-1.00000000000000))*(x11678)*(x11694)*(x11695)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11678)*(x11681)))+(sj1)+(((x11688)*(x11696)))+(((IkReal(-1.00000000000000))*(r02)*(x11678)*(x11682)))+(((IkReal(-1.00000000000000))*(r10)*(x11680)*(x11681)))+(((IkReal(-1.00000000000000))*(r11)*(x11679)*(x11686)))+(((IkReal(-1.00000000000000))*(r01)*(x11678)*(x11679)))+(((IkReal(-1.00000000000000))*(cj5)*(x11680)*(x11697)))+(((x11688)*(x11699)))+(((IkReal(-1.00000000000000))*(x11680)*(x11683))));
37868 evalcond[5]=((IkReal(0.0690000000000000))+(((x11689)*(x11701)))+(((IkReal(-1.00000000000000))*(x11685)*(x11692)))+(((IkReal(-0.0100000000000000))*(x11681)*(x11689)))+(((sj0)*(x11691)*(x11695)))+(((IkReal(-1.00000000000000))*(cj0)*(x11691)*(x11697)))+(((IkReal(-1.00000000000000))*(x11684)*(x11685)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11695)))+(((IkReal(0.0100000000000000))*(x11681)*(x11687)))+(((IkReal(-1.00000000000000))*(x11687)*(x11701)))+(((IkReal(-1.00000000000000))*(py)*(x11678)))+(((IkReal(0.0100000000000000))*(cj0)*(x11683)))+(((cj0)*(r12)*(x11684)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11697)))+(((px)*(sj0))));
37869 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(x11681)*(x11699)))+(((IkReal(-1.00000000000000))*(x11699)*(x11701)))+(((x11692)*(x11693)))+(((IkReal(-1.00000000000000))*(px)*(x11678)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11697)))+(((IkReal(-1.00000000000000))*(cj0)*(x11691)*(x11695)))+(((IkReal(-1.00000000000000))*(sj0)*(x11691)*(x11697)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11695)))+(((IkReal(0.0100000000000000))*(sj0)*(x11683)))+(((IkReal(-1.00000000000000))*(x11696)*(x11701)))+(((IkReal(-1.00000000000000))*(py)*(x11686)))+(((IkReal(0.0100000000000000))*(x11681)*(x11696)))+(((x11684)*(x11693)))+(((IkReal(0.364420000000000))*(cj1)))+(((r12)*(sj0)*(x11684))));
37870 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
37871 {
37872 {
37873 IkReal dummyeval[1];
37874 IkReal gconst11;
37875 gconst11=IKsign(sj1);
37876 dummyeval[0]=sj1;
37877 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
37878 {
37879 {
37880 IkReal dummyeval[1];
37881 dummyeval[0]=sj1;
37882 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
37883 {
37884 {
37885 IkReal dummyeval[1];
37886 dummyeval[0]=cj1;
37887 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
37888 {
37889 {
37890 IkReal evalcond[9];
37891 IkReal x11703=((IkReal(1.00000000000000))*(cj0));
37892 IkReal x11704=((cj4)*(sj6));
37893 IkReal x11705=((sj0)*(sj6));
37894 IkReal x11706=((cj5)*(sj4));
37895 IkReal x11707=((IkReal(0.374290000000000))*(sj5));
37896 IkReal x11708=((sj4)*(sj5));
37897 IkReal x11709=((cj0)*(cj6));
37898 IkReal x11710=((IkReal(0.0100000000000000))*(cj5));
37899 IkReal x11711=((cj4)*(sj5));
37900 IkReal x11712=((cj5)*(sj0));
37901 IkReal x11713=((IkReal(0.374290000000000))*(r02));
37902 IkReal x11714=((r20)*(sj6));
37903 IkReal x11715=((cj6)*(r21));
37904 IkReal x11716=((IkReal(1.00000000000000))*(sj0));
37905 IkReal x11717=((cj0)*(sj6));
37906 IkReal x11718=((cj4)*(cj6));
37907 IkReal x11719=((IkReal(0.374290000000000))*(r12));
37908 IkReal x11720=((cj0)*(cj5));
37909 IkReal x11721=((cj6)*(sj5));
37910 IkReal x11722=((cj6)*(r01));
37911 IkReal x11723=((r00)*(sj6));
37912 IkReal x11724=((IkReal(0.0100000000000000))*(sj5));
37913 IkReal x11725=((cj6)*(r11));
37914 IkReal x11726=((IkReal(1.00000000000000))*(r10));
37915 IkReal x11727=((r02)*(sj0));
37916 IkReal x11728=((cj6)*(sj4));
37917 IkReal x11729=((r12)*(x11716));
37918 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
37919 evalcond[1]=((((x11706)*(x11714)))+(((r21)*(x11704)))+(((r22)*(x11708)))+(((x11706)*(x11715)))+(((IkReal(-1.00000000000000))*(r20)*(x11718))));
37920 evalcond[2]=((IkReal(0.364420000000000))+(((x11707)*(x11715)))+(((IkReal(-1.00000000000000))*(x11710)*(x11714)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x11707)*(x11714)))+(((IkReal(-1.00000000000000))*(r22)*(x11724)))+(((IkReal(-1.00000000000000))*(x11710)*(x11715))));
37921 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x11716)*(x11721)))+(((IkReal(-1.00000000000000))*(r01)*(x11703)*(x11721)))+(((r12)*(x11712)))+(((IkReal(-1.00000000000000))*(sj5)*(x11703)*(x11723)))+(((IkReal(-1.00000000000000))*(sj5)*(x11705)*(x11726)))+(((r02)*(x11720))));
37922 evalcond[4]=((((IkReal(-1.00000000000000))*(x11703)*(x11706)*(x11725)))+(((IkReal(-1.00000000000000))*(r00)*(x11716)*(x11718)))+(((r01)*(sj0)*(x11704)))+(((cj4)*(r10)*(x11709)))+(((sj0)*(x11706)*(x11722)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11703)*(x11706)))+(((r00)*(x11705)*(x11706)))+(((IkReal(-1.00000000000000))*(r11)*(x11703)*(x11704)))+(((x11708)*(x11727)))+(((IkReal(-1.00000000000000))*(r12)*(x11703)*(x11708))));
37923 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x11708)*(x11729)))+(((cj4)*(r00)*(x11709)))+(((IkReal(-1.00000000000000))*(x11706)*(x11716)*(x11725)))+(((IkReal(-1.00000000000000))*(x11705)*(x11706)*(x11726)))+(((IkReal(-1.00000000000000))*(r02)*(x11703)*(x11708)))+(((IkReal(-1.00000000000000))*(x11703)*(x11706)*(x11723)))+(((IkReal(-1.00000000000000))*(r11)*(x11704)*(x11716)))+(((IkReal(-1.00000000000000))*(x11703)*(x11706)*(x11722)))+(((r10)*(sj0)*(x11718)))+(((IkReal(-1.00000000000000))*(r01)*(x11703)*(x11704))));
37924 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x11710)*(x11722)))+(((IkReal(-1.00000000000000))*(r00)*(x11705)*(x11710)))+(((x11719)*(x11720)))+(((IkReal(-1.00000000000000))*(r10)*(x11707)*(x11717)))+(((r11)*(x11709)*(x11710)))+(((sj0)*(x11707)*(x11722)))+(((r10)*(x11710)*(x11717)))+(((IkReal(-1.00000000000000))*(x11712)*(x11713)))+(((IkReal(-1.00000000000000))*(r11)*(x11707)*(x11709)))+(((IkReal(-1.00000000000000))*(py)*(x11703)))+(((cj0)*(r12)*(x11724)))+(((IkReal(-1.00000000000000))*(x11724)*(x11727)))+(((px)*(sj0)))+(((r00)*(x11705)*(x11707))));
37925 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x11703)*(x11704)))+(((IkReal(-1.00000000000000))*(x11704)*(x11712)*(x11726)))+(((r11)*(sj4)*(x11705)))+(((IkReal(-1.00000000000000))*(r10)*(x11716)*(x11728)))+(((IkReal(-1.00000000000000))*(r00)*(x11703)*(x11728)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x11703)*(x11718)))+(((r01)*(sj4)*(x11717)))+(((IkReal(-1.00000000000000))*(r11)*(x11712)*(x11718)))+(((IkReal(-1.00000000000000))*(r02)*(x11703)*(x11711)))+(((IkReal(-1.00000000000000))*(x11711)*(x11729))));
37926 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x11707)*(x11725)))+(((IkReal(-1.00000000000000))*(r00)*(x11707)*(x11717)))+(((sj0)*(x11710)*(x11725)))+(((x11712)*(x11719)))+(((IkReal(-1.00000000000000))*(px)*(x11703)))+(((r10)*(x11705)*(x11710)))+(((IkReal(-1.00000000000000))*(r01)*(x11707)*(x11709)))+(((x11713)*(x11720)))+(((IkReal(-1.00000000000000))*(py)*(x11716)))+(((r00)*(x11710)*(x11717)))+(((IkReal(-1.00000000000000))*(r10)*(x11705)*(x11707)))+(((cj0)*(r02)*(x11724)))+(((r01)*(x11709)*(x11710)))+(((r12)*(sj0)*(x11724))));
37927 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
37928 {
37929 {
37930 IkReal j3array[1], cj3array[1], sj3array[1];
37931 bool j3valid[1]={false};
37932 _nj3 = 1;
37933 IkReal x11730=((r20)*(sj6));
37934 IkReal x11731=((cj4)*(cj5));
37935 IkReal x11732=((cj6)*(r21));
37936 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11730)*(x11731)))+(((x11731)*(x11732)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x11732)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11730))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11730)*(x11731)))+(((x11731)*(x11732)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))+IKsqr(((((sj5)*(x11732)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11730)))))-1) <= IKFAST_SINCOS_THRESH )
37937     continue;
37938 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11730)*(x11731)))+(((x11731)*(x11732)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))), ((((sj5)*(x11732)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11730)))));
37939 sj3array[0]=IKsin(j3array[0]);
37940 cj3array[0]=IKcos(j3array[0]);
37941 if( j3array[0] > IKPI )
37942 {
37943     j3array[0]-=IK2PI;
37944 }
37945 else if( j3array[0] < -IKPI )
37946 {    j3array[0]+=IK2PI;
37947 }
37948 j3valid[0] = true;
37949 for(int ij3 = 0; ij3 < 1; ++ij3)
37950 {
37951 if( !j3valid[ij3] )
37952 {
37953     continue;
37954 }
37955 _ij3[0] = ij3; _ij3[1] = -1;
37956 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
37957 {
37958 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
37959 {
37960     j3valid[iij3]=false; _ij3[1] = iij3; break; 
37961 }
37962 }
37963 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
37964 {
37965 IkReal evalcond[4];
37966 IkReal x11733=IKcos(j3);
37967 IkReal x11734=((sj0)*(sj5));
37968 IkReal x11735=((r00)*(sj6));
37969 IkReal x11736=((cj6)*(r01));
37970 IkReal x11737=((cj5)*(sj0));
37971 IkReal x11738=((cj0)*(cj5));
37972 IkReal x11739=((cj6)*(sj4));
37973 IkReal x11740=((sj4)*(sj6));
37974 IkReal x11741=((cj0)*(r11));
37975 IkReal x11742=((cj4)*(cj6));
37976 IkReal x11743=((cj4)*(sj6));
37977 IkReal x11744=((IkReal(1.00000000000000))*(cj0));
37978 IkReal x11745=((cj4)*(sj5));
37979 IkReal x11746=((sj5)*(sj6));
37980 IkReal x11747=((cj6)*(sj5));
37981 IkReal x11748=((IkReal(1.00000000000000))*(IKsin(j3)));
37982 evalcond[0]=((((r20)*(x11746)))+(((IkReal(-1.00000000000000))*(x11733)))+(((r21)*(x11747)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
37983 evalcond[1]=((((cj5)*(r21)*(x11742)))+(((IkReal(-1.00000000000000))*(r21)*(x11740)))+(((cj5)*(r20)*(x11743)))+(((r22)*(x11745)))+(((IkReal(-1.00000000000000))*(x11748)))+(((r20)*(x11739))));
37984 evalcond[2]=((((x11734)*(x11735)))+(((x11734)*(x11736)))+(((IkReal(-1.00000000000000))*(r10)*(x11744)*(x11746)))+(((r12)*(x11738)))+(((IkReal(-1.00000000000000))*(r02)*(x11737)))+(((IkReal(-1.00000000000000))*(x11748)))+(((IkReal(-1.00000000000000))*(x11741)*(x11747))));
37985 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x11738)*(x11742)))+(((cj4)*(x11736)*(x11737)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x11740)))+(((r00)*(sj0)*(x11739)))+(((IkReal(-1.00000000000000))*(r10)*(x11738)*(x11743)))+(((x11740)*(x11741)))+(((cj4)*(r02)*(x11734)))+(x11733)+(((IkReal(-1.00000000000000))*(r10)*(x11739)*(x11744)))+(((IkReal(-1.00000000000000))*(r12)*(x11744)*(x11745)))+(((cj4)*(x11735)*(x11737))));
37986 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
37987 {
37988 continue;
37989 }
37990 }
37991 
37992 {
37993 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
37994 vinfos[0].jointtype = 1;
37995 vinfos[0].foffset = j0;
37996 vinfos[0].indices[0] = _ij0[0];
37997 vinfos[0].indices[1] = _ij0[1];
37998 vinfos[0].maxsolutions = _nj0;
37999 vinfos[1].jointtype = 1;
38000 vinfos[1].foffset = j1;
38001 vinfos[1].indices[0] = _ij1[0];
38002 vinfos[1].indices[1] = _ij1[1];
38003 vinfos[1].maxsolutions = _nj1;
38004 vinfos[2].jointtype = 1;
38005 vinfos[2].foffset = j2;
38006 vinfos[2].indices[0] = _ij2[0];
38007 vinfos[2].indices[1] = _ij2[1];
38008 vinfos[2].maxsolutions = _nj2;
38009 vinfos[3].jointtype = 1;
38010 vinfos[3].foffset = j3;
38011 vinfos[3].indices[0] = _ij3[0];
38012 vinfos[3].indices[1] = _ij3[1];
38013 vinfos[3].maxsolutions = _nj3;
38014 vinfos[4].jointtype = 1;
38015 vinfos[4].foffset = j4;
38016 vinfos[4].indices[0] = _ij4[0];
38017 vinfos[4].indices[1] = _ij4[1];
38018 vinfos[4].maxsolutions = _nj4;
38019 vinfos[5].jointtype = 1;
38020 vinfos[5].foffset = j5;
38021 vinfos[5].indices[0] = _ij5[0];
38022 vinfos[5].indices[1] = _ij5[1];
38023 vinfos[5].maxsolutions = _nj5;
38024 vinfos[6].jointtype = 1;
38025 vinfos[6].foffset = j6;
38026 vinfos[6].indices[0] = _ij6[0];
38027 vinfos[6].indices[1] = _ij6[1];
38028 vinfos[6].maxsolutions = _nj6;
38029 std::vector<int> vfree(0);
38030 solutions.AddSolution(vinfos,vfree);
38031 }
38032 }
38033 }
38034 
38035 } else
38036 {
38037 IkReal x11749=((IkReal(1.00000000000000))*(cj0));
38038 IkReal x11750=((cj4)*(sj6));
38039 IkReal x11751=((sj0)*(sj6));
38040 IkReal x11752=((cj5)*(sj4));
38041 IkReal x11753=((IkReal(0.374290000000000))*(sj5));
38042 IkReal x11754=((sj4)*(sj5));
38043 IkReal x11755=((cj0)*(cj6));
38044 IkReal x11756=((IkReal(0.0100000000000000))*(cj5));
38045 IkReal x11757=((cj4)*(sj5));
38046 IkReal x11758=((cj5)*(sj0));
38047 IkReal x11759=((IkReal(0.374290000000000))*(r02));
38048 IkReal x11760=((r20)*(sj6));
38049 IkReal x11761=((cj6)*(r21));
38050 IkReal x11762=((IkReal(1.00000000000000))*(sj0));
38051 IkReal x11763=((cj0)*(sj6));
38052 IkReal x11764=((cj4)*(cj6));
38053 IkReal x11765=((IkReal(0.374290000000000))*(r12));
38054 IkReal x11766=((cj0)*(cj5));
38055 IkReal x11767=((cj6)*(sj5));
38056 IkReal x11768=((cj6)*(r01));
38057 IkReal x11769=((r00)*(sj6));
38058 IkReal x11770=((IkReal(0.0100000000000000))*(sj5));
38059 IkReal x11771=((cj6)*(r11));
38060 IkReal x11772=((IkReal(1.00000000000000))*(r10));
38061 IkReal x11773=((r02)*(sj0));
38062 IkReal x11774=((cj6)*(sj4));
38063 IkReal x11775=((r12)*(x11762));
38064 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
38065 evalcond[1]=((((r22)*(x11754)))+(((x11752)*(x11760)))+(((r21)*(x11750)))+(((x11752)*(x11761)))+(((IkReal(-1.00000000000000))*(r20)*(x11764))));
38066 evalcond[2]=((IkReal(-0.364420000000000))+(((x11753)*(x11761)))+(((IkReal(-1.00000000000000))*(x11756)*(x11761)))+(((x11753)*(x11760)))+(((IkReal(-1.00000000000000))*(x11756)*(x11760)))+(((IkReal(-1.00000000000000))*(r22)*(x11770)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz));
38067 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x11749)*(x11767)))+(((IkReal(-1.00000000000000))*(sj5)*(x11749)*(x11769)))+(((IkReal(-1.00000000000000))*(r11)*(x11762)*(x11767)))+(((r12)*(x11758)))+(((r02)*(x11766)))+(((IkReal(-1.00000000000000))*(sj5)*(x11751)*(x11772))));
38068 evalcond[4]=((((IkReal(-1.00000000000000))*(r12)*(x11749)*(x11754)))+(((r00)*(x11751)*(x11752)))+(((IkReal(-1.00000000000000))*(r00)*(x11762)*(x11764)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11749)*(x11752)))+(((x11754)*(x11773)))+(((cj4)*(r10)*(x11755)))+(((IkReal(-1.00000000000000))*(r11)*(x11749)*(x11750)))+(((IkReal(-1.00000000000000))*(x11749)*(x11752)*(x11771)))+(((r01)*(sj0)*(x11750)))+(((sj0)*(x11752)*(x11768))));
38069 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r02)*(x11749)*(x11754)))+(((IkReal(-1.00000000000000))*(x11754)*(x11775)))+(((cj4)*(r00)*(x11755)))+(((IkReal(-1.00000000000000))*(r01)*(x11749)*(x11750)))+(((IkReal(-1.00000000000000))*(x11749)*(x11752)*(x11769)))+(((r10)*(sj0)*(x11764)))+(((IkReal(-1.00000000000000))*(x11749)*(x11752)*(x11768)))+(((IkReal(-1.00000000000000))*(x11751)*(x11752)*(x11772)))+(((IkReal(-1.00000000000000))*(r11)*(x11750)*(x11762)))+(((IkReal(-1.00000000000000))*(x11752)*(x11762)*(x11771))));
38070 evalcond[6]=((IkReal(0.0690000000000000))+(((sj0)*(x11753)*(x11768)))+(((r11)*(x11755)*(x11756)))+(((r10)*(x11756)*(x11763)))+(((IkReal(-1.00000000000000))*(r00)*(x11751)*(x11756)))+(((cj0)*(r12)*(x11770)))+(((IkReal(-1.00000000000000))*(sj0)*(x11756)*(x11768)))+(((x11765)*(x11766)))+(((IkReal(-1.00000000000000))*(x11770)*(x11773)))+(((IkReal(-1.00000000000000))*(r11)*(x11753)*(x11755)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(x11753)*(x11763)))+(((IkReal(-1.00000000000000))*(x11758)*(x11759)))+(((r00)*(x11751)*(x11753)))+(((IkReal(-1.00000000000000))*(py)*(x11749))));
38071 evalcond[7]=((((IkReal(-1.00000000000000))*(x11757)*(x11775)))+(((r11)*(sj4)*(x11751)))+(((IkReal(-1.00000000000000))*(r02)*(x11749)*(x11757)))+(((IkReal(-1.00000000000000))*(r11)*(x11758)*(x11764)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x11749)*(x11764)))+(((IkReal(-1.00000000000000))*(r10)*(x11762)*(x11774)))+(((r01)*(sj4)*(x11763)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x11749)*(x11750)))+(((IkReal(-1.00000000000000))*(r00)*(x11749)*(x11774)))+(((IkReal(-1.00000000000000))*(x11750)*(x11758)*(x11772))));
38072 evalcond[8]=((IkReal(0.0690000000000000))+(((cj0)*(r02)*(x11770)))+(((IkReal(-1.00000000000000))*(r01)*(x11753)*(x11755)))+(((IkReal(-1.00000000000000))*(r10)*(x11751)*(x11753)))+(((r10)*(x11751)*(x11756)))+(((IkReal(-1.00000000000000))*(sj0)*(x11753)*(x11771)))+(((IkReal(-1.00000000000000))*(r00)*(x11753)*(x11763)))+(((IkReal(-1.00000000000000))*(px)*(x11749)))+(((r01)*(x11755)*(x11756)))+(((sj0)*(x11756)*(x11771)))+(((r00)*(x11756)*(x11763)))+(((x11758)*(x11765)))+(((x11759)*(x11766)))+(((r12)*(sj0)*(x11770)))+(((IkReal(-1.00000000000000))*(py)*(x11762))));
38073 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
38074 {
38075 {
38076 IkReal j3array[1], cj3array[1], sj3array[1];
38077 bool j3valid[1]={false};
38078 _nj3 = 1;
38079 IkReal x11776=((IkReal(1.00000000000000))*(sj5));
38080 IkReal x11777=((cj6)*(r21));
38081 IkReal x11778=((r20)*(sj6));
38082 IkReal x11779=((IkReal(1.00000000000000))*(cj4)*(cj5));
38083 if( IKabs(((((IkReal(-1.00000000000000))*(x11777)*(x11779)))+(((IkReal(-1.00000000000000))*(x11778)*(x11779)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11776)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x11776)*(x11778)))+(((IkReal(-1.00000000000000))*(x11776)*(x11777)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x11777)*(x11779)))+(((IkReal(-1.00000000000000))*(x11778)*(x11779)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11776)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x11776)*(x11778)))+(((IkReal(-1.00000000000000))*(x11776)*(x11777)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
38084     continue;
38085 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x11777)*(x11779)))+(((IkReal(-1.00000000000000))*(x11778)*(x11779)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11776)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x11776)*(x11778)))+(((IkReal(-1.00000000000000))*(x11776)*(x11777)))+(((cj5)*(r22)))));
38086 sj3array[0]=IKsin(j3array[0]);
38087 cj3array[0]=IKcos(j3array[0]);
38088 if( j3array[0] > IKPI )
38089 {
38090     j3array[0]-=IK2PI;
38091 }
38092 else if( j3array[0] < -IKPI )
38093 {    j3array[0]+=IK2PI;
38094 }
38095 j3valid[0] = true;
38096 for(int ij3 = 0; ij3 < 1; ++ij3)
38097 {
38098 if( !j3valid[ij3] )
38099 {
38100     continue;
38101 }
38102 _ij3[0] = ij3; _ij3[1] = -1;
38103 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38104 {
38105 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38106 {
38107     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38108 }
38109 }
38110 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38111 {
38112 IkReal evalcond[4];
38113 IkReal x11780=IKsin(j3);
38114 IkReal x11781=IKcos(j3);
38115 IkReal x11782=((sj0)*(sj5));
38116 IkReal x11783=((r00)*(sj6));
38117 IkReal x11784=((cj6)*(r01));
38118 IkReal x11785=((cj5)*(sj0));
38119 IkReal x11786=((cj0)*(cj5));
38120 IkReal x11787=((cj6)*(sj4));
38121 IkReal x11788=((sj4)*(sj6));
38122 IkReal x11789=((cj0)*(r11));
38123 IkReal x11790=((cj4)*(cj6));
38124 IkReal x11791=((cj4)*(sj6));
38125 IkReal x11792=((IkReal(1.00000000000000))*(cj0));
38126 IkReal x11793=((cj4)*(sj5));
38127 IkReal x11794=((sj5)*(sj6));
38128 IkReal x11795=((cj6)*(sj5));
38129 evalcond[0]=((x11781)+(((r20)*(x11794)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r21)*(x11795))));
38130 evalcond[1]=((x11780)+(((IkReal(-1.00000000000000))*(r21)*(x11788)))+(((cj5)*(r21)*(x11790)))+(((cj5)*(r20)*(x11791)))+(((r20)*(x11787)))+(((r22)*(x11793))));
38131 evalcond[2]=((((x11782)*(x11784)))+(((IkReal(-1.00000000000000))*(r02)*(x11785)))+(((IkReal(-1.00000000000000))*(x11780)))+(((x11782)*(x11783)))+(((r12)*(x11786)))+(((IkReal(-1.00000000000000))*(r10)*(x11792)*(x11794)))+(((IkReal(-1.00000000000000))*(x11789)*(x11795))));
38132 evalcond[3]=((x11781)+(((IkReal(-1.00000000000000))*(r10)*(x11786)*(x11791)))+(((r00)*(sj0)*(x11787)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x11788)))+(((IkReal(-1.00000000000000))*(r12)*(x11792)*(x11793)))+(((x11788)*(x11789)))+(((cj4)*(x11784)*(x11785)))+(((cj4)*(x11783)*(x11785)))+(((IkReal(-1.00000000000000))*(r10)*(x11787)*(x11792)))+(((IkReal(-1.00000000000000))*(r11)*(x11786)*(x11790)))+(((cj4)*(r02)*(x11782))));
38133 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
38134 {
38135 continue;
38136 }
38137 }
38138 
38139 {
38140 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38141 vinfos[0].jointtype = 1;
38142 vinfos[0].foffset = j0;
38143 vinfos[0].indices[0] = _ij0[0];
38144 vinfos[0].indices[1] = _ij0[1];
38145 vinfos[0].maxsolutions = _nj0;
38146 vinfos[1].jointtype = 1;
38147 vinfos[1].foffset = j1;
38148 vinfos[1].indices[0] = _ij1[0];
38149 vinfos[1].indices[1] = _ij1[1];
38150 vinfos[1].maxsolutions = _nj1;
38151 vinfos[2].jointtype = 1;
38152 vinfos[2].foffset = j2;
38153 vinfos[2].indices[0] = _ij2[0];
38154 vinfos[2].indices[1] = _ij2[1];
38155 vinfos[2].maxsolutions = _nj2;
38156 vinfos[3].jointtype = 1;
38157 vinfos[3].foffset = j3;
38158 vinfos[3].indices[0] = _ij3[0];
38159 vinfos[3].indices[1] = _ij3[1];
38160 vinfos[3].maxsolutions = _nj3;
38161 vinfos[4].jointtype = 1;
38162 vinfos[4].foffset = j4;
38163 vinfos[4].indices[0] = _ij4[0];
38164 vinfos[4].indices[1] = _ij4[1];
38165 vinfos[4].maxsolutions = _nj4;
38166 vinfos[5].jointtype = 1;
38167 vinfos[5].foffset = j5;
38168 vinfos[5].indices[0] = _ij5[0];
38169 vinfos[5].indices[1] = _ij5[1];
38170 vinfos[5].maxsolutions = _nj5;
38171 vinfos[6].jointtype = 1;
38172 vinfos[6].foffset = j6;
38173 vinfos[6].indices[0] = _ij6[0];
38174 vinfos[6].indices[1] = _ij6[1];
38175 vinfos[6].maxsolutions = _nj6;
38176 std::vector<int> vfree(0);
38177 solutions.AddSolution(vinfos,vfree);
38178 }
38179 }
38180 }
38181 
38182 } else
38183 {
38184 if( 1 )
38185 {
38186 continue;
38187 
38188 } else
38189 {
38190 }
38191 }
38192 }
38193 }
38194 
38195 } else
38196 {
38197 {
38198 IkReal j3array[1], cj3array[1], sj3array[1];
38199 bool j3valid[1]={false};
38200 _nj3 = 1;
38201 IkReal x11796=((cj0)*(cj5));
38202 IkReal x11797=((IkReal(1.00000000000000))*(cj0));
38203 IkReal x11798=((cj6)*(r11));
38204 IkReal x11799=((r10)*(sj6));
38205 IkReal x11800=((cj5)*(sj0));
38206 IkReal x11801=((r00)*(sj5)*(sj6));
38207 IkReal x11802=((cj6)*(r01)*(sj5));
38208 IkReal x11803=((IkReal(1.00000000000000))*(sj0)*(sj5));
38209 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11799)))+(((r12)*(x11796)))+(((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11798)))+(((sj0)*(x11802)))+(((IkReal(-1.00000000000000))*(r02)*(x11800)))+(((sj0)*(x11801))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x11796)))+(((IkReal(-1.00000000000000))*(x11797)*(x11802)))+(((IkReal(-1.00000000000000))*(x11799)*(x11803)))+(((IkReal(-1.00000000000000))*(x11797)*(x11801)))+(((r12)*(x11800)))+(((IkReal(-1.00000000000000))*(x11798)*(x11803))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11799)))+(((r12)*(x11796)))+(((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11798)))+(((sj0)*(x11802)))+(((IkReal(-1.00000000000000))*(r02)*(x11800)))+(((sj0)*(x11801)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x11796)))+(((IkReal(-1.00000000000000))*(x11797)*(x11802)))+(((IkReal(-1.00000000000000))*(x11799)*(x11803)))+(((IkReal(-1.00000000000000))*(x11797)*(x11801)))+(((r12)*(x11800)))+(((IkReal(-1.00000000000000))*(x11798)*(x11803)))))))-1) <= IKFAST_SINCOS_THRESH )
38210     continue;
38211 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11799)))+(((r12)*(x11796)))+(((IkReal(-1.00000000000000))*(sj5)*(x11797)*(x11798)))+(((sj0)*(x11802)))+(((IkReal(-1.00000000000000))*(r02)*(x11800)))+(((sj0)*(x11801)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x11796)))+(((IkReal(-1.00000000000000))*(x11797)*(x11802)))+(((IkReal(-1.00000000000000))*(x11799)*(x11803)))+(((IkReal(-1.00000000000000))*(x11797)*(x11801)))+(((r12)*(x11800)))+(((IkReal(-1.00000000000000))*(x11798)*(x11803)))))));
38212 sj3array[0]=IKsin(j3array[0]);
38213 cj3array[0]=IKcos(j3array[0]);
38214 if( j3array[0] > IKPI )
38215 {
38216     j3array[0]-=IK2PI;
38217 }
38218 else if( j3array[0] < -IKPI )
38219 {    j3array[0]+=IK2PI;
38220 }
38221 j3valid[0] = true;
38222 for(int ij3 = 0; ij3 < 1; ++ij3)
38223 {
38224 if( !j3valid[ij3] )
38225 {
38226     continue;
38227 }
38228 _ij3[0] = ij3; _ij3[1] = -1;
38229 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38230 {
38231 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38232 {
38233     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38234 }
38235 }
38236 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38237 {
38238 IkReal evalcond[6];
38239 IkReal x11804=IKsin(j3);
38240 IkReal x11805=IKcos(j3);
38241 IkReal x11806=((sj0)*(sj5));
38242 IkReal x11807=((r00)*(sj6));
38243 IkReal x11808=((cj6)*(r01));
38244 IkReal x11809=((cj4)*(cj5));
38245 IkReal x11810=((IkReal(1.00000000000000))*(cj0));
38246 IkReal x11811=((cj5)*(r12));
38247 IkReal x11812=((IkReal(1.00000000000000))*(sj0));
38248 IkReal x11813=((cj6)*(r11));
38249 IkReal x11814=((cj5)*(r02));
38250 IkReal x11815=((IkReal(1.00000000000000))*(cj1));
38251 IkReal x11816=((cj6)*(sj4));
38252 IkReal x11817=((cj6)*(r21));
38253 IkReal x11818=((r20)*(sj6));
38254 IkReal x11819=((r10)*(sj6));
38255 IkReal x11820=((sj4)*(sj6));
38256 IkReal x11821=((cj4)*(r02));
38257 IkReal x11822=((IkReal(1.00000000000000))*(cj4)*(r12));
38258 IkReal x11823=((IkReal(1.00000000000000))*(x11804));
38259 IkReal x11824=((cj0)*(x11820));
38260 evalcond[0]=((((sj5)*(x11817)))+(((sj5)*(x11818)))+(((IkReal(-1.00000000000000))*(sj1)*(x11805)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
38261 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x11820)))+(((IkReal(-1.00000000000000))*(sj1)*(x11823)))+(((cj4)*(r22)*(sj5)))+(((x11809)*(x11818)))+(((x11809)*(x11817)))+(((r20)*(x11816))));
38262 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x11810)*(x11813)))+(((IkReal(-1.00000000000000))*(sj5)*(x11810)*(x11819)))+(((cj0)*(x11811)))+(((x11806)*(x11808)))+(((IkReal(-1.00000000000000))*(x11823)))+(((IkReal(-1.00000000000000))*(x11812)*(x11814)))+(((x11806)*(x11807))));
38263 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x11808)*(x11810)))+(((sj0)*(x11811)))+(((IkReal(-1.00000000000000))*(sj5)*(x11807)*(x11810)))+(((cj0)*(x11814)))+(((IkReal(-1.00000000000000))*(x11806)*(x11819)))+(((IkReal(-1.00000000000000))*(x11806)*(x11813)))+(((IkReal(-1.00000000000000))*(x11805)*(x11815))));
38264 evalcond[4]=((((r11)*(x11824)))+(((x11806)*(x11821)))+(((IkReal(-1.00000000000000))*(r01)*(x11812)*(x11820)))+(((sj0)*(x11807)*(x11809)))+(((r00)*(sj0)*(x11816)))+(((sj0)*(x11808)*(x11809)))+(((IkReal(-1.00000000000000))*(r10)*(x11810)*(x11816)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x11810)))+(((IkReal(-1.00000000000000))*(x11809)*(x11810)*(x11819)))+(x11805)+(((IkReal(-1.00000000000000))*(x11809)*(x11810)*(x11813))));
38265 evalcond[5]=((((IkReal(-1.00000000000000))*(sj5)*(x11810)*(x11821)))+(((IkReal(-1.00000000000000))*(x11808)*(x11809)*(x11810)))+(((r11)*(sj0)*(x11820)))+(((IkReal(-1.00000000000000))*(x11806)*(x11822)))+(((IkReal(-1.00000000000000))*(r00)*(x11810)*(x11816)))+(((IkReal(-1.00000000000000))*(r10)*(x11812)*(x11816)))+(((IkReal(-1.00000000000000))*(x11804)*(x11815)))+(((IkReal(-1.00000000000000))*(x11807)*(x11809)*(x11810)))+(((IkReal(-1.00000000000000))*(x11809)*(x11812)*(x11819)))+(((IkReal(-1.00000000000000))*(x11809)*(x11812)*(x11813)))+(((r01)*(x11824))));
38266 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
38267 {
38268 continue;
38269 }
38270 }
38271 
38272 {
38273 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38274 vinfos[0].jointtype = 1;
38275 vinfos[0].foffset = j0;
38276 vinfos[0].indices[0] = _ij0[0];
38277 vinfos[0].indices[1] = _ij0[1];
38278 vinfos[0].maxsolutions = _nj0;
38279 vinfos[1].jointtype = 1;
38280 vinfos[1].foffset = j1;
38281 vinfos[1].indices[0] = _ij1[0];
38282 vinfos[1].indices[1] = _ij1[1];
38283 vinfos[1].maxsolutions = _nj1;
38284 vinfos[2].jointtype = 1;
38285 vinfos[2].foffset = j2;
38286 vinfos[2].indices[0] = _ij2[0];
38287 vinfos[2].indices[1] = _ij2[1];
38288 vinfos[2].maxsolutions = _nj2;
38289 vinfos[3].jointtype = 1;
38290 vinfos[3].foffset = j3;
38291 vinfos[3].indices[0] = _ij3[0];
38292 vinfos[3].indices[1] = _ij3[1];
38293 vinfos[3].maxsolutions = _nj3;
38294 vinfos[4].jointtype = 1;
38295 vinfos[4].foffset = j4;
38296 vinfos[4].indices[0] = _ij4[0];
38297 vinfos[4].indices[1] = _ij4[1];
38298 vinfos[4].maxsolutions = _nj4;
38299 vinfos[5].jointtype = 1;
38300 vinfos[5].foffset = j5;
38301 vinfos[5].indices[0] = _ij5[0];
38302 vinfos[5].indices[1] = _ij5[1];
38303 vinfos[5].maxsolutions = _nj5;
38304 vinfos[6].jointtype = 1;
38305 vinfos[6].foffset = j6;
38306 vinfos[6].indices[0] = _ij6[0];
38307 vinfos[6].indices[1] = _ij6[1];
38308 vinfos[6].maxsolutions = _nj6;
38309 std::vector<int> vfree(0);
38310 solutions.AddSolution(vinfos,vfree);
38311 }
38312 }
38313 }
38314 
38315 }
38316 
38317 }
38318 
38319 } else
38320 {
38321 {
38322 IkReal j3array[1], cj3array[1], sj3array[1];
38323 bool j3valid[1]={false};
38324 _nj3 = 1;
38325 IkReal x11825=((sj5)*(sj6));
38326 IkReal x11826=((cj6)*(sj5));
38327 IkReal x11827=((IkReal(1.00000000000000))*(cj0));
38328 IkReal x11828=((IkReal(1.00000000000000))*(cj5));
38329 if( IKabs(((((r01)*(sj0)*(x11826)))+(((r00)*(sj0)*(x11825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11828)))+(((IkReal(-1.00000000000000))*(r11)*(x11826)*(x11827)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x11825)*(x11827))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x11826)))+(((IkReal(-1.00000000000000))*(r22)*(x11828)))+(((r20)*(x11825))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((r01)*(sj0)*(x11826)))+(((r00)*(sj0)*(x11825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11828)))+(((IkReal(-1.00000000000000))*(r11)*(x11826)*(x11827)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x11825)*(x11827)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x11826)))+(((IkReal(-1.00000000000000))*(r22)*(x11828)))+(((r20)*(x11825)))))))-1) <= IKFAST_SINCOS_THRESH )
38330     continue;
38331 j3array[0]=IKatan2(((((r01)*(sj0)*(x11826)))+(((r00)*(sj0)*(x11825)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11828)))+(((IkReal(-1.00000000000000))*(r11)*(x11826)*(x11827)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x11825)*(x11827)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((r21)*(x11826)))+(((IkReal(-1.00000000000000))*(r22)*(x11828)))+(((r20)*(x11825)))))));
38332 sj3array[0]=IKsin(j3array[0]);
38333 cj3array[0]=IKcos(j3array[0]);
38334 if( j3array[0] > IKPI )
38335 {
38336     j3array[0]-=IK2PI;
38337 }
38338 else if( j3array[0] < -IKPI )
38339 {    j3array[0]+=IK2PI;
38340 }
38341 j3valid[0] = true;
38342 for(int ij3 = 0; ij3 < 1; ++ij3)
38343 {
38344 if( !j3valid[ij3] )
38345 {
38346     continue;
38347 }
38348 _ij3[0] = ij3; _ij3[1] = -1;
38349 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38350 {
38351 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38352 {
38353     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38354 }
38355 }
38356 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38357 {
38358 IkReal evalcond[6];
38359 IkReal x11829=IKsin(j3);
38360 IkReal x11830=IKcos(j3);
38361 IkReal x11831=((sj0)*(sj5));
38362 IkReal x11832=((r00)*(sj6));
38363 IkReal x11833=((cj6)*(r01));
38364 IkReal x11834=((cj4)*(cj5));
38365 IkReal x11835=((IkReal(1.00000000000000))*(cj0));
38366 IkReal x11836=((cj5)*(r12));
38367 IkReal x11837=((IkReal(1.00000000000000))*(sj0));
38368 IkReal x11838=((cj6)*(r11));
38369 IkReal x11839=((cj5)*(r02));
38370 IkReal x11840=((IkReal(1.00000000000000))*(cj1));
38371 IkReal x11841=((cj6)*(sj4));
38372 IkReal x11842=((cj6)*(r21));
38373 IkReal x11843=((r20)*(sj6));
38374 IkReal x11844=((r10)*(sj6));
38375 IkReal x11845=((sj4)*(sj6));
38376 IkReal x11846=((cj4)*(r02));
38377 IkReal x11847=((IkReal(1.00000000000000))*(cj4)*(r12));
38378 IkReal x11848=((IkReal(1.00000000000000))*(x11829));
38379 IkReal x11849=((cj0)*(x11845));
38380 evalcond[0]=((((sj5)*(x11842)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x11830)))+(((sj5)*(x11843))));
38381 evalcond[1]=((((r20)*(x11841)))+(((IkReal(-1.00000000000000))*(sj1)*(x11848)))+(((x11834)*(x11843)))+(((cj4)*(r22)*(sj5)))+(((x11834)*(x11842)))+(((IkReal(-1.00000000000000))*(r21)*(x11845))));
38382 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x11835)*(x11844)))+(((IkReal(-1.00000000000000))*(sj5)*(x11835)*(x11838)))+(((x11831)*(x11833)))+(((IkReal(-1.00000000000000))*(x11837)*(x11839)))+(((x11831)*(x11832)))+(((IkReal(-1.00000000000000))*(x11848)))+(((cj0)*(x11836))));
38383 evalcond[3]=((((IkReal(-1.00000000000000))*(x11830)*(x11840)))+(((IkReal(-1.00000000000000))*(sj5)*(x11833)*(x11835)))+(((cj0)*(x11839)))+(((IkReal(-1.00000000000000))*(x11831)*(x11838)))+(((IkReal(-1.00000000000000))*(sj5)*(x11832)*(x11835)))+(((sj0)*(x11836)))+(((IkReal(-1.00000000000000))*(x11831)*(x11844))));
38384 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x11835)))+(((IkReal(-1.00000000000000))*(r10)*(x11835)*(x11841)))+(((sj0)*(x11833)*(x11834)))+(((x11831)*(x11846)))+(((IkReal(-1.00000000000000))*(r01)*(x11837)*(x11845)))+(((r11)*(x11849)))+(((IkReal(-1.00000000000000))*(x11834)*(x11835)*(x11838)))+(((IkReal(-1.00000000000000))*(x11834)*(x11835)*(x11844)))+(x11830)+(((sj0)*(x11832)*(x11834)))+(((r00)*(sj0)*(x11841))));
38385 evalcond[5]=((((IkReal(-1.00000000000000))*(x11834)*(x11837)*(x11844)))+(((IkReal(-1.00000000000000))*(x11832)*(x11834)*(x11835)))+(((IkReal(-1.00000000000000))*(x11834)*(x11837)*(x11838)))+(((r01)*(x11849)))+(((IkReal(-1.00000000000000))*(x11831)*(x11847)))+(((IkReal(-1.00000000000000))*(r10)*(x11837)*(x11841)))+(((IkReal(-1.00000000000000))*(x11833)*(x11834)*(x11835)))+(((IkReal(-1.00000000000000))*(r00)*(x11835)*(x11841)))+(((r11)*(sj0)*(x11845)))+(((IkReal(-1.00000000000000))*(sj5)*(x11835)*(x11846)))+(((IkReal(-1.00000000000000))*(x11829)*(x11840))));
38386 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
38387 {
38388 continue;
38389 }
38390 }
38391 
38392 {
38393 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38394 vinfos[0].jointtype = 1;
38395 vinfos[0].foffset = j0;
38396 vinfos[0].indices[0] = _ij0[0];
38397 vinfos[0].indices[1] = _ij0[1];
38398 vinfos[0].maxsolutions = _nj0;
38399 vinfos[1].jointtype = 1;
38400 vinfos[1].foffset = j1;
38401 vinfos[1].indices[0] = _ij1[0];
38402 vinfos[1].indices[1] = _ij1[1];
38403 vinfos[1].maxsolutions = _nj1;
38404 vinfos[2].jointtype = 1;
38405 vinfos[2].foffset = j2;
38406 vinfos[2].indices[0] = _ij2[0];
38407 vinfos[2].indices[1] = _ij2[1];
38408 vinfos[2].maxsolutions = _nj2;
38409 vinfos[3].jointtype = 1;
38410 vinfos[3].foffset = j3;
38411 vinfos[3].indices[0] = _ij3[0];
38412 vinfos[3].indices[1] = _ij3[1];
38413 vinfos[3].maxsolutions = _nj3;
38414 vinfos[4].jointtype = 1;
38415 vinfos[4].foffset = j4;
38416 vinfos[4].indices[0] = _ij4[0];
38417 vinfos[4].indices[1] = _ij4[1];
38418 vinfos[4].maxsolutions = _nj4;
38419 vinfos[5].jointtype = 1;
38420 vinfos[5].foffset = j5;
38421 vinfos[5].indices[0] = _ij5[0];
38422 vinfos[5].indices[1] = _ij5[1];
38423 vinfos[5].maxsolutions = _nj5;
38424 vinfos[6].jointtype = 1;
38425 vinfos[6].foffset = j6;
38426 vinfos[6].indices[0] = _ij6[0];
38427 vinfos[6].indices[1] = _ij6[1];
38428 vinfos[6].maxsolutions = _nj6;
38429 std::vector<int> vfree(0);
38430 solutions.AddSolution(vinfos,vfree);
38431 }
38432 }
38433 }
38434 
38435 }
38436 
38437 }
38438 
38439 } else
38440 {
38441 {
38442 IkReal j3array[1], cj3array[1], sj3array[1];
38443 bool j3valid[1]={false};
38444 _nj3 = 1;
38445 IkReal x11850=((r20)*(sj6));
38446 IkReal x11851=((cj4)*(cj5));
38447 IkReal x11852=((cj6)*(r21));
38448 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11851)*(x11852)))+(((x11850)*(x11851)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11850)))+(((sj5)*(x11852))))))) < IKFAST_ATAN2_MAGTHRESH )
38449     continue;
38450 j3array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11851)*(x11852)))+(((x11850)*(x11851)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))), ((gconst11)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11850)))+(((sj5)*(x11852)))))));
38451 sj3array[0]=IKsin(j3array[0]);
38452 cj3array[0]=IKcos(j3array[0]);
38453 if( j3array[0] > IKPI )
38454 {
38455     j3array[0]-=IK2PI;
38456 }
38457 else if( j3array[0] < -IKPI )
38458 {    j3array[0]+=IK2PI;
38459 }
38460 j3valid[0] = true;
38461 for(int ij3 = 0; ij3 < 1; ++ij3)
38462 {
38463 if( !j3valid[ij3] )
38464 {
38465     continue;
38466 }
38467 _ij3[0] = ij3; _ij3[1] = -1;
38468 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38469 {
38470 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38471 {
38472     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38473 }
38474 }
38475 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38476 {
38477 IkReal evalcond[6];
38478 IkReal x11853=IKsin(j3);
38479 IkReal x11854=IKcos(j3);
38480 IkReal x11855=((sj0)*(sj5));
38481 IkReal x11856=((r00)*(sj6));
38482 IkReal x11857=((cj6)*(r01));
38483 IkReal x11858=((cj4)*(cj5));
38484 IkReal x11859=((IkReal(1.00000000000000))*(cj0));
38485 IkReal x11860=((cj5)*(r12));
38486 IkReal x11861=((IkReal(1.00000000000000))*(sj0));
38487 IkReal x11862=((cj6)*(r11));
38488 IkReal x11863=((cj5)*(r02));
38489 IkReal x11864=((IkReal(1.00000000000000))*(cj1));
38490 IkReal x11865=((cj6)*(sj4));
38491 IkReal x11866=((cj6)*(r21));
38492 IkReal x11867=((r20)*(sj6));
38493 IkReal x11868=((r10)*(sj6));
38494 IkReal x11869=((sj4)*(sj6));
38495 IkReal x11870=((cj4)*(r02));
38496 IkReal x11871=((IkReal(1.00000000000000))*(cj4)*(r12));
38497 IkReal x11872=((IkReal(1.00000000000000))*(x11853));
38498 IkReal x11873=((cj0)*(x11869));
38499 evalcond[0]=((((sj5)*(x11866)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x11867)))+(((IkReal(-1.00000000000000))*(sj1)*(x11854))));
38500 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x11869)))+(((cj4)*(r22)*(sj5)))+(((x11858)*(x11866)))+(((x11858)*(x11867)))+(((r20)*(x11865)))+(((IkReal(-1.00000000000000))*(sj1)*(x11872))));
38501 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x11859)*(x11862)))+(((IkReal(-1.00000000000000))*(sj5)*(x11859)*(x11868)))+(((cj0)*(x11860)))+(((IkReal(-1.00000000000000))*(x11872)))+(((x11855)*(x11857)))+(((IkReal(-1.00000000000000))*(x11861)*(x11863)))+(((x11855)*(x11856))));
38502 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x11857)*(x11859)))+(((IkReal(-1.00000000000000))*(x11854)*(x11864)))+(((IkReal(-1.00000000000000))*(x11855)*(x11862)))+(((IkReal(-1.00000000000000))*(sj5)*(x11856)*(x11859)))+(((IkReal(-1.00000000000000))*(x11855)*(x11868)))+(((sj0)*(x11860)))+(((cj0)*(x11863))));
38503 evalcond[4]=((((r00)*(sj0)*(x11865)))+(((IkReal(-1.00000000000000))*(x11858)*(x11859)*(x11868)))+(((sj0)*(x11857)*(x11858)))+(((IkReal(-1.00000000000000))*(x11858)*(x11859)*(x11862)))+(((r11)*(x11873)))+(((x11855)*(x11870)))+(((IkReal(-1.00000000000000))*(r01)*(x11861)*(x11869)))+(((IkReal(-1.00000000000000))*(r10)*(x11859)*(x11865)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x11859)))+(x11854)+(((sj0)*(x11856)*(x11858))));
38504 evalcond[5]=((((r01)*(x11873)))+(((IkReal(-1.00000000000000))*(x11858)*(x11861)*(x11862)))+(((IkReal(-1.00000000000000))*(x11855)*(x11871)))+(((IkReal(-1.00000000000000))*(x11856)*(x11858)*(x11859)))+(((IkReal(-1.00000000000000))*(x11857)*(x11858)*(x11859)))+(((r11)*(sj0)*(x11869)))+(((IkReal(-1.00000000000000))*(x11858)*(x11861)*(x11868)))+(((IkReal(-1.00000000000000))*(r00)*(x11859)*(x11865)))+(((IkReal(-1.00000000000000))*(r10)*(x11861)*(x11865)))+(((IkReal(-1.00000000000000))*(sj5)*(x11859)*(x11870)))+(((IkReal(-1.00000000000000))*(x11853)*(x11864))));
38505 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
38506 {
38507 continue;
38508 }
38509 }
38510 
38511 {
38512 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38513 vinfos[0].jointtype = 1;
38514 vinfos[0].foffset = j0;
38515 vinfos[0].indices[0] = _ij0[0];
38516 vinfos[0].indices[1] = _ij0[1];
38517 vinfos[0].maxsolutions = _nj0;
38518 vinfos[1].jointtype = 1;
38519 vinfos[1].foffset = j1;
38520 vinfos[1].indices[0] = _ij1[0];
38521 vinfos[1].indices[1] = _ij1[1];
38522 vinfos[1].maxsolutions = _nj1;
38523 vinfos[2].jointtype = 1;
38524 vinfos[2].foffset = j2;
38525 vinfos[2].indices[0] = _ij2[0];
38526 vinfos[2].indices[1] = _ij2[1];
38527 vinfos[2].maxsolutions = _nj2;
38528 vinfos[3].jointtype = 1;
38529 vinfos[3].foffset = j3;
38530 vinfos[3].indices[0] = _ij3[0];
38531 vinfos[3].indices[1] = _ij3[1];
38532 vinfos[3].maxsolutions = _nj3;
38533 vinfos[4].jointtype = 1;
38534 vinfos[4].foffset = j4;
38535 vinfos[4].indices[0] = _ij4[0];
38536 vinfos[4].indices[1] = _ij4[1];
38537 vinfos[4].maxsolutions = _nj4;
38538 vinfos[5].jointtype = 1;
38539 vinfos[5].foffset = j5;
38540 vinfos[5].indices[0] = _ij5[0];
38541 vinfos[5].indices[1] = _ij5[1];
38542 vinfos[5].maxsolutions = _nj5;
38543 vinfos[6].jointtype = 1;
38544 vinfos[6].foffset = j6;
38545 vinfos[6].indices[0] = _ij6[0];
38546 vinfos[6].indices[1] = _ij6[1];
38547 vinfos[6].maxsolutions = _nj6;
38548 std::vector<int> vfree(0);
38549 solutions.AddSolution(vinfos,vfree);
38550 }
38551 }
38552 }
38553 
38554 }
38555 
38556 }
38557 
38558 } else
38559 {
38560 IkReal x11874=((IkReal(1.00000000000000))*(cj0));
38561 IkReal x11875=((cj4)*(sj6));
38562 IkReal x11876=((sj0)*(sj4));
38563 IkReal x11877=((cj5)*(sj6));
38564 IkReal x11878=((sj4)*(sj5));
38565 IkReal x11879=((r12)*(sj5));
38566 IkReal x11880=((IkReal(0.374290000000000))*(cj5));
38567 IkReal x11881=((r02)*(sj0));
38568 IkReal x11882=((IkReal(1.00000000000000))*(sj0));
38569 IkReal x11883=((cj0)*(r10));
38570 IkReal x11884=((cj4)*(cj6));
38571 IkReal x11885=((r00)*(sj0));
38572 IkReal x11886=((cj6)*(r21));
38573 IkReal x11887=((IkReal(0.374290000000000))*(sj5));
38574 IkReal x11888=((cj0)*(r00));
38575 IkReal x11889=((IkReal(0.0100000000000000))*(sj5));
38576 IkReal x11890=((cj0)*(r02));
38577 IkReal x11891=((cj5)*(sj4));
38578 IkReal x11892=((cj6)*(r01));
38579 IkReal x11893=((cj6)*(r11));
38580 IkReal x11894=((r01)*(sj0));
38581 IkReal x11895=((r10)*(sj0));
38582 IkReal x11896=((IkReal(0.0100000000000000))*(cj5)*(cj6));
38583 IkReal x11897=((sj6)*(x11887));
38584 IkReal x11898=((cj0)*(cj6)*(x11887));
38585 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
38586 evalcond[1]=((((r22)*(x11878)))+(((r21)*(x11875)))+(((x11886)*(x11891)))+(cj1)+(((IkReal(-1.00000000000000))*(r20)*(x11884)))+(((r20)*(sj4)*(x11877))));
38587 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x11880)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.0100000000000000))*(r20)*(x11877)))+(((IkReal(-0.0100000000000000))*(cj5)*(x11886)))+(((r20)*(x11897)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x11889)))+(((x11886)*(x11887))));
38588 evalcond[3]=((((r02)*(sj5)*(x11876)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x11874)*(x11877)))+(((IkReal(-1.00000000000000))*(r11)*(x11874)*(x11875)))+(((IkReal(-1.00000000000000))*(r00)*(x11882)*(x11884)))+(((x11883)*(x11884)))+(((IkReal(-1.00000000000000))*(r12)*(x11874)*(x11878)))+(((r00)*(x11876)*(x11877)))+(((IkReal(-1.00000000000000))*(x11874)*(x11891)*(x11893)))+(((x11875)*(x11894)))+(((cj5)*(x11876)*(x11892))));
38589 evalcond[4]=((((x11884)*(x11895)))+(((IkReal(-1.00000000000000))*(x11876)*(x11879)))+(((IkReal(-1.00000000000000))*(cj5)*(x11876)*(x11893)))+(((IkReal(-1.00000000000000))*(x11874)*(x11891)*(x11892)))+(((IkReal(-1.00000000000000))*(r01)*(x11874)*(x11875)))+(((x11884)*(x11888)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r10)*(x11876)*(x11877)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x11874)*(x11877)))+(((IkReal(-1.00000000000000))*(r11)*(x11875)*(x11882)))+(((IkReal(-1.00000000000000))*(r02)*(x11874)*(x11878))));
38590 evalcond[5]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x11874)))+(((IkReal(-1.00000000000000))*(cj0)*(x11887)*(x11893)))+(((IkReal(-0.0100000000000000))*(x11877)*(x11885)))+(((IkReal(-1.00000000000000))*(x11880)*(x11881)))+(((cj0)*(r12)*(x11880)))+(((IkReal(0.0100000000000000))*(cj0)*(x11879)))+(((IkReal(-1.00000000000000))*(x11881)*(x11889)))+(((x11885)*(x11897)))+(((IkReal(0.0100000000000000))*(x11877)*(x11883)))+(((sj0)*(x11887)*(x11892)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11893)))+(((IkReal(-1.00000000000000))*(x11883)*(x11897)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x11892))));
38591 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x11887)*(x11892)))+(((x11889)*(x11890)))+(((IkReal(-1.00000000000000))*(sj0)*(x11887)*(x11893)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x11893)))+(((IkReal(0.0100000000000000))*(sj0)*(x11879)))+(((r12)*(sj0)*(x11880)))+(((IkReal(-1.00000000000000))*(x11895)*(x11897)))+(((IkReal(0.0100000000000000))*(x11877)*(x11895)))+(((IkReal(-1.00000000000000))*(py)*(x11882)))+(((IkReal(-1.00000000000000))*(x11888)*(x11897)))+(((x11880)*(x11890)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x11892)))+(((IkReal(0.0100000000000000))*(x11877)*(x11888)))+(((IkReal(-1.00000000000000))*(px)*(x11874)))+(((IkReal(0.364420000000000))*(cj1))));
38592 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
38593 {
38594 {
38595 IkReal dummyeval[1];
38596 IkReal gconst12;
38597 gconst12=IKsign(sj1);
38598 dummyeval[0]=sj1;
38599 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
38600 {
38601 {
38602 IkReal dummyeval[1];
38603 dummyeval[0]=sj1;
38604 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
38605 {
38606 {
38607 IkReal dummyeval[1];
38608 dummyeval[0]=cj1;
38609 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
38610 {
38611 {
38612 IkReal evalcond[9];
38613 IkReal x11899=((IkReal(1.00000000000000))*(cj0));
38614 IkReal x11900=((cj4)*(sj6));
38615 IkReal x11901=((sj0)*(sj6));
38616 IkReal x11902=((cj5)*(sj4));
38617 IkReal x11903=((IkReal(0.374290000000000))*(sj5));
38618 IkReal x11904=((sj4)*(sj5));
38619 IkReal x11905=((cj0)*(cj6));
38620 IkReal x11906=((IkReal(0.0100000000000000))*(cj5));
38621 IkReal x11907=((cj4)*(sj5));
38622 IkReal x11908=((cj5)*(sj0));
38623 IkReal x11909=((IkReal(0.374290000000000))*(r02));
38624 IkReal x11910=((r20)*(sj6));
38625 IkReal x11911=((cj6)*(r21));
38626 IkReal x11912=((IkReal(1.00000000000000))*(sj0));
38627 IkReal x11913=((cj0)*(sj6));
38628 IkReal x11914=((cj4)*(cj6));
38629 IkReal x11915=((IkReal(0.374290000000000))*(r12));
38630 IkReal x11916=((cj0)*(cj5));
38631 IkReal x11917=((cj6)*(sj5));
38632 IkReal x11918=((cj6)*(r01));
38633 IkReal x11919=((r00)*(sj6));
38634 IkReal x11920=((IkReal(0.0100000000000000))*(sj5));
38635 IkReal x11921=((cj6)*(r11));
38636 IkReal x11922=((IkReal(1.00000000000000))*(r10));
38637 IkReal x11923=((r02)*(sj0));
38638 IkReal x11924=((cj6)*(sj4));
38639 IkReal x11925=((r12)*(x11912));
38640 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
38641 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x11914)))+(((r21)*(x11900)))+(((x11902)*(x11911)))+(((x11902)*(x11910)))+(((r22)*(x11904))));
38642 evalcond[2]=((IkReal(0.364420000000000))+(((IkReal(-1.00000000000000))*(x11906)*(x11910)))+(((x11903)*(x11911)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x11903)*(x11910)))+(pz)+(((IkReal(-1.00000000000000))*(x11906)*(x11911)))+(((IkReal(-1.00000000000000))*(r22)*(x11920))));
38643 evalcond[3]=((((r12)*(x11908)))+(((IkReal(-1.00000000000000))*(r11)*(x11912)*(x11917)))+(((IkReal(-1.00000000000000))*(r01)*(x11899)*(x11917)))+(((IkReal(-1.00000000000000))*(sj5)*(x11901)*(x11922)))+(((IkReal(-1.00000000000000))*(sj5)*(x11899)*(x11919)))+(((r02)*(x11916))));
38644 evalcond[4]=((((IkReal(-1.00000000000000))*(x11899)*(x11902)*(x11921)))+(((sj0)*(x11902)*(x11918)))+(((cj4)*(r10)*(x11905)))+(((IkReal(-1.00000000000000))*(r12)*(x11899)*(x11904)))+(((r01)*(sj0)*(x11900)))+(((x11904)*(x11923)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11899)*(x11902)))+(((r00)*(x11901)*(x11902)))+(((IkReal(-1.00000000000000))*(r00)*(x11912)*(x11914)))+(((IkReal(-1.00000000000000))*(r11)*(x11899)*(x11900))));
38645 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x11904)*(x11925)))+(((cj4)*(r00)*(x11905)))+(((IkReal(-1.00000000000000))*(r01)*(x11899)*(x11900)))+(((IkReal(-1.00000000000000))*(x11899)*(x11902)*(x11918)))+(((IkReal(-1.00000000000000))*(r02)*(x11899)*(x11904)))+(((IkReal(-1.00000000000000))*(x11902)*(x11912)*(x11921)))+(((IkReal(-1.00000000000000))*(x11899)*(x11902)*(x11919)))+(((IkReal(-1.00000000000000))*(x11901)*(x11902)*(x11922)))+(((r10)*(sj0)*(x11914)))+(((IkReal(-1.00000000000000))*(r11)*(x11900)*(x11912))));
38646 evalcond[6]=((IkReal(-0.0690000000000000))+(((sj0)*(x11903)*(x11918)))+(((IkReal(-1.00000000000000))*(x11908)*(x11909)))+(((IkReal(-1.00000000000000))*(r10)*(x11903)*(x11913)))+(((IkReal(-1.00000000000000))*(py)*(x11899)))+(((IkReal(-1.00000000000000))*(x11920)*(x11923)))+(((IkReal(-1.00000000000000))*(r11)*(x11903)*(x11905)))+(((r11)*(x11905)*(x11906)))+(((IkReal(-1.00000000000000))*(r00)*(x11901)*(x11906)))+(((IkReal(-1.00000000000000))*(sj0)*(x11906)*(x11918)))+(((cj0)*(r12)*(x11920)))+(((px)*(sj0)))+(((r10)*(x11906)*(x11913)))+(((x11915)*(x11916)))+(((r00)*(x11901)*(x11903))));
38647 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x11899)*(x11900)))+(((IkReal(-1.00000000000000))*(x11900)*(x11908)*(x11922)))+(((IkReal(-1.00000000000000))*(r00)*(x11899)*(x11924)))+(((r11)*(sj4)*(x11901)))+(((r01)*(sj4)*(x11913)))+(((IkReal(-1.00000000000000))*(r11)*(x11908)*(x11914)))+(((IkReal(-1.00000000000000))*(r02)*(x11899)*(x11907)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x11899)*(x11914)))+(((IkReal(-1.00000000000000))*(x11907)*(x11925)))+(((IkReal(-1.00000000000000))*(r10)*(x11912)*(x11924))));
38648 evalcond[8]=((IkReal(0.0690000000000000))+(((r12)*(sj0)*(x11920)))+(((IkReal(-1.00000000000000))*(px)*(x11899)))+(((IkReal(-1.00000000000000))*(r10)*(x11901)*(x11903)))+(((IkReal(-1.00000000000000))*(r00)*(x11903)*(x11913)))+(((cj0)*(r02)*(x11920)))+(((r00)*(x11906)*(x11913)))+(((r10)*(x11901)*(x11906)))+(((IkReal(-1.00000000000000))*(py)*(x11912)))+(((IkReal(-1.00000000000000))*(r01)*(x11903)*(x11905)))+(((x11909)*(x11916)))+(((r01)*(x11905)*(x11906)))+(((IkReal(-1.00000000000000))*(sj0)*(x11903)*(x11921)))+(((sj0)*(x11906)*(x11921)))+(((x11908)*(x11915))));
38649 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
38650 {
38651 {
38652 IkReal j3array[1], cj3array[1], sj3array[1];
38653 bool j3valid[1]={false};
38654 _nj3 = 1;
38655 IkReal x11926=((r20)*(sj6));
38656 IkReal x11927=((cj4)*(cj5));
38657 IkReal x11928=((cj6)*(r21));
38658 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11927)*(x11928)))+(((x11926)*(x11927)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x11926)))+(((sj5)*(x11928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11927)*(x11928)))+(((x11926)*(x11927)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))+IKsqr(((((sj5)*(x11926)))+(((sj5)*(x11928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
38659     continue;
38660 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x11927)*(x11928)))+(((x11926)*(x11927)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))), ((((sj5)*(x11926)))+(((sj5)*(x11928)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))));
38661 sj3array[0]=IKsin(j3array[0]);
38662 cj3array[0]=IKcos(j3array[0]);
38663 if( j3array[0] > IKPI )
38664 {
38665     j3array[0]-=IK2PI;
38666 }
38667 else if( j3array[0] < -IKPI )
38668 {    j3array[0]+=IK2PI;
38669 }
38670 j3valid[0] = true;
38671 for(int ij3 = 0; ij3 < 1; ++ij3)
38672 {
38673 if( !j3valid[ij3] )
38674 {
38675     continue;
38676 }
38677 _ij3[0] = ij3; _ij3[1] = -1;
38678 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38679 {
38680 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38681 {
38682     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38683 }
38684 }
38685 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38686 {
38687 IkReal evalcond[4];
38688 IkReal x11929=IKsin(j3);
38689 IkReal x11930=((sj0)*(sj5));
38690 IkReal x11931=((r00)*(sj6));
38691 IkReal x11932=((cj6)*(r01));
38692 IkReal x11933=((cj5)*(sj0));
38693 IkReal x11934=((cj0)*(cj5));
38694 IkReal x11935=((cj6)*(sj4));
38695 IkReal x11936=((sj4)*(sj6));
38696 IkReal x11937=((cj0)*(r11));
38697 IkReal x11938=((cj4)*(cj6));
38698 IkReal x11939=((cj4)*(sj6));
38699 IkReal x11940=((IkReal(1.00000000000000))*(cj0));
38700 IkReal x11941=((cj4)*(sj5));
38701 IkReal x11942=((sj5)*(sj6));
38702 IkReal x11943=((cj6)*(sj5));
38703 IkReal x11944=((IkReal(1.00000000000000))*(IKcos(j3)));
38704 evalcond[0]=((((r21)*(x11943)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x11942)))+(((IkReal(-1.00000000000000))*(x11944))));
38705 evalcond[1]=((((r22)*(x11941)))+(((r20)*(x11935)))+(((IkReal(-1.00000000000000))*(r21)*(x11936)))+(((IkReal(-1.00000000000000))*(x11929)))+(((cj5)*(r20)*(x11939)))+(((cj5)*(r21)*(x11938))));
38706 evalcond[2]=((((r12)*(x11934)))+(((x11930)*(x11932)))+(((IkReal(-1.00000000000000))*(x11937)*(x11943)))+(((x11930)*(x11931)))+(x11929)+(((IkReal(-1.00000000000000))*(r02)*(x11933)))+(((IkReal(-1.00000000000000))*(r10)*(x11940)*(x11942))));
38707 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x11936)))+(((cj4)*(x11931)*(x11933)))+(((x11936)*(x11937)))+(((cj4)*(x11932)*(x11933)))+(((cj4)*(r02)*(x11930)))+(((IkReal(-1.00000000000000))*(r11)*(x11934)*(x11938)))+(((r00)*(sj0)*(x11935)))+(((IkReal(-1.00000000000000))*(r10)*(x11934)*(x11939)))+(((IkReal(-1.00000000000000))*(x11944)))+(((IkReal(-1.00000000000000))*(r10)*(x11935)*(x11940)))+(((IkReal(-1.00000000000000))*(r12)*(x11940)*(x11941))));
38708 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
38709 {
38710 continue;
38711 }
38712 }
38713 
38714 {
38715 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38716 vinfos[0].jointtype = 1;
38717 vinfos[0].foffset = j0;
38718 vinfos[0].indices[0] = _ij0[0];
38719 vinfos[0].indices[1] = _ij0[1];
38720 vinfos[0].maxsolutions = _nj0;
38721 vinfos[1].jointtype = 1;
38722 vinfos[1].foffset = j1;
38723 vinfos[1].indices[0] = _ij1[0];
38724 vinfos[1].indices[1] = _ij1[1];
38725 vinfos[1].maxsolutions = _nj1;
38726 vinfos[2].jointtype = 1;
38727 vinfos[2].foffset = j2;
38728 vinfos[2].indices[0] = _ij2[0];
38729 vinfos[2].indices[1] = _ij2[1];
38730 vinfos[2].maxsolutions = _nj2;
38731 vinfos[3].jointtype = 1;
38732 vinfos[3].foffset = j3;
38733 vinfos[3].indices[0] = _ij3[0];
38734 vinfos[3].indices[1] = _ij3[1];
38735 vinfos[3].maxsolutions = _nj3;
38736 vinfos[4].jointtype = 1;
38737 vinfos[4].foffset = j4;
38738 vinfos[4].indices[0] = _ij4[0];
38739 vinfos[4].indices[1] = _ij4[1];
38740 vinfos[4].maxsolutions = _nj4;
38741 vinfos[5].jointtype = 1;
38742 vinfos[5].foffset = j5;
38743 vinfos[5].indices[0] = _ij5[0];
38744 vinfos[5].indices[1] = _ij5[1];
38745 vinfos[5].maxsolutions = _nj5;
38746 vinfos[6].jointtype = 1;
38747 vinfos[6].foffset = j6;
38748 vinfos[6].indices[0] = _ij6[0];
38749 vinfos[6].indices[1] = _ij6[1];
38750 vinfos[6].maxsolutions = _nj6;
38751 std::vector<int> vfree(0);
38752 solutions.AddSolution(vinfos,vfree);
38753 }
38754 }
38755 }
38756 
38757 } else
38758 {
38759 IkReal x11945=((IkReal(1.00000000000000))*(cj0));
38760 IkReal x11946=((cj4)*(sj6));
38761 IkReal x11947=((sj0)*(sj6));
38762 IkReal x11948=((cj5)*(sj4));
38763 IkReal x11949=((IkReal(0.374290000000000))*(sj5));
38764 IkReal x11950=((sj4)*(sj5));
38765 IkReal x11951=((cj0)*(cj6));
38766 IkReal x11952=((IkReal(0.0100000000000000))*(cj5));
38767 IkReal x11953=((cj4)*(sj5));
38768 IkReal x11954=((cj5)*(sj0));
38769 IkReal x11955=((IkReal(0.374290000000000))*(r02));
38770 IkReal x11956=((r20)*(sj6));
38771 IkReal x11957=((cj6)*(r21));
38772 IkReal x11958=((IkReal(1.00000000000000))*(sj0));
38773 IkReal x11959=((cj0)*(sj6));
38774 IkReal x11960=((cj4)*(cj6));
38775 IkReal x11961=((IkReal(0.374290000000000))*(r12));
38776 IkReal x11962=((cj0)*(cj5));
38777 IkReal x11963=((cj6)*(sj5));
38778 IkReal x11964=((cj6)*(r01));
38779 IkReal x11965=((r00)*(sj6));
38780 IkReal x11966=((IkReal(0.0100000000000000))*(sj5));
38781 IkReal x11967=((cj6)*(r11));
38782 IkReal x11968=((IkReal(1.00000000000000))*(r10));
38783 IkReal x11969=((r02)*(sj0));
38784 IkReal x11970=((cj6)*(sj4));
38785 IkReal x11971=((r12)*(x11958));
38786 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
38787 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x11960)))+(((r21)*(x11946)))+(((x11948)*(x11956)))+(((r22)*(x11950)))+(((x11948)*(x11957))));
38788 evalcond[2]=((IkReal(-0.364420000000000))+(((x11949)*(x11956)))+(((IkReal(-1.00000000000000))*(r22)*(x11966)))+(((IkReal(-1.00000000000000))*(x11952)*(x11956)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x11952)*(x11957)))+(((x11949)*(x11957))));
38789 evalcond[3]=((((r02)*(x11962)))+(((IkReal(-1.00000000000000))*(sj5)*(x11945)*(x11965)))+(((IkReal(-1.00000000000000))*(sj5)*(x11947)*(x11968)))+(((r12)*(x11954)))+(((IkReal(-1.00000000000000))*(r01)*(x11945)*(x11963)))+(((IkReal(-1.00000000000000))*(r11)*(x11958)*(x11963))));
38790 evalcond[4]=((((sj0)*(x11948)*(x11964)))+(((r01)*(sj0)*(x11946)))+(((x11950)*(x11969)))+(((cj4)*(r10)*(x11951)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x11945)*(x11948)))+(((r00)*(x11947)*(x11948)))+(((IkReal(-1.00000000000000))*(r11)*(x11945)*(x11946)))+(((IkReal(-1.00000000000000))*(x11945)*(x11948)*(x11967)))+(((IkReal(-1.00000000000000))*(r12)*(x11945)*(x11950)))+(((IkReal(-1.00000000000000))*(r00)*(x11958)*(x11960))));
38791 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x11945)*(x11946)))+(((IkReal(-1.00000000000000))*(x11945)*(x11948)*(x11965)))+(((IkReal(-1.00000000000000))*(x11947)*(x11948)*(x11968)))+(((r10)*(sj0)*(x11960)))+(((IkReal(-1.00000000000000))*(r02)*(x11945)*(x11950)))+(((IkReal(-1.00000000000000))*(x11950)*(x11971)))+(((cj4)*(r00)*(x11951)))+(((IkReal(-1.00000000000000))*(x11948)*(x11958)*(x11967)))+(((IkReal(-1.00000000000000))*(x11945)*(x11948)*(x11964)))+(((IkReal(-1.00000000000000))*(r11)*(x11946)*(x11958))));
38792 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x11945)))+(((IkReal(-1.00000000000000))*(r11)*(x11949)*(x11951)))+(((sj0)*(x11949)*(x11964)))+(((x11961)*(x11962)))+(((IkReal(-1.00000000000000))*(r00)*(x11947)*(x11952)))+(((r00)*(x11947)*(x11949)))+(((IkReal(-1.00000000000000))*(x11954)*(x11955)))+(((r10)*(x11952)*(x11959)))+(((IkReal(-1.00000000000000))*(r10)*(x11949)*(x11959)))+(((px)*(sj0)))+(((cj0)*(r12)*(x11966)))+(((r11)*(x11951)*(x11952)))+(((IkReal(-1.00000000000000))*(sj0)*(x11952)*(x11964)))+(((IkReal(-1.00000000000000))*(x11966)*(x11969))));
38793 evalcond[7]=((((r11)*(sj4)*(x11947)))+(((IkReal(-1.00000000000000))*(x11946)*(x11954)*(x11968)))+(((r01)*(sj4)*(x11959)))+(((IkReal(-1.00000000000000))*(r10)*(x11958)*(x11970)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x11945)*(x11946)))+(((IkReal(-1.00000000000000))*(r00)*(x11945)*(x11970)))+(((IkReal(-1.00000000000000))*(r11)*(x11954)*(x11960)))+(((IkReal(-1.00000000000000))*(r02)*(x11945)*(x11953)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x11945)*(x11960)))+(((IkReal(-1.00000000000000))*(x11953)*(x11971))));
38794 evalcond[8]=((IkReal(0.0690000000000000))+(((x11955)*(x11962)))+(((r01)*(x11951)*(x11952)))+(((r00)*(x11952)*(x11959)))+(((cj0)*(r02)*(x11966)))+(((IkReal(-1.00000000000000))*(sj0)*(x11949)*(x11967)))+(((r10)*(x11947)*(x11952)))+(((IkReal(-1.00000000000000))*(r01)*(x11949)*(x11951)))+(((sj0)*(x11952)*(x11967)))+(((x11954)*(x11961)))+(((IkReal(-1.00000000000000))*(r10)*(x11947)*(x11949)))+(((IkReal(-1.00000000000000))*(r00)*(x11949)*(x11959)))+(((r12)*(sj0)*(x11966)))+(((IkReal(-1.00000000000000))*(px)*(x11945)))+(((IkReal(-1.00000000000000))*(py)*(x11958))));
38795 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
38796 {
38797 {
38798 IkReal j3array[1], cj3array[1], sj3array[1];
38799 bool j3valid[1]={false};
38800 _nj3 = 1;
38801 IkReal x11972=((IkReal(1.00000000000000))*(sj5));
38802 IkReal x11973=((cj6)*(r21));
38803 IkReal x11974=((r20)*(sj6));
38804 IkReal x11975=((IkReal(1.00000000000000))*(cj4)*(cj5));
38805 if( IKabs(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11972)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x11973)*(x11975)))+(((IkReal(-1.00000000000000))*(x11974)*(x11975)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x11972)*(x11973)))+(((IkReal(-1.00000000000000))*(x11972)*(x11974)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11972)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x11973)*(x11975)))+(((IkReal(-1.00000000000000))*(x11974)*(x11975)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x11972)*(x11973)))+(((IkReal(-1.00000000000000))*(x11972)*(x11974)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
38806     continue;
38807 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj4)*(r22)*(x11972)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x11973)*(x11975)))+(((IkReal(-1.00000000000000))*(x11974)*(x11975)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x11972)*(x11973)))+(((IkReal(-1.00000000000000))*(x11972)*(x11974)))+(((cj5)*(r22)))));
38808 sj3array[0]=IKsin(j3array[0]);
38809 cj3array[0]=IKcos(j3array[0]);
38810 if( j3array[0] > IKPI )
38811 {
38812     j3array[0]-=IK2PI;
38813 }
38814 else if( j3array[0] < -IKPI )
38815 {    j3array[0]+=IK2PI;
38816 }
38817 j3valid[0] = true;
38818 for(int ij3 = 0; ij3 < 1; ++ij3)
38819 {
38820 if( !j3valid[ij3] )
38821 {
38822     continue;
38823 }
38824 _ij3[0] = ij3; _ij3[1] = -1;
38825 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38826 {
38827 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38828 {
38829     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38830 }
38831 }
38832 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38833 {
38834 IkReal evalcond[4];
38835 IkReal x11976=IKsin(j3);
38836 IkReal x11977=IKcos(j3);
38837 IkReal x11978=((sj0)*(sj5));
38838 IkReal x11979=((r00)*(sj6));
38839 IkReal x11980=((cj6)*(r01));
38840 IkReal x11981=((cj0)*(cj5));
38841 IkReal x11982=((IkReal(1.00000000000000))*(cj5));
38842 IkReal x11983=((cj4)*(cj5));
38843 IkReal x11984=((cj6)*(sj4));
38844 IkReal x11985=((sj4)*(sj6));
38845 IkReal x11986=((cj0)*(r11));
38846 IkReal x11987=((IkReal(1.00000000000000))*(cj4));
38847 IkReal x11988=((cj6)*(r21));
38848 IkReal x11989=((r20)*(sj6));
38849 IkReal x11990=((cj0)*(sj5));
38850 IkReal x11991=((r10)*(sj6));
38851 evalcond[0]=((((sj5)*(x11988)))+(((sj5)*(x11989)))+(x11977)+(((IkReal(-1.00000000000000))*(r22)*(x11982))));
38852 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x11985)))+(((r20)*(x11984)))+(((x11983)*(x11989)))+(x11976)+(((cj4)*(r22)*(sj5)))+(((x11983)*(x11988))));
38853 evalcond[2]=((((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x11986)))+(((r12)*(x11981)))+(((IkReal(-1.00000000000000))*(x11990)*(x11991)))+(((x11978)*(x11979)))+(x11976)+(((x11978)*(x11980)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x11982))));
38854 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x11985)))+(((IkReal(-1.00000000000000))*(r12)*(x11987)*(x11990)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x11984)))+(((IkReal(-1.00000000000000))*(x11981)*(x11987)*(x11991)))+(((sj0)*(x11979)*(x11983)))+(((x11985)*(x11986)))+(((cj4)*(r02)*(x11978)))+(((IkReal(-1.00000000000000))*(x11977)))+(((sj0)*(x11980)*(x11983)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x11981)*(x11987)))+(((r00)*(sj0)*(x11984))));
38855 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
38856 {
38857 continue;
38858 }
38859 }
38860 
38861 {
38862 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38863 vinfos[0].jointtype = 1;
38864 vinfos[0].foffset = j0;
38865 vinfos[0].indices[0] = _ij0[0];
38866 vinfos[0].indices[1] = _ij0[1];
38867 vinfos[0].maxsolutions = _nj0;
38868 vinfos[1].jointtype = 1;
38869 vinfos[1].foffset = j1;
38870 vinfos[1].indices[0] = _ij1[0];
38871 vinfos[1].indices[1] = _ij1[1];
38872 vinfos[1].maxsolutions = _nj1;
38873 vinfos[2].jointtype = 1;
38874 vinfos[2].foffset = j2;
38875 vinfos[2].indices[0] = _ij2[0];
38876 vinfos[2].indices[1] = _ij2[1];
38877 vinfos[2].maxsolutions = _nj2;
38878 vinfos[3].jointtype = 1;
38879 vinfos[3].foffset = j3;
38880 vinfos[3].indices[0] = _ij3[0];
38881 vinfos[3].indices[1] = _ij3[1];
38882 vinfos[3].maxsolutions = _nj3;
38883 vinfos[4].jointtype = 1;
38884 vinfos[4].foffset = j4;
38885 vinfos[4].indices[0] = _ij4[0];
38886 vinfos[4].indices[1] = _ij4[1];
38887 vinfos[4].maxsolutions = _nj4;
38888 vinfos[5].jointtype = 1;
38889 vinfos[5].foffset = j5;
38890 vinfos[5].indices[0] = _ij5[0];
38891 vinfos[5].indices[1] = _ij5[1];
38892 vinfos[5].maxsolutions = _nj5;
38893 vinfos[6].jointtype = 1;
38894 vinfos[6].foffset = j6;
38895 vinfos[6].indices[0] = _ij6[0];
38896 vinfos[6].indices[1] = _ij6[1];
38897 vinfos[6].maxsolutions = _nj6;
38898 std::vector<int> vfree(0);
38899 solutions.AddSolution(vinfos,vfree);
38900 }
38901 }
38902 }
38903 
38904 } else
38905 {
38906 if( 1 )
38907 {
38908 continue;
38909 
38910 } else
38911 {
38912 }
38913 }
38914 }
38915 }
38916 
38917 } else
38918 {
38919 {
38920 IkReal j3array[1], cj3array[1], sj3array[1];
38921 bool j3valid[1]={false};
38922 _nj3 = 1;
38923 IkReal x11992=((cj5)*(r02));
38924 IkReal x11993=((cj0)*(sj5));
38925 IkReal x11994=((r10)*(sj6));
38926 IkReal x11995=((IkReal(1.00000000000000))*(cj6));
38927 IkReal x11996=((sj0)*(sj5));
38928 IkReal x11997=((cj5)*(r12));
38929 IkReal x11998=((IkReal(1.00000000000000))*(r00)*(sj6));
38930 if( IKabs(((((sj0)*(x11992)))+(((x11993)*(x11994)))+(((IkReal(-1.00000000000000))*(cj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11995)*(x11996)))+(((IkReal(-1.00000000000000))*(x11996)*(x11998)))+(((cj6)*(r11)*(x11993))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x11993)*(x11998)))+(((IkReal(-1.00000000000000))*(r11)*(x11995)*(x11996)))+(((cj0)*(x11992)))+(((sj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11993)*(x11995)))+(((IkReal(-1.00000000000000))*(x11994)*(x11996))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x11992)))+(((x11993)*(x11994)))+(((IkReal(-1.00000000000000))*(cj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11995)*(x11996)))+(((IkReal(-1.00000000000000))*(x11996)*(x11998)))+(((cj6)*(r11)*(x11993)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x11993)*(x11998)))+(((IkReal(-1.00000000000000))*(r11)*(x11995)*(x11996)))+(((cj0)*(x11992)))+(((sj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11993)*(x11995)))+(((IkReal(-1.00000000000000))*(x11994)*(x11996)))))))-1) <= IKFAST_SINCOS_THRESH )
38931     continue;
38932 j3array[0]=IKatan2(((((sj0)*(x11992)))+(((x11993)*(x11994)))+(((IkReal(-1.00000000000000))*(cj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11995)*(x11996)))+(((IkReal(-1.00000000000000))*(x11996)*(x11998)))+(((cj6)*(r11)*(x11993)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x11993)*(x11998)))+(((IkReal(-1.00000000000000))*(r11)*(x11995)*(x11996)))+(((cj0)*(x11992)))+(((sj0)*(x11997)))+(((IkReal(-1.00000000000000))*(r01)*(x11993)*(x11995)))+(((IkReal(-1.00000000000000))*(x11994)*(x11996)))))));
38933 sj3array[0]=IKsin(j3array[0]);
38934 cj3array[0]=IKcos(j3array[0]);
38935 if( j3array[0] > IKPI )
38936 {
38937     j3array[0]-=IK2PI;
38938 }
38939 else if( j3array[0] < -IKPI )
38940 {    j3array[0]+=IK2PI;
38941 }
38942 j3valid[0] = true;
38943 for(int ij3 = 0; ij3 < 1; ++ij3)
38944 {
38945 if( !j3valid[ij3] )
38946 {
38947     continue;
38948 }
38949 _ij3[0] = ij3; _ij3[1] = -1;
38950 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
38951 {
38952 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
38953 {
38954     j3valid[iij3]=false; _ij3[1] = iij3; break; 
38955 }
38956 }
38957 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
38958 {
38959 IkReal evalcond[6];
38960 IkReal x11999=IKsin(j3);
38961 IkReal x12000=IKcos(j3);
38962 IkReal x12001=((sj0)*(sj5));
38963 IkReal x12002=((r00)*(sj6));
38964 IkReal x12003=((IkReal(1.00000000000000))*(cj4));
38965 IkReal x12004=((cj6)*(r01));
38966 IkReal x12005=((cj0)*(cj5));
38967 IkReal x12006=((cj5)*(sj0));
38968 IkReal x12007=((cj6)*(r11));
38969 IkReal x12008=((cj0)*(sj5));
38970 IkReal x12009=((IkReal(1.00000000000000))*(cj1));
38971 IkReal x12010=((cj6)*(sj4));
38972 IkReal x12011=((IkReal(1.00000000000000))*(sj1));
38973 IkReal x12012=((cj4)*(cj5));
38974 IkReal x12013=((cj6)*(r21));
38975 IkReal x12014=((r20)*(sj6));
38976 IkReal x12015=((r10)*(sj6));
38977 IkReal x12016=((IkReal(1.00000000000000))*(cj0));
38978 IkReal x12017=((cj0)*(sj4)*(sj6));
38979 IkReal x12018=((sj0)*(sj4)*(sj6));
38980 evalcond[0]=((((sj5)*(x12014)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x12000)*(x12011)))+(((sj5)*(x12013))));
38981 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12012)*(x12013)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x11999)*(x12011)))+(((r20)*(x12010)))+(((x12012)*(x12014))));
38982 evalcond[2]=((((IkReal(-1.00000000000000))*(x12008)*(x12015)))+(((IkReal(-1.00000000000000))*(x12007)*(x12008)))+(((x12001)*(x12002)))+(((r12)*(x12005)))+(((IkReal(-1.00000000000000))*(r02)*(x12006)))+(x11999)+(((x12001)*(x12004))));
38983 evalcond[3]=((((IkReal(-1.00000000000000))*(x12001)*(x12007)))+(((IkReal(-1.00000000000000))*(x12001)*(x12015)))+(((IkReal(-1.00000000000000))*(x12004)*(x12008)))+(((r02)*(x12005)))+(((r12)*(x12006)))+(((IkReal(-1.00000000000000))*(x12000)*(x12009)))+(((IkReal(-1.00000000000000))*(x12002)*(x12008))));
38984 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x12010)*(x12016)))+(((IkReal(-1.00000000000000))*(x12003)*(x12005)*(x12015)))+(((IkReal(-1.00000000000000))*(r01)*(x12018)))+(((cj4)*(x12004)*(x12006)))+(((r11)*(x12017)))+(((cj4)*(x12002)*(x12006)))+(((IkReal(-1.00000000000000))*(x12003)*(x12005)*(x12007)))+(((IkReal(-1.00000000000000))*(x12000)))+(((IkReal(-1.00000000000000))*(r12)*(x12003)*(x12008)))+(((r00)*(sj0)*(x12010)))+(((cj4)*(r02)*(x12001))));
38985 evalcond[5]=((((IkReal(-1.00000000000000))*(x12003)*(x12006)*(x12007)))+(((IkReal(-1.00000000000000))*(x11999)*(x12009)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12010)))+(((IkReal(-1.00000000000000))*(r12)*(x12001)*(x12003)))+(((IkReal(-1.00000000000000))*(x12002)*(x12003)*(x12005)))+(((IkReal(-1.00000000000000))*(x12003)*(x12006)*(x12015)))+(((r01)*(x12017)))+(((IkReal(-1.00000000000000))*(r00)*(x12010)*(x12016)))+(((r11)*(x12018)))+(((IkReal(-1.00000000000000))*(r02)*(x12003)*(x12008)))+(((IkReal(-1.00000000000000))*(x12003)*(x12004)*(x12005))));
38986 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
38987 {
38988 continue;
38989 }
38990 }
38991 
38992 {
38993 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
38994 vinfos[0].jointtype = 1;
38995 vinfos[0].foffset = j0;
38996 vinfos[0].indices[0] = _ij0[0];
38997 vinfos[0].indices[1] = _ij0[1];
38998 vinfos[0].maxsolutions = _nj0;
38999 vinfos[1].jointtype = 1;
39000 vinfos[1].foffset = j1;
39001 vinfos[1].indices[0] = _ij1[0];
39002 vinfos[1].indices[1] = _ij1[1];
39003 vinfos[1].maxsolutions = _nj1;
39004 vinfos[2].jointtype = 1;
39005 vinfos[2].foffset = j2;
39006 vinfos[2].indices[0] = _ij2[0];
39007 vinfos[2].indices[1] = _ij2[1];
39008 vinfos[2].maxsolutions = _nj2;
39009 vinfos[3].jointtype = 1;
39010 vinfos[3].foffset = j3;
39011 vinfos[3].indices[0] = _ij3[0];
39012 vinfos[3].indices[1] = _ij3[1];
39013 vinfos[3].maxsolutions = _nj3;
39014 vinfos[4].jointtype = 1;
39015 vinfos[4].foffset = j4;
39016 vinfos[4].indices[0] = _ij4[0];
39017 vinfos[4].indices[1] = _ij4[1];
39018 vinfos[4].maxsolutions = _nj4;
39019 vinfos[5].jointtype = 1;
39020 vinfos[5].foffset = j5;
39021 vinfos[5].indices[0] = _ij5[0];
39022 vinfos[5].indices[1] = _ij5[1];
39023 vinfos[5].maxsolutions = _nj5;
39024 vinfos[6].jointtype = 1;
39025 vinfos[6].foffset = j6;
39026 vinfos[6].indices[0] = _ij6[0];
39027 vinfos[6].indices[1] = _ij6[1];
39028 vinfos[6].maxsolutions = _nj6;
39029 std::vector<int> vfree(0);
39030 solutions.AddSolution(vinfos,vfree);
39031 }
39032 }
39033 }
39034 
39035 }
39036 
39037 }
39038 
39039 } else
39040 {
39041 {
39042 IkReal j3array[1], cj3array[1], sj3array[1];
39043 bool j3valid[1]={false};
39044 _nj3 = 1;
39045 IkReal x12019=((sj5)*(sj6));
39046 IkReal x12020=((IkReal(1.00000000000000))*(sj0));
39047 IkReal x12021=((cj6)*(sj5));
39048 IkReal x12022=((IkReal(1.00000000000000))*(cj5));
39049 if( IKabs(((((cj0)*(r10)*(x12019)))+(((IkReal(-1.00000000000000))*(r00)*(x12019)*(x12020)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12022)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x12021)))+(((IkReal(-1.00000000000000))*(r01)*(x12020)*(x12021))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x12022)))+(((r21)*(x12021)))+(((r20)*(x12019))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r10)*(x12019)))+(((IkReal(-1.00000000000000))*(r00)*(x12019)*(x12020)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12022)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x12021)))+(((IkReal(-1.00000000000000))*(r01)*(x12020)*(x12021)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x12022)))+(((r21)*(x12021)))+(((r20)*(x12019)))))))-1) <= IKFAST_SINCOS_THRESH )
39050     continue;
39051 j3array[0]=IKatan2(((((cj0)*(r10)*(x12019)))+(((IkReal(-1.00000000000000))*(r00)*(x12019)*(x12020)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12022)))+(((cj5)*(r02)*(sj0)))+(((cj0)*(r11)*(x12021)))+(((IkReal(-1.00000000000000))*(r01)*(x12020)*(x12021)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x12022)))+(((r21)*(x12021)))+(((r20)*(x12019)))))));
39052 sj3array[0]=IKsin(j3array[0]);
39053 cj3array[0]=IKcos(j3array[0]);
39054 if( j3array[0] > IKPI )
39055 {
39056     j3array[0]-=IK2PI;
39057 }
39058 else if( j3array[0] < -IKPI )
39059 {    j3array[0]+=IK2PI;
39060 }
39061 j3valid[0] = true;
39062 for(int ij3 = 0; ij3 < 1; ++ij3)
39063 {
39064 if( !j3valid[ij3] )
39065 {
39066     continue;
39067 }
39068 _ij3[0] = ij3; _ij3[1] = -1;
39069 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39070 {
39071 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39072 {
39073     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39074 }
39075 }
39076 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39077 {
39078 IkReal evalcond[6];
39079 IkReal x12023=IKsin(j3);
39080 IkReal x12024=IKcos(j3);
39081 IkReal x12025=((sj0)*(sj5));
39082 IkReal x12026=((r00)*(sj6));
39083 IkReal x12027=((IkReal(1.00000000000000))*(cj4));
39084 IkReal x12028=((cj6)*(r01));
39085 IkReal x12029=((cj0)*(cj5));
39086 IkReal x12030=((cj5)*(sj0));
39087 IkReal x12031=((cj6)*(r11));
39088 IkReal x12032=((cj0)*(sj5));
39089 IkReal x12033=((IkReal(1.00000000000000))*(cj1));
39090 IkReal x12034=((cj6)*(sj4));
39091 IkReal x12035=((IkReal(1.00000000000000))*(sj1));
39092 IkReal x12036=((cj4)*(cj5));
39093 IkReal x12037=((cj6)*(r21));
39094 IkReal x12038=((r20)*(sj6));
39095 IkReal x12039=((r10)*(sj6));
39096 IkReal x12040=((IkReal(1.00000000000000))*(cj0));
39097 IkReal x12041=((cj0)*(sj4)*(sj6));
39098 IkReal x12042=((sj0)*(sj4)*(sj6));
39099 evalcond[0]=((((sj5)*(x12037)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12038)))+(((IkReal(-1.00000000000000))*(x12024)*(x12035))));
39100 evalcond[1]=((((x12036)*(x12038)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x12023)*(x12035)))+(((cj4)*(r22)*(sj5)))+(((x12036)*(x12037)))+(((r20)*(x12034))));
39101 evalcond[2]=((((IkReal(-1.00000000000000))*(x12032)*(x12039)))+(((x12025)*(x12028)))+(((x12025)*(x12026)))+(x12023)+(((r12)*(x12029)))+(((IkReal(-1.00000000000000))*(r02)*(x12030)))+(((IkReal(-1.00000000000000))*(x12031)*(x12032))));
39102 evalcond[3]=((((IkReal(-1.00000000000000))*(x12028)*(x12032)))+(((IkReal(-1.00000000000000))*(x12026)*(x12032)))+(((IkReal(-1.00000000000000))*(x12025)*(x12039)))+(((r02)*(x12029)))+(((IkReal(-1.00000000000000))*(x12024)*(x12033)))+(((IkReal(-1.00000000000000))*(x12025)*(x12031)))+(((r12)*(x12030))));
39103 evalcond[4]=((((cj4)*(x12028)*(x12030)))+(((IkReal(-1.00000000000000))*(r12)*(x12027)*(x12032)))+(((r11)*(x12041)))+(((IkReal(-1.00000000000000))*(r01)*(x12042)))+(((IkReal(-1.00000000000000))*(r10)*(x12034)*(x12040)))+(((r00)*(sj0)*(x12034)))+(((IkReal(-1.00000000000000))*(x12024)))+(((IkReal(-1.00000000000000))*(x12027)*(x12029)*(x12031)))+(((cj4)*(x12026)*(x12030)))+(((cj4)*(r02)*(x12025)))+(((IkReal(-1.00000000000000))*(x12027)*(x12029)*(x12039))));
39104 evalcond[5]=((((IkReal(-1.00000000000000))*(x12027)*(x12028)*(x12029)))+(((IkReal(-1.00000000000000))*(x12023)*(x12033)))+(((IkReal(-1.00000000000000))*(x12026)*(x12027)*(x12029)))+(((IkReal(-1.00000000000000))*(x12027)*(x12030)*(x12031)))+(((IkReal(-1.00000000000000))*(r02)*(x12027)*(x12032)))+(((IkReal(-1.00000000000000))*(r00)*(x12034)*(x12040)))+(((r11)*(x12042)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12034)))+(((r01)*(x12041)))+(((IkReal(-1.00000000000000))*(x12027)*(x12030)*(x12039)))+(((IkReal(-1.00000000000000))*(r12)*(x12025)*(x12027))));
39105 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
39106 {
39107 continue;
39108 }
39109 }
39110 
39111 {
39112 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39113 vinfos[0].jointtype = 1;
39114 vinfos[0].foffset = j0;
39115 vinfos[0].indices[0] = _ij0[0];
39116 vinfos[0].indices[1] = _ij0[1];
39117 vinfos[0].maxsolutions = _nj0;
39118 vinfos[1].jointtype = 1;
39119 vinfos[1].foffset = j1;
39120 vinfos[1].indices[0] = _ij1[0];
39121 vinfos[1].indices[1] = _ij1[1];
39122 vinfos[1].maxsolutions = _nj1;
39123 vinfos[2].jointtype = 1;
39124 vinfos[2].foffset = j2;
39125 vinfos[2].indices[0] = _ij2[0];
39126 vinfos[2].indices[1] = _ij2[1];
39127 vinfos[2].maxsolutions = _nj2;
39128 vinfos[3].jointtype = 1;
39129 vinfos[3].foffset = j3;
39130 vinfos[3].indices[0] = _ij3[0];
39131 vinfos[3].indices[1] = _ij3[1];
39132 vinfos[3].maxsolutions = _nj3;
39133 vinfos[4].jointtype = 1;
39134 vinfos[4].foffset = j4;
39135 vinfos[4].indices[0] = _ij4[0];
39136 vinfos[4].indices[1] = _ij4[1];
39137 vinfos[4].maxsolutions = _nj4;
39138 vinfos[5].jointtype = 1;
39139 vinfos[5].foffset = j5;
39140 vinfos[5].indices[0] = _ij5[0];
39141 vinfos[5].indices[1] = _ij5[1];
39142 vinfos[5].maxsolutions = _nj5;
39143 vinfos[6].jointtype = 1;
39144 vinfos[6].foffset = j6;
39145 vinfos[6].indices[0] = _ij6[0];
39146 vinfos[6].indices[1] = _ij6[1];
39147 vinfos[6].maxsolutions = _nj6;
39148 std::vector<int> vfree(0);
39149 solutions.AddSolution(vinfos,vfree);
39150 }
39151 }
39152 }
39153 
39154 }
39155 
39156 }
39157 
39158 } else
39159 {
39160 {
39161 IkReal j3array[1], cj3array[1], sj3array[1];
39162 bool j3valid[1]={false};
39163 _nj3 = 1;
39164 IkReal x12043=((r20)*(sj6));
39165 IkReal x12044=((cj4)*(cj5));
39166 IkReal x12045=((cj6)*(r21));
39167 if( IKabs(((gconst12)*(((((x12043)*(x12044)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12044)*(x12045)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((sj5)*(x12043)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12045))))))) < IKFAST_ATAN2_MAGTHRESH )
39168     continue;
39169 j3array[0]=IKatan2(((gconst12)*(((((x12043)*(x12044)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12044)*(x12045)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))), ((gconst12)*(((((sj5)*(x12043)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12045)))))));
39170 sj3array[0]=IKsin(j3array[0]);
39171 cj3array[0]=IKcos(j3array[0]);
39172 if( j3array[0] > IKPI )
39173 {
39174     j3array[0]-=IK2PI;
39175 }
39176 else if( j3array[0] < -IKPI )
39177 {    j3array[0]+=IK2PI;
39178 }
39179 j3valid[0] = true;
39180 for(int ij3 = 0; ij3 < 1; ++ij3)
39181 {
39182 if( !j3valid[ij3] )
39183 {
39184     continue;
39185 }
39186 _ij3[0] = ij3; _ij3[1] = -1;
39187 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39188 {
39189 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39190 {
39191     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39192 }
39193 }
39194 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39195 {
39196 IkReal evalcond[6];
39197 IkReal x12046=IKsin(j3);
39198 IkReal x12047=IKcos(j3);
39199 IkReal x12048=((sj0)*(sj5));
39200 IkReal x12049=((r00)*(sj6));
39201 IkReal x12050=((IkReal(1.00000000000000))*(cj4));
39202 IkReal x12051=((cj6)*(r01));
39203 IkReal x12052=((cj0)*(cj5));
39204 IkReal x12053=((cj5)*(sj0));
39205 IkReal x12054=((cj6)*(r11));
39206 IkReal x12055=((cj0)*(sj5));
39207 IkReal x12056=((IkReal(1.00000000000000))*(cj1));
39208 IkReal x12057=((cj6)*(sj4));
39209 IkReal x12058=((IkReal(1.00000000000000))*(sj1));
39210 IkReal x12059=((cj4)*(cj5));
39211 IkReal x12060=((cj6)*(r21));
39212 IkReal x12061=((r20)*(sj6));
39213 IkReal x12062=((r10)*(sj6));
39214 IkReal x12063=((IkReal(1.00000000000000))*(cj0));
39215 IkReal x12064=((cj0)*(sj4)*(sj6));
39216 IkReal x12065=((sj0)*(sj4)*(sj6));
39217 evalcond[0]=((((IkReal(-1.00000000000000))*(x12047)*(x12058)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12061)))+(((sj5)*(x12060))));
39218 evalcond[1]=((((x12059)*(x12061)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x12046)*(x12058)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12057)))+(((x12059)*(x12060))));
39219 evalcond[2]=((((x12048)*(x12049)))+(x12046)+(((IkReal(-1.00000000000000))*(x12054)*(x12055)))+(((IkReal(-1.00000000000000))*(x12055)*(x12062)))+(((r12)*(x12052)))+(((IkReal(-1.00000000000000))*(r02)*(x12053)))+(((x12048)*(x12051))));
39220 evalcond[3]=((((IkReal(-1.00000000000000))*(x12047)*(x12056)))+(((r12)*(x12053)))+(((IkReal(-1.00000000000000))*(x12049)*(x12055)))+(((IkReal(-1.00000000000000))*(x12051)*(x12055)))+(((r02)*(x12052)))+(((IkReal(-1.00000000000000))*(x12048)*(x12054)))+(((IkReal(-1.00000000000000))*(x12048)*(x12062))));
39221 evalcond[4]=((((r11)*(x12064)))+(((cj4)*(r02)*(x12048)))+(((IkReal(-1.00000000000000))*(x12050)*(x12052)*(x12062)))+(((cj4)*(x12049)*(x12053)))+(((IkReal(-1.00000000000000))*(x12050)*(x12052)*(x12054)))+(((IkReal(-1.00000000000000))*(x12047)))+(((IkReal(-1.00000000000000))*(r01)*(x12065)))+(((IkReal(-1.00000000000000))*(r12)*(x12050)*(x12055)))+(((IkReal(-1.00000000000000))*(r10)*(x12057)*(x12063)))+(((r00)*(sj0)*(x12057)))+(((cj4)*(x12051)*(x12053))));
39222 evalcond[5]=((((r11)*(x12065)))+(((r01)*(x12064)))+(((IkReal(-1.00000000000000))*(r02)*(x12050)*(x12055)))+(((IkReal(-1.00000000000000))*(x12050)*(x12053)*(x12062)))+(((IkReal(-1.00000000000000))*(x12050)*(x12053)*(x12054)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12057)))+(((IkReal(-1.00000000000000))*(r00)*(x12057)*(x12063)))+(((IkReal(-1.00000000000000))*(r12)*(x12048)*(x12050)))+(((IkReal(-1.00000000000000))*(x12049)*(x12050)*(x12052)))+(((IkReal(-1.00000000000000))*(x12046)*(x12056)))+(((IkReal(-1.00000000000000))*(x12050)*(x12051)*(x12052))));
39223 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
39224 {
39225 continue;
39226 }
39227 }
39228 
39229 {
39230 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39231 vinfos[0].jointtype = 1;
39232 vinfos[0].foffset = j0;
39233 vinfos[0].indices[0] = _ij0[0];
39234 vinfos[0].indices[1] = _ij0[1];
39235 vinfos[0].maxsolutions = _nj0;
39236 vinfos[1].jointtype = 1;
39237 vinfos[1].foffset = j1;
39238 vinfos[1].indices[0] = _ij1[0];
39239 vinfos[1].indices[1] = _ij1[1];
39240 vinfos[1].maxsolutions = _nj1;
39241 vinfos[2].jointtype = 1;
39242 vinfos[2].foffset = j2;
39243 vinfos[2].indices[0] = _ij2[0];
39244 vinfos[2].indices[1] = _ij2[1];
39245 vinfos[2].maxsolutions = _nj2;
39246 vinfos[3].jointtype = 1;
39247 vinfos[3].foffset = j3;
39248 vinfos[3].indices[0] = _ij3[0];
39249 vinfos[3].indices[1] = _ij3[1];
39250 vinfos[3].maxsolutions = _nj3;
39251 vinfos[4].jointtype = 1;
39252 vinfos[4].foffset = j4;
39253 vinfos[4].indices[0] = _ij4[0];
39254 vinfos[4].indices[1] = _ij4[1];
39255 vinfos[4].maxsolutions = _nj4;
39256 vinfos[5].jointtype = 1;
39257 vinfos[5].foffset = j5;
39258 vinfos[5].indices[0] = _ij5[0];
39259 vinfos[5].indices[1] = _ij5[1];
39260 vinfos[5].maxsolutions = _nj5;
39261 vinfos[6].jointtype = 1;
39262 vinfos[6].foffset = j6;
39263 vinfos[6].indices[0] = _ij6[0];
39264 vinfos[6].indices[1] = _ij6[1];
39265 vinfos[6].maxsolutions = _nj6;
39266 std::vector<int> vfree(0);
39267 solutions.AddSolution(vinfos,vfree);
39268 }
39269 }
39270 }
39271 
39272 }
39273 
39274 }
39275 
39276 } else
39277 {
39278 if( 1 )
39279 {
39280 continue;
39281 
39282 } else
39283 {
39284 }
39285 }
39286 }
39287 }
39288 }
39289 }
39290 }
39291 }
39292 
39293 } else
39294 {
39295 {
39296 IkReal j3array[1], cj3array[1], sj3array[1];
39297 bool j3valid[1]={false};
39298 _nj3 = 1;
39299 IkReal x12066=((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30);
39300 IkReal x12067=((sj5)*(sj6));
39301 IkReal x12068=((r00)*(sj0));
39302 IkReal x12069=((cj1)*(cj2));
39303 IkReal x12070=((cj0)*(r10));
39304 IkReal x12071=((cj6)*(sj5));
39305 IkReal x12072=((r01)*(sj0));
39306 IkReal x12073=((IkReal(1.00000000000000))*(cj0));
39307 IkReal x12074=((cj5)*(r12));
39308 IkReal x12075=((IkReal(1.00000000000000))*(cj5));
39309 IkReal x12076=((r02)*(sj0));
39310 if( IKabs(((x12066)*(((((IkReal(-1.00000000000000))*(x12067)*(x12070)))+(((IkReal(-1.00000000000000))*(r11)*(x12071)*(x12073)))+(((x12071)*(x12072)))+(((cj0)*(x12074)))+(((IkReal(-1.00000000000000))*(x12075)*(x12076)))+(((x12067)*(x12068))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x12066)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(sj2)*(x12075)))+(((IkReal(-1.00000000000000))*(x12069)*(x12071)*(x12072)))+(((cj5)*(x12069)*(x12076)))+(((r21)*(sj2)*(x12071)))+(((x12067)*(x12069)*(x12070)))+(((IkReal(-1.00000000000000))*(x12067)*(x12068)*(x12069)))+(((r20)*(sj2)*(x12067)))+(((IkReal(-1.00000000000000))*(x12069)*(x12073)*(x12074)))+(((cj0)*(r11)*(x12069)*(x12071))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x12066)*(((((IkReal(-1.00000000000000))*(x12067)*(x12070)))+(((IkReal(-1.00000000000000))*(r11)*(x12071)*(x12073)))+(((x12071)*(x12072)))+(((cj0)*(x12074)))+(((IkReal(-1.00000000000000))*(x12075)*(x12076)))+(((x12067)*(x12068)))))))+IKsqr(((x12066)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(sj2)*(x12075)))+(((IkReal(-1.00000000000000))*(x12069)*(x12071)*(x12072)))+(((cj5)*(x12069)*(x12076)))+(((r21)*(sj2)*(x12071)))+(((x12067)*(x12069)*(x12070)))+(((IkReal(-1.00000000000000))*(x12067)*(x12068)*(x12069)))+(((r20)*(sj2)*(x12067)))+(((IkReal(-1.00000000000000))*(x12069)*(x12073)*(x12074)))+(((cj0)*(r11)*(x12069)*(x12071)))))))-1) <= IKFAST_SINCOS_THRESH )
39311     continue;
39312 j3array[0]=IKatan2(((x12066)*(((((IkReal(-1.00000000000000))*(x12067)*(x12070)))+(((IkReal(-1.00000000000000))*(r11)*(x12071)*(x12073)))+(((x12071)*(x12072)))+(((cj0)*(x12074)))+(((IkReal(-1.00000000000000))*(x12075)*(x12076)))+(((x12067)*(x12068)))))), ((x12066)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(sj2)*(x12075)))+(((IkReal(-1.00000000000000))*(x12069)*(x12071)*(x12072)))+(((cj5)*(x12069)*(x12076)))+(((r21)*(sj2)*(x12071)))+(((x12067)*(x12069)*(x12070)))+(((IkReal(-1.00000000000000))*(x12067)*(x12068)*(x12069)))+(((r20)*(sj2)*(x12067)))+(((IkReal(-1.00000000000000))*(x12069)*(x12073)*(x12074)))+(((cj0)*(r11)*(x12069)*(x12071)))))));
39313 sj3array[0]=IKsin(j3array[0]);
39314 cj3array[0]=IKcos(j3array[0]);
39315 if( j3array[0] > IKPI )
39316 {
39317     j3array[0]-=IK2PI;
39318 }
39319 else if( j3array[0] < -IKPI )
39320 {    j3array[0]+=IK2PI;
39321 }
39322 j3valid[0] = true;
39323 for(int ij3 = 0; ij3 < 1; ++ij3)
39324 {
39325 if( !j3valid[ij3] )
39326 {
39327     continue;
39328 }
39329 _ij3[0] = ij3; _ij3[1] = -1;
39330 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39331 {
39332 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39333 {
39334     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39335 }
39336 }
39337 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39338 {
39339 IkReal evalcond[6];
39340 IkReal x12077=IKcos(j3);
39341 IkReal x12078=IKsin(j3);
39342 IkReal x12079=((sj0)*(sj5));
39343 IkReal x12080=((r00)*(sj6));
39344 IkReal x12081=((IkReal(1.00000000000000))*(cj4));
39345 IkReal x12082=((cj6)*(r01));
39346 IkReal x12083=((cj0)*(cj5));
39347 IkReal x12084=((cj5)*(sj0));
39348 IkReal x12085=((cj6)*(r11));
39349 IkReal x12086=((cj6)*(sj4));
39350 IkReal x12087=((IkReal(1.00000000000000))*(cj1));
39351 IkReal x12088=((cj4)*(cj5));
39352 IkReal x12089=((cj6)*(r21));
39353 IkReal x12090=((r20)*(sj6));
39354 IkReal x12091=((r10)*(sj6));
39355 IkReal x12092=((cj0)*(sj5));
39356 IkReal x12093=((IkReal(1.00000000000000))*(cj0));
39357 IkReal x12094=((IkReal(1.00000000000000))*(x12092));
39358 IkReal x12095=((IkReal(1.00000000000000))*(x12078));
39359 IkReal x12096=((cj0)*(sj4)*(sj6));
39360 IkReal x12097=((cj2)*(x12078));
39361 IkReal x12098=((sj0)*(sj4)*(sj6));
39362 IkReal x12099=((IkReal(1.00000000000000))*(sj1)*(x12077));
39363 evalcond[0]=((((sj5)*(x12090)))+(((IkReal(-1.00000000000000))*(x12087)*(x12097)))+(((IkReal(-1.00000000000000))*(x12099)))+(((sj5)*(x12089)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
39364 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12086)))+(((x12088)*(x12089)))+(((IkReal(-1.00000000000000))*(sj1)*(x12095)))+(((cj1)*(cj2)*(x12077)))+(((x12088)*(x12090))));
39365 evalcond[2]=((((r12)*(x12083)))+(((x12079)*(x12080)))+(((IkReal(-1.00000000000000))*(x12091)*(x12094)))+(((x12079)*(x12082)))+(((IkReal(-1.00000000000000))*(r02)*(x12084)))+(((IkReal(-1.00000000000000))*(sj2)*(x12095)))+(((IkReal(-1.00000000000000))*(x12085)*(x12094))));
39366 evalcond[3]=((((r12)*(x12084)))+(((IkReal(-1.00000000000000))*(x12079)*(x12085)))+(((IkReal(-1.00000000000000))*(x12077)*(x12087)))+(((IkReal(-1.00000000000000))*(x12082)*(x12094)))+(((r02)*(x12083)))+(((IkReal(-1.00000000000000))*(x12079)*(x12091)))+(((IkReal(-1.00000000000000))*(x12080)*(x12094)))+(((sj1)*(x12097))));
39367 evalcond[4]=((((sj2)*(x12077)))+(((cj4)*(r02)*(x12079)))+(((IkReal(-1.00000000000000))*(x12081)*(x12083)*(x12085)))+(((IkReal(-1.00000000000000))*(x12081)*(x12083)*(x12091)))+(((r00)*(sj0)*(x12086)))+(((IkReal(-1.00000000000000))*(r12)*(x12081)*(x12092)))+(((cj4)*(x12082)*(x12084)))+(((cj4)*(x12080)*(x12084)))+(((r11)*(x12096)))+(((IkReal(-1.00000000000000))*(r01)*(x12098)))+(((IkReal(-1.00000000000000))*(r10)*(x12086)*(x12093))));
39368 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x12081)*(x12092)))+(((IkReal(-1.00000000000000))*(cj2)*(x12099)))+(((IkReal(-1.00000000000000))*(r00)*(x12086)*(x12093)))+(((IkReal(-1.00000000000000))*(x12081)*(x12082)*(x12083)))+(((IkReal(-1.00000000000000))*(x12078)*(x12087)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12086)))+(((IkReal(-1.00000000000000))*(x12081)*(x12084)*(x12085)))+(((r11)*(x12098)))+(((IkReal(-1.00000000000000))*(r12)*(x12079)*(x12081)))+(((IkReal(-1.00000000000000))*(x12081)*(x12084)*(x12091)))+(((IkReal(-1.00000000000000))*(x12080)*(x12081)*(x12083)))+(((r01)*(x12096))));
39369 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
39370 {
39371 continue;
39372 }
39373 }
39374 
39375 {
39376 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39377 vinfos[0].jointtype = 1;
39378 vinfos[0].foffset = j0;
39379 vinfos[0].indices[0] = _ij0[0];
39380 vinfos[0].indices[1] = _ij0[1];
39381 vinfos[0].maxsolutions = _nj0;
39382 vinfos[1].jointtype = 1;
39383 vinfos[1].foffset = j1;
39384 vinfos[1].indices[0] = _ij1[0];
39385 vinfos[1].indices[1] = _ij1[1];
39386 vinfos[1].maxsolutions = _nj1;
39387 vinfos[2].jointtype = 1;
39388 vinfos[2].foffset = j2;
39389 vinfos[2].indices[0] = _ij2[0];
39390 vinfos[2].indices[1] = _ij2[1];
39391 vinfos[2].maxsolutions = _nj2;
39392 vinfos[3].jointtype = 1;
39393 vinfos[3].foffset = j3;
39394 vinfos[3].indices[0] = _ij3[0];
39395 vinfos[3].indices[1] = _ij3[1];
39396 vinfos[3].maxsolutions = _nj3;
39397 vinfos[4].jointtype = 1;
39398 vinfos[4].foffset = j4;
39399 vinfos[4].indices[0] = _ij4[0];
39400 vinfos[4].indices[1] = _ij4[1];
39401 vinfos[4].maxsolutions = _nj4;
39402 vinfos[5].jointtype = 1;
39403 vinfos[5].foffset = j5;
39404 vinfos[5].indices[0] = _ij5[0];
39405 vinfos[5].indices[1] = _ij5[1];
39406 vinfos[5].maxsolutions = _nj5;
39407 vinfos[6].jointtype = 1;
39408 vinfos[6].foffset = j6;
39409 vinfos[6].indices[0] = _ij6[0];
39410 vinfos[6].indices[1] = _ij6[1];
39411 vinfos[6].maxsolutions = _nj6;
39412 std::vector<int> vfree(0);
39413 solutions.AddSolution(vinfos,vfree);
39414 }
39415 }
39416 }
39417 
39418 }
39419 
39420 }
39421 
39422 } else
39423 {
39424 {
39425 IkReal j3array[1], cj3array[1], sj3array[1];
39426 bool j3valid[1]={false};
39427 _nj3 = 1;
39428 IkReal x12100=(cj1)*(cj1);
39429 IkReal x12101=(sj1)*(sj1);
39430 IkReal x12102=((r00)*(sj6));
39431 IkReal x12103=((cj6)*(r01));
39432 IkReal x12104=((IkReal(1.00000000000000))*(cj1));
39433 IkReal x12105=((cj5)*(r22));
39434 IkReal x12106=((sj5)*(sj6));
39435 IkReal x12107=((r10)*(sj0));
39436 IkReal x12108=((cj1)*(cj5));
39437 IkReal x12109=((cj0)*(r02));
39438 IkReal x12110=((r12)*(sj0));
39439 IkReal x12111=((IkReal(1.00000000000000))*(sj1));
39440 IkReal x12112=((cj6)*(sj5));
39441 IkReal x12113=((cj0)*(sj5));
39442 IkReal x12114=((r11)*(sj0));
39443 IkReal x12115=((sj1)*(x12113));
39444 if( IKabs(((((IKabs(((((cj2)*(x12101)))+(((cj2)*(x12100))))) != 0)?((IkReal)1/(((((cj2)*(x12101)))+(((cj2)*(x12100)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x12109)*(x12111)))+(((cj1)*(r20)*(x12106)))+(((sj1)*(x12106)*(x12107)))+(((sj1)*(x12112)*(x12114)))+(((IkReal(-1.00000000000000))*(x12104)*(x12105)))+(((x12102)*(x12115)))+(((x12103)*(x12115)))+(((IkReal(-1.00000000000000))*(cj5)*(x12110)*(x12111)))+(((cj1)*(r21)*(x12112))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x12101)+(x12100))) != 0)?((IkReal)1/(((x12101)+(x12100)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x12112)))+(((IkReal(-1.00000000000000))*(x12102)*(x12104)*(x12113)))+(((IkReal(-1.00000000000000))*(x12103)*(x12104)*(x12113)))+(((x12108)*(x12109)))+(((IkReal(-1.00000000000000))*(x12105)*(x12111)))+(((IkReal(-1.00000000000000))*(x12104)*(x12112)*(x12114)))+(((x12108)*(x12110)))+(((r20)*(sj1)*(x12106)))+(((IkReal(-1.00000000000000))*(x12104)*(x12106)*(x12107))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x12101)))+(((cj2)*(x12100))))) != 0)?((IkReal)1/(((((cj2)*(x12101)))+(((cj2)*(x12100)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x12109)*(x12111)))+(((cj1)*(r20)*(x12106)))+(((sj1)*(x12106)*(x12107)))+(((sj1)*(x12112)*(x12114)))+(((IkReal(-1.00000000000000))*(x12104)*(x12105)))+(((x12102)*(x12115)))+(((x12103)*(x12115)))+(((IkReal(-1.00000000000000))*(cj5)*(x12110)*(x12111)))+(((cj1)*(r21)*(x12112)))))))+IKsqr(((((IKabs(((x12101)+(x12100))) != 0)?((IkReal)1/(((x12101)+(x12100)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x12112)))+(((IkReal(-1.00000000000000))*(x12102)*(x12104)*(x12113)))+(((IkReal(-1.00000000000000))*(x12103)*(x12104)*(x12113)))+(((x12108)*(x12109)))+(((IkReal(-1.00000000000000))*(x12105)*(x12111)))+(((IkReal(-1.00000000000000))*(x12104)*(x12112)*(x12114)))+(((x12108)*(x12110)))+(((r20)*(sj1)*(x12106)))+(((IkReal(-1.00000000000000))*(x12104)*(x12106)*(x12107)))))))-1) <= IKFAST_SINCOS_THRESH )
39445     continue;
39446 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x12101)))+(((cj2)*(x12100))))) != 0)?((IkReal)1/(((((cj2)*(x12101)))+(((cj2)*(x12100)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x12109)*(x12111)))+(((cj1)*(r20)*(x12106)))+(((sj1)*(x12106)*(x12107)))+(((sj1)*(x12112)*(x12114)))+(((IkReal(-1.00000000000000))*(x12104)*(x12105)))+(((x12102)*(x12115)))+(((x12103)*(x12115)))+(((IkReal(-1.00000000000000))*(cj5)*(x12110)*(x12111)))+(((cj1)*(r21)*(x12112)))))), ((((IKabs(((x12101)+(x12100))) != 0)?((IkReal)1/(((x12101)+(x12100)))):(IkReal)1.0e30))*(((((r21)*(sj1)*(x12112)))+(((IkReal(-1.00000000000000))*(x12102)*(x12104)*(x12113)))+(((IkReal(-1.00000000000000))*(x12103)*(x12104)*(x12113)))+(((x12108)*(x12109)))+(((IkReal(-1.00000000000000))*(x12105)*(x12111)))+(((IkReal(-1.00000000000000))*(x12104)*(x12112)*(x12114)))+(((x12108)*(x12110)))+(((r20)*(sj1)*(x12106)))+(((IkReal(-1.00000000000000))*(x12104)*(x12106)*(x12107)))))));
39447 sj3array[0]=IKsin(j3array[0]);
39448 cj3array[0]=IKcos(j3array[0]);
39449 if( j3array[0] > IKPI )
39450 {
39451     j3array[0]-=IK2PI;
39452 }
39453 else if( j3array[0] < -IKPI )
39454 {    j3array[0]+=IK2PI;
39455 }
39456 j3valid[0] = true;
39457 for(int ij3 = 0; ij3 < 1; ++ij3)
39458 {
39459 if( !j3valid[ij3] )
39460 {
39461     continue;
39462 }
39463 _ij3[0] = ij3; _ij3[1] = -1;
39464 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39465 {
39466 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39467 {
39468     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39469 }
39470 }
39471 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39472 {
39473 IkReal evalcond[6];
39474 IkReal x12116=IKcos(j3);
39475 IkReal x12117=IKsin(j3);
39476 IkReal x12118=((sj0)*(sj5));
39477 IkReal x12119=((r00)*(sj6));
39478 IkReal x12120=((IkReal(1.00000000000000))*(cj4));
39479 IkReal x12121=((cj6)*(r01));
39480 IkReal x12122=((cj0)*(cj5));
39481 IkReal x12123=((cj5)*(sj0));
39482 IkReal x12124=((cj6)*(r11));
39483 IkReal x12125=((cj6)*(sj4));
39484 IkReal x12126=((IkReal(1.00000000000000))*(cj1));
39485 IkReal x12127=((cj4)*(cj5));
39486 IkReal x12128=((cj6)*(r21));
39487 IkReal x12129=((r20)*(sj6));
39488 IkReal x12130=((r10)*(sj6));
39489 IkReal x12131=((cj0)*(sj5));
39490 IkReal x12132=((IkReal(1.00000000000000))*(cj0));
39491 IkReal x12133=((IkReal(1.00000000000000))*(x12131));
39492 IkReal x12134=((IkReal(1.00000000000000))*(x12117));
39493 IkReal x12135=((cj0)*(sj4)*(sj6));
39494 IkReal x12136=((cj2)*(x12117));
39495 IkReal x12137=((sj0)*(sj4)*(sj6));
39496 IkReal x12138=((IkReal(1.00000000000000))*(sj1)*(x12116));
39497 evalcond[0]=((((IkReal(-1.00000000000000))*(x12126)*(x12136)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12128)))+(((IkReal(-1.00000000000000))*(x12138)))+(((sj5)*(x12129))));
39498 evalcond[1]=((((cj1)*(cj2)*(x12116)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12127)*(x12129)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x12134)))+(((r20)*(x12125)))+(((x12127)*(x12128))));
39499 evalcond[2]=((((x12118)*(x12121)))+(((IkReal(-1.00000000000000))*(x12124)*(x12133)))+(((x12118)*(x12119)))+(((IkReal(-1.00000000000000))*(x12130)*(x12133)))+(((IkReal(-1.00000000000000))*(sj2)*(x12134)))+(((r12)*(x12122)))+(((IkReal(-1.00000000000000))*(r02)*(x12123))));
39500 evalcond[3]=((((IkReal(-1.00000000000000))*(x12119)*(x12133)))+(((r02)*(x12122)))+(((r12)*(x12123)))+(((IkReal(-1.00000000000000))*(x12118)*(x12124)))+(((IkReal(-1.00000000000000))*(x12116)*(x12126)))+(((sj1)*(x12136)))+(((IkReal(-1.00000000000000))*(x12118)*(x12130)))+(((IkReal(-1.00000000000000))*(x12121)*(x12133))));
39501 evalcond[4]=((((cj4)*(x12119)*(x12123)))+(((cj4)*(x12121)*(x12123)))+(((sj2)*(x12116)))+(((IkReal(-1.00000000000000))*(r01)*(x12137)))+(((IkReal(-1.00000000000000))*(x12120)*(x12122)*(x12124)))+(((cj4)*(r02)*(x12118)))+(((r00)*(sj0)*(x12125)))+(((IkReal(-1.00000000000000))*(r10)*(x12125)*(x12132)))+(((r11)*(x12135)))+(((IkReal(-1.00000000000000))*(r12)*(x12120)*(x12131)))+(((IkReal(-1.00000000000000))*(x12120)*(x12122)*(x12130))));
39502 evalcond[5]=((((IkReal(-1.00000000000000))*(x12117)*(x12126)))+(((IkReal(-1.00000000000000))*(r02)*(x12120)*(x12131)))+(((r11)*(x12137)))+(((IkReal(-1.00000000000000))*(x12120)*(x12123)*(x12124)))+(((IkReal(-1.00000000000000))*(r00)*(x12125)*(x12132)))+(((IkReal(-1.00000000000000))*(x12119)*(x12120)*(x12122)))+(((IkReal(-1.00000000000000))*(r12)*(x12118)*(x12120)))+(((IkReal(-1.00000000000000))*(x12120)*(x12121)*(x12122)))+(((IkReal(-1.00000000000000))*(cj2)*(x12138)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12125)))+(((r01)*(x12135)))+(((IkReal(-1.00000000000000))*(x12120)*(x12123)*(x12130))));
39503 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
39504 {
39505 continue;
39506 }
39507 }
39508 
39509 {
39510 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39511 vinfos[0].jointtype = 1;
39512 vinfos[0].foffset = j0;
39513 vinfos[0].indices[0] = _ij0[0];
39514 vinfos[0].indices[1] = _ij0[1];
39515 vinfos[0].maxsolutions = _nj0;
39516 vinfos[1].jointtype = 1;
39517 vinfos[1].foffset = j1;
39518 vinfos[1].indices[0] = _ij1[0];
39519 vinfos[1].indices[1] = _ij1[1];
39520 vinfos[1].maxsolutions = _nj1;
39521 vinfos[2].jointtype = 1;
39522 vinfos[2].foffset = j2;
39523 vinfos[2].indices[0] = _ij2[0];
39524 vinfos[2].indices[1] = _ij2[1];
39525 vinfos[2].maxsolutions = _nj2;
39526 vinfos[3].jointtype = 1;
39527 vinfos[3].foffset = j3;
39528 vinfos[3].indices[0] = _ij3[0];
39529 vinfos[3].indices[1] = _ij3[1];
39530 vinfos[3].maxsolutions = _nj3;
39531 vinfos[4].jointtype = 1;
39532 vinfos[4].foffset = j4;
39533 vinfos[4].indices[0] = _ij4[0];
39534 vinfos[4].indices[1] = _ij4[1];
39535 vinfos[4].maxsolutions = _nj4;
39536 vinfos[5].jointtype = 1;
39537 vinfos[5].foffset = j5;
39538 vinfos[5].indices[0] = _ij5[0];
39539 vinfos[5].indices[1] = _ij5[1];
39540 vinfos[5].maxsolutions = _nj5;
39541 vinfos[6].jointtype = 1;
39542 vinfos[6].foffset = j6;
39543 vinfos[6].indices[0] = _ij6[0];
39544 vinfos[6].indices[1] = _ij6[1];
39545 vinfos[6].maxsolutions = _nj6;
39546 std::vector<int> vfree(0);
39547 solutions.AddSolution(vinfos,vfree);
39548 }
39549 }
39550 }
39551 
39552 }
39553 
39554 }
39555 
39556 } else
39557 {
39558 {
39559 IkReal j3array[1], cj3array[1], sj3array[1];
39560 bool j3valid[1]={false};
39561 _nj3 = 1;
39562 IkReal x12139=((sj1)*(sj6));
39563 IkReal x12140=((r20)*(sj5));
39564 IkReal x12141=((IkReal(1.00000000000000))*(r21));
39565 IkReal x12142=((cj5)*(cj6));
39566 IkReal x12143=((r22)*(sj5));
39567 IkReal x12144=((cj4)*(sj1));
39568 IkReal x12145=((cj1)*(cj2));
39569 IkReal x12146=((cj5)*(r20));
39570 IkReal x12147=((cj4)*(x12145));
39571 IkReal x12148=((IkReal(1.00000000000000))*(cj5)*(r22));
39572 IkReal x12149=((cj6)*(r20)*(sj4));
39573 IkReal x12150=((cj6)*(r21)*(sj5));
39574 if( IKabs(((gconst4)*(((((sj6)*(x12140)*(x12145)))+(((x12143)*(x12144)))+(((x12145)*(x12150)))+(((sj1)*(x12149)))+(((cj4)*(x12139)*(x12146)))+(((r21)*(x12142)*(x12144)))+(((IkReal(-1.00000000000000))*(sj4)*(x12139)*(x12141)))+(((IkReal(-1.00000000000000))*(x12145)*(x12148))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(sj6)*(x12146)*(x12147)))+(((sj1)*(x12150)))+(((x12139)*(x12140)))+(((IkReal(-1.00000000000000))*(x12141)*(x12142)*(x12147)))+(((IkReal(-1.00000000000000))*(sj1)*(x12148)))+(((IkReal(-1.00000000000000))*(x12143)*(x12147)))+(((IkReal(-1.00000000000000))*(x12145)*(x12149)))+(((r21)*(sj4)*(sj6)*(x12145))))))) < IKFAST_ATAN2_MAGTHRESH )
39575     continue;
39576 j3array[0]=IKatan2(((gconst4)*(((((sj6)*(x12140)*(x12145)))+(((x12143)*(x12144)))+(((x12145)*(x12150)))+(((sj1)*(x12149)))+(((cj4)*(x12139)*(x12146)))+(((r21)*(x12142)*(x12144)))+(((IkReal(-1.00000000000000))*(sj4)*(x12139)*(x12141)))+(((IkReal(-1.00000000000000))*(x12145)*(x12148)))))), ((gconst4)*(((((IkReal(-1.00000000000000))*(sj6)*(x12146)*(x12147)))+(((sj1)*(x12150)))+(((x12139)*(x12140)))+(((IkReal(-1.00000000000000))*(x12141)*(x12142)*(x12147)))+(((IkReal(-1.00000000000000))*(sj1)*(x12148)))+(((IkReal(-1.00000000000000))*(x12143)*(x12147)))+(((IkReal(-1.00000000000000))*(x12145)*(x12149)))+(((r21)*(sj4)*(sj6)*(x12145)))))));
39577 sj3array[0]=IKsin(j3array[0]);
39578 cj3array[0]=IKcos(j3array[0]);
39579 if( j3array[0] > IKPI )
39580 {
39581     j3array[0]-=IK2PI;
39582 }
39583 else if( j3array[0] < -IKPI )
39584 {    j3array[0]+=IK2PI;
39585 }
39586 j3valid[0] = true;
39587 for(int ij3 = 0; ij3 < 1; ++ij3)
39588 {
39589 if( !j3valid[ij3] )
39590 {
39591     continue;
39592 }
39593 _ij3[0] = ij3; _ij3[1] = -1;
39594 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39595 {
39596 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39597 {
39598     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39599 }
39600 }
39601 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39602 {
39603 IkReal evalcond[6];
39604 IkReal x12151=IKcos(j3);
39605 IkReal x12152=IKsin(j3);
39606 IkReal x12153=((sj0)*(sj5));
39607 IkReal x12154=((r00)*(sj6));
39608 IkReal x12155=((IkReal(1.00000000000000))*(cj4));
39609 IkReal x12156=((cj6)*(r01));
39610 IkReal x12157=((cj0)*(cj5));
39611 IkReal x12158=((cj5)*(sj0));
39612 IkReal x12159=((cj6)*(r11));
39613 IkReal x12160=((cj6)*(sj4));
39614 IkReal x12161=((IkReal(1.00000000000000))*(cj1));
39615 IkReal x12162=((cj4)*(cj5));
39616 IkReal x12163=((cj6)*(r21));
39617 IkReal x12164=((r20)*(sj6));
39618 IkReal x12165=((r10)*(sj6));
39619 IkReal x12166=((cj0)*(sj5));
39620 IkReal x12167=((IkReal(1.00000000000000))*(cj0));
39621 IkReal x12168=((IkReal(1.00000000000000))*(x12166));
39622 IkReal x12169=((IkReal(1.00000000000000))*(x12152));
39623 IkReal x12170=((cj0)*(sj4)*(sj6));
39624 IkReal x12171=((cj2)*(x12152));
39625 IkReal x12172=((sj0)*(sj4)*(sj6));
39626 IkReal x12173=((IkReal(1.00000000000000))*(sj1)*(x12151));
39627 evalcond[0]=((((IkReal(-1.00000000000000))*(x12161)*(x12171)))+(((sj5)*(x12163)))+(((IkReal(-1.00000000000000))*(x12173)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12164))));
39628 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12162)*(x12163)))+(((IkReal(-1.00000000000000))*(sj1)*(x12169)))+(((cj4)*(r22)*(sj5)))+(((x12162)*(x12164)))+(((r20)*(x12160)))+(((cj1)*(cj2)*(x12151))));
39629 evalcond[2]=((((IkReal(-1.00000000000000))*(x12165)*(x12168)))+(((x12153)*(x12154)))+(((IkReal(-1.00000000000000))*(sj2)*(x12169)))+(((IkReal(-1.00000000000000))*(r02)*(x12158)))+(((x12153)*(x12156)))+(((IkReal(-1.00000000000000))*(x12159)*(x12168)))+(((r12)*(x12157))));
39630 evalcond[3]=((((IkReal(-1.00000000000000))*(x12153)*(x12165)))+(((IkReal(-1.00000000000000))*(x12151)*(x12161)))+(((r12)*(x12158)))+(((IkReal(-1.00000000000000))*(x12156)*(x12168)))+(((IkReal(-1.00000000000000))*(x12153)*(x12159)))+(((sj1)*(x12171)))+(((IkReal(-1.00000000000000))*(x12154)*(x12168)))+(((r02)*(x12157))));
39631 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x12172)))+(((sj2)*(x12151)))+(((IkReal(-1.00000000000000))*(r12)*(x12155)*(x12166)))+(((cj4)*(r02)*(x12153)))+(((r00)*(sj0)*(x12160)))+(((IkReal(-1.00000000000000))*(r10)*(x12160)*(x12167)))+(((r11)*(x12170)))+(((cj4)*(x12154)*(x12158)))+(((IkReal(-1.00000000000000))*(x12155)*(x12157)*(x12165)))+(((cj4)*(x12156)*(x12158)))+(((IkReal(-1.00000000000000))*(x12155)*(x12157)*(x12159))));
39632 evalcond[5]=((((IkReal(-1.00000000000000))*(x12154)*(x12155)*(x12157)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12160)))+(((IkReal(-1.00000000000000))*(x12155)*(x12158)*(x12165)))+(((IkReal(-1.00000000000000))*(r12)*(x12153)*(x12155)))+(((IkReal(-1.00000000000000))*(r00)*(x12160)*(x12167)))+(((r11)*(x12172)))+(((IkReal(-1.00000000000000))*(x12155)*(x12156)*(x12157)))+(((IkReal(-1.00000000000000))*(x12152)*(x12161)))+(((IkReal(-1.00000000000000))*(r02)*(x12155)*(x12166)))+(((IkReal(-1.00000000000000))*(cj2)*(x12173)))+(((r01)*(x12170)))+(((IkReal(-1.00000000000000))*(x12155)*(x12158)*(x12159))));
39633 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
39634 {
39635 continue;
39636 }
39637 }
39638 
39639 {
39640 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39641 vinfos[0].jointtype = 1;
39642 vinfos[0].foffset = j0;
39643 vinfos[0].indices[0] = _ij0[0];
39644 vinfos[0].indices[1] = _ij0[1];
39645 vinfos[0].maxsolutions = _nj0;
39646 vinfos[1].jointtype = 1;
39647 vinfos[1].foffset = j1;
39648 vinfos[1].indices[0] = _ij1[0];
39649 vinfos[1].indices[1] = _ij1[1];
39650 vinfos[1].maxsolutions = _nj1;
39651 vinfos[2].jointtype = 1;
39652 vinfos[2].foffset = j2;
39653 vinfos[2].indices[0] = _ij2[0];
39654 vinfos[2].indices[1] = _ij2[1];
39655 vinfos[2].maxsolutions = _nj2;
39656 vinfos[3].jointtype = 1;
39657 vinfos[3].foffset = j3;
39658 vinfos[3].indices[0] = _ij3[0];
39659 vinfos[3].indices[1] = _ij3[1];
39660 vinfos[3].maxsolutions = _nj3;
39661 vinfos[4].jointtype = 1;
39662 vinfos[4].foffset = j4;
39663 vinfos[4].indices[0] = _ij4[0];
39664 vinfos[4].indices[1] = _ij4[1];
39665 vinfos[4].maxsolutions = _nj4;
39666 vinfos[5].jointtype = 1;
39667 vinfos[5].foffset = j5;
39668 vinfos[5].indices[0] = _ij5[0];
39669 vinfos[5].indices[1] = _ij5[1];
39670 vinfos[5].maxsolutions = _nj5;
39671 vinfos[6].jointtype = 1;
39672 vinfos[6].foffset = j6;
39673 vinfos[6].indices[0] = _ij6[0];
39674 vinfos[6].indices[1] = _ij6[1];
39675 vinfos[6].maxsolutions = _nj6;
39676 std::vector<int> vfree(0);
39677 solutions.AddSolution(vinfos,vfree);
39678 }
39679 }
39680 }
39681 
39682 }
39683 
39684 }
39685 }
39686 }
39687 
39688 }
39689 
39690 }
39691 
39692 } else
39693 {
39694 {
39695 IkReal j4array[1], cj4array[1], sj4array[1];
39696 bool j4valid[1]={false};
39697 _nj4 = 1;
39698 IkReal x12174=((cj5)*(sj0));
39699 IkReal x12175=((cj2)*(sj6));
39700 IkReal x12176=((IkReal(1.00000000000000))*(cj0));
39701 IkReal x12177=((cj2)*(cj6));
39702 IkReal x12178=((cj1)*(cj6)*(sj2));
39703 IkReal x12179=((r10)*(x12176));
39704 IkReal x12180=((cj1)*(sj2)*(sj6));
39705 IkReal x12181=((cj1)*(sj2)*(sj5));
39706 if( IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(r21)*(x12175)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x12180)))+(((IkReal(-1.00000000000000))*(x12178)*(x12179)))+(((cj0)*(r11)*(x12180)))+(((r00)*(sj0)*(x12178)))+(((r20)*(x12177))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12176)*(x12178)))+(((cj2)*(r22)*(sj5)))+(((r01)*(x12174)*(x12178)))+(((IkReal(-1.00000000000000))*(cj5)*(x12179)*(x12180)))+(((IkReal(-1.00000000000000))*(r12)*(x12176)*(x12181)))+(((r02)*(sj0)*(x12181)))+(((cj5)*(r20)*(x12175)))+(((cj5)*(r21)*(x12177)))+(((r00)*(x12174)*(x12180))))))) < IKFAST_ATAN2_MAGTHRESH )
39707     continue;
39708 j4array[0]=IKatan2(((gconst0)*(((((IkReal(-1.00000000000000))*(r21)*(x12175)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x12180)))+(((IkReal(-1.00000000000000))*(x12178)*(x12179)))+(((cj0)*(r11)*(x12180)))+(((r00)*(sj0)*(x12178)))+(((r20)*(x12177)))))), ((gconst0)*(((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12176)*(x12178)))+(((cj2)*(r22)*(sj5)))+(((r01)*(x12174)*(x12178)))+(((IkReal(-1.00000000000000))*(cj5)*(x12179)*(x12180)))+(((IkReal(-1.00000000000000))*(r12)*(x12176)*(x12181)))+(((r02)*(sj0)*(x12181)))+(((cj5)*(r20)*(x12175)))+(((cj5)*(r21)*(x12177)))+(((r00)*(x12174)*(x12180)))))));
39709 sj4array[0]=IKsin(j4array[0]);
39710 cj4array[0]=IKcos(j4array[0]);
39711 if( j4array[0] > IKPI )
39712 {
39713     j4array[0]-=IK2PI;
39714 }
39715 else if( j4array[0] < -IKPI )
39716 {    j4array[0]+=IK2PI;
39717 }
39718 j4valid[0] = true;
39719 for(int ij4 = 0; ij4 < 1; ++ij4)
39720 {
39721 if( !j4valid[ij4] )
39722 {
39723     continue;
39724 }
39725 _ij4[0] = ij4; _ij4[1] = -1;
39726 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
39727 {
39728 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
39729 {
39730     j4valid[iij4]=false; _ij4[1] = iij4; break; 
39731 }
39732 }
39733 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
39734 {
39735 IkReal evalcond[3];
39736 IkReal x12182=IKsin(j4);
39737 IkReal x12183=IKcos(j4);
39738 IkReal x12184=((r00)*(sj6));
39739 IkReal x12185=((cj6)*(r01));
39740 IkReal x12186=((IkReal(1.00000000000000))*(cj0));
39741 IkReal x12187=((IkReal(1.00000000000000))*(sj0));
39742 IkReal x12188=((r10)*(sj6));
39743 IkReal x12189=((sj5)*(x12182));
39744 IkReal x12190=((IkReal(1.00000000000000))*(cj6)*(r11));
39745 IkReal x12191=((cj5)*(x12182));
39746 IkReal x12192=((cj6)*(x12183));
39747 IkReal x12193=((sj0)*(x12191));
39748 IkReal x12194=((r01)*(sj6)*(x12183));
39749 IkReal x12195=((r11)*(sj6)*(x12183));
39750 evalcond[0]=((((IkReal(-1.00000000000000))*(r20)*(x12192)))+(((IkReal(-1.00000000000000))*(cj1)*(sj2)))+(((r22)*(x12189)))+(((r20)*(sj6)*(x12191)))+(((r21)*(sj6)*(x12183)))+(((cj6)*(r21)*(x12191))));
39751 evalcond[1]=((((IkReal(-1.00000000000000))*(r12)*(x12186)*(x12189)))+(((x12184)*(x12193)))+(((IkReal(-1.00000000000000))*(x12186)*(x12188)*(x12191)))+(((x12185)*(x12193)))+(((sj0)*(x12194)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12186)*(x12191)))+(cj2)+(((IkReal(-1.00000000000000))*(x12186)*(x12195)))+(((IkReal(-1.00000000000000))*(r00)*(x12187)*(x12192)))+(((r02)*(sj0)*(x12189)))+(((cj0)*(r10)*(x12192))));
39752 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x12187)*(x12189)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12187)*(x12191)))+(((IkReal(-1.00000000000000))*(x12187)*(x12195)))+(((r10)*(sj0)*(x12192)))+(((IkReal(-1.00000000000000))*(x12186)*(x12194)))+(((IkReal(-1.00000000000000))*(r02)*(x12186)*(x12189)))+(((sj1)*(sj2)))+(((cj0)*(r00)*(x12192)))+(((IkReal(-1.00000000000000))*(x12187)*(x12188)*(x12191)))+(((IkReal(-1.00000000000000))*(x12185)*(x12186)*(x12191)))+(((IkReal(-1.00000000000000))*(x12184)*(x12186)*(x12191))));
39753 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
39754 {
39755 continue;
39756 }
39757 }
39758 
39759 {
39760 IkReal dummyeval[1];
39761 IkReal gconst4;
39762 gconst4=IKsign((((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2))))));
39763 dummyeval[0]=(((sj1)*(sj1))+((((cj1)*(cj1))*((cj2)*(cj2)))));
39764 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
39765 {
39766 {
39767 IkReal dummyeval[2];
39768 IkReal x12196=(cj1)*(cj1);
39769 IkReal x12197=(sj1)*(sj1);
39770 dummyeval[0]=((((cj2)*(x12196)))+(((cj2)*(x12197))));
39771 dummyeval[1]=((x12196)+(x12197));
39772 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
39773 {
39774 {
39775 IkReal dummyeval[2];
39776 dummyeval[0]=sj2;
39777 dummyeval[1]=sj1;
39778 if( IKabs(dummyeval[0]) < 0.0000010000000000  || IKabs(dummyeval[1]) < 0.0000010000000000  )
39779 {
39780 {
39781 IkReal evalcond[9];
39782 IkReal x12198=((cj5)*(sj4));
39783 IkReal x12199=((IkReal(1.00000000000000))*(sj6));
39784 IkReal x12200=((r10)*(sj0));
39785 IkReal x12201=((sj4)*(sj5));
39786 IkReal x12202=((cj4)*(cj5));
39787 IkReal x12203=((IkReal(1.00000000000000))*(r02));
39788 IkReal x12204=((IkReal(0.374290000000000))*(cj0));
39789 IkReal x12205=((cj5)*(r12));
39790 IkReal x12206=((cj6)*(sj5));
39791 IkReal x12207=((cj0)*(r11));
39792 IkReal x12208=((cj5)*(sj0));
39793 IkReal x12209=((r20)*(sj6));
39794 IkReal x12210=((IkReal(1.00000000000000))*(sj0));
39795 IkReal x12211=((IkReal(1.00000000000000))*(cj6));
39796 IkReal x12212=((IkReal(0.0100000000000000))*(cj5));
39797 IkReal x12213=((IkReal(0.0100000000000000))*(sj5));
39798 IkReal x12214=((sj5)*(sj6));
39799 IkReal x12215=((cj0)*(r10));
39800 IkReal x12216=((cj4)*(cj6));
39801 IkReal x12217=((cj0)*(r01));
39802 IkReal x12218=((cj0)*(r00));
39803 IkReal x12219=((cj6)*(r21));
39804 IkReal x12220=((IkReal(0.374290000000000))*(sj0));
39805 IkReal x12221=((IkReal(0.374290000000000))*(sj5));
39806 IkReal x12222=((cj6)*(r11));
39807 IkReal x12223=((sj0)*(sj4));
39808 IkReal x12224=((cj4)*(sj5));
39809 IkReal x12225=((cj4)*(sj6));
39810 IkReal x12226=((IkReal(1.00000000000000))*(cj0));
39811 IkReal x12227=((r02)*(sj0));
39812 IkReal x12228=((r00)*(sj0)*(sj6));
39813 IkReal x12229=((cj6)*(r01)*(sj0));
39814 IkReal x12230=((r00)*(x12216));
39815 IkReal x12231=((r12)*(x12226));
39816 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
39817 evalcond[1]=((((r21)*(x12225)))+(((x12198)*(x12219)))+(((r22)*(x12201)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12211)))+(((x12198)*(x12209))));
39818 evalcond[2]=((((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x12212)*(x12219)))+(((IkReal(-1.00000000000000))*(r22)*(x12213)))+(((IkReal(0.374290000000000))*(r21)*(x12206)))+(pz)+(((x12209)*(x12221)))+(((IkReal(0.0690000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x12209)*(x12212))));
39819 evalcond[3]=((((cj0)*(x12205)))+(((r01)*(sj0)*(x12206)))+(((IkReal(-1.00000000000000))*(sj5)*(x12199)*(x12215)))+(((IkReal(-1.00000000000000))*(x12206)*(x12207)))+(((r00)*(sj0)*(x12214)))+(((IkReal(-1.00000000000000))*(x12203)*(x12208))));
39820 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(x12199)*(x12207)))+(((IkReal(-1.00000000000000))*(x12201)*(x12231)))+(((x12198)*(x12228)))+(((IkReal(-1.00000000000000))*(x12198)*(x12207)*(x12211)))+(((x12198)*(x12229)))+(((r01)*(sj0)*(x12225)))+(((x12215)*(x12216)))+(((IkReal(-1.00000000000000))*(x12198)*(x12199)*(x12215)))+(((x12201)*(x12227)))+(((IkReal(-1.00000000000000))*(x12210)*(x12230))));
39821 evalcond[5]=((((cj6)*(r00)*(x12223)))+(((x12202)*(x12228)))+(((IkReal(-1.00000000000000))*(x12199)*(x12202)*(x12215)))+(((IkReal(-1.00000000000000))*(r01)*(x12199)*(x12223)))+(((IkReal(-1.00000000000000))*(sj4)*(x12211)*(x12215)))+(((IkReal(-1.00000000000000))*(x12202)*(x12207)*(x12211)))+(((sj4)*(sj6)*(x12207)))+(((IkReal(-1.00000000000000))*(x12224)*(x12231)))+(((x12202)*(x12229)))+(((x12224)*(x12227))));
39822 evalcond[6]=((((IkReal(-1.00000000000000))*(x12198)*(x12199)*(x12218)))+(((x12216)*(x12218)))+(((IkReal(-1.00000000000000))*(x12198)*(x12210)*(x12222)))+(((IkReal(-1.00000000000000))*(cj4)*(x12199)*(x12217)))+(((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x12199)))+(((x12200)*(x12216)))+(((IkReal(-1.00000000000000))*(x12198)*(x12199)*(x12200)))+(((IkReal(-1.00000000000000))*(x12198)*(x12211)*(x12217)))+(((IkReal(-1.00000000000000))*(cj0)*(x12201)*(x12203)))+(((IkReal(-1.00000000000000))*(r12)*(x12201)*(x12210))));
39823 evalcond[7]=((((IkReal(-1.00000000000000))*(x12213)*(x12227)))+(((sj6)*(x12212)*(x12215)))+(((r00)*(x12214)*(x12220)))+(((IkReal(-1.00000000000000))*(r11)*(x12204)*(x12206)))+(((IkReal(-0.374290000000000))*(r02)*(x12208)))+(((x12204)*(x12205)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12208)))+(((cj0)*(r12)*(x12213)))+(((IkReal(-1.00000000000000))*(r10)*(x12204)*(x12214)))+(((cj6)*(x12207)*(x12212)))+(((IkReal(-1.00000000000000))*(py)*(x12226)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x12208)))+(((r01)*(x12206)*(x12220))));
39824 evalcond[8]=((IkReal(0.0690000000000000))+(((cj5)*(r02)*(x12204)))+(((cj0)*(r02)*(x12213)))+(((IkReal(-0.0690000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r01)*(x12204)*(x12206)))+(((sj6)*(x12212)*(x12218)))+(((cj6)*(x12212)*(x12217)))+(((IkReal(-1.00000000000000))*(r00)*(x12204)*(x12214)))+(((IkReal(0.0100000000000000))*(x12208)*(x12222)))+(((x12205)*(x12220)))+(((IkReal(-1.00000000000000))*(px)*(x12226)))+(((r12)*(sj0)*(x12213)))+(((sj6)*(x12200)*(x12212)))+(((IkReal(-0.374290000000000))*(x12200)*(x12214)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(r11)*(x12206)*(x12220)))+(((IkReal(-1.00000000000000))*(py)*(x12210))));
39825 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
39826 {
39827 {
39828 IkReal dummyeval[1];
39829 IkReal gconst5;
39830 gconst5=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
39831 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
39832 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
39833 {
39834 {
39835 IkReal dummyeval[1];
39836 IkReal gconst6;
39837 gconst6=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
39838 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
39839 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
39840 {
39841 continue;
39842 
39843 } else
39844 {
39845 {
39846 IkReal j3array[1], cj3array[1], sj3array[1];
39847 bool j3valid[1]={false};
39848 _nj3 = 1;
39849 IkReal x12232=((sj5)*(sj6));
39850 IkReal x12233=((IkReal(1.00000000000000))*(sj0));
39851 IkReal x12234=((cj5)*(r12));
39852 IkReal x12235=((cj0)*(r00));
39853 IkReal x12236=((cj0)*(cj1));
39854 IkReal x12237=((cj6)*(sj5));
39855 IkReal x12238=((cj5)*(r02));
39856 IkReal x12239=((IkReal(1.00000000000000))*(cj1));
39857 IkReal x12240=((sj0)*(sj1));
39858 IkReal x12241=((cj0)*(sj1));
39859 IkReal x12242=((cj5)*(r22));
39860 if( IKabs(((gconst6)*(((((r01)*(x12237)*(x12241)))+(((cj1)*(r20)*(x12232)))+(((r11)*(x12237)*(x12240)))+(((r10)*(x12232)*(x12240)))+(((IkReal(-1.00000000000000))*(x12239)*(x12242)))+(((IkReal(-1.00000000000000))*(x12238)*(x12241)))+(((IkReal(-1.00000000000000))*(sj1)*(x12233)*(x12234)))+(((sj1)*(x12232)*(x12235)))+(((cj1)*(r21)*(x12237))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((IkReal(-1.00000000000000))*(cj1)*(r10)*(x12232)*(x12233)))+(((IkReal(-1.00000000000000))*(x12232)*(x12235)*(x12239)))+(((x12236)*(x12238)))+(((IkReal(-1.00000000000000))*(r01)*(x12236)*(x12237)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x12233)*(x12237)))+(((r21)*(sj1)*(x12237)))+(((IkReal(-1.00000000000000))*(sj1)*(x12242)))+(((cj1)*(sj0)*(x12234)))+(((r20)*(sj1)*(x12232))))))) < IKFAST_ATAN2_MAGTHRESH )
39861     continue;
39862 j3array[0]=IKatan2(((gconst6)*(((((r01)*(x12237)*(x12241)))+(((cj1)*(r20)*(x12232)))+(((r11)*(x12237)*(x12240)))+(((r10)*(x12232)*(x12240)))+(((IkReal(-1.00000000000000))*(x12239)*(x12242)))+(((IkReal(-1.00000000000000))*(x12238)*(x12241)))+(((IkReal(-1.00000000000000))*(sj1)*(x12233)*(x12234)))+(((sj1)*(x12232)*(x12235)))+(((cj1)*(r21)*(x12237)))))), ((gconst6)*(((((IkReal(-1.00000000000000))*(cj1)*(r10)*(x12232)*(x12233)))+(((IkReal(-1.00000000000000))*(x12232)*(x12235)*(x12239)))+(((x12236)*(x12238)))+(((IkReal(-1.00000000000000))*(r01)*(x12236)*(x12237)))+(((IkReal(-1.00000000000000))*(cj1)*(r11)*(x12233)*(x12237)))+(((r21)*(sj1)*(x12237)))+(((IkReal(-1.00000000000000))*(sj1)*(x12242)))+(((cj1)*(sj0)*(x12234)))+(((r20)*(sj1)*(x12232)))))));
39863 sj3array[0]=IKsin(j3array[0]);
39864 cj3array[0]=IKcos(j3array[0]);
39865 if( j3array[0] > IKPI )
39866 {
39867     j3array[0]-=IK2PI;
39868 }
39869 else if( j3array[0] < -IKPI )
39870 {    j3array[0]+=IK2PI;
39871 }
39872 j3valid[0] = true;
39873 for(int ij3 = 0; ij3 < 1; ++ij3)
39874 {
39875 if( !j3valid[ij3] )
39876 {
39877     continue;
39878 }
39879 _ij3[0] = ij3; _ij3[1] = -1;
39880 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
39881 {
39882 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
39883 {
39884     j3valid[iij3]=false; _ij3[1] = iij3; break; 
39885 }
39886 }
39887 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
39888 {
39889 IkReal evalcond[4];
39890 IkReal x12243=IKcos(j3);
39891 IkReal x12244=IKsin(j3);
39892 IkReal x12245=((IkReal(1.00000000000000))*(cj4));
39893 IkReal x12246=((sj0)*(sj5));
39894 IkReal x12247=((cj0)*(cj5));
39895 IkReal x12248=((cj6)*(r01));
39896 IkReal x12249=((r00)*(sj6));
39897 IkReal x12250=((cj6)*(r11));
39898 IkReal x12251=((cj5)*(sj0));
39899 IkReal x12252=((cj6)*(sj4));
39900 IkReal x12253=((sj4)*(sj6));
39901 IkReal x12254=((cj4)*(cj5));
39902 IkReal x12255=((cj6)*(r21));
39903 IkReal x12256=((r20)*(sj6));
39904 IkReal x12257=((r10)*(sj6));
39905 IkReal x12258=((cj1)*(x12243));
39906 IkReal x12259=((IkReal(1.00000000000000))*(cj0)*(sj5));
39907 IkReal x12260=((IkReal(1.00000000000000))*(x12244));
39908 IkReal x12261=((IkReal(1.00000000000000))*(sj1)*(x12243));
39909 IkReal x12262=((cj1)*(x12260));
39910 IkReal x12263=((x12261)+(x12262));
39911 evalcond[0]=((((IkReal(-1.00000000000000))*(x12263)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12255)))+(((sj5)*(x12256))));
39912 evalcond[1]=((x12258)+(((x12254)*(x12255)))+(((x12254)*(x12256)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x12253)))+(((IkReal(-1.00000000000000))*(sj1)*(x12260)))+(((r20)*(x12252))));
39913 evalcond[2]=((((IkReal(-1.00000000000000))*(x12249)*(x12259)))+(((r02)*(x12247)))+(((sj1)*(x12244)))+(((IkReal(-1.00000000000000))*(x12248)*(x12259)))+(((IkReal(-1.00000000000000))*(x12258)))+(((IkReal(-1.00000000000000))*(x12246)*(x12250)))+(((r12)*(x12251)))+(((IkReal(-1.00000000000000))*(x12246)*(x12257))));
39914 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x12245)*(x12246)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12252)))+(((cj0)*(r01)*(x12253)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12252)))+(((IkReal(-1.00000000000000))*(x12245)*(x12247)*(x12249)))+(((IkReal(-1.00000000000000))*(x12245)*(x12250)*(x12251)))+(((IkReal(-1.00000000000000))*(x12263)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12245)))+(((IkReal(-1.00000000000000))*(x12245)*(x12247)*(x12248)))+(((r11)*(sj0)*(x12253)))+(((IkReal(-1.00000000000000))*(x12245)*(x12251)*(x12257))));
39915 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
39916 {
39917 continue;
39918 }
39919 }
39920 
39921 {
39922 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
39923 vinfos[0].jointtype = 1;
39924 vinfos[0].foffset = j0;
39925 vinfos[0].indices[0] = _ij0[0];
39926 vinfos[0].indices[1] = _ij0[1];
39927 vinfos[0].maxsolutions = _nj0;
39928 vinfos[1].jointtype = 1;
39929 vinfos[1].foffset = j1;
39930 vinfos[1].indices[0] = _ij1[0];
39931 vinfos[1].indices[1] = _ij1[1];
39932 vinfos[1].maxsolutions = _nj1;
39933 vinfos[2].jointtype = 1;
39934 vinfos[2].foffset = j2;
39935 vinfos[2].indices[0] = _ij2[0];
39936 vinfos[2].indices[1] = _ij2[1];
39937 vinfos[2].maxsolutions = _nj2;
39938 vinfos[3].jointtype = 1;
39939 vinfos[3].foffset = j3;
39940 vinfos[3].indices[0] = _ij3[0];
39941 vinfos[3].indices[1] = _ij3[1];
39942 vinfos[3].maxsolutions = _nj3;
39943 vinfos[4].jointtype = 1;
39944 vinfos[4].foffset = j4;
39945 vinfos[4].indices[0] = _ij4[0];
39946 vinfos[4].indices[1] = _ij4[1];
39947 vinfos[4].maxsolutions = _nj4;
39948 vinfos[5].jointtype = 1;
39949 vinfos[5].foffset = j5;
39950 vinfos[5].indices[0] = _ij5[0];
39951 vinfos[5].indices[1] = _ij5[1];
39952 vinfos[5].maxsolutions = _nj5;
39953 vinfos[6].jointtype = 1;
39954 vinfos[6].foffset = j6;
39955 vinfos[6].indices[0] = _ij6[0];
39956 vinfos[6].indices[1] = _ij6[1];
39957 vinfos[6].maxsolutions = _nj6;
39958 std::vector<int> vfree(0);
39959 solutions.AddSolution(vinfos,vfree);
39960 }
39961 }
39962 }
39963 
39964 }
39965 
39966 }
39967 
39968 } else
39969 {
39970 {
39971 IkReal j3array[1], cj3array[1], sj3array[1];
39972 bool j3valid[1]={false};
39973 _nj3 = 1;
39974 IkReal x12264=((sj1)*(sj5));
39975 IkReal x12265=((r20)*(sj6));
39976 IkReal x12266=((cj4)*(r22));
39977 IkReal x12267=((IkReal(1.00000000000000))*(cj1));
39978 IkReal x12268=((cj5)*(sj1));
39979 IkReal x12269=((cj6)*(r21));
39980 IkReal x12270=((cj1)*(sj5));
39981 IkReal x12271=((cj4)*(cj5));
39982 IkReal x12272=((cj6)*(r20)*(sj4));
39983 IkReal x12273=((r21)*(sj4)*(sj6));
39984 if( IKabs(((gconst5)*(((((cj4)*(x12265)*(x12268)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x12267)))+(((sj1)*(x12272)))+(((IkReal(-1.00000000000000))*(sj1)*(x12273)))+(((x12264)*(x12266)))+(((cj4)*(x12268)*(x12269)))+(((x12269)*(x12270)))+(((x12265)*(x12270))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(r22)*(x12268)))+(((x12264)*(x12269)))+(((IkReal(-1.00000000000000))*(x12267)*(x12272)))+(((cj1)*(x12273)))+(((IkReal(-1.00000000000000))*(x12267)*(x12269)*(x12271)))+(((IkReal(-1.00000000000000))*(x12265)*(x12267)*(x12271)))+(((x12264)*(x12265)))+(((IkReal(-1.00000000000000))*(sj5)*(x12266)*(x12267))))))) < IKFAST_ATAN2_MAGTHRESH )
39985     continue;
39986 j3array[0]=IKatan2(((gconst5)*(((((cj4)*(x12265)*(x12268)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)*(x12267)))+(((sj1)*(x12272)))+(((IkReal(-1.00000000000000))*(sj1)*(x12273)))+(((x12264)*(x12266)))+(((cj4)*(x12268)*(x12269)))+(((x12269)*(x12270)))+(((x12265)*(x12270)))))), ((gconst5)*(((((IkReal(-1.00000000000000))*(r22)*(x12268)))+(((x12264)*(x12269)))+(((IkReal(-1.00000000000000))*(x12267)*(x12272)))+(((cj1)*(x12273)))+(((IkReal(-1.00000000000000))*(x12267)*(x12269)*(x12271)))+(((IkReal(-1.00000000000000))*(x12265)*(x12267)*(x12271)))+(((x12264)*(x12265)))+(((IkReal(-1.00000000000000))*(sj5)*(x12266)*(x12267)))))));
39987 sj3array[0]=IKsin(j3array[0]);
39988 cj3array[0]=IKcos(j3array[0]);
39989 if( j3array[0] > IKPI )
39990 {
39991     j3array[0]-=IK2PI;
39992 }
39993 else if( j3array[0] < -IKPI )
39994 {    j3array[0]+=IK2PI;
39995 }
39996 j3valid[0] = true;
39997 for(int ij3 = 0; ij3 < 1; ++ij3)
39998 {
39999 if( !j3valid[ij3] )
40000 {
40001     continue;
40002 }
40003 _ij3[0] = ij3; _ij3[1] = -1;
40004 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40005 {
40006 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40007 {
40008     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40009 }
40010 }
40011 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40012 {
40013 IkReal evalcond[4];
40014 IkReal x12274=IKcos(j3);
40015 IkReal x12275=IKsin(j3);
40016 IkReal x12276=((IkReal(1.00000000000000))*(cj4));
40017 IkReal x12277=((sj0)*(sj5));
40018 IkReal x12278=((cj0)*(cj5));
40019 IkReal x12279=((cj6)*(r01));
40020 IkReal x12280=((r00)*(sj6));
40021 IkReal x12281=((cj6)*(r11));
40022 IkReal x12282=((cj5)*(sj0));
40023 IkReal x12283=((cj6)*(sj4));
40024 IkReal x12284=((sj4)*(sj6));
40025 IkReal x12285=((cj4)*(cj5));
40026 IkReal x12286=((cj6)*(r21));
40027 IkReal x12287=((r20)*(sj6));
40028 IkReal x12288=((r10)*(sj6));
40029 IkReal x12289=((cj1)*(x12274));
40030 IkReal x12290=((IkReal(1.00000000000000))*(cj0)*(sj5));
40031 IkReal x12291=((IkReal(1.00000000000000))*(x12275));
40032 IkReal x12292=((IkReal(1.00000000000000))*(sj1)*(x12274));
40033 IkReal x12293=((cj1)*(x12291));
40034 IkReal x12294=((x12293)+(x12292));
40035 evalcond[0]=((((IkReal(-1.00000000000000))*(x12294)))+(((sj5)*(x12287)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12286))));
40036 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x12284)))+(((x12285)*(x12286)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12283)))+(x12289)+(((x12285)*(x12287)))+(((IkReal(-1.00000000000000))*(sj1)*(x12291))));
40037 evalcond[2]=((((r12)*(x12282)))+(((IkReal(-1.00000000000000))*(x12279)*(x12290)))+(((IkReal(-1.00000000000000))*(x12289)))+(((r02)*(x12278)))+(((IkReal(-1.00000000000000))*(x12277)*(x12288)))+(((sj1)*(x12275)))+(((IkReal(-1.00000000000000))*(x12277)*(x12281)))+(((IkReal(-1.00000000000000))*(x12280)*(x12290))));
40038 evalcond[3]=((((IkReal(-1.00000000000000))*(x12294)))+(((r11)*(sj0)*(x12284)))+(((IkReal(-1.00000000000000))*(r12)*(x12276)*(x12277)))+(((IkReal(-1.00000000000000))*(x12276)*(x12278)*(x12280)))+(((IkReal(-1.00000000000000))*(x12276)*(x12278)*(x12279)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12283)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12283)))+(((cj0)*(r01)*(x12284)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12276)))+(((IkReal(-1.00000000000000))*(x12276)*(x12282)*(x12288)))+(((IkReal(-1.00000000000000))*(x12276)*(x12281)*(x12282))));
40039 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40040 {
40041 continue;
40042 }
40043 }
40044 
40045 {
40046 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40047 vinfos[0].jointtype = 1;
40048 vinfos[0].foffset = j0;
40049 vinfos[0].indices[0] = _ij0[0];
40050 vinfos[0].indices[1] = _ij0[1];
40051 vinfos[0].maxsolutions = _nj0;
40052 vinfos[1].jointtype = 1;
40053 vinfos[1].foffset = j1;
40054 vinfos[1].indices[0] = _ij1[0];
40055 vinfos[1].indices[1] = _ij1[1];
40056 vinfos[1].maxsolutions = _nj1;
40057 vinfos[2].jointtype = 1;
40058 vinfos[2].foffset = j2;
40059 vinfos[2].indices[0] = _ij2[0];
40060 vinfos[2].indices[1] = _ij2[1];
40061 vinfos[2].maxsolutions = _nj2;
40062 vinfos[3].jointtype = 1;
40063 vinfos[3].foffset = j3;
40064 vinfos[3].indices[0] = _ij3[0];
40065 vinfos[3].indices[1] = _ij3[1];
40066 vinfos[3].maxsolutions = _nj3;
40067 vinfos[4].jointtype = 1;
40068 vinfos[4].foffset = j4;
40069 vinfos[4].indices[0] = _ij4[0];
40070 vinfos[4].indices[1] = _ij4[1];
40071 vinfos[4].maxsolutions = _nj4;
40072 vinfos[5].jointtype = 1;
40073 vinfos[5].foffset = j5;
40074 vinfos[5].indices[0] = _ij5[0];
40075 vinfos[5].indices[1] = _ij5[1];
40076 vinfos[5].maxsolutions = _nj5;
40077 vinfos[6].jointtype = 1;
40078 vinfos[6].foffset = j6;
40079 vinfos[6].indices[0] = _ij6[0];
40080 vinfos[6].indices[1] = _ij6[1];
40081 vinfos[6].maxsolutions = _nj6;
40082 std::vector<int> vfree(0);
40083 solutions.AddSolution(vinfos,vfree);
40084 }
40085 }
40086 }
40087 
40088 }
40089 
40090 }
40091 
40092 } else
40093 {
40094 IkReal x12295=((cj5)*(sj4));
40095 IkReal x12296=((IkReal(1.00000000000000))*(sj6));
40096 IkReal x12297=((r10)*(sj0));
40097 IkReal x12298=((sj4)*(sj5));
40098 IkReal x12299=((cj4)*(cj5));
40099 IkReal x12300=((IkReal(1.00000000000000))*(r02));
40100 IkReal x12301=((IkReal(0.374290000000000))*(cj0));
40101 IkReal x12302=((cj5)*(r12));
40102 IkReal x12303=((cj6)*(sj5));
40103 IkReal x12304=((cj0)*(r11));
40104 IkReal x12305=((cj5)*(sj0));
40105 IkReal x12306=((r20)*(sj6));
40106 IkReal x12307=((IkReal(1.00000000000000))*(sj0));
40107 IkReal x12308=((IkReal(1.00000000000000))*(cj6));
40108 IkReal x12309=((IkReal(0.0100000000000000))*(cj5));
40109 IkReal x12310=((IkReal(0.0100000000000000))*(sj5));
40110 IkReal x12311=((sj5)*(sj6));
40111 IkReal x12312=((cj0)*(r10));
40112 IkReal x12313=((cj4)*(cj6));
40113 IkReal x12314=((cj0)*(r01));
40114 IkReal x12315=((cj0)*(r00));
40115 IkReal x12316=((cj6)*(r21));
40116 IkReal x12317=((IkReal(0.374290000000000))*(sj0));
40117 IkReal x12318=((IkReal(0.374290000000000))*(sj5));
40118 IkReal x12319=((cj6)*(r11));
40119 IkReal x12320=((sj0)*(sj4));
40120 IkReal x12321=((cj4)*(sj5));
40121 IkReal x12322=((cj4)*(sj6));
40122 IkReal x12323=((IkReal(1.00000000000000))*(cj0));
40123 IkReal x12324=((r02)*(sj0));
40124 IkReal x12325=((r00)*(sj0)*(sj6));
40125 IkReal x12326=((cj6)*(r01)*(sj0));
40126 IkReal x12327=((r00)*(x12313));
40127 IkReal x12328=((r12)*(x12323));
40128 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
40129 evalcond[1]=((((r22)*(x12298)))+(((x12295)*(x12306)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12308)))+(((x12295)*(x12316)))+(((r21)*(x12322))));
40130 evalcond[2]=((((x12306)*(x12318)))+(((IkReal(-1.00000000000000))*(r22)*(x12310)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-0.0690000000000000))*(cj1)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x12306)*(x12309)))+(((IkReal(0.374290000000000))*(r21)*(x12303)))+(((IkReal(-1.00000000000000))*(x12309)*(x12316))));
40131 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x12296)*(x12312)))+(((r01)*(sj0)*(x12303)))+(((IkReal(-1.00000000000000))*(x12303)*(x12304)))+(((cj0)*(x12302)))+(((r00)*(sj0)*(x12311)))+(((IkReal(-1.00000000000000))*(x12300)*(x12305))));
40132 evalcond[4]=((IkReal(-1.00000000000000))+(((r01)*(sj0)*(x12322)))+(((IkReal(-1.00000000000000))*(x12295)*(x12304)*(x12308)))+(((IkReal(-1.00000000000000))*(x12298)*(x12328)))+(((IkReal(-1.00000000000000))*(x12295)*(x12296)*(x12312)))+(((IkReal(-1.00000000000000))*(cj4)*(x12296)*(x12304)))+(((x12298)*(x12324)))+(((x12312)*(x12313)))+(((x12295)*(x12326)))+(((IkReal(-1.00000000000000))*(x12307)*(x12327)))+(((x12295)*(x12325))));
40133 evalcond[5]=((((IkReal(-1.00000000000000))*(x12296)*(x12299)*(x12312)))+(((IkReal(-1.00000000000000))*(r01)*(x12296)*(x12320)))+(((x12321)*(x12324)))+(((x12299)*(x12325)))+(((IkReal(-1.00000000000000))*(sj4)*(x12308)*(x12312)))+(((x12299)*(x12326)))+(((sj4)*(sj6)*(x12304)))+(((cj6)*(r00)*(x12320)))+(((IkReal(-1.00000000000000))*(x12321)*(x12328)))+(((IkReal(-1.00000000000000))*(x12299)*(x12304)*(x12308))));
40134 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(r11)*(sj0)*(x12296)))+(((IkReal(-1.00000000000000))*(x12295)*(x12296)*(x12297)))+(((IkReal(-1.00000000000000))*(x12295)*(x12308)*(x12314)))+(((x12313)*(x12315)))+(((IkReal(-1.00000000000000))*(x12295)*(x12307)*(x12319)))+(((x12297)*(x12313)))+(((IkReal(-1.00000000000000))*(r12)*(x12298)*(x12307)))+(((IkReal(-1.00000000000000))*(x12295)*(x12296)*(x12315)))+(((IkReal(-1.00000000000000))*(cj4)*(x12296)*(x12314)))+(((IkReal(-1.00000000000000))*(cj0)*(x12298)*(x12300))));
40135 evalcond[7]=((((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12305)))+(((sj6)*(x12309)*(x12312)))+(((r01)*(x12303)*(x12317)))+(((cj6)*(x12304)*(x12309)))+(((x12301)*(x12302)))+(((IkReal(-1.00000000000000))*(r11)*(x12301)*(x12303)))+(((r00)*(x12311)*(x12317)))+(((IkReal(-0.0100000000000000))*(cj6)*(r01)*(x12305)))+(((IkReal(-1.00000000000000))*(x12310)*(x12324)))+(((IkReal(-1.00000000000000))*(r10)*(x12301)*(x12311)))+(((IkReal(-1.00000000000000))*(py)*(x12323)))+(((cj0)*(r12)*(x12310)))+(((px)*(sj0)))+(((IkReal(-0.374290000000000))*(r02)*(x12305))));
40136 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x12323)))+(((cj0)*(r02)*(x12310)))+(((cj5)*(r02)*(x12301)))+(((IkReal(0.0690000000000000))*(sj1)))+(((x12302)*(x12317)))+(((sj6)*(x12309)*(x12315)))+(((r12)*(sj0)*(x12310)))+(((cj6)*(x12309)*(x12314)))+(((IkReal(-1.00000000000000))*(r00)*(x12301)*(x12311)))+(((IkReal(-0.374290000000000))*(x12297)*(x12311)))+(((IkReal(-1.00000000000000))*(py)*(x12307)))+(((IkReal(0.0100000000000000))*(x12305)*(x12319)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(r11)*(x12303)*(x12317)))+(((IkReal(-1.00000000000000))*(r01)*(x12301)*(x12303)))+(((sj6)*(x12297)*(x12309))));
40137 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
40138 {
40139 {
40140 IkReal dummyeval[1];
40141 IkReal gconst7;
40142 gconst7=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
40143 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
40144 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
40145 {
40146 {
40147 IkReal dummyeval[1];
40148 IkReal gconst8;
40149 gconst8=IKsign((((cj1)*(cj1))+((sj1)*(sj1))));
40150 dummyeval[0]=(((cj1)*(cj1))+((sj1)*(sj1)));
40151 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
40152 {
40153 continue;
40154 
40155 } else
40156 {
40157 {
40158 IkReal j3array[1], cj3array[1], sj3array[1];
40159 bool j3valid[1]={false};
40160 _nj3 = 1;
40161 IkReal x12329=((IkReal(1.00000000000000))*(sj0));
40162 IkReal x12330=((cj6)*(r21));
40163 IkReal x12331=((cj0)*(r00));
40164 IkReal x12332=((cj5)*(sj1));
40165 IkReal x12333=((r12)*(sj0));
40166 IkReal x12334=((cj1)*(cj5));
40167 IkReal x12335=((cj0)*(r02));
40168 IkReal x12336=((sj1)*(sj5));
40169 IkReal x12337=((cj6)*(r11));
40170 IkReal x12338=((cj1)*(sj5));
40171 IkReal x12339=((sj6)*(x12336));
40172 IkReal x12340=((IkReal(1.00000000000000))*(x12338));
40173 IkReal x12341=((cj0)*(cj6)*(r01));
40174 if( IKabs(((gconst8)*(((((x12332)*(x12335)))+(((IkReal(-1.00000000000000))*(r10)*(x12329)*(x12339)))+(((IkReal(-1.00000000000000))*(x12331)*(x12339)))+(((IkReal(-1.00000000000000))*(x12336)*(x12341)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x12340)))+(((IkReal(-1.00000000000000))*(x12329)*(x12336)*(x12337)))+(((r22)*(x12334)))+(((IkReal(-1.00000000000000))*(x12330)*(x12340)))+(((x12332)*(x12333))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((x12333)*(x12334)))+(((IkReal(-1.00000000000000))*(r22)*(x12332)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x12329)*(x12338)))+(((IkReal(-1.00000000000000))*(sj6)*(x12331)*(x12340)))+(((x12330)*(x12336)))+(((r20)*(x12339)))+(((IkReal(-1.00000000000000))*(x12329)*(x12337)*(x12338)))+(((x12334)*(x12335)))+(((IkReal(-1.00000000000000))*(x12340)*(x12341))))))) < IKFAST_ATAN2_MAGTHRESH )
40175     continue;
40176 j3array[0]=IKatan2(((gconst8)*(((((x12332)*(x12335)))+(((IkReal(-1.00000000000000))*(r10)*(x12329)*(x12339)))+(((IkReal(-1.00000000000000))*(x12331)*(x12339)))+(((IkReal(-1.00000000000000))*(x12336)*(x12341)))+(((IkReal(-1.00000000000000))*(r20)*(sj6)*(x12340)))+(((IkReal(-1.00000000000000))*(x12329)*(x12336)*(x12337)))+(((r22)*(x12334)))+(((IkReal(-1.00000000000000))*(x12330)*(x12340)))+(((x12332)*(x12333)))))), ((gconst8)*(((((x12333)*(x12334)))+(((IkReal(-1.00000000000000))*(r22)*(x12332)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x12329)*(x12338)))+(((IkReal(-1.00000000000000))*(sj6)*(x12331)*(x12340)))+(((x12330)*(x12336)))+(((r20)*(x12339)))+(((IkReal(-1.00000000000000))*(x12329)*(x12337)*(x12338)))+(((x12334)*(x12335)))+(((IkReal(-1.00000000000000))*(x12340)*(x12341)))))));
40177 sj3array[0]=IKsin(j3array[0]);
40178 cj3array[0]=IKcos(j3array[0]);
40179 if( j3array[0] > IKPI )
40180 {
40181     j3array[0]-=IK2PI;
40182 }
40183 else if( j3array[0] < -IKPI )
40184 {    j3array[0]+=IK2PI;
40185 }
40186 j3valid[0] = true;
40187 for(int ij3 = 0; ij3 < 1; ++ij3)
40188 {
40189 if( !j3valid[ij3] )
40190 {
40191     continue;
40192 }
40193 _ij3[0] = ij3; _ij3[1] = -1;
40194 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40195 {
40196 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40197 {
40198     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40199 }
40200 }
40201 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40202 {
40203 IkReal evalcond[4];
40204 IkReal x12342=IKsin(j3);
40205 IkReal x12343=IKcos(j3);
40206 IkReal x12344=((IkReal(1.00000000000000))*(cj4));
40207 IkReal x12345=((sj0)*(sj5));
40208 IkReal x12346=((cj0)*(cj5));
40209 IkReal x12347=((cj6)*(r01));
40210 IkReal x12348=((r00)*(sj6));
40211 IkReal x12349=((cj6)*(r11));
40212 IkReal x12350=((cj5)*(sj0));
40213 IkReal x12351=((cj6)*(sj4));
40214 IkReal x12352=((sj4)*(sj6));
40215 IkReal x12353=((cj4)*(cj5));
40216 IkReal x12354=((cj6)*(r21));
40217 IkReal x12355=((r20)*(sj6));
40218 IkReal x12356=((r10)*(sj6));
40219 IkReal x12357=((cj1)*(x12342));
40220 IkReal x12358=((IkReal(1.00000000000000))*(cj0)*(sj5));
40221 IkReal x12359=((IkReal(1.00000000000000))*(x12343));
40222 IkReal x12360=((IkReal(1.00000000000000))*(sj1)*(x12342));
40223 IkReal x12361=((cj1)*(x12359));
40224 IkReal x12362=((x12361)+(x12360));
40225 evalcond[0]=((((sj5)*(x12355)))+(((sj5)*(x12354)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x12359)))+(x12357));
40226 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x12352)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(x12362)))+(((x12353)*(x12354)))+(((r20)*(x12351)))+(((x12353)*(x12355))));
40227 evalcond[2]=((((r02)*(x12346)))+(((IkReal(-1.00000000000000))*(x12348)*(x12358)))+(((IkReal(-1.00000000000000))*(x12362)))+(((IkReal(-1.00000000000000))*(x12345)*(x12356)))+(((r12)*(x12350)))+(((IkReal(-1.00000000000000))*(x12347)*(x12358)))+(((IkReal(-1.00000000000000))*(x12345)*(x12349))));
40228 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x12344)*(x12345)))+(((sj1)*(x12343)))+(((IkReal(-1.00000000000000))*(x12357)))+(((IkReal(-1.00000000000000))*(x12344)*(x12349)*(x12350)))+(((IkReal(-1.00000000000000))*(x12344)*(x12346)*(x12348)))+(((IkReal(-1.00000000000000))*(x12344)*(x12346)*(x12347)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12344)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12351)))+(((r11)*(sj0)*(x12352)))+(((cj0)*(r01)*(x12352)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12351)))+(((IkReal(-1.00000000000000))*(x12344)*(x12350)*(x12356))));
40229 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40230 {
40231 continue;
40232 }
40233 }
40234 
40235 {
40236 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40237 vinfos[0].jointtype = 1;
40238 vinfos[0].foffset = j0;
40239 vinfos[0].indices[0] = _ij0[0];
40240 vinfos[0].indices[1] = _ij0[1];
40241 vinfos[0].maxsolutions = _nj0;
40242 vinfos[1].jointtype = 1;
40243 vinfos[1].foffset = j1;
40244 vinfos[1].indices[0] = _ij1[0];
40245 vinfos[1].indices[1] = _ij1[1];
40246 vinfos[1].maxsolutions = _nj1;
40247 vinfos[2].jointtype = 1;
40248 vinfos[2].foffset = j2;
40249 vinfos[2].indices[0] = _ij2[0];
40250 vinfos[2].indices[1] = _ij2[1];
40251 vinfos[2].maxsolutions = _nj2;
40252 vinfos[3].jointtype = 1;
40253 vinfos[3].foffset = j3;
40254 vinfos[3].indices[0] = _ij3[0];
40255 vinfos[3].indices[1] = _ij3[1];
40256 vinfos[3].maxsolutions = _nj3;
40257 vinfos[4].jointtype = 1;
40258 vinfos[4].foffset = j4;
40259 vinfos[4].indices[0] = _ij4[0];
40260 vinfos[4].indices[1] = _ij4[1];
40261 vinfos[4].maxsolutions = _nj4;
40262 vinfos[5].jointtype = 1;
40263 vinfos[5].foffset = j5;
40264 vinfos[5].indices[0] = _ij5[0];
40265 vinfos[5].indices[1] = _ij5[1];
40266 vinfos[5].maxsolutions = _nj5;
40267 vinfos[6].jointtype = 1;
40268 vinfos[6].foffset = j6;
40269 vinfos[6].indices[0] = _ij6[0];
40270 vinfos[6].indices[1] = _ij6[1];
40271 vinfos[6].maxsolutions = _nj6;
40272 std::vector<int> vfree(0);
40273 solutions.AddSolution(vinfos,vfree);
40274 }
40275 }
40276 }
40277 
40278 }
40279 
40280 }
40281 
40282 } else
40283 {
40284 {
40285 IkReal j3array[1], cj3array[1], sj3array[1];
40286 bool j3valid[1]={false};
40287 _nj3 = 1;
40288 IkReal x12363=((sj1)*(sj6));
40289 IkReal x12364=((r20)*(sj5));
40290 IkReal x12365=((IkReal(1.00000000000000))*(r21));
40291 IkReal x12366=((cj1)*(cj6));
40292 IkReal x12367=((r20)*(sj4));
40293 IkReal x12368=((cj6)*(sj1));
40294 IkReal x12369=((cj4)*(cj5));
40295 IkReal x12370=((cj1)*(sj6));
40296 IkReal x12371=((cj5)*(r22));
40297 IkReal x12372=((cj4)*(r22)*(sj5));
40298 if( IKabs(((gconst7)*(((((cj1)*(x12371)))+(((IkReal(-1.00000000000000))*(sj5)*(x12365)*(x12366)))+(((x12367)*(x12368)))+(((r21)*(x12368)*(x12369)))+(((sj1)*(x12372)))+(((r20)*(x12363)*(x12369)))+(((IkReal(-1.00000000000000))*(x12364)*(x12370)))+(((IkReal(-1.00000000000000))*(sj4)*(x12363)*(x12365))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((r20)*(x12369)*(x12370)))+(((r21)*(sj5)*(x12368)))+(((x12363)*(x12364)))+(((x12366)*(x12367)))+(((IkReal(-1.00000000000000))*(sj1)*(x12371)))+(((IkReal(-1.00000000000000))*(sj4)*(x12365)*(x12370)))+(((cj1)*(x12372)))+(((r21)*(x12366)*(x12369))))))) < IKFAST_ATAN2_MAGTHRESH )
40299     continue;
40300 j3array[0]=IKatan2(((gconst7)*(((((cj1)*(x12371)))+(((IkReal(-1.00000000000000))*(sj5)*(x12365)*(x12366)))+(((x12367)*(x12368)))+(((r21)*(x12368)*(x12369)))+(((sj1)*(x12372)))+(((r20)*(x12363)*(x12369)))+(((IkReal(-1.00000000000000))*(x12364)*(x12370)))+(((IkReal(-1.00000000000000))*(sj4)*(x12363)*(x12365)))))), ((gconst7)*(((((r20)*(x12369)*(x12370)))+(((r21)*(sj5)*(x12368)))+(((x12363)*(x12364)))+(((x12366)*(x12367)))+(((IkReal(-1.00000000000000))*(sj1)*(x12371)))+(((IkReal(-1.00000000000000))*(sj4)*(x12365)*(x12370)))+(((cj1)*(x12372)))+(((r21)*(x12366)*(x12369)))))));
40301 sj3array[0]=IKsin(j3array[0]);
40302 cj3array[0]=IKcos(j3array[0]);
40303 if( j3array[0] > IKPI )
40304 {
40305     j3array[0]-=IK2PI;
40306 }
40307 else if( j3array[0] < -IKPI )
40308 {    j3array[0]+=IK2PI;
40309 }
40310 j3valid[0] = true;
40311 for(int ij3 = 0; ij3 < 1; ++ij3)
40312 {
40313 if( !j3valid[ij3] )
40314 {
40315     continue;
40316 }
40317 _ij3[0] = ij3; _ij3[1] = -1;
40318 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40319 {
40320 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40321 {
40322     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40323 }
40324 }
40325 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40326 {
40327 IkReal evalcond[4];
40328 IkReal x12373=IKsin(j3);
40329 IkReal x12374=IKcos(j3);
40330 IkReal x12375=((IkReal(1.00000000000000))*(cj4));
40331 IkReal x12376=((sj0)*(sj5));
40332 IkReal x12377=((cj0)*(cj5));
40333 IkReal x12378=((cj6)*(r01));
40334 IkReal x12379=((r00)*(sj6));
40335 IkReal x12380=((cj6)*(r11));
40336 IkReal x12381=((cj5)*(sj0));
40337 IkReal x12382=((cj6)*(sj4));
40338 IkReal x12383=((sj4)*(sj6));
40339 IkReal x12384=((cj4)*(cj5));
40340 IkReal x12385=((cj6)*(r21));
40341 IkReal x12386=((r20)*(sj6));
40342 IkReal x12387=((r10)*(sj6));
40343 IkReal x12388=((cj1)*(x12373));
40344 IkReal x12389=((IkReal(1.00000000000000))*(cj0)*(sj5));
40345 IkReal x12390=((IkReal(1.00000000000000))*(x12374));
40346 IkReal x12391=((IkReal(1.00000000000000))*(sj1)*(x12373));
40347 IkReal x12392=((cj1)*(x12390));
40348 IkReal x12393=((x12391)+(x12392));
40349 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x12390)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(x12388)+(((sj5)*(x12386)))+(((sj5)*(x12385))));
40350 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x12383)))+(((x12384)*(x12386)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12382)))+(((IkReal(-1.00000000000000))*(x12393)))+(((x12384)*(x12385))));
40351 evalcond[2]=((((IkReal(-1.00000000000000))*(x12379)*(x12389)))+(((r12)*(x12381)))+(((IkReal(-1.00000000000000))*(x12376)*(x12380)))+(((r02)*(x12377)))+(((IkReal(-1.00000000000000))*(x12378)*(x12389)))+(((IkReal(-1.00000000000000))*(x12393)))+(((IkReal(-1.00000000000000))*(x12376)*(x12387))));
40352 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12375)))+(((IkReal(-1.00000000000000))*(x12375)*(x12377)*(x12378)))+(((IkReal(-1.00000000000000))*(x12388)))+(((cj0)*(r01)*(x12383)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12382)))+(((IkReal(-1.00000000000000))*(x12375)*(x12377)*(x12379)))+(((IkReal(-1.00000000000000))*(x12375)*(x12381)*(x12387)))+(((r11)*(sj0)*(x12383)))+(((sj1)*(x12374)))+(((IkReal(-1.00000000000000))*(x12375)*(x12380)*(x12381)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12382)))+(((IkReal(-1.00000000000000))*(r12)*(x12375)*(x12376))));
40353 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40354 {
40355 continue;
40356 }
40357 }
40358 
40359 {
40360 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40361 vinfos[0].jointtype = 1;
40362 vinfos[0].foffset = j0;
40363 vinfos[0].indices[0] = _ij0[0];
40364 vinfos[0].indices[1] = _ij0[1];
40365 vinfos[0].maxsolutions = _nj0;
40366 vinfos[1].jointtype = 1;
40367 vinfos[1].foffset = j1;
40368 vinfos[1].indices[0] = _ij1[0];
40369 vinfos[1].indices[1] = _ij1[1];
40370 vinfos[1].maxsolutions = _nj1;
40371 vinfos[2].jointtype = 1;
40372 vinfos[2].foffset = j2;
40373 vinfos[2].indices[0] = _ij2[0];
40374 vinfos[2].indices[1] = _ij2[1];
40375 vinfos[2].maxsolutions = _nj2;
40376 vinfos[3].jointtype = 1;
40377 vinfos[3].foffset = j3;
40378 vinfos[3].indices[0] = _ij3[0];
40379 vinfos[3].indices[1] = _ij3[1];
40380 vinfos[3].maxsolutions = _nj3;
40381 vinfos[4].jointtype = 1;
40382 vinfos[4].foffset = j4;
40383 vinfos[4].indices[0] = _ij4[0];
40384 vinfos[4].indices[1] = _ij4[1];
40385 vinfos[4].maxsolutions = _nj4;
40386 vinfos[5].jointtype = 1;
40387 vinfos[5].foffset = j5;
40388 vinfos[5].indices[0] = _ij5[0];
40389 vinfos[5].indices[1] = _ij5[1];
40390 vinfos[5].maxsolutions = _nj5;
40391 vinfos[6].jointtype = 1;
40392 vinfos[6].foffset = j6;
40393 vinfos[6].indices[0] = _ij6[0];
40394 vinfos[6].indices[1] = _ij6[1];
40395 vinfos[6].maxsolutions = _nj6;
40396 std::vector<int> vfree(0);
40397 solutions.AddSolution(vinfos,vfree);
40398 }
40399 }
40400 }
40401 
40402 }
40403 
40404 }
40405 
40406 } else
40407 {
40408 IkReal x12394=((IkReal(1.00000000000000))*(cj0));
40409 IkReal x12395=((cj4)*(sj6));
40410 IkReal x12396=((sj0)*(sj4));
40411 IkReal x12397=((cj5)*(sj6));
40412 IkReal x12398=((sj4)*(sj5));
40413 IkReal x12399=((r12)*(sj5));
40414 IkReal x12400=((IkReal(0.374290000000000))*(cj5));
40415 IkReal x12401=((r02)*(sj0));
40416 IkReal x12402=((cj6)*(r21));
40417 IkReal x12403=((IkReal(0.0100000000000000))*(cj5));
40418 IkReal x12404=((IkReal(1.00000000000000))*(sj0));
40419 IkReal x12405=((cj0)*(r10));
40420 IkReal x12406=((cj4)*(cj6));
40421 IkReal x12407=((r00)*(sj0));
40422 IkReal x12408=((IkReal(0.374290000000000))*(sj5));
40423 IkReal x12409=((cj0)*(r00));
40424 IkReal x12410=((IkReal(0.0100000000000000))*(sj5));
40425 IkReal x12411=((cj0)*(r02));
40426 IkReal x12412=((cj5)*(sj4));
40427 IkReal x12413=((cj6)*(r01));
40428 IkReal x12414=((cj6)*(r11));
40429 IkReal x12415=((r10)*(sj0));
40430 IkReal x12416=((sj6)*(x12408));
40431 IkReal x12417=((cj0)*(cj6)*(x12408));
40432 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j1)), IkReal(6.28318530717959))));
40433 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)))+(((x12402)*(x12412)))+(((r22)*(x12398)))+(((r20)*(sj4)*(x12397)))+(((r21)*(x12395)))+(((IkReal(-1.00000000000000))*(r20)*(x12406))));
40434 evalcond[2]=((((x12402)*(x12408)))+(((IkReal(-1.00000000000000))*(r22)*(x12410)))+(((IkReal(-1.00000000000000))*(r22)*(x12400)))+(pz)+(((IkReal(-1.00000000000000))*(x12402)*(x12403)))+(((IkReal(0.0690000000000000))*(cj2)))+(((r20)*(x12416)))+(((IkReal(-0.0100000000000000))*(r20)*(x12397))));
40435 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12394)*(x12397)))+(((r02)*(sj5)*(x12396)))+(((IkReal(-1.00000000000000))*(r00)*(x12404)*(x12406)))+(cj2)+(((cj5)*(x12396)*(x12413)))+(((r01)*(sj0)*(x12395)))+(((IkReal(-1.00000000000000))*(r12)*(x12394)*(x12398)))+(((IkReal(-1.00000000000000))*(x12394)*(x12412)*(x12414)))+(((r00)*(x12396)*(x12397)))+(((x12405)*(x12406)))+(((IkReal(-1.00000000000000))*(r11)*(x12394)*(x12395))));
40436 evalcond[4]=((((IkReal(-1.00000000000000))*(x12394)*(x12412)*(x12413)))+(((IkReal(-1.00000000000000))*(x12396)*(x12399)))+(((IkReal(-1.00000000000000))*(r01)*(x12394)*(x12395)))+(((IkReal(-1.00000000000000))*(r02)*(x12394)*(x12398)))+(((x12406)*(x12409)))+(((IkReal(-1.00000000000000))*(r11)*(x12395)*(x12404)))+(((IkReal(-1.00000000000000))*(cj5)*(x12396)*(x12414)))+(((x12406)*(x12415)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12394)*(x12397)))+(((IkReal(-1.00000000000000))*(r10)*(x12396)*(x12397))));
40437 evalcond[5]=((((IkReal(-1.00000000000000))*(py)*(x12394)))+(((IkReal(0.0100000000000000))*(x12397)*(x12405)))+(((IkReal(-0.0100000000000000))*(x12397)*(x12407)))+(((x12407)*(x12416)))+(((IkReal(-1.00000000000000))*(x12401)*(x12410)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x12405)*(x12416)))+(((IkReal(-1.00000000000000))*(cj0)*(x12408)*(x12414)))+(((IkReal(-1.00000000000000))*(x12400)*(x12401)))+(((cj0)*(x12403)*(x12414)))+(((sj0)*(x12408)*(x12413)))+(((IkReal(0.0100000000000000))*(cj0)*(x12399)))+(((cj0)*(r12)*(x12400)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x12403)*(x12413))));
40438 evalcond[6]=((IkReal(0.433420000000000))+(((IkReal(-1.00000000000000))*(x12415)*(x12416)))+(((cj0)*(x12403)*(x12413)))+(((IkReal(-1.00000000000000))*(px)*(x12394)))+(((IkReal(0.0100000000000000))*(sj0)*(x12399)))+(((IkReal(-1.00000000000000))*(x12409)*(x12416)))+(((x12410)*(x12411)))+(((sj0)*(x12403)*(x12414)))+(((IkReal(0.0100000000000000))*(x12397)*(x12415)))+(((IkReal(0.0100000000000000))*(x12397)*(x12409)))+(((IkReal(-1.00000000000000))*(sj0)*(x12408)*(x12414)))+(((IkReal(-1.00000000000000))*(py)*(x12404)))+(((x12400)*(x12411)))+(((IkReal(-1.00000000000000))*(cj0)*(x12408)*(x12413)))+(((r12)*(sj0)*(x12400))));
40439 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
40440 {
40441 {
40442 IkReal dummyeval[1];
40443 IkReal gconst9;
40444 gconst9=IKsign(cj2);
40445 dummyeval[0]=cj2;
40446 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
40447 {
40448 {
40449 IkReal dummyeval[1];
40450 dummyeval[0]=cj2;
40451 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
40452 {
40453 {
40454 IkReal dummyeval[1];
40455 dummyeval[0]=sj2;
40456 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
40457 {
40458 {
40459 IkReal evalcond[9];
40460 IkReal x12418=((cj5)*(sj4));
40461 IkReal x12419=((IkReal(1.00000000000000))*(sj6));
40462 IkReal x12420=((r10)*(sj0));
40463 IkReal x12421=((sj4)*(sj5));
40464 IkReal x12422=((cj5)*(cj6));
40465 IkReal x12423=((r01)*(sj0));
40466 IkReal x12424=((IkReal(1.00000000000000))*(r02));
40467 IkReal x12425=((IkReal(0.374290000000000))*(cj0));
40468 IkReal x12426=((cj5)*(r12));
40469 IkReal x12427=((cj6)*(sj5));
40470 IkReal x12428=((cj0)*(r11));
40471 IkReal x12429=((cj5)*(sj0));
40472 IkReal x12430=((r20)*(sj6));
40473 IkReal x12431=((IkReal(1.00000000000000))*(sj0));
40474 IkReal x12432=((cj4)*(cj5));
40475 IkReal x12433=((IkReal(1.00000000000000))*(cj6));
40476 IkReal x12434=((IkReal(0.0100000000000000))*(sj5));
40477 IkReal x12435=((sj5)*(sj6));
40478 IkReal x12436=((cj0)*(r10));
40479 IkReal x12437=((cj4)*(cj6));
40480 IkReal x12438=((cj0)*(r01));
40481 IkReal x12439=((IkReal(1.00000000000000))*(cj4));
40482 IkReal x12440=((cj0)*(r00));
40483 IkReal x12441=((IkReal(0.374290000000000))*(sj0));
40484 IkReal x12442=((cj0)*(r12));
40485 IkReal x12443=((IkReal(0.374290000000000))*(sj5));
40486 IkReal x12444=((cj4)*(sj6));
40487 IkReal x12445=((IkReal(1.00000000000000))*(cj0));
40488 IkReal x12446=((r02)*(sj0));
40489 IkReal x12447=((IkReal(0.0100000000000000))*(cj5));
40490 IkReal x12448=((r11)*(sj0));
40491 IkReal x12449=((r00)*(sj0)*(sj6));
40492 IkReal x12450=((r00)*(x12437));
40493 IkReal x12451=((sj6)*(x12447));
40494 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
40495 evalcond[1]=((((x12418)*(x12430)))+(((cj6)*(r21)*(x12418)))+(((r21)*(x12444)))+(((r22)*(x12421)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12433))));
40496 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x12430)*(x12447)))+(((IkReal(0.374290000000000))*(r21)*(x12427)))+(((IkReal(-0.0100000000000000))*(r21)*(x12422)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((x12430)*(x12443)))+(((IkReal(-1.00000000000000))*(r22)*(x12434))));
40497 evalcond[3]=((((IkReal(-1.00000000000000))*(x12424)*(x12429)))+(((IkReal(-1.00000000000000))*(sj5)*(x12419)*(x12436)))+(((IkReal(-1.00000000000000))*(x12427)*(x12428)))+(((cj0)*(x12426)))+(((r00)*(sj0)*(x12435)))+(((x12423)*(x12427))));
40498 evalcond[4]=((IkReal(1.00000000000000))+(((cj6)*(x12418)*(x12423)))+(((IkReal(-1.00000000000000))*(x12421)*(x12442)))+(((x12421)*(x12446)))+(((IkReal(-1.00000000000000))*(x12418)*(x12428)*(x12433)))+(((x12436)*(x12437)))+(((IkReal(-1.00000000000000))*(cj4)*(x12419)*(x12428)))+(((IkReal(-1.00000000000000))*(x12418)*(x12419)*(x12436)))+(((IkReal(-1.00000000000000))*(x12431)*(x12450)))+(((x12418)*(x12449)))+(((x12423)*(x12444))));
40499 evalcond[5]=((((cj4)*(sj5)*(x12446)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((cj4)*(x12422)*(x12423)))+(((r00)*(x12429)*(x12444)))+(((IkReal(-1.00000000000000))*(sj4)*(x12433)*(x12436)))+(((IkReal(-1.00000000000000))*(sj4)*(x12419)*(x12423)))+(((sj4)*(sj6)*(x12428)))+(((IkReal(-1.00000000000000))*(x12419)*(x12432)*(x12436)))+(((IkReal(-1.00000000000000))*(sj5)*(x12439)*(x12442)))+(((IkReal(-1.00000000000000))*(x12422)*(x12428)*(x12439))));
40500 evalcond[6]=((((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12418)*(x12431)))+(((IkReal(-1.00000000000000))*(x12418)*(x12419)*(x12420)))+(((IkReal(-1.00000000000000))*(x12418)*(x12419)*(x12440)))+(((IkReal(-1.00000000000000))*(r12)*(x12421)*(x12431)))+(((x12420)*(x12437)))+(((IkReal(-1.00000000000000))*(cj4)*(x12419)*(x12448)))+(((IkReal(-1.00000000000000))*(cj4)*(x12419)*(x12438)))+(((IkReal(-1.00000000000000))*(cj0)*(x12421)*(x12424)))+(((x12437)*(x12440)))+(((IkReal(-1.00000000000000))*(x12418)*(x12433)*(x12438))));
40501 evalcond[7]=((((x12436)*(x12451)))+(((x12425)*(x12426)))+(((IkReal(-1.00000000000000))*(py)*(x12445)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12429)))+(((IkReal(-1.00000000000000))*(r10)*(x12425)*(x12435)))+(((IkReal(-0.0100000000000000))*(x12422)*(x12423)))+(((IkReal(-0.374290000000000))*(r02)*(x12429)))+(((IkReal(-1.00000000000000))*(x12434)*(x12446)))+(((IkReal(-1.00000000000000))*(r11)*(x12425)*(x12427)))+(((r00)*(x12435)*(x12441)))+(((x12434)*(x12442)))+(((IkReal(0.0100000000000000))*(x12422)*(x12428)))+(((px)*(sj0)))+(((IkReal(0.374290000000000))*(x12423)*(x12427))));
40502 evalcond[8]=((IkReal(0.433420000000000))+(((x12440)*(x12451)))+(((IkReal(-1.00000000000000))*(px)*(x12445)))+(((cj0)*(r02)*(x12434)))+(((IkReal(-1.00000000000000))*(py)*(x12431)))+(((cj5)*(r02)*(x12425)))+(((x12420)*(x12451)))+(((IkReal(-1.00000000000000))*(r11)*(x12427)*(x12441)))+(((IkReal(0.0100000000000000))*(x12422)*(x12448)))+(((r12)*(sj0)*(x12434)))+(((IkReal(-1.00000000000000))*(r01)*(x12425)*(x12427)))+(((IkReal(-0.374290000000000))*(x12420)*(x12435)))+(((x12426)*(x12441)))+(((IkReal(-1.00000000000000))*(r00)*(x12425)*(x12435)))+(((IkReal(0.0100000000000000))*(x12422)*(x12438))));
40503 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
40504 {
40505 {
40506 IkReal j3array[1], cj3array[1], sj3array[1];
40507 bool j3valid[1]={false};
40508 _nj3 = 1;
40509 IkReal x12452=((IkReal(1.00000000000000))*(cj4));
40510 IkReal x12453=((cj6)*(r21));
40511 IkReal x12454=((r20)*(sj6));
40512 if( IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12454)))+(((sj5)*(x12453))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12453)))+(((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12452)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12454)))+(((sj5)*(x12453)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12453)))+(((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12452)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
40513     continue;
40514 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12454)))+(((sj5)*(x12453)))), ((((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12453)))+(((IkReal(-1.00000000000000))*(cj5)*(x12452)*(x12454)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12452)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
40515 sj3array[0]=IKsin(j3array[0]);
40516 cj3array[0]=IKcos(j3array[0]);
40517 if( j3array[0] > IKPI )
40518 {
40519     j3array[0]-=IK2PI;
40520 }
40521 else if( j3array[0] < -IKPI )
40522 {    j3array[0]+=IK2PI;
40523 }
40524 j3valid[0] = true;
40525 for(int ij3 = 0; ij3 < 1; ++ij3)
40526 {
40527 if( !j3valid[ij3] )
40528 {
40529     continue;
40530 }
40531 _ij3[0] = ij3; _ij3[1] = -1;
40532 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40533 {
40534 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40535 {
40536     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40537 }
40538 }
40539 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40540 {
40541 IkReal evalcond[4];
40542 IkReal x12455=IKcos(j3);
40543 IkReal x12456=((IkReal(1.00000000000000))*(cj4));
40544 IkReal x12457=((sj0)*(sj5));
40545 IkReal x12458=((cj0)*(cj5));
40546 IkReal x12459=((cj6)*(r01));
40547 IkReal x12460=((r00)*(sj6));
40548 IkReal x12461=((cj6)*(r11));
40549 IkReal x12462=((cj5)*(sj0));
40550 IkReal x12463=((cj6)*(sj4));
40551 IkReal x12464=((sj4)*(sj6));
40552 IkReal x12465=((cj4)*(cj5));
40553 IkReal x12466=((cj6)*(r21));
40554 IkReal x12467=((r20)*(sj6));
40555 IkReal x12468=((r10)*(sj6));
40556 IkReal x12469=((IkReal(1.00000000000000))*(IKsin(j3)));
40557 IkReal x12470=((IkReal(1.00000000000000))*(cj0)*(sj5));
40558 evalcond[0]=((((sj5)*(x12466)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12467)))+(((IkReal(-1.00000000000000))*(x12469))));
40559 evalcond[1]=((((x12465)*(x12467)))+(((x12465)*(x12466)))+(((IkReal(-1.00000000000000))*(r21)*(x12464)))+(((r20)*(x12463)))+(((cj4)*(r22)*(sj5)))+(x12455));
40560 evalcond[2]=((((IkReal(-1.00000000000000))*(x12457)*(x12468)))+(((IkReal(-1.00000000000000))*(x12459)*(x12470)))+(((IkReal(-1.00000000000000))*(x12457)*(x12461)))+(((IkReal(-1.00000000000000))*(x12460)*(x12470)))+(((r02)*(x12458)))+(((r12)*(x12462)))+(((IkReal(-1.00000000000000))*(x12455))));
40561 evalcond[3]=((((IkReal(-1.00000000000000))*(x12456)*(x12461)*(x12462)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12463)))+(((IkReal(-1.00000000000000))*(x12456)*(x12458)*(x12460)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12463)))+(((IkReal(-1.00000000000000))*(r12)*(x12456)*(x12457)))+(((cj0)*(r01)*(x12464)))+(((IkReal(-1.00000000000000))*(x12469)))+(((IkReal(-1.00000000000000))*(x12456)*(x12462)*(x12468)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12456)))+(((r11)*(sj0)*(x12464)))+(((IkReal(-1.00000000000000))*(x12456)*(x12458)*(x12459))));
40562 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40563 {
40564 continue;
40565 }
40566 }
40567 
40568 {
40569 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40570 vinfos[0].jointtype = 1;
40571 vinfos[0].foffset = j0;
40572 vinfos[0].indices[0] = _ij0[0];
40573 vinfos[0].indices[1] = _ij0[1];
40574 vinfos[0].maxsolutions = _nj0;
40575 vinfos[1].jointtype = 1;
40576 vinfos[1].foffset = j1;
40577 vinfos[1].indices[0] = _ij1[0];
40578 vinfos[1].indices[1] = _ij1[1];
40579 vinfos[1].maxsolutions = _nj1;
40580 vinfos[2].jointtype = 1;
40581 vinfos[2].foffset = j2;
40582 vinfos[2].indices[0] = _ij2[0];
40583 vinfos[2].indices[1] = _ij2[1];
40584 vinfos[2].maxsolutions = _nj2;
40585 vinfos[3].jointtype = 1;
40586 vinfos[3].foffset = j3;
40587 vinfos[3].indices[0] = _ij3[0];
40588 vinfos[3].indices[1] = _ij3[1];
40589 vinfos[3].maxsolutions = _nj3;
40590 vinfos[4].jointtype = 1;
40591 vinfos[4].foffset = j4;
40592 vinfos[4].indices[0] = _ij4[0];
40593 vinfos[4].indices[1] = _ij4[1];
40594 vinfos[4].maxsolutions = _nj4;
40595 vinfos[5].jointtype = 1;
40596 vinfos[5].foffset = j5;
40597 vinfos[5].indices[0] = _ij5[0];
40598 vinfos[5].indices[1] = _ij5[1];
40599 vinfos[5].maxsolutions = _nj5;
40600 vinfos[6].jointtype = 1;
40601 vinfos[6].foffset = j6;
40602 vinfos[6].indices[0] = _ij6[0];
40603 vinfos[6].indices[1] = _ij6[1];
40604 vinfos[6].maxsolutions = _nj6;
40605 std::vector<int> vfree(0);
40606 solutions.AddSolution(vinfos,vfree);
40607 }
40608 }
40609 }
40610 
40611 } else
40612 {
40613 IkReal x12471=((cj5)*(sj4));
40614 IkReal x12472=((IkReal(1.00000000000000))*(sj6));
40615 IkReal x12473=((r10)*(sj0));
40616 IkReal x12474=((sj4)*(sj5));
40617 IkReal x12475=((cj5)*(cj6));
40618 IkReal x12476=((r01)*(sj0));
40619 IkReal x12477=((IkReal(1.00000000000000))*(r02));
40620 IkReal x12478=((IkReal(0.374290000000000))*(cj0));
40621 IkReal x12479=((cj5)*(r12));
40622 IkReal x12480=((cj6)*(sj5));
40623 IkReal x12481=((cj0)*(r11));
40624 IkReal x12482=((cj5)*(sj0));
40625 IkReal x12483=((r20)*(sj6));
40626 IkReal x12484=((IkReal(1.00000000000000))*(sj0));
40627 IkReal x12485=((cj4)*(cj5));
40628 IkReal x12486=((IkReal(1.00000000000000))*(cj6));
40629 IkReal x12487=((IkReal(0.0100000000000000))*(sj5));
40630 IkReal x12488=((sj5)*(sj6));
40631 IkReal x12489=((cj0)*(r10));
40632 IkReal x12490=((cj4)*(cj6));
40633 IkReal x12491=((cj0)*(r01));
40634 IkReal x12492=((IkReal(1.00000000000000))*(cj4));
40635 IkReal x12493=((cj0)*(r00));
40636 IkReal x12494=((IkReal(0.374290000000000))*(sj0));
40637 IkReal x12495=((cj0)*(r12));
40638 IkReal x12496=((IkReal(0.374290000000000))*(sj5));
40639 IkReal x12497=((cj4)*(sj6));
40640 IkReal x12498=((IkReal(1.00000000000000))*(cj0));
40641 IkReal x12499=((r02)*(sj0));
40642 IkReal x12500=((IkReal(0.0100000000000000))*(cj5));
40643 IkReal x12501=((r11)*(sj0));
40644 IkReal x12502=((r00)*(sj0)*(sj6));
40645 IkReal x12503=((r00)*(x12490));
40646 IkReal x12504=((sj6)*(x12500));
40647 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
40648 evalcond[1]=((((r21)*(x12497)))+(((r22)*(x12474)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12486)))+(((x12471)*(x12483)))+(((cj6)*(r21)*(x12471))));
40649 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r22)*(x12487)))+(((x12483)*(x12496)))+(((IkReal(0.374290000000000))*(r21)*(x12480)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-0.0100000000000000))*(r21)*(x12475)))+(pz)+(((IkReal(-1.00000000000000))*(x12483)*(x12500))));
40650 evalcond[3]=((((r00)*(sj0)*(x12488)))+(((cj0)*(x12479)))+(((x12476)*(x12480)))+(((IkReal(-1.00000000000000))*(sj5)*(x12472)*(x12489)))+(((IkReal(-1.00000000000000))*(x12480)*(x12481)))+(((IkReal(-1.00000000000000))*(x12477)*(x12482))));
40651 evalcond[4]=((IkReal(-1.00000000000000))+(((x12476)*(x12497)))+(((cj6)*(x12471)*(x12476)))+(((x12471)*(x12502)))+(((x12474)*(x12499)))+(((x12489)*(x12490)))+(((IkReal(-1.00000000000000))*(x12471)*(x12481)*(x12486)))+(((IkReal(-1.00000000000000))*(x12471)*(x12472)*(x12489)))+(((IkReal(-1.00000000000000))*(x12474)*(x12495)))+(((IkReal(-1.00000000000000))*(cj4)*(x12472)*(x12481)))+(((IkReal(-1.00000000000000))*(x12484)*(x12503))));
40652 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x12486)*(x12489)))+(((cj4)*(sj5)*(x12499)))+(((cj4)*(x12475)*(x12476)))+(((IkReal(-1.00000000000000))*(sj5)*(x12492)*(x12495)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((sj4)*(sj6)*(x12481)))+(((IkReal(-1.00000000000000))*(x12475)*(x12481)*(x12492)))+(((IkReal(-1.00000000000000))*(x12472)*(x12485)*(x12489)))+(((IkReal(-1.00000000000000))*(sj4)*(x12472)*(x12476)))+(((r00)*(x12482)*(x12497))));
40653 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x12472)*(x12501)))+(((IkReal(-1.00000000000000))*(cj4)*(x12472)*(x12491)))+(((IkReal(-1.00000000000000))*(x12471)*(x12486)*(x12491)))+(((IkReal(-1.00000000000000))*(cj0)*(x12474)*(x12477)))+(((IkReal(-1.00000000000000))*(x12471)*(x12472)*(x12493)))+(((IkReal(-1.00000000000000))*(r12)*(x12474)*(x12484)))+(((x12473)*(x12490)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12471)*(x12484)))+(((IkReal(-1.00000000000000))*(x12471)*(x12472)*(x12473)))+(((x12490)*(x12493))));
40654 evalcond[7]=((((x12489)*(x12504)))+(((x12478)*(x12479)))+(((IkReal(0.374290000000000))*(x12476)*(x12480)))+(((r00)*(x12488)*(x12494)))+(((IkReal(-0.374290000000000))*(r02)*(x12482)))+(((IkReal(-0.0100000000000000))*(x12475)*(x12476)))+(((IkReal(-1.00000000000000))*(r10)*(x12478)*(x12488)))+(((IkReal(-1.00000000000000))*(py)*(x12498)))+(((IkReal(-1.00000000000000))*(x12487)*(x12499)))+(((x12487)*(x12495)))+(((IkReal(-1.00000000000000))*(r11)*(x12478)*(x12480)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(x12475)*(x12481)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12482))));
40655 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(-0.374290000000000))*(x12473)*(x12488)))+(((x12473)*(x12504)))+(((IkReal(0.0100000000000000))*(x12475)*(x12501)))+(((IkReal(0.0100000000000000))*(x12475)*(x12491)))+(((IkReal(-1.00000000000000))*(r11)*(x12480)*(x12494)))+(((IkReal(-1.00000000000000))*(px)*(x12498)))+(((IkReal(-1.00000000000000))*(r00)*(x12478)*(x12488)))+(((r12)*(sj0)*(x12487)))+(((IkReal(-1.00000000000000))*(py)*(x12484)))+(((cj5)*(r02)*(x12478)))+(((x12479)*(x12494)))+(((IkReal(-1.00000000000000))*(r01)*(x12478)*(x12480)))+(((x12493)*(x12504)))+(((cj0)*(r02)*(x12487))));
40656 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
40657 {
40658 {
40659 IkReal j3array[1], cj3array[1], sj3array[1];
40660 bool j3valid[1]={false};
40661 _nj3 = 1;
40662 IkReal x12505=((IkReal(1.00000000000000))*(r21));
40663 IkReal x12506=((cj4)*(cj5));
40664 IkReal x12507=((r20)*(sj6));
40665 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x12507)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12505)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12506)))+(((x12506)*(x12507)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12505))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x12507)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12505)))+(((cj5)*(r22)))))+IKsqr(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12506)))+(((x12506)*(x12507)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12505)))))-1) <= IKFAST_SINCOS_THRESH )
40666     continue;
40667 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x12507)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12505)))+(((cj5)*(r22)))), ((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12506)))+(((x12506)*(x12507)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12505)))));
40668 sj3array[0]=IKsin(j3array[0]);
40669 cj3array[0]=IKcos(j3array[0]);
40670 if( j3array[0] > IKPI )
40671 {
40672     j3array[0]-=IK2PI;
40673 }
40674 else if( j3array[0] < -IKPI )
40675 {    j3array[0]+=IK2PI;
40676 }
40677 j3valid[0] = true;
40678 for(int ij3 = 0; ij3 < 1; ++ij3)
40679 {
40680 if( !j3valid[ij3] )
40681 {
40682     continue;
40683 }
40684 _ij3[0] = ij3; _ij3[1] = -1;
40685 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40686 {
40687 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40688 {
40689     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40690 }
40691 }
40692 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40693 {
40694 IkReal evalcond[4];
40695 IkReal x12508=IKsin(j3);
40696 IkReal x12509=((IkReal(1.00000000000000))*(cj4));
40697 IkReal x12510=((sj0)*(sj5));
40698 IkReal x12511=((cj0)*(cj5));
40699 IkReal x12512=((cj6)*(r01));
40700 IkReal x12513=((r00)*(sj6));
40701 IkReal x12514=((cj6)*(r11));
40702 IkReal x12515=((cj5)*(sj0));
40703 IkReal x12516=((cj6)*(sj4));
40704 IkReal x12517=((sj4)*(sj6));
40705 IkReal x12518=((cj4)*(cj5));
40706 IkReal x12519=((cj6)*(r21));
40707 IkReal x12520=((r20)*(sj6));
40708 IkReal x12521=((r10)*(sj6));
40709 IkReal x12522=((IkReal(1.00000000000000))*(IKcos(j3)));
40710 IkReal x12523=((IkReal(1.00000000000000))*(cj0)*(sj5));
40711 evalcond[0]=((((sj5)*(x12520)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12519)))+(x12508));
40712 evalcond[1]=((((r20)*(x12516)))+(((x12518)*(x12520)))+(((cj4)*(r22)*(sj5)))+(((x12518)*(x12519)))+(((IkReal(-1.00000000000000))*(x12522)))+(((IkReal(-1.00000000000000))*(r21)*(x12517))));
40713 evalcond[2]=((((IkReal(-1.00000000000000))*(x12512)*(x12523)))+(((r12)*(x12515)))+(((IkReal(-1.00000000000000))*(x12510)*(x12514)))+(((IkReal(-1.00000000000000))*(x12513)*(x12523)))+(((IkReal(-1.00000000000000))*(x12510)*(x12521)))+(((IkReal(-1.00000000000000))*(x12522)))+(((r02)*(x12511))));
40714 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12516)))+(((r11)*(sj0)*(x12517)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12509)))+(((IkReal(-1.00000000000000))*(x12509)*(x12515)*(x12521)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12516)))+(((IkReal(-1.00000000000000))*(x12509)*(x12511)*(x12512)))+(((IkReal(-1.00000000000000))*(x12508)))+(((IkReal(-1.00000000000000))*(x12509)*(x12514)*(x12515)))+(((cj0)*(r01)*(x12517)))+(((IkReal(-1.00000000000000))*(r12)*(x12509)*(x12510)))+(((IkReal(-1.00000000000000))*(x12509)*(x12511)*(x12513))));
40715 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40716 {
40717 continue;
40718 }
40719 }
40720 
40721 {
40722 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40723 vinfos[0].jointtype = 1;
40724 vinfos[0].foffset = j0;
40725 vinfos[0].indices[0] = _ij0[0];
40726 vinfos[0].indices[1] = _ij0[1];
40727 vinfos[0].maxsolutions = _nj0;
40728 vinfos[1].jointtype = 1;
40729 vinfos[1].foffset = j1;
40730 vinfos[1].indices[0] = _ij1[0];
40731 vinfos[1].indices[1] = _ij1[1];
40732 vinfos[1].maxsolutions = _nj1;
40733 vinfos[2].jointtype = 1;
40734 vinfos[2].foffset = j2;
40735 vinfos[2].indices[0] = _ij2[0];
40736 vinfos[2].indices[1] = _ij2[1];
40737 vinfos[2].maxsolutions = _nj2;
40738 vinfos[3].jointtype = 1;
40739 vinfos[3].foffset = j3;
40740 vinfos[3].indices[0] = _ij3[0];
40741 vinfos[3].indices[1] = _ij3[1];
40742 vinfos[3].maxsolutions = _nj3;
40743 vinfos[4].jointtype = 1;
40744 vinfos[4].foffset = j4;
40745 vinfos[4].indices[0] = _ij4[0];
40746 vinfos[4].indices[1] = _ij4[1];
40747 vinfos[4].maxsolutions = _nj4;
40748 vinfos[5].jointtype = 1;
40749 vinfos[5].foffset = j5;
40750 vinfos[5].indices[0] = _ij5[0];
40751 vinfos[5].indices[1] = _ij5[1];
40752 vinfos[5].maxsolutions = _nj5;
40753 vinfos[6].jointtype = 1;
40754 vinfos[6].foffset = j6;
40755 vinfos[6].indices[0] = _ij6[0];
40756 vinfos[6].indices[1] = _ij6[1];
40757 vinfos[6].maxsolutions = _nj6;
40758 std::vector<int> vfree(0);
40759 solutions.AddSolution(vinfos,vfree);
40760 }
40761 }
40762 }
40763 
40764 } else
40765 {
40766 IkReal x12524=((IkReal(1.00000000000000))*(cj0));
40767 IkReal x12525=((cj4)*(sj6));
40768 IkReal x12526=((sj0)*(sj4));
40769 IkReal x12527=((cj5)*(sj6));
40770 IkReal x12528=((sj4)*(sj5));
40771 IkReal x12529=((r12)*(sj5));
40772 IkReal x12530=((IkReal(0.374290000000000))*(cj5));
40773 IkReal x12531=((r02)*(sj0));
40774 IkReal x12532=((r20)*(sj4));
40775 IkReal x12533=((IkReal(1.00000000000000))*(sj0));
40776 IkReal x12534=((IkReal(1.00000000000000))*(cj5));
40777 IkReal x12535=((cj0)*(r10));
40778 IkReal x12536=((cj4)*(cj6));
40779 IkReal x12537=((r00)*(sj0));
40780 IkReal x12538=((cj6)*(r21));
40781 IkReal x12539=((IkReal(0.374290000000000))*(sj5));
40782 IkReal x12540=((cj0)*(r00));
40783 IkReal x12541=((IkReal(0.0100000000000000))*(sj5));
40784 IkReal x12542=((cj0)*(r02));
40785 IkReal x12543=((cj5)*(sj4));
40786 IkReal x12544=((cj6)*(r01));
40787 IkReal x12545=((cj6)*(r11));
40788 IkReal x12546=((r01)*(sj0));
40789 IkReal x12547=((r10)*(sj0));
40790 IkReal x12548=((IkReal(0.0100000000000000))*(cj5)*(cj6));
40791 IkReal x12549=((sj6)*(x12539));
40792 IkReal x12550=((cj0)*(cj6)*(x12539));
40793 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
40794 evalcond[1]=((((sj5)*(x12538)))+(((IkReal(-1.00000000000000))*(r22)*(x12534)))+(((r20)*(sj5)*(sj6))));
40795 evalcond[2]=((IkReal(-1.00000000000000))+(((r22)*(x12528)))+(((x12527)*(x12532)))+(((r21)*(x12525)))+(((x12538)*(x12543)))+(((IkReal(-1.00000000000000))*(r20)*(x12536))));
40796 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x12530)))+(((r20)*(x12549)))+(((IkReal(-1.00000000000000))*(r22)*(x12541)))+(((IkReal(-0.0100000000000000))*(cj5)*(x12538)))+(pz)+(((IkReal(-0.0100000000000000))*(r20)*(x12527)))+(((x12538)*(x12539))));
40797 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x12532)))+(((cj4)*(r22)*(sj5)))+(((cj5)*(r21)*(x12536)))+(((cj5)*(r20)*(x12525))));
40798 evalcond[5]=((((IkReal(-1.00000000000000))*(x12524)*(x12543)*(x12545)))+(((IkReal(-1.00000000000000))*(r00)*(x12533)*(x12536)))+(((x12525)*(x12546)))+(((x12535)*(x12536)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12524)*(x12527)))+(((cj5)*(x12526)*(x12544)))+(((r00)*(x12526)*(x12527)))+(((IkReal(-1.00000000000000))*(r11)*(x12524)*(x12525)))+(((IkReal(-1.00000000000000))*(r12)*(x12524)*(x12528)))+(((r02)*(sj5)*(x12526))));
40799 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x12524)*(x12528)))+(((IkReal(-1.00000000000000))*(r11)*(x12525)*(x12533)))+(((x12536)*(x12540)))+(((IkReal(-1.00000000000000))*(r10)*(x12526)*(x12527)))+(((IkReal(-1.00000000000000))*(r01)*(x12524)*(x12525)))+(((x12536)*(x12547)))+(((IkReal(-1.00000000000000))*(x12526)*(x12529)))+(((IkReal(-1.00000000000000))*(x12524)*(x12543)*(x12544)))+(((IkReal(-1.00000000000000))*(x12526)*(x12534)*(x12545)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12524)*(x12527))));
40800 evalcond[7]=((IkReal(0.0690000000000000))+(((sj0)*(x12539)*(x12544)))+(((x12537)*(x12549)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12545)))+(((cj0)*(r12)*(x12530)))+(((IkReal(-1.00000000000000))*(py)*(x12524)))+(((IkReal(0.0100000000000000))*(x12527)*(x12535)))+(((IkReal(-1.00000000000000))*(x12531)*(x12541)))+(((IkReal(-0.0100000000000000))*(x12527)*(x12537)))+(((IkReal(-1.00000000000000))*(x12530)*(x12531)))+(((IkReal(-1.00000000000000))*(x12535)*(x12549)))+(((IkReal(-1.00000000000000))*(cj0)*(x12539)*(x12545)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x12544)))+(((IkReal(0.0100000000000000))*(cj0)*(x12529)))+(((px)*(sj0))));
40801 evalcond[8]=((IkReal(0.433420000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12544)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x12545)))+(((r12)*(sj0)*(x12530)))+(((IkReal(0.0100000000000000))*(x12527)*(x12540)))+(((IkReal(-1.00000000000000))*(x12540)*(x12549)))+(((x12530)*(x12542)))+(((IkReal(-1.00000000000000))*(sj0)*(x12539)*(x12545)))+(((IkReal(-1.00000000000000))*(cj0)*(x12539)*(x12544)))+(((x12541)*(x12542)))+(((IkReal(-1.00000000000000))*(x12547)*(x12549)))+(((IkReal(0.0100000000000000))*(sj0)*(x12529)))+(((IkReal(-1.00000000000000))*(py)*(x12533)))+(((IkReal(-1.00000000000000))*(px)*(x12524)))+(((IkReal(0.0100000000000000))*(x12527)*(x12547))));
40802 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
40803 {
40804 {
40805 IkReal j3array[1], cj3array[1], sj3array[1];
40806 bool j3valid[1]={false};
40807 _nj3 = 1;
40808 IkReal x12551=((cj0)*(cj5));
40809 IkReal x12552=((IkReal(1.00000000000000))*(cj0));
40810 IkReal x12553=((cj6)*(r11));
40811 IkReal x12554=((r10)*(sj6));
40812 IkReal x12555=((cj5)*(sj0));
40813 IkReal x12556=((r00)*(sj5)*(sj6));
40814 IkReal x12557=((cj6)*(r01)*(sj5));
40815 IkReal x12558=((IkReal(1.00000000000000))*(sj0)*(sj5));
40816 if( IKabs(((((sj0)*(x12557)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12553)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12554)))+(((sj0)*(x12556)))+(((IkReal(-1.00000000000000))*(r02)*(x12555)))+(((r12)*(x12551))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r12)*(x12555)))+(((r02)*(x12551)))+(((IkReal(-1.00000000000000))*(x12552)*(x12557)))+(((IkReal(-1.00000000000000))*(x12553)*(x12558)))+(((IkReal(-1.00000000000000))*(x12552)*(x12556)))+(((IkReal(-1.00000000000000))*(x12554)*(x12558))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x12557)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12553)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12554)))+(((sj0)*(x12556)))+(((IkReal(-1.00000000000000))*(r02)*(x12555)))+(((r12)*(x12551)))))+IKsqr(((((r12)*(x12555)))+(((r02)*(x12551)))+(((IkReal(-1.00000000000000))*(x12552)*(x12557)))+(((IkReal(-1.00000000000000))*(x12553)*(x12558)))+(((IkReal(-1.00000000000000))*(x12552)*(x12556)))+(((IkReal(-1.00000000000000))*(x12554)*(x12558)))))-1) <= IKFAST_SINCOS_THRESH )
40817     continue;
40818 j3array[0]=IKatan2(((((sj0)*(x12557)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12553)))+(((IkReal(-1.00000000000000))*(sj5)*(x12552)*(x12554)))+(((sj0)*(x12556)))+(((IkReal(-1.00000000000000))*(r02)*(x12555)))+(((r12)*(x12551)))), ((((r12)*(x12555)))+(((r02)*(x12551)))+(((IkReal(-1.00000000000000))*(x12552)*(x12557)))+(((IkReal(-1.00000000000000))*(x12553)*(x12558)))+(((IkReal(-1.00000000000000))*(x12552)*(x12556)))+(((IkReal(-1.00000000000000))*(x12554)*(x12558)))));
40819 sj3array[0]=IKsin(j3array[0]);
40820 cj3array[0]=IKcos(j3array[0]);
40821 if( j3array[0] > IKPI )
40822 {
40823     j3array[0]-=IK2PI;
40824 }
40825 else if( j3array[0] < -IKPI )
40826 {    j3array[0]+=IK2PI;
40827 }
40828 j3valid[0] = true;
40829 for(int ij3 = 0; ij3 < 1; ++ij3)
40830 {
40831 if( !j3valid[ij3] )
40832 {
40833     continue;
40834 }
40835 _ij3[0] = ij3; _ij3[1] = -1;
40836 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40837 {
40838 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40839 {
40840     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40841 }
40842 }
40843 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40844 {
40845 IkReal evalcond[4];
40846 IkReal x12559=IKcos(j3);
40847 IkReal x12560=((sj0)*(sj5));
40848 IkReal x12561=((r00)*(sj6));
40849 IkReal x12562=((cj6)*(sj0));
40850 IkReal x12563=((IkReal(1.00000000000000))*(cj4));
40851 IkReal x12564=((r00)*(sj4));
40852 IkReal x12565=((cj0)*(cj5));
40853 IkReal x12566=((cj5)*(sj0));
40854 IkReal x12567=((cj6)*(r11));
40855 IkReal x12568=((r10)*(sj6));
40856 IkReal x12569=((cj0)*(sj5));
40857 IkReal x12570=((r10)*(sj4));
40858 IkReal x12571=((IkReal(1.00000000000000))*(IKsin(j3)));
40859 IkReal x12572=((cj4)*(cj5)*(r01));
40860 IkReal x12573=((IkReal(1.00000000000000))*(cj0)*(cj6));
40861 IkReal x12574=((cj0)*(sj4)*(sj6));
40862 IkReal x12575=((sj0)*(sj4)*(sj6));
40863 evalcond[0]=((((IkReal(-1.00000000000000))*(x12567)*(x12569)))+(((x12560)*(x12561)))+(((cj6)*(r01)*(x12560)))+(((IkReal(-1.00000000000000))*(r02)*(x12566)))+(((IkReal(-1.00000000000000))*(x12568)*(x12569)))+(((IkReal(-1.00000000000000))*(x12571)))+(((r12)*(x12565))));
40864 evalcond[1]=((((r02)*(x12565)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x12569)))+(((IkReal(-1.00000000000000))*(x12561)*(x12569)))+(((r12)*(x12566)))+(((IkReal(-1.00000000000000))*(x12560)*(x12568)))+(((IkReal(-1.00000000000000))*(x12560)*(x12567)))+(((IkReal(-1.00000000000000))*(x12559))));
40865 evalcond[2]=((x12559)+(((IkReal(-1.00000000000000))*(x12563)*(x12565)*(x12567)))+(((x12562)*(x12564)))+(((cj4)*(x12561)*(x12566)))+(((IkReal(-1.00000000000000))*(x12563)*(x12565)*(x12568)))+(((x12562)*(x12572)))+(((IkReal(-1.00000000000000))*(x12570)*(x12573)))+(((r11)*(x12574)))+(((IkReal(-1.00000000000000))*(r01)*(x12575)))+(((cj4)*(r02)*(x12560)))+(((IkReal(-1.00000000000000))*(r12)*(x12563)*(x12569))));
40866 evalcond[3]=((((r01)*(x12574)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12562)*(x12563)))+(((IkReal(-1.00000000000000))*(x12561)*(x12563)*(x12565)))+(((IkReal(-1.00000000000000))*(r12)*(x12560)*(x12563)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x12563)*(x12565)))+(((IkReal(-1.00000000000000))*(x12563)*(x12566)*(x12568)))+(((IkReal(-1.00000000000000))*(x12562)*(x12570)))+(((IkReal(-1.00000000000000))*(r02)*(x12563)*(x12569)))+(((IkReal(-1.00000000000000))*(x12571)))+(((IkReal(-1.00000000000000))*(x12564)*(x12573)))+(((r11)*(x12575))));
40867 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
40868 {
40869 continue;
40870 }
40871 }
40872 
40873 {
40874 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
40875 vinfos[0].jointtype = 1;
40876 vinfos[0].foffset = j0;
40877 vinfos[0].indices[0] = _ij0[0];
40878 vinfos[0].indices[1] = _ij0[1];
40879 vinfos[0].maxsolutions = _nj0;
40880 vinfos[1].jointtype = 1;
40881 vinfos[1].foffset = j1;
40882 vinfos[1].indices[0] = _ij1[0];
40883 vinfos[1].indices[1] = _ij1[1];
40884 vinfos[1].maxsolutions = _nj1;
40885 vinfos[2].jointtype = 1;
40886 vinfos[2].foffset = j2;
40887 vinfos[2].indices[0] = _ij2[0];
40888 vinfos[2].indices[1] = _ij2[1];
40889 vinfos[2].maxsolutions = _nj2;
40890 vinfos[3].jointtype = 1;
40891 vinfos[3].foffset = j3;
40892 vinfos[3].indices[0] = _ij3[0];
40893 vinfos[3].indices[1] = _ij3[1];
40894 vinfos[3].maxsolutions = _nj3;
40895 vinfos[4].jointtype = 1;
40896 vinfos[4].foffset = j4;
40897 vinfos[4].indices[0] = _ij4[0];
40898 vinfos[4].indices[1] = _ij4[1];
40899 vinfos[4].maxsolutions = _nj4;
40900 vinfos[5].jointtype = 1;
40901 vinfos[5].foffset = j5;
40902 vinfos[5].indices[0] = _ij5[0];
40903 vinfos[5].indices[1] = _ij5[1];
40904 vinfos[5].maxsolutions = _nj5;
40905 vinfos[6].jointtype = 1;
40906 vinfos[6].foffset = j6;
40907 vinfos[6].indices[0] = _ij6[0];
40908 vinfos[6].indices[1] = _ij6[1];
40909 vinfos[6].maxsolutions = _nj6;
40910 std::vector<int> vfree(0);
40911 solutions.AddSolution(vinfos,vfree);
40912 }
40913 }
40914 }
40915 
40916 } else
40917 {
40918 IkReal x12576=((IkReal(1.00000000000000))*(cj0));
40919 IkReal x12577=((cj4)*(sj6));
40920 IkReal x12578=((sj0)*(sj4));
40921 IkReal x12579=((cj5)*(sj6));
40922 IkReal x12580=((sj4)*(sj5));
40923 IkReal x12581=((r12)*(sj5));
40924 IkReal x12582=((IkReal(0.374290000000000))*(cj5));
40925 IkReal x12583=((r02)*(sj0));
40926 IkReal x12584=((r20)*(sj4));
40927 IkReal x12585=((IkReal(1.00000000000000))*(sj0));
40928 IkReal x12586=((IkReal(1.00000000000000))*(cj5));
40929 IkReal x12587=((cj0)*(r10));
40930 IkReal x12588=((cj4)*(cj6));
40931 IkReal x12589=((r00)*(sj0));
40932 IkReal x12590=((cj6)*(r21));
40933 IkReal x12591=((IkReal(0.374290000000000))*(sj5));
40934 IkReal x12592=((cj0)*(r00));
40935 IkReal x12593=((IkReal(0.0100000000000000))*(sj5));
40936 IkReal x12594=((cj0)*(r02));
40937 IkReal x12595=((cj5)*(sj4));
40938 IkReal x12596=((cj6)*(r01));
40939 IkReal x12597=((cj6)*(r11));
40940 IkReal x12598=((r01)*(sj0));
40941 IkReal x12599=((r10)*(sj0));
40942 IkReal x12600=((IkReal(0.0100000000000000))*(cj5)*(cj6));
40943 IkReal x12601=((sj6)*(x12591));
40944 IkReal x12602=((cj0)*(cj6)*(x12591));
40945 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
40946 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x12586)))+(((sj5)*(x12590)))+(((r20)*(sj5)*(sj6))));
40947 evalcond[2]=((IkReal(1.00000000000000))+(((x12579)*(x12584)))+(((r21)*(x12577)))+(((r22)*(x12580)))+(((x12590)*(x12595)))+(((IkReal(-1.00000000000000))*(r20)*(x12588))));
40948 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x12593)))+(((IkReal(-0.0100000000000000))*(cj5)*(x12590)))+(((IkReal(-0.0100000000000000))*(r20)*(x12579)))+(((x12590)*(x12591)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x12582)))+(((r20)*(x12601))));
40949 evalcond[4]=((((cj5)*(r20)*(x12577)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(x12584)))+(((cj5)*(r21)*(x12588)))+(((cj4)*(r22)*(sj5))));
40950 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12576)*(x12579)))+(((IkReal(-1.00000000000000))*(r00)*(x12585)*(x12588)))+(((r02)*(sj5)*(x12578)))+(((r00)*(x12578)*(x12579)))+(((cj5)*(x12578)*(x12596)))+(((IkReal(-1.00000000000000))*(x12576)*(x12595)*(x12597)))+(((x12587)*(x12588)))+(((IkReal(-1.00000000000000))*(r12)*(x12576)*(x12580)))+(((IkReal(-1.00000000000000))*(r11)*(x12576)*(x12577)))+(((x12577)*(x12598))));
40951 evalcond[6]=((((IkReal(-1.00000000000000))*(x12576)*(x12595)*(x12596)))+(((IkReal(-1.00000000000000))*(r11)*(x12577)*(x12585)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12576)*(x12579)))+(((x12588)*(x12599)))+(((IkReal(-1.00000000000000))*(r01)*(x12576)*(x12577)))+(((IkReal(-1.00000000000000))*(x12578)*(x12581)))+(((IkReal(-1.00000000000000))*(x12578)*(x12586)*(x12597)))+(((x12588)*(x12592)))+(((IkReal(-1.00000000000000))*(r10)*(x12578)*(x12579)))+(((IkReal(-1.00000000000000))*(r02)*(x12576)*(x12580))));
40952 evalcond[7]=((IkReal(-0.0690000000000000))+(((IkReal(-0.0100000000000000))*(x12579)*(x12589)))+(((x12589)*(x12601)))+(((IkReal(-1.00000000000000))*(x12582)*(x12583)))+(((IkReal(-1.00000000000000))*(cj0)*(x12591)*(x12597)))+(((IkReal(-1.00000000000000))*(x12583)*(x12593)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12597)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x12596)))+(((sj0)*(x12591)*(x12596)))+(((IkReal(-1.00000000000000))*(x12587)*(x12601)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(x12579)*(x12587)))+(((cj0)*(r12)*(x12582)))+(((IkReal(-1.00000000000000))*(py)*(x12576)))+(((IkReal(0.0100000000000000))*(cj0)*(x12581))));
40953 evalcond[8]=((IkReal(0.433420000000000))+(((x12582)*(x12594)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x12597)))+(((x12593)*(x12594)))+(((IkReal(-1.00000000000000))*(sj0)*(x12591)*(x12597)))+(((IkReal(-1.00000000000000))*(px)*(x12576)))+(((r12)*(sj0)*(x12582)))+(((IkReal(-1.00000000000000))*(cj0)*(x12591)*(x12596)))+(((IkReal(-1.00000000000000))*(py)*(x12585)))+(((IkReal(0.0100000000000000))*(sj0)*(x12581)))+(((IkReal(0.0100000000000000))*(x12579)*(x12592)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12596)))+(((IkReal(-1.00000000000000))*(x12599)*(x12601)))+(((IkReal(-1.00000000000000))*(x12592)*(x12601)))+(((IkReal(0.0100000000000000))*(x12579)*(x12599))));
40954 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
40955 {
40956 {
40957 IkReal j3array[1], cj3array[1], sj3array[1];
40958 bool j3valid[1]={false};
40959 _nj3 = 1;
40960 IkReal x12603=((cj5)*(r02));
40961 IkReal x12604=((cj0)*(sj5));
40962 IkReal x12605=((r10)*(sj6));
40963 IkReal x12606=((IkReal(1.00000000000000))*(cj6));
40964 IkReal x12607=((sj0)*(sj5));
40965 IkReal x12608=((cj5)*(r12));
40966 IkReal x12609=((IkReal(1.00000000000000))*(r00)*(sj6));
40967 if( IKabs(((((x12604)*(x12605)))+(((IkReal(-1.00000000000000))*(x12607)*(x12609)))+(((IkReal(-1.00000000000000))*(cj0)*(x12608)))+(((cj6)*(r11)*(x12604)))+(((sj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r01)*(x12606)*(x12607))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r11)*(x12606)*(x12607)))+(((IkReal(-1.00000000000000))*(x12604)*(x12609)))+(((sj0)*(x12608)))+(((IkReal(-1.00000000000000))*(r01)*(x12604)*(x12606)))+(((IkReal(-1.00000000000000))*(x12605)*(x12607))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x12604)*(x12605)))+(((IkReal(-1.00000000000000))*(x12607)*(x12609)))+(((IkReal(-1.00000000000000))*(cj0)*(x12608)))+(((cj6)*(r11)*(x12604)))+(((sj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r01)*(x12606)*(x12607)))))+IKsqr(((((cj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r11)*(x12606)*(x12607)))+(((IkReal(-1.00000000000000))*(x12604)*(x12609)))+(((sj0)*(x12608)))+(((IkReal(-1.00000000000000))*(r01)*(x12604)*(x12606)))+(((IkReal(-1.00000000000000))*(x12605)*(x12607)))))-1) <= IKFAST_SINCOS_THRESH )
40968     continue;
40969 j3array[0]=IKatan2(((((x12604)*(x12605)))+(((IkReal(-1.00000000000000))*(x12607)*(x12609)))+(((IkReal(-1.00000000000000))*(cj0)*(x12608)))+(((cj6)*(r11)*(x12604)))+(((sj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r01)*(x12606)*(x12607)))), ((((cj0)*(x12603)))+(((IkReal(-1.00000000000000))*(r11)*(x12606)*(x12607)))+(((IkReal(-1.00000000000000))*(x12604)*(x12609)))+(((sj0)*(x12608)))+(((IkReal(-1.00000000000000))*(r01)*(x12604)*(x12606)))+(((IkReal(-1.00000000000000))*(x12605)*(x12607)))));
40970 sj3array[0]=IKsin(j3array[0]);
40971 cj3array[0]=IKcos(j3array[0]);
40972 if( j3array[0] > IKPI )
40973 {
40974     j3array[0]-=IK2PI;
40975 }
40976 else if( j3array[0] < -IKPI )
40977 {    j3array[0]+=IK2PI;
40978 }
40979 j3valid[0] = true;
40980 for(int ij3 = 0; ij3 < 1; ++ij3)
40981 {
40982 if( !j3valid[ij3] )
40983 {
40984     continue;
40985 }
40986 _ij3[0] = ij3; _ij3[1] = -1;
40987 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
40988 {
40989 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
40990 {
40991     j3valid[iij3]=false; _ij3[1] = iij3; break; 
40992 }
40993 }
40994 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
40995 {
40996 IkReal evalcond[4];
40997 IkReal x12610=IKsin(j3);
40998 IkReal x12611=((sj0)*(sj5));
40999 IkReal x12612=((r00)*(sj6));
41000 IkReal x12613=((IkReal(1.00000000000000))*(cj4));
41001 IkReal x12614=((cj6)*(sj0));
41002 IkReal x12615=((r00)*(sj4));
41003 IkReal x12616=((cj0)*(cj5));
41004 IkReal x12617=((cj6)*(r01));
41005 IkReal x12618=((cj5)*(sj0));
41006 IkReal x12619=((cj0)*(sj5));
41007 IkReal x12620=((cj6)*(r11));
41008 IkReal x12621=((r10)*(sj6));
41009 IkReal x12622=((r10)*(sj4));
41010 IkReal x12623=((IkReal(1.00000000000000))*(IKcos(j3)));
41011 IkReal x12624=((cj0)*(sj4)*(sj6));
41012 IkReal x12625=((sj0)*(sj4)*(sj6));
41013 IkReal x12626=((IkReal(1.00000000000000))*(cj0)*(cj6));
41014 evalcond[0]=((((IkReal(-1.00000000000000))*(x12619)*(x12621)))+(((IkReal(-1.00000000000000))*(r02)*(x12618)))+(((x12611)*(x12612)))+(((IkReal(-1.00000000000000))*(x12619)*(x12620)))+(((x12611)*(x12617)))+(((r12)*(x12616)))+(x12610));
41015 evalcond[1]=((((IkReal(-1.00000000000000))*(x12617)*(x12619)))+(((r12)*(x12618)))+(((IkReal(-1.00000000000000))*(x12612)*(x12619)))+(((IkReal(-1.00000000000000))*(x12623)))+(((r02)*(x12616)))+(((IkReal(-1.00000000000000))*(x12611)*(x12620)))+(((IkReal(-1.00000000000000))*(x12611)*(x12621))));
41016 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x12613)*(x12619)))+(((IkReal(-1.00000000000000))*(x12622)*(x12626)))+(((IkReal(-1.00000000000000))*(x12623)))+(((x12614)*(x12615)))+(((r11)*(x12624)))+(((cj4)*(cj5)*(r01)*(x12614)))+(((cj4)*(x12612)*(x12618)))+(((IkReal(-1.00000000000000))*(r01)*(x12625)))+(((cj4)*(r02)*(x12611)))+(((IkReal(-1.00000000000000))*(x12613)*(x12616)*(x12620)))+(((IkReal(-1.00000000000000))*(x12613)*(x12616)*(x12621))));
41017 evalcond[3]=((((IkReal(-1.00000000000000))*(x12615)*(x12626)))+(((IkReal(-1.00000000000000))*(x12614)*(x12622)))+(((IkReal(-1.00000000000000))*(x12613)*(x12618)*(x12621)))+(((IkReal(-1.00000000000000))*(x12610)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12613)*(x12614)))+(((IkReal(-1.00000000000000))*(x12613)*(x12616)*(x12617)))+(((IkReal(-1.00000000000000))*(x12612)*(x12613)*(x12616)))+(((r11)*(x12625)))+(((IkReal(-1.00000000000000))*(r12)*(x12611)*(x12613)))+(((r01)*(x12624)))+(((IkReal(-1.00000000000000))*(r02)*(x12613)*(x12619))));
41018 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
41019 {
41020 continue;
41021 }
41022 }
41023 
41024 {
41025 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41026 vinfos[0].jointtype = 1;
41027 vinfos[0].foffset = j0;
41028 vinfos[0].indices[0] = _ij0[0];
41029 vinfos[0].indices[1] = _ij0[1];
41030 vinfos[0].maxsolutions = _nj0;
41031 vinfos[1].jointtype = 1;
41032 vinfos[1].foffset = j1;
41033 vinfos[1].indices[0] = _ij1[0];
41034 vinfos[1].indices[1] = _ij1[1];
41035 vinfos[1].maxsolutions = _nj1;
41036 vinfos[2].jointtype = 1;
41037 vinfos[2].foffset = j2;
41038 vinfos[2].indices[0] = _ij2[0];
41039 vinfos[2].indices[1] = _ij2[1];
41040 vinfos[2].maxsolutions = _nj2;
41041 vinfos[3].jointtype = 1;
41042 vinfos[3].foffset = j3;
41043 vinfos[3].indices[0] = _ij3[0];
41044 vinfos[3].indices[1] = _ij3[1];
41045 vinfos[3].maxsolutions = _nj3;
41046 vinfos[4].jointtype = 1;
41047 vinfos[4].foffset = j4;
41048 vinfos[4].indices[0] = _ij4[0];
41049 vinfos[4].indices[1] = _ij4[1];
41050 vinfos[4].maxsolutions = _nj4;
41051 vinfos[5].jointtype = 1;
41052 vinfos[5].foffset = j5;
41053 vinfos[5].indices[0] = _ij5[0];
41054 vinfos[5].indices[1] = _ij5[1];
41055 vinfos[5].maxsolutions = _nj5;
41056 vinfos[6].jointtype = 1;
41057 vinfos[6].foffset = j6;
41058 vinfos[6].indices[0] = _ij6[0];
41059 vinfos[6].indices[1] = _ij6[1];
41060 vinfos[6].maxsolutions = _nj6;
41061 std::vector<int> vfree(0);
41062 solutions.AddSolution(vinfos,vfree);
41063 }
41064 }
41065 }
41066 
41067 } else
41068 {
41069 if( 1 )
41070 {
41071 continue;
41072 
41073 } else
41074 {
41075 }
41076 }
41077 }
41078 }
41079 }
41080 }
41081 
41082 } else
41083 {
41084 {
41085 IkReal j3array[1], cj3array[1], sj3array[1];
41086 bool j3valid[1]={false};
41087 _nj3 = 1;
41088 IkReal x12627=((cj0)*(cj5));
41089 IkReal x12628=((IkReal(1.00000000000000))*(cj0));
41090 IkReal x12629=((cj6)*(r11));
41091 IkReal x12630=((r10)*(sj6));
41092 IkReal x12631=((cj5)*(sj0));
41093 IkReal x12632=((r00)*(sj5)*(sj6));
41094 IkReal x12633=((cj6)*(r01)*(sj5));
41095 IkReal x12634=((IkReal(1.00000000000000))*(sj0)*(sj5));
41096 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x12627)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12629)))+(((IkReal(-1.00000000000000))*(r02)*(x12631)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12630)))+(((sj0)*(x12632)))+(((sj0)*(x12633))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r12)*(x12631)))+(((IkReal(-1.00000000000000))*(x12630)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12633)))+(((IkReal(-1.00000000000000))*(x12629)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12632)))+(((r02)*(x12627))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x12627)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12629)))+(((IkReal(-1.00000000000000))*(r02)*(x12631)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12630)))+(((sj0)*(x12632)))+(((sj0)*(x12633)))))))+IKsqr(((((r12)*(x12631)))+(((IkReal(-1.00000000000000))*(x12630)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12633)))+(((IkReal(-1.00000000000000))*(x12629)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12632)))+(((r02)*(x12627)))))-1) <= IKFAST_SINCOS_THRESH )
41097     continue;
41098 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((r12)*(x12627)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12629)))+(((IkReal(-1.00000000000000))*(r02)*(x12631)))+(((IkReal(-1.00000000000000))*(sj5)*(x12628)*(x12630)))+(((sj0)*(x12632)))+(((sj0)*(x12633)))))), ((((r12)*(x12631)))+(((IkReal(-1.00000000000000))*(x12630)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12633)))+(((IkReal(-1.00000000000000))*(x12629)*(x12634)))+(((IkReal(-1.00000000000000))*(x12628)*(x12632)))+(((r02)*(x12627)))));
41099 sj3array[0]=IKsin(j3array[0]);
41100 cj3array[0]=IKcos(j3array[0]);
41101 if( j3array[0] > IKPI )
41102 {
41103     j3array[0]-=IK2PI;
41104 }
41105 else if( j3array[0] < -IKPI )
41106 {    j3array[0]+=IK2PI;
41107 }
41108 j3valid[0] = true;
41109 for(int ij3 = 0; ij3 < 1; ++ij3)
41110 {
41111 if( !j3valid[ij3] )
41112 {
41113     continue;
41114 }
41115 _ij3[0] = ij3; _ij3[1] = -1;
41116 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41117 {
41118 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41119 {
41120     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41121 }
41122 }
41123 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41124 {
41125 IkReal evalcond[6];
41126 IkReal x12635=IKsin(j3);
41127 IkReal x12636=IKcos(j3);
41128 IkReal x12637=((sj0)*(sj5));
41129 IkReal x12638=((r00)*(sj6));
41130 IkReal x12639=((IkReal(1.00000000000000))*(cj4));
41131 IkReal x12640=((cj6)*(r01));
41132 IkReal x12641=((cj0)*(cj5));
41133 IkReal x12642=((cj5)*(sj0));
41134 IkReal x12643=((cj6)*(r11));
41135 IkReal x12644=((cj0)*(sj5));
41136 IkReal x12645=((cj6)*(sj4));
41137 IkReal x12646=((cj4)*(cj5));
41138 IkReal x12647=((cj6)*(r21));
41139 IkReal x12648=((r20)*(sj6));
41140 IkReal x12649=((r10)*(sj6));
41141 IkReal x12650=((IkReal(1.00000000000000))*(cj0));
41142 IkReal x12651=((IkReal(1.00000000000000))*(x12635));
41143 IkReal x12652=((cj0)*(sj4)*(sj6));
41144 IkReal x12653=((sj0)*(sj4)*(sj6));
41145 evalcond[0]=((((sj5)*(x12648)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x12651)))+(((sj5)*(x12647))));
41146 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12646)*(x12647)))+(((cj4)*(r22)*(sj5)))+(((x12646)*(x12648)))+(((cj2)*(x12636)))+(((r20)*(x12645))));
41147 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x12651)))+(((IkReal(-1.00000000000000))*(r02)*(x12642)))+(((x12637)*(x12640)))+(((x12637)*(x12638)))+(((r12)*(x12641)))+(((IkReal(-1.00000000000000))*(x12644)*(x12649)))+(((IkReal(-1.00000000000000))*(x12643)*(x12644))));
41148 evalcond[3]=((((IkReal(-1.00000000000000))*(x12636)))+(((r02)*(x12641)))+(((r12)*(x12642)))+(((IkReal(-1.00000000000000))*(x12637)*(x12649)))+(((IkReal(-1.00000000000000))*(x12638)*(x12644)))+(((IkReal(-1.00000000000000))*(x12640)*(x12644)))+(((IkReal(-1.00000000000000))*(x12637)*(x12643))));
41149 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x12653)))+(((sj2)*(x12636)))+(((cj4)*(r02)*(x12637)))+(((cj4)*(x12638)*(x12642)))+(((IkReal(-1.00000000000000))*(r12)*(x12639)*(x12644)))+(((r11)*(x12652)))+(((IkReal(-1.00000000000000))*(x12639)*(x12641)*(x12649)))+(((cj4)*(x12640)*(x12642)))+(((IkReal(-1.00000000000000))*(r10)*(x12645)*(x12650)))+(((IkReal(-1.00000000000000))*(x12639)*(x12641)*(x12643)))+(((r00)*(sj0)*(x12645))));
41150 evalcond[5]=((((IkReal(-1.00000000000000))*(x12639)*(x12640)*(x12641)))+(((IkReal(-1.00000000000000))*(x12639)*(x12642)*(x12649)))+(((IkReal(-1.00000000000000))*(x12651)))+(((r01)*(x12652)))+(((IkReal(-1.00000000000000))*(x12638)*(x12639)*(x12641)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12645)))+(((IkReal(-1.00000000000000))*(r00)*(x12645)*(x12650)))+(((IkReal(-1.00000000000000))*(r02)*(x12639)*(x12644)))+(((r11)*(x12653)))+(((IkReal(-1.00000000000000))*(r12)*(x12637)*(x12639)))+(((IkReal(-1.00000000000000))*(x12639)*(x12642)*(x12643))));
41151 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
41152 {
41153 continue;
41154 }
41155 }
41156 
41157 {
41158 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41159 vinfos[0].jointtype = 1;
41160 vinfos[0].foffset = j0;
41161 vinfos[0].indices[0] = _ij0[0];
41162 vinfos[0].indices[1] = _ij0[1];
41163 vinfos[0].maxsolutions = _nj0;
41164 vinfos[1].jointtype = 1;
41165 vinfos[1].foffset = j1;
41166 vinfos[1].indices[0] = _ij1[0];
41167 vinfos[1].indices[1] = _ij1[1];
41168 vinfos[1].maxsolutions = _nj1;
41169 vinfos[2].jointtype = 1;
41170 vinfos[2].foffset = j2;
41171 vinfos[2].indices[0] = _ij2[0];
41172 vinfos[2].indices[1] = _ij2[1];
41173 vinfos[2].maxsolutions = _nj2;
41174 vinfos[3].jointtype = 1;
41175 vinfos[3].foffset = j3;
41176 vinfos[3].indices[0] = _ij3[0];
41177 vinfos[3].indices[1] = _ij3[1];
41178 vinfos[3].maxsolutions = _nj3;
41179 vinfos[4].jointtype = 1;
41180 vinfos[4].foffset = j4;
41181 vinfos[4].indices[0] = _ij4[0];
41182 vinfos[4].indices[1] = _ij4[1];
41183 vinfos[4].maxsolutions = _nj4;
41184 vinfos[5].jointtype = 1;
41185 vinfos[5].foffset = j5;
41186 vinfos[5].indices[0] = _ij5[0];
41187 vinfos[5].indices[1] = _ij5[1];
41188 vinfos[5].maxsolutions = _nj5;
41189 vinfos[6].jointtype = 1;
41190 vinfos[6].foffset = j6;
41191 vinfos[6].indices[0] = _ij6[0];
41192 vinfos[6].indices[1] = _ij6[1];
41193 vinfos[6].maxsolutions = _nj6;
41194 std::vector<int> vfree(0);
41195 solutions.AddSolution(vinfos,vfree);
41196 }
41197 }
41198 }
41199 
41200 }
41201 
41202 }
41203 
41204 } else
41205 {
41206 {
41207 IkReal j3array[1], cj3array[1], sj3array[1];
41208 bool j3valid[1]={false};
41209 _nj3 = 1;
41210 IkReal x12654=((sj5)*(sj6));
41211 IkReal x12655=((IkReal(1.00000000000000))*(cj6)*(sj5));
41212 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x12654))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12654)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12654))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x12654)))))))+IKsqr(((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12654)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12654)))))-1) <= IKFAST_SINCOS_THRESH )
41213     continue;
41214 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((cj6)*(r21)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x12654)))))), ((((cj0)*(cj5)*(r02)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12654)))+(((cj5)*(r12)*(sj0)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x12655)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12654)))));
41215 sj3array[0]=IKsin(j3array[0]);
41216 cj3array[0]=IKcos(j3array[0]);
41217 if( j3array[0] > IKPI )
41218 {
41219     j3array[0]-=IK2PI;
41220 }
41221 else if( j3array[0] < -IKPI )
41222 {    j3array[0]+=IK2PI;
41223 }
41224 j3valid[0] = true;
41225 for(int ij3 = 0; ij3 < 1; ++ij3)
41226 {
41227 if( !j3valid[ij3] )
41228 {
41229     continue;
41230 }
41231 _ij3[0] = ij3; _ij3[1] = -1;
41232 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41233 {
41234 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41235 {
41236     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41237 }
41238 }
41239 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41240 {
41241 IkReal evalcond[6];
41242 IkReal x12656=IKsin(j3);
41243 IkReal x12657=IKcos(j3);
41244 IkReal x12658=((sj0)*(sj5));
41245 IkReal x12659=((r00)*(sj6));
41246 IkReal x12660=((IkReal(1.00000000000000))*(cj4));
41247 IkReal x12661=((cj6)*(r01));
41248 IkReal x12662=((cj0)*(cj5));
41249 IkReal x12663=((cj5)*(sj0));
41250 IkReal x12664=((cj6)*(r11));
41251 IkReal x12665=((cj0)*(sj5));
41252 IkReal x12666=((cj6)*(sj4));
41253 IkReal x12667=((cj4)*(cj5));
41254 IkReal x12668=((cj6)*(r21));
41255 IkReal x12669=((r20)*(sj6));
41256 IkReal x12670=((r10)*(sj6));
41257 IkReal x12671=((IkReal(1.00000000000000))*(cj0));
41258 IkReal x12672=((IkReal(1.00000000000000))*(x12656));
41259 IkReal x12673=((cj0)*(sj4)*(sj6));
41260 IkReal x12674=((sj0)*(sj4)*(sj6));
41261 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x12672)))+(((sj5)*(x12669)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12668))));
41262 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj2)*(x12657)))+(((x12667)*(x12668)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12666)))+(((x12667)*(x12669))));
41263 evalcond[2]=((((x12658)*(x12661)))+(((IkReal(-1.00000000000000))*(x12664)*(x12665)))+(((x12658)*(x12659)))+(((IkReal(-1.00000000000000))*(sj2)*(x12672)))+(((r12)*(x12662)))+(((IkReal(-1.00000000000000))*(r02)*(x12663)))+(((IkReal(-1.00000000000000))*(x12665)*(x12670))));
41264 evalcond[3]=((((r02)*(x12662)))+(((IkReal(-1.00000000000000))*(x12659)*(x12665)))+(((IkReal(-1.00000000000000))*(x12658)*(x12670)))+(((IkReal(-1.00000000000000))*(x12658)*(x12664)))+(((r12)*(x12663)))+(((IkReal(-1.00000000000000))*(x12661)*(x12665)))+(((IkReal(-1.00000000000000))*(x12657))));
41265 evalcond[4]=((((sj2)*(x12657)))+(((cj4)*(r02)*(x12658)))+(((cj4)*(x12661)*(x12663)))+(((r11)*(x12673)))+(((cj4)*(x12659)*(x12663)))+(((IkReal(-1.00000000000000))*(r01)*(x12674)))+(((IkReal(-1.00000000000000))*(x12660)*(x12662)*(x12664)))+(((r00)*(sj0)*(x12666)))+(((IkReal(-1.00000000000000))*(r10)*(x12666)*(x12671)))+(((IkReal(-1.00000000000000))*(x12660)*(x12662)*(x12670)))+(((IkReal(-1.00000000000000))*(r12)*(x12660)*(x12665))));
41266 evalcond[5]=((((IkReal(-1.00000000000000))*(x12672)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12666)))+(((IkReal(-1.00000000000000))*(x12660)*(x12661)*(x12662)))+(((r11)*(x12674)))+(((IkReal(-1.00000000000000))*(x12660)*(x12663)*(x12664)))+(((IkReal(-1.00000000000000))*(r12)*(x12658)*(x12660)))+(((r01)*(x12673)))+(((IkReal(-1.00000000000000))*(r00)*(x12666)*(x12671)))+(((IkReal(-1.00000000000000))*(x12660)*(x12663)*(x12670)))+(((IkReal(-1.00000000000000))*(r02)*(x12660)*(x12665)))+(((IkReal(-1.00000000000000))*(x12659)*(x12660)*(x12662))));
41267 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
41268 {
41269 continue;
41270 }
41271 }
41272 
41273 {
41274 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41275 vinfos[0].jointtype = 1;
41276 vinfos[0].foffset = j0;
41277 vinfos[0].indices[0] = _ij0[0];
41278 vinfos[0].indices[1] = _ij0[1];
41279 vinfos[0].maxsolutions = _nj0;
41280 vinfos[1].jointtype = 1;
41281 vinfos[1].foffset = j1;
41282 vinfos[1].indices[0] = _ij1[0];
41283 vinfos[1].indices[1] = _ij1[1];
41284 vinfos[1].maxsolutions = _nj1;
41285 vinfos[2].jointtype = 1;
41286 vinfos[2].foffset = j2;
41287 vinfos[2].indices[0] = _ij2[0];
41288 vinfos[2].indices[1] = _ij2[1];
41289 vinfos[2].maxsolutions = _nj2;
41290 vinfos[3].jointtype = 1;
41291 vinfos[3].foffset = j3;
41292 vinfos[3].indices[0] = _ij3[0];
41293 vinfos[3].indices[1] = _ij3[1];
41294 vinfos[3].maxsolutions = _nj3;
41295 vinfos[4].jointtype = 1;
41296 vinfos[4].foffset = j4;
41297 vinfos[4].indices[0] = _ij4[0];
41298 vinfos[4].indices[1] = _ij4[1];
41299 vinfos[4].maxsolutions = _nj4;
41300 vinfos[5].jointtype = 1;
41301 vinfos[5].foffset = j5;
41302 vinfos[5].indices[0] = _ij5[0];
41303 vinfos[5].indices[1] = _ij5[1];
41304 vinfos[5].maxsolutions = _nj5;
41305 vinfos[6].jointtype = 1;
41306 vinfos[6].foffset = j6;
41307 vinfos[6].indices[0] = _ij6[0];
41308 vinfos[6].indices[1] = _ij6[1];
41309 vinfos[6].maxsolutions = _nj6;
41310 std::vector<int> vfree(0);
41311 solutions.AddSolution(vinfos,vfree);
41312 }
41313 }
41314 }
41315 
41316 }
41317 
41318 }
41319 
41320 } else
41321 {
41322 {
41323 IkReal j3array[1], cj3array[1], sj3array[1];
41324 bool j3valid[1]={false};
41325 _nj3 = 1;
41326 IkReal x12675=((IkReal(1.00000000000000))*(cj4));
41327 IkReal x12676=((cj6)*(r21));
41328 IkReal x12677=((r20)*(sj6));
41329 if( IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12677)))+(((sj5)*(x12676))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x12675)*(x12677)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x12675)*(x12676)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12675)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
41330     continue;
41331 j3array[0]=IKatan2(((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12677)))+(((sj5)*(x12676)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(cj5)*(x12675)*(x12677)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x12675)*(x12676)))+(((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12675)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))));
41332 sj3array[0]=IKsin(j3array[0]);
41333 cj3array[0]=IKcos(j3array[0]);
41334 if( j3array[0] > IKPI )
41335 {
41336     j3array[0]-=IK2PI;
41337 }
41338 else if( j3array[0] < -IKPI )
41339 {    j3array[0]+=IK2PI;
41340 }
41341 j3valid[0] = true;
41342 for(int ij3 = 0; ij3 < 1; ++ij3)
41343 {
41344 if( !j3valid[ij3] )
41345 {
41346     continue;
41347 }
41348 _ij3[0] = ij3; _ij3[1] = -1;
41349 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41350 {
41351 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41352 {
41353     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41354 }
41355 }
41356 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41357 {
41358 IkReal evalcond[6];
41359 IkReal x12678=IKsin(j3);
41360 IkReal x12679=IKcos(j3);
41361 IkReal x12680=((sj0)*(sj5));
41362 IkReal x12681=((r00)*(sj6));
41363 IkReal x12682=((IkReal(1.00000000000000))*(cj4));
41364 IkReal x12683=((cj6)*(r01));
41365 IkReal x12684=((cj0)*(cj5));
41366 IkReal x12685=((cj5)*(sj0));
41367 IkReal x12686=((cj6)*(r11));
41368 IkReal x12687=((cj0)*(sj5));
41369 IkReal x12688=((cj6)*(sj4));
41370 IkReal x12689=((cj4)*(cj5));
41371 IkReal x12690=((cj6)*(r21));
41372 IkReal x12691=((r20)*(sj6));
41373 IkReal x12692=((r10)*(sj6));
41374 IkReal x12693=((IkReal(1.00000000000000))*(cj0));
41375 IkReal x12694=((IkReal(1.00000000000000))*(x12678));
41376 IkReal x12695=((cj0)*(sj4)*(sj6));
41377 IkReal x12696=((sj0)*(sj4)*(sj6));
41378 evalcond[0]=((((sj5)*(x12691)))+(((sj5)*(x12690)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x12694))));
41379 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x12689)*(x12690)))+(((x12689)*(x12691)))+(((cj2)*(x12679)))+(((r20)*(x12688))));
41380 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x12694)))+(((x12680)*(x12683)))+(((r12)*(x12684)))+(((x12680)*(x12681)))+(((IkReal(-1.00000000000000))*(x12686)*(x12687)))+(((IkReal(-1.00000000000000))*(r02)*(x12685)))+(((IkReal(-1.00000000000000))*(x12687)*(x12692))));
41381 evalcond[3]=((((IkReal(-1.00000000000000))*(x12679)))+(((r12)*(x12685)))+(((r02)*(x12684)))+(((IkReal(-1.00000000000000))*(x12680)*(x12692)))+(((IkReal(-1.00000000000000))*(x12681)*(x12687)))+(((IkReal(-1.00000000000000))*(x12680)*(x12686)))+(((IkReal(-1.00000000000000))*(x12683)*(x12687))));
41382 evalcond[4]=((((IkReal(-1.00000000000000))*(x12682)*(x12684)*(x12692)))+(((cj4)*(x12683)*(x12685)))+(((r00)*(sj0)*(x12688)))+(((r11)*(x12695)))+(((cj4)*(x12681)*(x12685)))+(((cj4)*(r02)*(x12680)))+(((sj2)*(x12679)))+(((IkReal(-1.00000000000000))*(r10)*(x12688)*(x12693)))+(((IkReal(-1.00000000000000))*(r01)*(x12696)))+(((IkReal(-1.00000000000000))*(r12)*(x12682)*(x12687)))+(((IkReal(-1.00000000000000))*(x12682)*(x12684)*(x12686))));
41383 evalcond[5]=((((IkReal(-1.00000000000000))*(x12681)*(x12682)*(x12684)))+(((IkReal(-1.00000000000000))*(x12682)*(x12685)*(x12692)))+(((r01)*(x12695)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12688)))+(((IkReal(-1.00000000000000))*(x12682)*(x12685)*(x12686)))+(((IkReal(-1.00000000000000))*(r12)*(x12680)*(x12682)))+(((r11)*(x12696)))+(((IkReal(-1.00000000000000))*(r02)*(x12682)*(x12687)))+(((IkReal(-1.00000000000000))*(x12694)))+(((IkReal(-1.00000000000000))*(x12682)*(x12683)*(x12684)))+(((IkReal(-1.00000000000000))*(r00)*(x12688)*(x12693))));
41384 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
41385 {
41386 continue;
41387 }
41388 }
41389 
41390 {
41391 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41392 vinfos[0].jointtype = 1;
41393 vinfos[0].foffset = j0;
41394 vinfos[0].indices[0] = _ij0[0];
41395 vinfos[0].indices[1] = _ij0[1];
41396 vinfos[0].maxsolutions = _nj0;
41397 vinfos[1].jointtype = 1;
41398 vinfos[1].foffset = j1;
41399 vinfos[1].indices[0] = _ij1[0];
41400 vinfos[1].indices[1] = _ij1[1];
41401 vinfos[1].maxsolutions = _nj1;
41402 vinfos[2].jointtype = 1;
41403 vinfos[2].foffset = j2;
41404 vinfos[2].indices[0] = _ij2[0];
41405 vinfos[2].indices[1] = _ij2[1];
41406 vinfos[2].maxsolutions = _nj2;
41407 vinfos[3].jointtype = 1;
41408 vinfos[3].foffset = j3;
41409 vinfos[3].indices[0] = _ij3[0];
41410 vinfos[3].indices[1] = _ij3[1];
41411 vinfos[3].maxsolutions = _nj3;
41412 vinfos[4].jointtype = 1;
41413 vinfos[4].foffset = j4;
41414 vinfos[4].indices[0] = _ij4[0];
41415 vinfos[4].indices[1] = _ij4[1];
41416 vinfos[4].maxsolutions = _nj4;
41417 vinfos[5].jointtype = 1;
41418 vinfos[5].foffset = j5;
41419 vinfos[5].indices[0] = _ij5[0];
41420 vinfos[5].indices[1] = _ij5[1];
41421 vinfos[5].maxsolutions = _nj5;
41422 vinfos[6].jointtype = 1;
41423 vinfos[6].foffset = j6;
41424 vinfos[6].indices[0] = _ij6[0];
41425 vinfos[6].indices[1] = _ij6[1];
41426 vinfos[6].maxsolutions = _nj6;
41427 std::vector<int> vfree(0);
41428 solutions.AddSolution(vinfos,vfree);
41429 }
41430 }
41431 }
41432 
41433 }
41434 
41435 }
41436 
41437 } else
41438 {
41439 IkReal x12697=((IkReal(1.00000000000000))*(cj0));
41440 IkReal x12698=((cj4)*(sj6));
41441 IkReal x12699=((sj0)*(sj4));
41442 IkReal x12700=((cj5)*(sj6));
41443 IkReal x12701=((sj4)*(sj5));
41444 IkReal x12702=((r12)*(sj5));
41445 IkReal x12703=((IkReal(0.374290000000000))*(cj5));
41446 IkReal x12704=((r02)*(sj0));
41447 IkReal x12705=((IkReal(1.00000000000000))*(sj0));
41448 IkReal x12706=((cj0)*(r10));
41449 IkReal x12707=((cj4)*(cj6));
41450 IkReal x12708=((r00)*(sj0));
41451 IkReal x12709=((cj6)*(r21));
41452 IkReal x12710=((IkReal(0.374290000000000))*(sj5));
41453 IkReal x12711=((cj0)*(r00));
41454 IkReal x12712=((IkReal(0.0100000000000000))*(sj5));
41455 IkReal x12713=((cj0)*(r02));
41456 IkReal x12714=((cj5)*(sj4));
41457 IkReal x12715=((cj6)*(r01));
41458 IkReal x12716=((cj6)*(r11));
41459 IkReal x12717=((r01)*(sj0));
41460 IkReal x12718=((r10)*(sj0));
41461 IkReal x12719=((IkReal(0.0100000000000000))*(cj5)*(cj6));
41462 IkReal x12720=((sj6)*(x12710));
41463 IkReal x12721=((cj0)*(cj6)*(x12710));
41464 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j1, IkReal(6.28318530717959))));
41465 evalcond[1]=((sj2)+(((IkReal(-1.00000000000000))*(r20)*(x12707)))+(((r22)*(x12701)))+(((x12709)*(x12714)))+(((r21)*(x12698)))+(((r20)*(sj4)*(x12700))));
41466 evalcond[2]=((((r20)*(x12720)))+(((IkReal(-1.00000000000000))*(r22)*(x12712)))+(((IkReal(-0.0100000000000000))*(r20)*(x12700)))+(((IkReal(-0.0690000000000000))*(cj2)))+(((IkReal(-0.0100000000000000))*(cj5)*(x12709)))+(((IkReal(-1.00000000000000))*(r22)*(x12703)))+(pz)+(((x12709)*(x12710))));
41467 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x12697)*(x12698)))+(((x12698)*(x12717)))+(((IkReal(-1.00000000000000))*(r12)*(x12697)*(x12701)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12697)*(x12700)))+(((x12706)*(x12707)))+(((IkReal(-1.00000000000000))*(r00)*(x12705)*(x12707)))+(((r00)*(x12699)*(x12700)))+(((IkReal(-1.00000000000000))*(x12697)*(x12714)*(x12716)))+(cj2)+(((r02)*(sj5)*(x12699)))+(((cj5)*(x12699)*(x12715))));
41468 evalcond[4]=((((x12707)*(x12711)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12697)*(x12700)))+(((IkReal(-1.00000000000000))*(x12699)*(x12702)))+(((x12707)*(x12718)))+(((IkReal(-1.00000000000000))*(r02)*(x12697)*(x12701)))+(((IkReal(-1.00000000000000))*(cj5)*(x12699)*(x12716)))+(((IkReal(-1.00000000000000))*(r01)*(x12697)*(x12698)))+(((IkReal(-1.00000000000000))*(r11)*(x12698)*(x12705)))+(((IkReal(-1.00000000000000))*(x12697)*(x12714)*(x12715)))+(((IkReal(-1.00000000000000))*(r10)*(x12699)*(x12700))));
41469 evalcond[5]=((((IkReal(-1.00000000000000))*(py)*(x12697)))+(((IkReal(-1.00000000000000))*(x12706)*(x12720)))+(((IkReal(-1.00000000000000))*(cj0)*(x12710)*(x12716)))+(((IkReal(-1.00000000000000))*(x12704)*(x12712)))+(((x12708)*(x12720)))+(((IkReal(0.0100000000000000))*(x12700)*(x12706)))+(((sj0)*(x12710)*(x12715)))+(((IkReal(0.0690000000000000))*(sj2)))+(((IkReal(0.0100000000000000))*(cj0)*(x12702)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12716)))+(((cj0)*(r12)*(x12703)))+(((IkReal(-1.00000000000000))*(x12703)*(x12704)))+(((px)*(sj0)))+(((IkReal(-0.0100000000000000))*(x12700)*(x12708)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x12715))));
41470 evalcond[6]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(x12700)*(x12718)))+(((x12712)*(x12713)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12715)))+(((IkReal(0.0100000000000000))*(sj0)*(x12702)))+(((r12)*(sj0)*(x12703)))+(((IkReal(-1.00000000000000))*(x12711)*(x12720)))+(((IkReal(-1.00000000000000))*(sj0)*(x12710)*(x12716)))+(((x12703)*(x12713)))+(((IkReal(-1.00000000000000))*(x12718)*(x12720)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x12716)))+(((IkReal(-1.00000000000000))*(cj0)*(x12710)*(x12715)))+(((IkReal(-1.00000000000000))*(px)*(x12697)))+(((IkReal(0.0100000000000000))*(x12700)*(x12711)))+(((IkReal(-1.00000000000000))*(py)*(x12705))));
41471 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
41472 {
41473 {
41474 IkReal dummyeval[1];
41475 IkReal gconst10;
41476 gconst10=IKsign(cj2);
41477 dummyeval[0]=cj2;
41478 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
41479 {
41480 {
41481 IkReal dummyeval[1];
41482 dummyeval[0]=cj2;
41483 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
41484 {
41485 {
41486 IkReal dummyeval[1];
41487 dummyeval[0]=sj2;
41488 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
41489 {
41490 {
41491 IkReal evalcond[9];
41492 IkReal x12722=((cj5)*(sj4));
41493 IkReal x12723=((IkReal(1.00000000000000))*(sj6));
41494 IkReal x12724=((r10)*(sj0));
41495 IkReal x12725=((sj4)*(sj5));
41496 IkReal x12726=((cj5)*(cj6));
41497 IkReal x12727=((r01)*(sj0));
41498 IkReal x12728=((IkReal(1.00000000000000))*(r02));
41499 IkReal x12729=((IkReal(0.374290000000000))*(cj0));
41500 IkReal x12730=((cj5)*(r12));
41501 IkReal x12731=((cj6)*(sj5));
41502 IkReal x12732=((cj0)*(r11));
41503 IkReal x12733=((cj5)*(sj0));
41504 IkReal x12734=((r20)*(sj6));
41505 IkReal x12735=((IkReal(1.00000000000000))*(sj0));
41506 IkReal x12736=((cj4)*(cj5));
41507 IkReal x12737=((IkReal(1.00000000000000))*(cj6));
41508 IkReal x12738=((IkReal(0.0100000000000000))*(sj5));
41509 IkReal x12739=((sj5)*(sj6));
41510 IkReal x12740=((cj0)*(r10));
41511 IkReal x12741=((cj4)*(cj6));
41512 IkReal x12742=((cj0)*(r01));
41513 IkReal x12743=((IkReal(1.00000000000000))*(cj4));
41514 IkReal x12744=((cj0)*(r00));
41515 IkReal x12745=((IkReal(0.374290000000000))*(sj0));
41516 IkReal x12746=((cj0)*(r12));
41517 IkReal x12747=((IkReal(0.374290000000000))*(sj5));
41518 IkReal x12748=((cj4)*(sj6));
41519 IkReal x12749=((IkReal(1.00000000000000))*(cj0));
41520 IkReal x12750=((r02)*(sj0));
41521 IkReal x12751=((IkReal(0.0100000000000000))*(cj5));
41522 IkReal x12752=((r11)*(sj0));
41523 IkReal x12753=((r00)*(sj0)*(sj6));
41524 IkReal x12754=((r00)*(x12741));
41525 IkReal x12755=((sj6)*(x12751));
41526 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j2)), IkReal(6.28318530717959))));
41527 evalcond[1]=((((r22)*(x12725)))+(((cj6)*(r21)*(x12722)))+(((r21)*(x12748)))+(((x12722)*(x12734)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12737))));
41528 evalcond[2]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(x12734)*(x12751)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((x12734)*(x12747)))+(((IkReal(0.374290000000000))*(r21)*(x12731)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x12738)))+(((IkReal(-0.0100000000000000))*(r21)*(x12726))));
41529 evalcond[3]=((((IkReal(-1.00000000000000))*(x12731)*(x12732)))+(((x12727)*(x12731)))+(((r00)*(sj0)*(x12739)))+(((IkReal(-1.00000000000000))*(sj5)*(x12723)*(x12740)))+(((IkReal(-1.00000000000000))*(x12728)*(x12733)))+(((cj0)*(x12730))));
41530 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x12725)*(x12746)))+(((cj6)*(x12722)*(x12727)))+(((IkReal(-1.00000000000000))*(x12722)*(x12732)*(x12737)))+(((IkReal(-1.00000000000000))*(x12722)*(x12723)*(x12740)))+(((x12725)*(x12750)))+(((x12740)*(x12741)))+(((IkReal(-1.00000000000000))*(x12735)*(x12754)))+(((x12722)*(x12753)))+(((x12727)*(x12748)))+(((IkReal(-1.00000000000000))*(cj4)*(x12723)*(x12732))));
41531 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x12723)*(x12727)))+(((IkReal(-1.00000000000000))*(sj5)*(x12743)*(x12746)))+(((cj4)*(x12726)*(x12727)))+(((cj4)*(sj5)*(x12750)))+(((IkReal(-1.00000000000000))*(sj4)*(x12737)*(x12740)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((r00)*(x12733)*(x12748)))+(((sj4)*(sj6)*(x12732)))+(((IkReal(-1.00000000000000))*(x12726)*(x12732)*(x12743)))+(((IkReal(-1.00000000000000))*(x12723)*(x12736)*(x12740))));
41532 evalcond[6]=((((IkReal(-1.00000000000000))*(cj4)*(x12723)*(x12752)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12722)*(x12735)))+(((IkReal(-1.00000000000000))*(r12)*(x12725)*(x12735)))+(((IkReal(-1.00000000000000))*(x12722)*(x12723)*(x12724)))+(((IkReal(-1.00000000000000))*(cj0)*(x12725)*(x12728)))+(((IkReal(-1.00000000000000))*(x12722)*(x12723)*(x12744)))+(((x12741)*(x12744)))+(((IkReal(-1.00000000000000))*(cj4)*(x12723)*(x12742)))+(((x12724)*(x12741)))+(((IkReal(-1.00000000000000))*(x12722)*(x12737)*(x12742))));
41533 evalcond[7]=((((IkReal(-1.00000000000000))*(x12738)*(x12750)))+(((IkReal(-1.00000000000000))*(r11)*(x12729)*(x12731)))+(((x12740)*(x12755)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12733)))+(((IkReal(-1.00000000000000))*(py)*(x12749)))+(((IkReal(-0.374290000000000))*(r02)*(x12733)))+(((IkReal(0.374290000000000))*(x12727)*(x12731)))+(((IkReal(0.0100000000000000))*(x12726)*(x12732)))+(((r00)*(x12739)*(x12745)))+(((IkReal(-1.00000000000000))*(r10)*(x12729)*(x12739)))+(((IkReal(-0.0100000000000000))*(x12726)*(x12727)))+(((x12729)*(x12730)))+(((x12738)*(x12746)))+(((px)*(sj0))));
41534 evalcond[8]=((IkReal(-0.295420000000000))+(((cj5)*(r02)*(x12729)))+(((IkReal(-0.374290000000000))*(x12724)*(x12739)))+(((IkReal(-1.00000000000000))*(r11)*(x12731)*(x12745)))+(((r12)*(sj0)*(x12738)))+(((cj0)*(r02)*(x12738)))+(((IkReal(-1.00000000000000))*(r00)*(x12729)*(x12739)))+(((IkReal(0.0100000000000000))*(x12726)*(x12742)))+(((IkReal(-1.00000000000000))*(px)*(x12749)))+(((IkReal(-1.00000000000000))*(r01)*(x12729)*(x12731)))+(((IkReal(-1.00000000000000))*(py)*(x12735)))+(((x12744)*(x12755)))+(((x12724)*(x12755)))+(((x12730)*(x12745)))+(((IkReal(0.0100000000000000))*(x12726)*(x12752))));
41535 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
41536 {
41537 {
41538 IkReal j3array[1], cj3array[1], sj3array[1];
41539 bool j3valid[1]={false};
41540 _nj3 = 1;
41541 IkReal x12756=((IkReal(1.00000000000000))*(r21));
41542 IkReal x12757=((cj4)*(cj5));
41543 IkReal x12758=((r20)*(sj6));
41544 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x12758)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12756))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12757)))+(((x12757)*(x12758)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12756))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x12758)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12756)))))+IKsqr(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12757)))+(((x12757)*(x12758)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12756)))))-1) <= IKFAST_SINCOS_THRESH )
41545     continue;
41546 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x12758)))+(((cj5)*(r22)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12756)))), ((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(r21)*(x12757)))+(((x12757)*(x12758)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12756)))));
41547 sj3array[0]=IKsin(j3array[0]);
41548 cj3array[0]=IKcos(j3array[0]);
41549 if( j3array[0] > IKPI )
41550 {
41551     j3array[0]-=IK2PI;
41552 }
41553 else if( j3array[0] < -IKPI )
41554 {    j3array[0]+=IK2PI;
41555 }
41556 j3valid[0] = true;
41557 for(int ij3 = 0; ij3 < 1; ++ij3)
41558 {
41559 if( !j3valid[ij3] )
41560 {
41561     continue;
41562 }
41563 _ij3[0] = ij3; _ij3[1] = -1;
41564 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41565 {
41566 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41567 {
41568     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41569 }
41570 }
41571 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41572 {
41573 IkReal evalcond[4];
41574 IkReal x12759=IKcos(j3);
41575 IkReal x12760=IKsin(j3);
41576 IkReal x12761=((IkReal(1.00000000000000))*(cj4));
41577 IkReal x12762=((sj0)*(sj5));
41578 IkReal x12763=((cj0)*(cj5));
41579 IkReal x12764=((cj6)*(r01));
41580 IkReal x12765=((r00)*(sj6));
41581 IkReal x12766=((cj6)*(r11));
41582 IkReal x12767=((cj5)*(sj0));
41583 IkReal x12768=((cj6)*(sj4));
41584 IkReal x12769=((sj4)*(sj6));
41585 IkReal x12770=((cj4)*(cj5));
41586 IkReal x12771=((cj6)*(r21));
41587 IkReal x12772=((r20)*(sj6));
41588 IkReal x12773=((r10)*(sj6));
41589 IkReal x12774=((IkReal(1.00000000000000))*(cj0)*(sj5));
41590 evalcond[0]=((x12760)+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12771)))+(((sj5)*(x12772))));
41591 evalcond[1]=((((r20)*(x12768)))+(((x12770)*(x12772)))+(((x12770)*(x12771)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(r21)*(x12769)))+(((IkReal(-1.00000000000000))*(x12759))));
41592 evalcond[2]=((((IkReal(-1.00000000000000))*(x12762)*(x12766)))+(((r02)*(x12763)))+(((r12)*(x12767)))+(((IkReal(-1.00000000000000))*(x12765)*(x12774)))+(((IkReal(-1.00000000000000))*(x12762)*(x12773)))+(((IkReal(-1.00000000000000))*(x12764)*(x12774)))+(x12759));
41593 evalcond[3]=((((IkReal(-1.00000000000000))*(x12761)*(x12763)*(x12765)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12768)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12768)))+(((IkReal(-1.00000000000000))*(x12761)*(x12763)*(x12764)))+(x12760)+(((IkReal(-1.00000000000000))*(x12761)*(x12766)*(x12767)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12761)))+(((IkReal(-1.00000000000000))*(x12761)*(x12767)*(x12773)))+(((cj0)*(r01)*(x12769)))+(((IkReal(-1.00000000000000))*(r12)*(x12761)*(x12762)))+(((r11)*(sj0)*(x12769))));
41594 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
41595 {
41596 continue;
41597 }
41598 }
41599 
41600 {
41601 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41602 vinfos[0].jointtype = 1;
41603 vinfos[0].foffset = j0;
41604 vinfos[0].indices[0] = _ij0[0];
41605 vinfos[0].indices[1] = _ij0[1];
41606 vinfos[0].maxsolutions = _nj0;
41607 vinfos[1].jointtype = 1;
41608 vinfos[1].foffset = j1;
41609 vinfos[1].indices[0] = _ij1[0];
41610 vinfos[1].indices[1] = _ij1[1];
41611 vinfos[1].maxsolutions = _nj1;
41612 vinfos[2].jointtype = 1;
41613 vinfos[2].foffset = j2;
41614 vinfos[2].indices[0] = _ij2[0];
41615 vinfos[2].indices[1] = _ij2[1];
41616 vinfos[2].maxsolutions = _nj2;
41617 vinfos[3].jointtype = 1;
41618 vinfos[3].foffset = j3;
41619 vinfos[3].indices[0] = _ij3[0];
41620 vinfos[3].indices[1] = _ij3[1];
41621 vinfos[3].maxsolutions = _nj3;
41622 vinfos[4].jointtype = 1;
41623 vinfos[4].foffset = j4;
41624 vinfos[4].indices[0] = _ij4[0];
41625 vinfos[4].indices[1] = _ij4[1];
41626 vinfos[4].maxsolutions = _nj4;
41627 vinfos[5].jointtype = 1;
41628 vinfos[5].foffset = j5;
41629 vinfos[5].indices[0] = _ij5[0];
41630 vinfos[5].indices[1] = _ij5[1];
41631 vinfos[5].maxsolutions = _nj5;
41632 vinfos[6].jointtype = 1;
41633 vinfos[6].foffset = j6;
41634 vinfos[6].indices[0] = _ij6[0];
41635 vinfos[6].indices[1] = _ij6[1];
41636 vinfos[6].maxsolutions = _nj6;
41637 std::vector<int> vfree(0);
41638 solutions.AddSolution(vinfos,vfree);
41639 }
41640 }
41641 }
41642 
41643 } else
41644 {
41645 IkReal x12775=((cj5)*(sj4));
41646 IkReal x12776=((IkReal(1.00000000000000))*(sj6));
41647 IkReal x12777=((r10)*(sj0));
41648 IkReal x12778=((sj4)*(sj5));
41649 IkReal x12779=((cj5)*(cj6));
41650 IkReal x12780=((r01)*(sj0));
41651 IkReal x12781=((IkReal(1.00000000000000))*(r02));
41652 IkReal x12782=((IkReal(0.374290000000000))*(cj0));
41653 IkReal x12783=((cj5)*(r12));
41654 IkReal x12784=((cj6)*(sj5));
41655 IkReal x12785=((cj0)*(r11));
41656 IkReal x12786=((cj5)*(sj0));
41657 IkReal x12787=((r20)*(sj6));
41658 IkReal x12788=((IkReal(1.00000000000000))*(sj0));
41659 IkReal x12789=((cj4)*(cj5));
41660 IkReal x12790=((IkReal(1.00000000000000))*(cj6));
41661 IkReal x12791=((IkReal(0.0100000000000000))*(sj5));
41662 IkReal x12792=((sj5)*(sj6));
41663 IkReal x12793=((cj0)*(r10));
41664 IkReal x12794=((cj4)*(cj6));
41665 IkReal x12795=((cj0)*(r01));
41666 IkReal x12796=((IkReal(1.00000000000000))*(cj4));
41667 IkReal x12797=((cj0)*(r00));
41668 IkReal x12798=((IkReal(0.374290000000000))*(sj0));
41669 IkReal x12799=((cj0)*(r12));
41670 IkReal x12800=((IkReal(0.374290000000000))*(sj5));
41671 IkReal x12801=((cj4)*(sj6));
41672 IkReal x12802=((IkReal(1.00000000000000))*(cj0));
41673 IkReal x12803=((r02)*(sj0));
41674 IkReal x12804=((IkReal(0.0100000000000000))*(cj5));
41675 IkReal x12805=((r11)*(sj0));
41676 IkReal x12806=((r00)*(sj0)*(sj6));
41677 IkReal x12807=((r00)*(x12794));
41678 IkReal x12808=((sj6)*(x12804));
41679 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j2, IkReal(6.28318530717959))));
41680 evalcond[1]=((((x12775)*(x12787)))+(((IkReal(-1.00000000000000))*(cj4)*(r20)*(x12790)))+(((r21)*(x12801)))+(((r22)*(x12778)))+(((cj6)*(r21)*(x12775))));
41681 evalcond[2]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(x12787)*(x12804)))+(((x12787)*(x12800)))+(((IkReal(0.374290000000000))*(r21)*(x12784)))+(((IkReal(-1.00000000000000))*(r22)*(x12791)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-0.0100000000000000))*(r21)*(x12779))));
41682 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x12776)*(x12793)))+(((IkReal(-1.00000000000000))*(x12784)*(x12785)))+(((r00)*(sj0)*(x12792)))+(((IkReal(-1.00000000000000))*(x12781)*(x12786)))+(((x12780)*(x12784)))+(((cj0)*(x12783))));
41683 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x12788)*(x12807)))+(((x12778)*(x12803)))+(((IkReal(-1.00000000000000))*(cj4)*(x12776)*(x12785)))+(((IkReal(-1.00000000000000))*(x12775)*(x12776)*(x12793)))+(((x12780)*(x12801)))+(((IkReal(-1.00000000000000))*(x12778)*(x12799)))+(((x12775)*(x12806)))+(((cj6)*(x12775)*(x12780)))+(((x12793)*(x12794)))+(((IkReal(-1.00000000000000))*(x12775)*(x12785)*(x12790))));
41684 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x12776)*(x12780)))+(((IkReal(-1.00000000000000))*(x12776)*(x12789)*(x12793)))+(((IkReal(-1.00000000000000))*(sj4)*(x12790)*(x12793)))+(((cj4)*(x12779)*(x12780)))+(((r00)*(x12786)*(x12801)))+(((cj4)*(sj5)*(x12803)))+(((cj6)*(r00)*(sj0)*(sj4)))+(((sj4)*(sj6)*(x12785)))+(((IkReal(-1.00000000000000))*(x12779)*(x12785)*(x12796)))+(((IkReal(-1.00000000000000))*(sj5)*(x12796)*(x12799))));
41685 evalcond[6]=((((x12794)*(x12797)))+(((IkReal(-1.00000000000000))*(cj4)*(x12776)*(x12795)))+(((IkReal(-1.00000000000000))*(x12775)*(x12776)*(x12777)))+(((IkReal(-1.00000000000000))*(x12775)*(x12776)*(x12797)))+(((IkReal(-1.00000000000000))*(cj0)*(x12778)*(x12781)))+(((IkReal(-1.00000000000000))*(x12775)*(x12790)*(x12795)))+(((x12777)*(x12794)))+(((IkReal(-1.00000000000000))*(cj4)*(x12776)*(x12805)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x12775)*(x12788)))+(((IkReal(-1.00000000000000))*(r12)*(x12778)*(x12788))));
41686 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x12782)*(x12784)))+(((IkReal(-0.0100000000000000))*(r00)*(sj6)*(x12786)))+(((IkReal(-1.00000000000000))*(py)*(x12802)))+(((IkReal(-0.374290000000000))*(r02)*(x12786)))+(((IkReal(0.374290000000000))*(x12780)*(x12784)))+(((x12793)*(x12808)))+(((x12782)*(x12783)))+(((IkReal(-0.0100000000000000))*(x12779)*(x12780)))+(((x12791)*(x12799)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(x12779)*(x12785)))+(((r00)*(x12792)*(x12798)))+(((IkReal(-1.00000000000000))*(x12791)*(x12803)))+(((IkReal(-1.00000000000000))*(r10)*(x12782)*(x12792))));
41687 evalcond[8]=((IkReal(-0.295420000000000))+(((x12783)*(x12798)))+(((IkReal(-1.00000000000000))*(px)*(x12802)))+(((IkReal(-1.00000000000000))*(r00)*(x12782)*(x12792)))+(((cj5)*(r02)*(x12782)))+(((IkReal(-1.00000000000000))*(r01)*(x12782)*(x12784)))+(((cj0)*(r02)*(x12791)))+(((IkReal(0.0100000000000000))*(x12779)*(x12795)))+(((IkReal(-0.374290000000000))*(x12777)*(x12792)))+(((IkReal(-1.00000000000000))*(r11)*(x12784)*(x12798)))+(((IkReal(0.0100000000000000))*(x12779)*(x12805)))+(((x12777)*(x12808)))+(((IkReal(-1.00000000000000))*(py)*(x12788)))+(((x12797)*(x12808)))+(((r12)*(sj0)*(x12791))));
41688 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
41689 {
41690 {
41691 IkReal j3array[1], cj3array[1], sj3array[1];
41692 bool j3valid[1]={false};
41693 _nj3 = 1;
41694 IkReal x12809=((IkReal(1.00000000000000))*(cj4));
41695 IkReal x12810=((cj6)*(r21));
41696 IkReal x12811=((r20)*(sj6));
41697 if( IKabs(((((sj5)*(x12811)))+(((sj5)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12809)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12811)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj5)*(x12811)))+(((sj5)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))))+IKsqr(((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12809)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12811)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))-1) <= IKFAST_SINCOS_THRESH )
41698     continue;
41699 j3array[0]=IKatan2(((((sj5)*(x12811)))+(((sj5)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))), ((((IkReal(-1.00000000000000))*(r22)*(sj5)*(x12809)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12810)))+(((IkReal(-1.00000000000000))*(cj5)*(x12809)*(x12811)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))));
41700 sj3array[0]=IKsin(j3array[0]);
41701 cj3array[0]=IKcos(j3array[0]);
41702 if( j3array[0] > IKPI )
41703 {
41704     j3array[0]-=IK2PI;
41705 }
41706 else if( j3array[0] < -IKPI )
41707 {    j3array[0]+=IK2PI;
41708 }
41709 j3valid[0] = true;
41710 for(int ij3 = 0; ij3 < 1; ++ij3)
41711 {
41712 if( !j3valid[ij3] )
41713 {
41714     continue;
41715 }
41716 _ij3[0] = ij3; _ij3[1] = -1;
41717 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41718 {
41719 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41720 {
41721     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41722 }
41723 }
41724 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41725 {
41726 IkReal evalcond[4];
41727 IkReal x12812=IKcos(j3);
41728 IkReal x12813=IKsin(j3);
41729 IkReal x12814=((IkReal(1.00000000000000))*(cj4));
41730 IkReal x12815=((sj0)*(sj5));
41731 IkReal x12816=((cj0)*(cj5));
41732 IkReal x12817=((cj6)*(r01));
41733 IkReal x12818=((r00)*(sj6));
41734 IkReal x12819=((cj6)*(r11));
41735 IkReal x12820=((cj5)*(sj0));
41736 IkReal x12821=((cj6)*(sj4));
41737 IkReal x12822=((sj4)*(sj6));
41738 IkReal x12823=((cj4)*(cj5));
41739 IkReal x12824=((cj6)*(r21));
41740 IkReal x12825=((r20)*(sj6));
41741 IkReal x12826=((r10)*(sj6));
41742 IkReal x12827=((IkReal(1.00000000000000))*(cj0)*(sj5));
41743 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12825)))+(((IkReal(-1.00000000000000))*(x12813)))+(((sj5)*(x12824))));
41744 evalcond[1]=((((x12823)*(x12825)))+(((x12823)*(x12824)))+(((cj4)*(r22)*(sj5)))+(x12812)+(((r20)*(x12821)))+(((IkReal(-1.00000000000000))*(r21)*(x12822))));
41745 evalcond[2]=((((r12)*(x12820)))+(((r02)*(x12816)))+(((IkReal(-1.00000000000000))*(x12815)*(x12826)))+(((IkReal(-1.00000000000000))*(x12818)*(x12827)))+(x12812)+(((IkReal(-1.00000000000000))*(x12817)*(x12827)))+(((IkReal(-1.00000000000000))*(x12815)*(x12819))));
41746 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r00)*(x12821)))+(((IkReal(-1.00000000000000))*(x12814)*(x12820)*(x12826)))+(((r11)*(sj0)*(x12822)))+(((IkReal(-1.00000000000000))*(x12814)*(x12816)*(x12818)))+(x12813)+(((IkReal(-1.00000000000000))*(x12814)*(x12816)*(x12817)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(sj5)*(x12814)))+(((cj0)*(r01)*(x12822)))+(((IkReal(-1.00000000000000))*(x12814)*(x12819)*(x12820)))+(((IkReal(-1.00000000000000))*(r12)*(x12814)*(x12815)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12821))));
41747 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
41748 {
41749 continue;
41750 }
41751 }
41752 
41753 {
41754 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41755 vinfos[0].jointtype = 1;
41756 vinfos[0].foffset = j0;
41757 vinfos[0].indices[0] = _ij0[0];
41758 vinfos[0].indices[1] = _ij0[1];
41759 vinfos[0].maxsolutions = _nj0;
41760 vinfos[1].jointtype = 1;
41761 vinfos[1].foffset = j1;
41762 vinfos[1].indices[0] = _ij1[0];
41763 vinfos[1].indices[1] = _ij1[1];
41764 vinfos[1].maxsolutions = _nj1;
41765 vinfos[2].jointtype = 1;
41766 vinfos[2].foffset = j2;
41767 vinfos[2].indices[0] = _ij2[0];
41768 vinfos[2].indices[1] = _ij2[1];
41769 vinfos[2].maxsolutions = _nj2;
41770 vinfos[3].jointtype = 1;
41771 vinfos[3].foffset = j3;
41772 vinfos[3].indices[0] = _ij3[0];
41773 vinfos[3].indices[1] = _ij3[1];
41774 vinfos[3].maxsolutions = _nj3;
41775 vinfos[4].jointtype = 1;
41776 vinfos[4].foffset = j4;
41777 vinfos[4].indices[0] = _ij4[0];
41778 vinfos[4].indices[1] = _ij4[1];
41779 vinfos[4].maxsolutions = _nj4;
41780 vinfos[5].jointtype = 1;
41781 vinfos[5].foffset = j5;
41782 vinfos[5].indices[0] = _ij5[0];
41783 vinfos[5].indices[1] = _ij5[1];
41784 vinfos[5].maxsolutions = _nj5;
41785 vinfos[6].jointtype = 1;
41786 vinfos[6].foffset = j6;
41787 vinfos[6].indices[0] = _ij6[0];
41788 vinfos[6].indices[1] = _ij6[1];
41789 vinfos[6].maxsolutions = _nj6;
41790 std::vector<int> vfree(0);
41791 solutions.AddSolution(vinfos,vfree);
41792 }
41793 }
41794 }
41795 
41796 } else
41797 {
41798 IkReal x12828=((IkReal(1.00000000000000))*(cj0));
41799 IkReal x12829=((cj4)*(sj6));
41800 IkReal x12830=((sj0)*(sj4));
41801 IkReal x12831=((cj5)*(sj6));
41802 IkReal x12832=((sj4)*(sj5));
41803 IkReal x12833=((r12)*(sj5));
41804 IkReal x12834=((IkReal(0.374290000000000))*(cj5));
41805 IkReal x12835=((r02)*(sj0));
41806 IkReal x12836=((r20)*(sj4));
41807 IkReal x12837=((IkReal(1.00000000000000))*(sj0));
41808 IkReal x12838=((IkReal(1.00000000000000))*(cj5));
41809 IkReal x12839=((cj0)*(r10));
41810 IkReal x12840=((cj4)*(cj6));
41811 IkReal x12841=((r00)*(sj0));
41812 IkReal x12842=((cj6)*(r21));
41813 IkReal x12843=((IkReal(0.374290000000000))*(sj5));
41814 IkReal x12844=((cj0)*(r00));
41815 IkReal x12845=((IkReal(0.0100000000000000))*(sj5));
41816 IkReal x12846=((cj0)*(r02));
41817 IkReal x12847=((cj5)*(sj4));
41818 IkReal x12848=((cj6)*(r01));
41819 IkReal x12849=((cj6)*(r11));
41820 IkReal x12850=((r01)*(sj0));
41821 IkReal x12851=((r10)*(sj0));
41822 IkReal x12852=((IkReal(0.0100000000000000))*(cj5)*(cj6));
41823 IkReal x12853=((sj6)*(x12843));
41824 IkReal x12854=((cj0)*(cj6)*(x12843));
41825 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
41826 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x12838)))+(((r20)*(sj5)*(sj6)))+(((sj5)*(x12842))));
41827 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x12840)))+(((r21)*(x12829)))+(((x12842)*(x12847)))+(((r22)*(x12832)))+(((x12831)*(x12836))));
41828 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x12845)))+(((IkReal(-1.00000000000000))*(r22)*(x12834)))+(((IkReal(-0.0100000000000000))*(cj5)*(x12842)))+(((IkReal(-0.0100000000000000))*(r20)*(x12831)))+(pz)+(((r20)*(x12853)))+(((x12842)*(x12843))));
41829 evalcond[4]=((((cj5)*(r21)*(x12840)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r20)*(x12829)))+(((cj6)*(x12836)))+(((cj4)*(r22)*(sj5))));
41830 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x12828)*(x12832)))+(((IkReal(-1.00000000000000))*(x12828)*(x12847)*(x12849)))+(((r02)*(sj5)*(x12830)))+(((x12829)*(x12850)))+(((x12839)*(x12840)))+(((cj5)*(x12830)*(x12848)))+(((IkReal(-1.00000000000000))*(r00)*(x12837)*(x12840)))+(((r00)*(x12830)*(x12831)))+(((IkReal(-1.00000000000000))*(r11)*(x12828)*(x12829)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12828)*(x12831))));
41831 evalcond[6]=((((IkReal(-1.00000000000000))*(x12830)*(x12833)))+(((IkReal(-1.00000000000000))*(x12830)*(x12838)*(x12849)))+(((IkReal(-1.00000000000000))*(r02)*(x12828)*(x12832)))+(((x12840)*(x12851)))+(((IkReal(-1.00000000000000))*(r10)*(x12830)*(x12831)))+(((IkReal(-1.00000000000000))*(x12828)*(x12847)*(x12848)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12828)*(x12831)))+(((IkReal(-1.00000000000000))*(r11)*(x12829)*(x12837)))+(((IkReal(-1.00000000000000))*(r01)*(x12828)*(x12829)))+(((x12840)*(x12844))));
41832 evalcond[7]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(x12831)*(x12839)))+(((cj0)*(r12)*(x12834)))+(((IkReal(-1.00000000000000))*(x12835)*(x12845)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x12848)))+(((x12841)*(x12853)))+(((IkReal(-1.00000000000000))*(cj0)*(x12843)*(x12849)))+(((sj0)*(x12843)*(x12848)))+(((IkReal(-1.00000000000000))*(x12839)*(x12853)))+(((IkReal(-1.00000000000000))*(py)*(x12828)))+(((IkReal(-0.0100000000000000))*(x12831)*(x12841)))+(((IkReal(0.0100000000000000))*(cj0)*(x12833)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12849)))+(((IkReal(-1.00000000000000))*(x12834)*(x12835))));
41833 evalcond[8]=((IkReal(-0.295420000000000))+(((x12845)*(x12846)))+(((r12)*(sj0)*(x12834)))+(((IkReal(-1.00000000000000))*(x12851)*(x12853)))+(((IkReal(-1.00000000000000))*(sj0)*(x12843)*(x12849)))+(((IkReal(0.0100000000000000))*(x12831)*(x12851)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12848)))+(((IkReal(0.0100000000000000))*(sj0)*(x12833)))+(((IkReal(-1.00000000000000))*(py)*(x12837)))+(((x12834)*(x12846)))+(((IkReal(-1.00000000000000))*(x12844)*(x12853)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x12849)))+(((IkReal(-1.00000000000000))*(cj0)*(x12843)*(x12848)))+(((IkReal(0.0100000000000000))*(x12831)*(x12844)))+(((IkReal(-1.00000000000000))*(px)*(x12828))));
41834 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
41835 {
41836 {
41837 IkReal j3array[1], cj3array[1], sj3array[1];
41838 bool j3valid[1]={false};
41839 _nj3 = 1;
41840 IkReal x12855=((sj0)*(sj5));
41841 IkReal x12856=((r00)*(sj6));
41842 IkReal x12857=((IkReal(1.00000000000000))*(cj5));
41843 IkReal x12858=((cj6)*(r11));
41844 IkReal x12859=((cj6)*(r01));
41845 IkReal x12860=((r10)*(sj6));
41846 IkReal x12861=((cj0)*(sj5));
41847 if( IKabs(((((IkReal(-1.00000000000000))*(x12860)*(x12861)))+(((x12855)*(x12856)))+(((IkReal(-1.00000000000000))*(x12858)*(x12861)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12857)))+(((x12855)*(x12859))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12857)))+(((x12856)*(x12861)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12857)))+(((x12855)*(x12860)))+(((x12859)*(x12861)))+(((x12855)*(x12858))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x12860)*(x12861)))+(((x12855)*(x12856)))+(((IkReal(-1.00000000000000))*(x12858)*(x12861)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12857)))+(((x12855)*(x12859)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12857)))+(((x12856)*(x12861)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12857)))+(((x12855)*(x12860)))+(((x12859)*(x12861)))+(((x12855)*(x12858)))))-1) <= IKFAST_SINCOS_THRESH )
41848     continue;
41849 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x12860)*(x12861)))+(((x12855)*(x12856)))+(((IkReal(-1.00000000000000))*(x12858)*(x12861)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12857)))+(((x12855)*(x12859)))), ((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12857)))+(((x12856)*(x12861)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12857)))+(((x12855)*(x12860)))+(((x12859)*(x12861)))+(((x12855)*(x12858)))));
41850 sj3array[0]=IKsin(j3array[0]);
41851 cj3array[0]=IKcos(j3array[0]);
41852 if( j3array[0] > IKPI )
41853 {
41854     j3array[0]-=IK2PI;
41855 }
41856 else if( j3array[0] < -IKPI )
41857 {    j3array[0]+=IK2PI;
41858 }
41859 j3valid[0] = true;
41860 for(int ij3 = 0; ij3 < 1; ++ij3)
41861 {
41862 if( !j3valid[ij3] )
41863 {
41864     continue;
41865 }
41866 _ij3[0] = ij3; _ij3[1] = -1;
41867 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
41868 {
41869 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
41870 {
41871     j3valid[iij3]=false; _ij3[1] = iij3; break; 
41872 }
41873 }
41874 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
41875 {
41876 IkReal evalcond[4];
41877 IkReal x12862=IKcos(j3);
41878 IkReal x12863=IKsin(j3);
41879 IkReal x12864=((sj0)*(sj5));
41880 IkReal x12865=((r00)*(sj6));
41881 IkReal x12866=((cj6)*(sj0));
41882 IkReal x12867=((IkReal(1.00000000000000))*(cj4));
41883 IkReal x12868=((r00)*(sj4));
41884 IkReal x12869=((cj0)*(cj5));
41885 IkReal x12870=((cj5)*(sj0));
41886 IkReal x12871=((cj6)*(r11));
41887 IkReal x12872=((r10)*(sj6));
41888 IkReal x12873=((cj0)*(sj5));
41889 IkReal x12874=((r10)*(sj4));
41890 IkReal x12875=((cj4)*(cj5)*(r01));
41891 IkReal x12876=((IkReal(1.00000000000000))*(cj0)*(cj6));
41892 IkReal x12877=((cj0)*(sj4)*(sj6));
41893 IkReal x12878=((sj0)*(sj4)*(sj6));
41894 evalcond[0]=((((cj6)*(r01)*(x12864)))+(((IkReal(-1.00000000000000))*(x12871)*(x12873)))+(((IkReal(-1.00000000000000))*(x12863)))+(((IkReal(-1.00000000000000))*(x12872)*(x12873)))+(((x12864)*(x12865)))+(((IkReal(-1.00000000000000))*(r02)*(x12870)))+(((r12)*(x12869))));
41895 evalcond[1]=((((r02)*(x12869)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x12873)))+(((IkReal(-1.00000000000000))*(x12864)*(x12871)))+(((IkReal(-1.00000000000000))*(x12865)*(x12873)))+(((IkReal(-1.00000000000000))*(x12864)*(x12872)))+(x12862)+(((r12)*(x12870))));
41896 evalcond[2]=((((IkReal(-1.00000000000000))*(r12)*(x12867)*(x12873)))+(((cj4)*(r02)*(x12864)))+(((cj4)*(x12865)*(x12870)))+(((IkReal(-1.00000000000000))*(r01)*(x12878)))+(((IkReal(-1.00000000000000))*(x12867)*(x12869)*(x12872)))+(((IkReal(-1.00000000000000))*(x12874)*(x12876)))+(((r11)*(x12877)))+(((x12866)*(x12875)))+(((IkReal(-1.00000000000000))*(x12867)*(x12869)*(x12871)))+(((x12866)*(x12868)))+(x12862));
41897 evalcond[3]=((((r01)*(x12877)))+(((r11)*(x12878)))+(((IkReal(-1.00000000000000))*(r02)*(x12867)*(x12873)))+(((IkReal(-1.00000000000000))*(x12866)*(x12874)))+(((IkReal(-1.00000000000000))*(x12868)*(x12876)))+(((IkReal(-1.00000000000000))*(cj6)*(r01)*(x12867)*(x12869)))+(((IkReal(-1.00000000000000))*(r12)*(x12864)*(x12867)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12866)*(x12867)))+(((IkReal(-1.00000000000000))*(x12867)*(x12870)*(x12872)))+(((IkReal(-1.00000000000000))*(x12865)*(x12867)*(x12869)))+(x12863));
41898 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
41899 {
41900 continue;
41901 }
41902 }
41903 
41904 {
41905 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
41906 vinfos[0].jointtype = 1;
41907 vinfos[0].foffset = j0;
41908 vinfos[0].indices[0] = _ij0[0];
41909 vinfos[0].indices[1] = _ij0[1];
41910 vinfos[0].maxsolutions = _nj0;
41911 vinfos[1].jointtype = 1;
41912 vinfos[1].foffset = j1;
41913 vinfos[1].indices[0] = _ij1[0];
41914 vinfos[1].indices[1] = _ij1[1];
41915 vinfos[1].maxsolutions = _nj1;
41916 vinfos[2].jointtype = 1;
41917 vinfos[2].foffset = j2;
41918 vinfos[2].indices[0] = _ij2[0];
41919 vinfos[2].indices[1] = _ij2[1];
41920 vinfos[2].maxsolutions = _nj2;
41921 vinfos[3].jointtype = 1;
41922 vinfos[3].foffset = j3;
41923 vinfos[3].indices[0] = _ij3[0];
41924 vinfos[3].indices[1] = _ij3[1];
41925 vinfos[3].maxsolutions = _nj3;
41926 vinfos[4].jointtype = 1;
41927 vinfos[4].foffset = j4;
41928 vinfos[4].indices[0] = _ij4[0];
41929 vinfos[4].indices[1] = _ij4[1];
41930 vinfos[4].maxsolutions = _nj4;
41931 vinfos[5].jointtype = 1;
41932 vinfos[5].foffset = j5;
41933 vinfos[5].indices[0] = _ij5[0];
41934 vinfos[5].indices[1] = _ij5[1];
41935 vinfos[5].maxsolutions = _nj5;
41936 vinfos[6].jointtype = 1;
41937 vinfos[6].foffset = j6;
41938 vinfos[6].indices[0] = _ij6[0];
41939 vinfos[6].indices[1] = _ij6[1];
41940 vinfos[6].maxsolutions = _nj6;
41941 std::vector<int> vfree(0);
41942 solutions.AddSolution(vinfos,vfree);
41943 }
41944 }
41945 }
41946 
41947 } else
41948 {
41949 IkReal x12879=((IkReal(1.00000000000000))*(cj0));
41950 IkReal x12880=((cj4)*(sj6));
41951 IkReal x12881=((sj0)*(sj4));
41952 IkReal x12882=((cj5)*(sj6));
41953 IkReal x12883=((sj4)*(sj5));
41954 IkReal x12884=((r12)*(sj5));
41955 IkReal x12885=((IkReal(0.374290000000000))*(cj5));
41956 IkReal x12886=((r02)*(sj0));
41957 IkReal x12887=((r20)*(sj4));
41958 IkReal x12888=((IkReal(1.00000000000000))*(sj0));
41959 IkReal x12889=((IkReal(1.00000000000000))*(cj5));
41960 IkReal x12890=((cj0)*(r10));
41961 IkReal x12891=((cj4)*(cj6));
41962 IkReal x12892=((r00)*(sj0));
41963 IkReal x12893=((cj6)*(r21));
41964 IkReal x12894=((IkReal(0.374290000000000))*(sj5));
41965 IkReal x12895=((cj0)*(r00));
41966 IkReal x12896=((IkReal(0.0100000000000000))*(sj5));
41967 IkReal x12897=((cj0)*(r02));
41968 IkReal x12898=((cj5)*(sj4));
41969 IkReal x12899=((cj6)*(r01));
41970 IkReal x12900=((cj6)*(r11));
41971 IkReal x12901=((r01)*(sj0));
41972 IkReal x12902=((r10)*(sj0));
41973 IkReal x12903=((IkReal(0.0100000000000000))*(cj5)*(cj6));
41974 IkReal x12904=((sj6)*(x12894));
41975 IkReal x12905=((cj0)*(cj6)*(x12894));
41976 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
41977 evalcond[1]=((((sj5)*(x12893)))+(((IkReal(-1.00000000000000))*(r22)*(x12889)))+(((r20)*(sj5)*(sj6))));
41978 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r20)*(x12891)))+(((x12882)*(x12887)))+(((x12893)*(x12898)))+(((r21)*(x12880)))+(((r22)*(x12883))));
41979 evalcond[3]=((((IkReal(-1.00000000000000))*(r22)*(x12896)))+(((IkReal(-0.0100000000000000))*(r20)*(x12882)))+(((x12893)*(x12894)))+(pz)+(((IkReal(-1.00000000000000))*(r22)*(x12885)))+(((IkReal(-0.0100000000000000))*(cj5)*(x12893)))+(((r20)*(x12904))));
41980 evalcond[4]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj5)*(r21)*(x12891)))+(((cj4)*(r22)*(sj5)))+(((cj6)*(x12887)))+(((cj5)*(r20)*(x12880))));
41981 evalcond[5]=((((IkReal(-1.00000000000000))*(x12879)*(x12898)*(x12900)))+(((IkReal(-1.00000000000000))*(r00)*(x12888)*(x12891)))+(((IkReal(-1.00000000000000))*(r12)*(x12879)*(x12883)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12879)*(x12882)))+(((r00)*(x12881)*(x12882)))+(((r02)*(sj5)*(x12881)))+(((cj5)*(x12881)*(x12899)))+(((x12890)*(x12891)))+(((IkReal(-1.00000000000000))*(r11)*(x12879)*(x12880)))+(((x12880)*(x12901))));
41982 evalcond[6]=((((IkReal(-1.00000000000000))*(x12879)*(x12898)*(x12899)))+(((IkReal(-1.00000000000000))*(x12881)*(x12884)))+(((IkReal(-1.00000000000000))*(x12881)*(x12889)*(x12900)))+(((x12891)*(x12902)))+(((IkReal(-1.00000000000000))*(r11)*(x12880)*(x12888)))+(((IkReal(-1.00000000000000))*(r02)*(x12879)*(x12883)))+(((IkReal(-1.00000000000000))*(r01)*(x12879)*(x12880)))+(((x12891)*(x12895)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12879)*(x12882)))+(((IkReal(-1.00000000000000))*(r10)*(x12881)*(x12882))));
41983 evalcond[7]=((IkReal(-0.0690000000000000))+(((cj0)*(r12)*(x12885)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x12899)))+(((IkReal(-1.00000000000000))*(py)*(x12879)))+(((IkReal(-1.00000000000000))*(x12890)*(x12904)))+(((sj0)*(x12894)*(x12899)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12900)))+(((IkReal(-0.0100000000000000))*(x12882)*(x12892)))+(((IkReal(0.0100000000000000))*(cj0)*(x12884)))+(((x12892)*(x12904)))+(((IkReal(-1.00000000000000))*(cj0)*(x12894)*(x12900)))+(((IkReal(-1.00000000000000))*(x12886)*(x12896)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(x12882)*(x12890)))+(((IkReal(-1.00000000000000))*(x12885)*(x12886))));
41984 evalcond[8]=((IkReal(-0.295420000000000))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x12900)))+(((IkReal(0.0100000000000000))*(x12882)*(x12902)))+(((x12896)*(x12897)))+(((IkReal(-1.00000000000000))*(x12902)*(x12904)))+(((x12885)*(x12897)))+(((IkReal(-1.00000000000000))*(x12895)*(x12904)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x12899)))+(((IkReal(-1.00000000000000))*(cj0)*(x12894)*(x12899)))+(((IkReal(0.0100000000000000))*(sj0)*(x12884)))+(((IkReal(-1.00000000000000))*(py)*(x12888)))+(((r12)*(sj0)*(x12885)))+(((IkReal(-1.00000000000000))*(px)*(x12879)))+(((IkReal(-1.00000000000000))*(sj0)*(x12894)*(x12900)))+(((IkReal(0.0100000000000000))*(x12882)*(x12895))));
41985 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
41986 {
41987 {
41988 IkReal j3array[1], cj3array[1], sj3array[1];
41989 bool j3valid[1]={false};
41990 _nj3 = 1;
41991 IkReal x12906=((IkReal(1.00000000000000))*(cj5));
41992 IkReal x12907=((r10)*(sj5)*(sj6));
41993 IkReal x12908=((cj6)*(sj0)*(sj5));
41994 IkReal x12909=((r00)*(sj5)*(sj6));
41995 IkReal x12910=((cj0)*(cj6)*(sj5));
41996 if( IKabs(((((IkReal(-1.00000000000000))*(sj0)*(x12909)))+(((IkReal(-1.00000000000000))*(r01)*(x12908)))+(((cj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12906)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x12910))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12906)))+(((r11)*(x12908)))+(((r01)*(x12910)))+(((sj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12906)))+(((cj0)*(x12909))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj0)*(x12909)))+(((IkReal(-1.00000000000000))*(r01)*(x12908)))+(((cj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12906)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x12910)))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12906)))+(((r11)*(x12908)))+(((r01)*(x12910)))+(((sj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12906)))+(((cj0)*(x12909)))))-1) <= IKFAST_SINCOS_THRESH )
41997     continue;
41998 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj0)*(x12909)))+(((IkReal(-1.00000000000000))*(r01)*(x12908)))+(((cj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x12906)))+(((cj5)*(r02)*(sj0)))+(((r11)*(x12910)))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12906)))+(((r11)*(x12908)))+(((r01)*(x12910)))+(((sj0)*(x12907)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12906)))+(((cj0)*(x12909)))));
41999 sj3array[0]=IKsin(j3array[0]);
42000 cj3array[0]=IKcos(j3array[0]);
42001 if( j3array[0] > IKPI )
42002 {
42003     j3array[0]-=IK2PI;
42004 }
42005 else if( j3array[0] < -IKPI )
42006 {    j3array[0]+=IK2PI;
42007 }
42008 j3valid[0] = true;
42009 for(int ij3 = 0; ij3 < 1; ++ij3)
42010 {
42011 if( !j3valid[ij3] )
42012 {
42013     continue;
42014 }
42015 _ij3[0] = ij3; _ij3[1] = -1;
42016 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42017 {
42018 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42019 {
42020     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42021 }
42022 }
42023 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42024 {
42025 IkReal evalcond[4];
42026 IkReal x12911=IKcos(j3);
42027 IkReal x12912=IKsin(j3);
42028 IkReal x12913=((sj0)*(sj5));
42029 IkReal x12914=((r00)*(sj6));
42030 IkReal x12915=((IkReal(1.00000000000000))*(cj4));
42031 IkReal x12916=((cj6)*(sj0));
42032 IkReal x12917=((r00)*(sj4));
42033 IkReal x12918=((cj0)*(cj5));
42034 IkReal x12919=((cj6)*(r01));
42035 IkReal x12920=((cj5)*(sj0));
42036 IkReal x12921=((cj0)*(sj5));
42037 IkReal x12922=((cj6)*(r11));
42038 IkReal x12923=((r10)*(sj6));
42039 IkReal x12924=((r10)*(sj4));
42040 IkReal x12925=((cj0)*(sj4)*(sj6));
42041 IkReal x12926=((sj0)*(sj4)*(sj6));
42042 IkReal x12927=((IkReal(1.00000000000000))*(cj0)*(cj6));
42043 evalcond[0]=((((IkReal(-1.00000000000000))*(x12921)*(x12922)))+(((x12913)*(x12919)))+(((IkReal(-1.00000000000000))*(x12921)*(x12923)))+(x12912)+(((r12)*(x12918)))+(((IkReal(-1.00000000000000))*(r02)*(x12920)))+(((x12913)*(x12914))));
42044 evalcond[1]=((((r12)*(x12920)))+(((IkReal(-1.00000000000000))*(x12913)*(x12922)))+(((IkReal(-1.00000000000000))*(x12913)*(x12923)))+(((IkReal(-1.00000000000000))*(x12919)*(x12921)))+(x12911)+(((IkReal(-1.00000000000000))*(x12914)*(x12921)))+(((r02)*(x12918))));
42045 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x12926)))+(((cj4)*(x12914)*(x12920)))+(((IkReal(-1.00000000000000))*(x12924)*(x12927)))+(((IkReal(-1.00000000000000))*(x12911)))+(((r11)*(x12925)))+(((cj4)*(r02)*(x12913)))+(((IkReal(-1.00000000000000))*(x12915)*(x12918)*(x12922)))+(((x12916)*(x12917)))+(((IkReal(-1.00000000000000))*(r12)*(x12915)*(x12921)))+(((cj4)*(cj5)*(r01)*(x12916)))+(((IkReal(-1.00000000000000))*(x12915)*(x12918)*(x12923))));
42046 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x12915)*(x12916)))+(((IkReal(-1.00000000000000))*(x12914)*(x12915)*(x12918)))+(((r11)*(x12926)))+(((IkReal(-1.00000000000000))*(x12915)*(x12920)*(x12923)))+(((IkReal(-1.00000000000000))*(x12917)*(x12927)))+(((IkReal(-1.00000000000000))*(x12916)*(x12924)))+(x12912)+(((IkReal(-1.00000000000000))*(r02)*(x12915)*(x12921)))+(((r01)*(x12925)))+(((IkReal(-1.00000000000000))*(x12915)*(x12918)*(x12919)))+(((IkReal(-1.00000000000000))*(r12)*(x12913)*(x12915))));
42047 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
42048 {
42049 continue;
42050 }
42051 }
42052 
42053 {
42054 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42055 vinfos[0].jointtype = 1;
42056 vinfos[0].foffset = j0;
42057 vinfos[0].indices[0] = _ij0[0];
42058 vinfos[0].indices[1] = _ij0[1];
42059 vinfos[0].maxsolutions = _nj0;
42060 vinfos[1].jointtype = 1;
42061 vinfos[1].foffset = j1;
42062 vinfos[1].indices[0] = _ij1[0];
42063 vinfos[1].indices[1] = _ij1[1];
42064 vinfos[1].maxsolutions = _nj1;
42065 vinfos[2].jointtype = 1;
42066 vinfos[2].foffset = j2;
42067 vinfos[2].indices[0] = _ij2[0];
42068 vinfos[2].indices[1] = _ij2[1];
42069 vinfos[2].maxsolutions = _nj2;
42070 vinfos[3].jointtype = 1;
42071 vinfos[3].foffset = j3;
42072 vinfos[3].indices[0] = _ij3[0];
42073 vinfos[3].indices[1] = _ij3[1];
42074 vinfos[3].maxsolutions = _nj3;
42075 vinfos[4].jointtype = 1;
42076 vinfos[4].foffset = j4;
42077 vinfos[4].indices[0] = _ij4[0];
42078 vinfos[4].indices[1] = _ij4[1];
42079 vinfos[4].maxsolutions = _nj4;
42080 vinfos[5].jointtype = 1;
42081 vinfos[5].foffset = j5;
42082 vinfos[5].indices[0] = _ij5[0];
42083 vinfos[5].indices[1] = _ij5[1];
42084 vinfos[5].maxsolutions = _nj5;
42085 vinfos[6].jointtype = 1;
42086 vinfos[6].foffset = j6;
42087 vinfos[6].indices[0] = _ij6[0];
42088 vinfos[6].indices[1] = _ij6[1];
42089 vinfos[6].maxsolutions = _nj6;
42090 std::vector<int> vfree(0);
42091 solutions.AddSolution(vinfos,vfree);
42092 }
42093 }
42094 }
42095 
42096 } else
42097 {
42098 if( 1 )
42099 {
42100 continue;
42101 
42102 } else
42103 {
42104 }
42105 }
42106 }
42107 }
42108 }
42109 }
42110 
42111 } else
42112 {
42113 {
42114 IkReal j3array[1], cj3array[1], sj3array[1];
42115 bool j3valid[1]={false};
42116 _nj3 = 1;
42117 IkReal x12928=((sj0)*(sj5));
42118 IkReal x12929=((r00)*(sj6));
42119 IkReal x12930=((IkReal(1.00000000000000))*(cj5));
42120 IkReal x12931=((cj6)*(r11));
42121 IkReal x12932=((cj6)*(r01));
42122 IkReal x12933=((cj0)*(sj5));
42123 IkReal x12934=((r10)*(sj6));
42124 if( IKabs(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x12931)*(x12933)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12930)))+(((x12928)*(x12929)))+(((x12928)*(x12932)))+(((IkReal(-1.00000000000000))*(x12933)*(x12934))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12930)))+(((x12928)*(x12934)))+(((x12929)*(x12933)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12930)))+(((x12928)*(x12931)))+(((x12932)*(x12933))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x12931)*(x12933)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12930)))+(((x12928)*(x12929)))+(((x12928)*(x12932)))+(((IkReal(-1.00000000000000))*(x12933)*(x12934)))))))+IKsqr(((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12930)))+(((x12928)*(x12934)))+(((x12929)*(x12933)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12930)))+(((x12928)*(x12931)))+(((x12932)*(x12933)))))-1) <= IKFAST_SINCOS_THRESH )
42125     continue;
42126 j3array[0]=IKatan2(((((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x12931)*(x12933)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x12930)))+(((x12928)*(x12929)))+(((x12928)*(x12932)))+(((IkReal(-1.00000000000000))*(x12933)*(x12934)))))), ((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12930)))+(((x12928)*(x12934)))+(((x12929)*(x12933)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12930)))+(((x12928)*(x12931)))+(((x12932)*(x12933)))));
42127 sj3array[0]=IKsin(j3array[0]);
42128 cj3array[0]=IKcos(j3array[0]);
42129 if( j3array[0] > IKPI )
42130 {
42131     j3array[0]-=IK2PI;
42132 }
42133 else if( j3array[0] < -IKPI )
42134 {    j3array[0]+=IK2PI;
42135 }
42136 j3valid[0] = true;
42137 for(int ij3 = 0; ij3 < 1; ++ij3)
42138 {
42139 if( !j3valid[ij3] )
42140 {
42141     continue;
42142 }
42143 _ij3[0] = ij3; _ij3[1] = -1;
42144 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42145 {
42146 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42147 {
42148     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42149 }
42150 }
42151 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42152 {
42153 IkReal evalcond[6];
42154 IkReal x12935=IKsin(j3);
42155 IkReal x12936=IKcos(j3);
42156 IkReal x12937=((sj0)*(sj5));
42157 IkReal x12938=((r00)*(sj6));
42158 IkReal x12939=((IkReal(1.00000000000000))*(cj4));
42159 IkReal x12940=((cj6)*(r01));
42160 IkReal x12941=((cj0)*(cj5));
42161 IkReal x12942=((cj5)*(sj0));
42162 IkReal x12943=((cj6)*(r11));
42163 IkReal x12944=((cj6)*(sj4));
42164 IkReal x12945=((cj0)*(sj5));
42165 IkReal x12946=((cj4)*(cj5));
42166 IkReal x12947=((cj6)*(r21));
42167 IkReal x12948=((r20)*(sj6));
42168 IkReal x12949=((r10)*(sj6));
42169 IkReal x12950=((IkReal(1.00000000000000))*(cj0));
42170 IkReal x12951=((cj0)*(sj4)*(sj6));
42171 IkReal x12952=((sj0)*(sj4)*(sj6));
42172 evalcond[0]=((((sj5)*(x12947)))+(((sj5)*(x12948)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((cj2)*(x12935))));
42173 evalcond[1]=((((x12946)*(x12947)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12946)*(x12948)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x12944)))+(((IkReal(-1.00000000000000))*(cj2)*(x12936))));
42174 evalcond[2]=((((r12)*(x12941)))+(((IkReal(-1.00000000000000))*(r02)*(x12942)))+(((x12937)*(x12940)))+(((x12937)*(x12938)))+(((IkReal(-1.00000000000000))*(x12943)*(x12945)))+(((IkReal(-1.00000000000000))*(x12945)*(x12949)))+(((IkReal(-1.00000000000000))*(sj2)*(x12935))));
42175 evalcond[3]=((((IkReal(-1.00000000000000))*(x12937)*(x12943)))+(x12936)+(((r12)*(x12942)))+(((IkReal(-1.00000000000000))*(x12937)*(x12949)))+(((IkReal(-1.00000000000000))*(x12938)*(x12945)))+(((IkReal(-1.00000000000000))*(x12940)*(x12945)))+(((r02)*(x12941))));
42176 evalcond[4]=((((sj2)*(x12936)))+(((cj4)*(r02)*(x12937)))+(((cj4)*(x12940)*(x12942)))+(((r11)*(x12951)))+(((IkReal(-1.00000000000000))*(x12939)*(x12941)*(x12949)))+(((IkReal(-1.00000000000000))*(r12)*(x12939)*(x12945)))+(((IkReal(-1.00000000000000))*(r10)*(x12944)*(x12950)))+(((cj4)*(x12938)*(x12942)))+(((IkReal(-1.00000000000000))*(r01)*(x12952)))+(((r00)*(sj0)*(x12944)))+(((IkReal(-1.00000000000000))*(x12939)*(x12941)*(x12943))));
42177 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x12944)*(x12950)))+(((r11)*(x12952)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12944)))+(((IkReal(-1.00000000000000))*(x12939)*(x12942)*(x12943)))+(((IkReal(-1.00000000000000))*(x12938)*(x12939)*(x12941)))+(x12935)+(((IkReal(-1.00000000000000))*(x12939)*(x12942)*(x12949)))+(((IkReal(-1.00000000000000))*(x12939)*(x12940)*(x12941)))+(((IkReal(-1.00000000000000))*(r12)*(x12937)*(x12939)))+(((IkReal(-1.00000000000000))*(r02)*(x12939)*(x12945)))+(((r01)*(x12951))));
42178 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
42179 {
42180 continue;
42181 }
42182 }
42183 
42184 {
42185 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42186 vinfos[0].jointtype = 1;
42187 vinfos[0].foffset = j0;
42188 vinfos[0].indices[0] = _ij0[0];
42189 vinfos[0].indices[1] = _ij0[1];
42190 vinfos[0].maxsolutions = _nj0;
42191 vinfos[1].jointtype = 1;
42192 vinfos[1].foffset = j1;
42193 vinfos[1].indices[0] = _ij1[0];
42194 vinfos[1].indices[1] = _ij1[1];
42195 vinfos[1].maxsolutions = _nj1;
42196 vinfos[2].jointtype = 1;
42197 vinfos[2].foffset = j2;
42198 vinfos[2].indices[0] = _ij2[0];
42199 vinfos[2].indices[1] = _ij2[1];
42200 vinfos[2].maxsolutions = _nj2;
42201 vinfos[3].jointtype = 1;
42202 vinfos[3].foffset = j3;
42203 vinfos[3].indices[0] = _ij3[0];
42204 vinfos[3].indices[1] = _ij3[1];
42205 vinfos[3].maxsolutions = _nj3;
42206 vinfos[4].jointtype = 1;
42207 vinfos[4].foffset = j4;
42208 vinfos[4].indices[0] = _ij4[0];
42209 vinfos[4].indices[1] = _ij4[1];
42210 vinfos[4].maxsolutions = _nj4;
42211 vinfos[5].jointtype = 1;
42212 vinfos[5].foffset = j5;
42213 vinfos[5].indices[0] = _ij5[0];
42214 vinfos[5].indices[1] = _ij5[1];
42215 vinfos[5].maxsolutions = _nj5;
42216 vinfos[6].jointtype = 1;
42217 vinfos[6].foffset = j6;
42218 vinfos[6].indices[0] = _ij6[0];
42219 vinfos[6].indices[1] = _ij6[1];
42220 vinfos[6].maxsolutions = _nj6;
42221 std::vector<int> vfree(0);
42222 solutions.AddSolution(vinfos,vfree);
42223 }
42224 }
42225 }
42226 
42227 }
42228 
42229 }
42230 
42231 } else
42232 {
42233 {
42234 IkReal j3array[1], cj3array[1], sj3array[1];
42235 bool j3valid[1]={false};
42236 _nj3 = 1;
42237 IkReal x12953=((cj6)*(sj5));
42238 IkReal x12954=((IkReal(1.00000000000000))*(cj5));
42239 IkReal x12955=((sj5)*(sj6));
42240 if( IKabs(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x12953)))+(((IkReal(-1.00000000000000))*(r20)*(x12955)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((r11)*(sj0)*(x12953)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12954)))+(((cj0)*(r01)*(x12953)))+(((r10)*(sj0)*(x12955)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12954)))+(((cj0)*(r00)*(x12955))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x12953)))+(((IkReal(-1.00000000000000))*(r20)*(x12955)))+(((cj5)*(r22)))))))+IKsqr(((((r11)*(sj0)*(x12953)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12954)))+(((cj0)*(r01)*(x12953)))+(((r10)*(sj0)*(x12955)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12954)))+(((cj0)*(r00)*(x12955)))))-1) <= IKFAST_SINCOS_THRESH )
42241     continue;
42242 j3array[0]=IKatan2(((((IKabs(cj2) != 0)?((IkReal)1/(cj2)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r21)*(x12953)))+(((IkReal(-1.00000000000000))*(r20)*(x12955)))+(((cj5)*(r22)))))), ((((r11)*(sj0)*(x12953)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x12954)))+(((cj0)*(r01)*(x12953)))+(((r10)*(sj0)*(x12955)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x12954)))+(((cj0)*(r00)*(x12955)))));
42243 sj3array[0]=IKsin(j3array[0]);
42244 cj3array[0]=IKcos(j3array[0]);
42245 if( j3array[0] > IKPI )
42246 {
42247     j3array[0]-=IK2PI;
42248 }
42249 else if( j3array[0] < -IKPI )
42250 {    j3array[0]+=IK2PI;
42251 }
42252 j3valid[0] = true;
42253 for(int ij3 = 0; ij3 < 1; ++ij3)
42254 {
42255 if( !j3valid[ij3] )
42256 {
42257     continue;
42258 }
42259 _ij3[0] = ij3; _ij3[1] = -1;
42260 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42261 {
42262 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42263 {
42264     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42265 }
42266 }
42267 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42268 {
42269 IkReal evalcond[6];
42270 IkReal x12956=IKsin(j3);
42271 IkReal x12957=IKcos(j3);
42272 IkReal x12958=((sj0)*(sj5));
42273 IkReal x12959=((r00)*(sj6));
42274 IkReal x12960=((IkReal(1.00000000000000))*(cj4));
42275 IkReal x12961=((cj6)*(r01));
42276 IkReal x12962=((cj0)*(cj5));
42277 IkReal x12963=((cj5)*(sj0));
42278 IkReal x12964=((cj6)*(r11));
42279 IkReal x12965=((cj6)*(sj4));
42280 IkReal x12966=((cj0)*(sj5));
42281 IkReal x12967=((cj4)*(cj5));
42282 IkReal x12968=((cj6)*(r21));
42283 IkReal x12969=((r20)*(sj6));
42284 IkReal x12970=((r10)*(sj6));
42285 IkReal x12971=((IkReal(1.00000000000000))*(cj0));
42286 IkReal x12972=((cj0)*(sj4)*(sj6));
42287 IkReal x12973=((sj0)*(sj4)*(sj6));
42288 evalcond[0]=((((cj2)*(x12956)))+(((sj5)*(x12968)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12969))));
42289 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x12957)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x12967)*(x12968)))+(((cj4)*(r22)*(sj5)))+(((x12967)*(x12969)))+(((r20)*(x12965))));
42290 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x12956)))+(((IkReal(-1.00000000000000))*(x12966)*(x12970)))+(((IkReal(-1.00000000000000))*(x12964)*(x12966)))+(((x12958)*(x12959)))+(((x12958)*(x12961)))+(((IkReal(-1.00000000000000))*(r02)*(x12963)))+(((r12)*(x12962))));
42291 evalcond[3]=((((IkReal(-1.00000000000000))*(x12958)*(x12964)))+(((r12)*(x12963)))+(((IkReal(-1.00000000000000))*(x12961)*(x12966)))+(((r02)*(x12962)))+(((IkReal(-1.00000000000000))*(x12958)*(x12970)))+(((IkReal(-1.00000000000000))*(x12959)*(x12966)))+(x12957));
42292 evalcond[4]=((((IkReal(-1.00000000000000))*(x12960)*(x12962)*(x12970)))+(((cj4)*(r02)*(x12958)))+(((IkReal(-1.00000000000000))*(r10)*(x12965)*(x12971)))+(((IkReal(-1.00000000000000))*(x12960)*(x12962)*(x12964)))+(((r00)*(sj0)*(x12965)))+(((cj4)*(x12959)*(x12963)))+(((cj4)*(x12961)*(x12963)))+(((IkReal(-1.00000000000000))*(r12)*(x12960)*(x12966)))+(((IkReal(-1.00000000000000))*(r01)*(x12973)))+(((sj2)*(x12957)))+(((r11)*(x12972))));
42293 evalcond[5]=((((r11)*(x12973)))+(((r01)*(x12972)))+(((IkReal(-1.00000000000000))*(x12960)*(x12961)*(x12962)))+(((IkReal(-1.00000000000000))*(x12960)*(x12963)*(x12964)))+(((IkReal(-1.00000000000000))*(r12)*(x12958)*(x12960)))+(((IkReal(-1.00000000000000))*(r00)*(x12965)*(x12971)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12965)))+(((IkReal(-1.00000000000000))*(x12959)*(x12960)*(x12962)))+(((IkReal(-1.00000000000000))*(x12960)*(x12963)*(x12970)))+(x12956)+(((IkReal(-1.00000000000000))*(r02)*(x12960)*(x12966))));
42294 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
42295 {
42296 continue;
42297 }
42298 }
42299 
42300 {
42301 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42302 vinfos[0].jointtype = 1;
42303 vinfos[0].foffset = j0;
42304 vinfos[0].indices[0] = _ij0[0];
42305 vinfos[0].indices[1] = _ij0[1];
42306 vinfos[0].maxsolutions = _nj0;
42307 vinfos[1].jointtype = 1;
42308 vinfos[1].foffset = j1;
42309 vinfos[1].indices[0] = _ij1[0];
42310 vinfos[1].indices[1] = _ij1[1];
42311 vinfos[1].maxsolutions = _nj1;
42312 vinfos[2].jointtype = 1;
42313 vinfos[2].foffset = j2;
42314 vinfos[2].indices[0] = _ij2[0];
42315 vinfos[2].indices[1] = _ij2[1];
42316 vinfos[2].maxsolutions = _nj2;
42317 vinfos[3].jointtype = 1;
42318 vinfos[3].foffset = j3;
42319 vinfos[3].indices[0] = _ij3[0];
42320 vinfos[3].indices[1] = _ij3[1];
42321 vinfos[3].maxsolutions = _nj3;
42322 vinfos[4].jointtype = 1;
42323 vinfos[4].foffset = j4;
42324 vinfos[4].indices[0] = _ij4[0];
42325 vinfos[4].indices[1] = _ij4[1];
42326 vinfos[4].maxsolutions = _nj4;
42327 vinfos[5].jointtype = 1;
42328 vinfos[5].foffset = j5;
42329 vinfos[5].indices[0] = _ij5[0];
42330 vinfos[5].indices[1] = _ij5[1];
42331 vinfos[5].maxsolutions = _nj5;
42332 vinfos[6].jointtype = 1;
42333 vinfos[6].foffset = j6;
42334 vinfos[6].indices[0] = _ij6[0];
42335 vinfos[6].indices[1] = _ij6[1];
42336 vinfos[6].maxsolutions = _nj6;
42337 std::vector<int> vfree(0);
42338 solutions.AddSolution(vinfos,vfree);
42339 }
42340 }
42341 }
42342 
42343 }
42344 
42345 }
42346 
42347 } else
42348 {
42349 {
42350 IkReal j3array[1], cj3array[1], sj3array[1];
42351 bool j3valid[1]={false};
42352 _nj3 = 1;
42353 IkReal x12974=((IkReal(1.00000000000000))*(r21));
42354 IkReal x12975=((cj4)*(cj5));
42355 IkReal x12976=((r20)*(sj6));
42356 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(sj5)*(x12976)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12974)))+(((cj5)*(r22))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12974)))+(((cj6)*(r21)*(x12975)))+(((x12975)*(x12976))))))) < IKFAST_ATAN2_MAGTHRESH )
42357     continue;
42358 j3array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(sj5)*(x12976)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x12974)))+(((cj5)*(r22)))))), ((gconst10)*(((((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(sj6)*(x12974)))+(((cj6)*(r21)*(x12975)))+(((x12975)*(x12976)))))));
42359 sj3array[0]=IKsin(j3array[0]);
42360 cj3array[0]=IKcos(j3array[0]);
42361 if( j3array[0] > IKPI )
42362 {
42363     j3array[0]-=IK2PI;
42364 }
42365 else if( j3array[0] < -IKPI )
42366 {    j3array[0]+=IK2PI;
42367 }
42368 j3valid[0] = true;
42369 for(int ij3 = 0; ij3 < 1; ++ij3)
42370 {
42371 if( !j3valid[ij3] )
42372 {
42373     continue;
42374 }
42375 _ij3[0] = ij3; _ij3[1] = -1;
42376 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42377 {
42378 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42379 {
42380     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42381 }
42382 }
42383 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42384 {
42385 IkReal evalcond[6];
42386 IkReal x12977=IKsin(j3);
42387 IkReal x12978=IKcos(j3);
42388 IkReal x12979=((sj0)*(sj5));
42389 IkReal x12980=((r00)*(sj6));
42390 IkReal x12981=((IkReal(1.00000000000000))*(cj4));
42391 IkReal x12982=((cj6)*(r01));
42392 IkReal x12983=((cj0)*(cj5));
42393 IkReal x12984=((cj5)*(sj0));
42394 IkReal x12985=((cj6)*(r11));
42395 IkReal x12986=((cj6)*(sj4));
42396 IkReal x12987=((cj0)*(sj5));
42397 IkReal x12988=((cj4)*(cj5));
42398 IkReal x12989=((cj6)*(r21));
42399 IkReal x12990=((r20)*(sj6));
42400 IkReal x12991=((r10)*(sj6));
42401 IkReal x12992=((IkReal(1.00000000000000))*(cj0));
42402 IkReal x12993=((cj0)*(sj4)*(sj6));
42403 IkReal x12994=((sj0)*(sj4)*(sj6));
42404 evalcond[0]=((((sj5)*(x12990)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x12989)))+(((cj2)*(x12977))));
42405 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj2)*(x12978)))+(((x12988)*(x12989)))+(((cj4)*(r22)*(sj5)))+(((x12988)*(x12990)))+(((r20)*(x12986))));
42406 evalcond[2]=((((r12)*(x12983)))+(((x12979)*(x12982)))+(((IkReal(-1.00000000000000))*(x12987)*(x12991)))+(((x12979)*(x12980)))+(((IkReal(-1.00000000000000))*(sj2)*(x12977)))+(((IkReal(-1.00000000000000))*(r02)*(x12984)))+(((IkReal(-1.00000000000000))*(x12985)*(x12987))));
42407 evalcond[3]=((((r02)*(x12983)))+(((IkReal(-1.00000000000000))*(x12982)*(x12987)))+(x12978)+(((IkReal(-1.00000000000000))*(x12979)*(x12991)))+(((IkReal(-1.00000000000000))*(x12979)*(x12985)))+(((IkReal(-1.00000000000000))*(x12980)*(x12987)))+(((r12)*(x12984))));
42408 evalcond[4]=((((IkReal(-1.00000000000000))*(x12981)*(x12983)*(x12985)))+(((IkReal(-1.00000000000000))*(r12)*(x12981)*(x12987)))+(((sj2)*(x12978)))+(((cj4)*(x12980)*(x12984)))+(((cj4)*(r02)*(x12979)))+(((IkReal(-1.00000000000000))*(r10)*(x12986)*(x12992)))+(((IkReal(-1.00000000000000))*(x12981)*(x12983)*(x12991)))+(((cj4)*(x12982)*(x12984)))+(((IkReal(-1.00000000000000))*(r01)*(x12994)))+(((r11)*(x12993)))+(((r00)*(sj0)*(x12986))));
42409 evalcond[5]=((((IkReal(-1.00000000000000))*(x12980)*(x12981)*(x12983)))+(((r01)*(x12993)))+(((r11)*(x12994)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x12986)))+(((IkReal(-1.00000000000000))*(x12981)*(x12984)*(x12985)))+(x12977)+(((IkReal(-1.00000000000000))*(r02)*(x12981)*(x12987)))+(((IkReal(-1.00000000000000))*(x12981)*(x12984)*(x12991)))+(((IkReal(-1.00000000000000))*(x12981)*(x12982)*(x12983)))+(((IkReal(-1.00000000000000))*(r00)*(x12986)*(x12992)))+(((IkReal(-1.00000000000000))*(r12)*(x12979)*(x12981))));
42410 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
42411 {
42412 continue;
42413 }
42414 }
42415 
42416 {
42417 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42418 vinfos[0].jointtype = 1;
42419 vinfos[0].foffset = j0;
42420 vinfos[0].indices[0] = _ij0[0];
42421 vinfos[0].indices[1] = _ij0[1];
42422 vinfos[0].maxsolutions = _nj0;
42423 vinfos[1].jointtype = 1;
42424 vinfos[1].foffset = j1;
42425 vinfos[1].indices[0] = _ij1[0];
42426 vinfos[1].indices[1] = _ij1[1];
42427 vinfos[1].maxsolutions = _nj1;
42428 vinfos[2].jointtype = 1;
42429 vinfos[2].foffset = j2;
42430 vinfos[2].indices[0] = _ij2[0];
42431 vinfos[2].indices[1] = _ij2[1];
42432 vinfos[2].maxsolutions = _nj2;
42433 vinfos[3].jointtype = 1;
42434 vinfos[3].foffset = j3;
42435 vinfos[3].indices[0] = _ij3[0];
42436 vinfos[3].indices[1] = _ij3[1];
42437 vinfos[3].maxsolutions = _nj3;
42438 vinfos[4].jointtype = 1;
42439 vinfos[4].foffset = j4;
42440 vinfos[4].indices[0] = _ij4[0];
42441 vinfos[4].indices[1] = _ij4[1];
42442 vinfos[4].maxsolutions = _nj4;
42443 vinfos[5].jointtype = 1;
42444 vinfos[5].foffset = j5;
42445 vinfos[5].indices[0] = _ij5[0];
42446 vinfos[5].indices[1] = _ij5[1];
42447 vinfos[5].maxsolutions = _nj5;
42448 vinfos[6].jointtype = 1;
42449 vinfos[6].foffset = j6;
42450 vinfos[6].indices[0] = _ij6[0];
42451 vinfos[6].indices[1] = _ij6[1];
42452 vinfos[6].maxsolutions = _nj6;
42453 std::vector<int> vfree(0);
42454 solutions.AddSolution(vinfos,vfree);
42455 }
42456 }
42457 }
42458 
42459 }
42460 
42461 }
42462 
42463 } else
42464 {
42465 IkReal x12995=((IkReal(1.00000000000000))*(cj0));
42466 IkReal x12996=((cj4)*(sj6));
42467 IkReal x12997=((sj0)*(sj4));
42468 IkReal x12998=((cj5)*(sj6));
42469 IkReal x12999=((sj4)*(sj5));
42470 IkReal x13000=((r12)*(sj5));
42471 IkReal x13001=((IkReal(0.374290000000000))*(cj5));
42472 IkReal x13002=((r02)*(sj0));
42473 IkReal x13003=((IkReal(1.00000000000000))*(sj0));
42474 IkReal x13004=((cj0)*(r10));
42475 IkReal x13005=((cj4)*(cj6));
42476 IkReal x13006=((r00)*(sj0));
42477 IkReal x13007=((cj6)*(r21));
42478 IkReal x13008=((IkReal(0.374290000000000))*(sj5));
42479 IkReal x13009=((IkReal(0.0100000000000000))*(sj5));
42480 IkReal x13010=((cj0)*(r02));
42481 IkReal x13011=((cj5)*(sj4));
42482 IkReal x13012=((cj6)*(r01));
42483 IkReal x13013=((cj0)*(r00));
42484 IkReal x13014=((cj6)*(r11));
42485 IkReal x13015=((r01)*(sj0));
42486 IkReal x13016=((r10)*(sj0));
42487 IkReal x13017=((IkReal(0.0100000000000000))*(cj5)*(cj6));
42488 IkReal x13018=((sj6)*(x13008));
42489 IkReal x13019=((cj0)*(cj6)*(x13008));
42490 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j2)), IkReal(6.28318530717959))));
42491 evalcond[1]=((((x13007)*(x13011)))+(((r21)*(x12996)))+(((r20)*(sj4)*(x12998)))+(((IkReal(-1.00000000000000))*(cj1)))+(((r22)*(x12999)))+(((IkReal(-1.00000000000000))*(r20)*(x13005))));
42492 evalcond[2]=((((IkReal(-0.0100000000000000))*(cj5)*(x13007)))+(((x13007)*(x13008)))+(((r20)*(x13018)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x13009)))+(((IkReal(-1.00000000000000))*(r22)*(x13001)))+(((IkReal(-0.0100000000000000))*(r20)*(x12998)))+(pz));
42493 evalcond[3]=((((r00)*(x12997)*(x12998)))+(((r02)*(sj5)*(x12997)))+(((IkReal(-1.00000000000000))*(r10)*(sj4)*(x12995)*(x12998)))+(((IkReal(-1.00000000000000))*(r11)*(x12995)*(x12996)))+(((x12996)*(x13015)))+(((x13004)*(x13005)))+(((IkReal(-1.00000000000000))*(r12)*(x12995)*(x12999)))+(((IkReal(-1.00000000000000))*(x12995)*(x13011)*(x13014)))+(((IkReal(-1.00000000000000))*(r00)*(x13003)*(x13005)))+(((cj5)*(x12997)*(x13012))));
42494 evalcond[4]=((((IkReal(-1.00000000000000))*(r02)*(x12995)*(x12999)))+(((IkReal(-1.00000000000000))*(x12997)*(x13000)))+(((IkReal(-1.00000000000000))*(r01)*(x12995)*(x12996)))+(sj1)+(((IkReal(-1.00000000000000))*(r11)*(x12996)*(x13003)))+(((x13005)*(x13016)))+(((x13005)*(x13013)))+(((IkReal(-1.00000000000000))*(r10)*(x12997)*(x12998)))+(((IkReal(-1.00000000000000))*(x12995)*(x13011)*(x13012)))+(((IkReal(-1.00000000000000))*(cj5)*(x12997)*(x13014)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x12995)*(x12998))));
42495 evalcond[5]=((IkReal(0.0690000000000000))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x13014)))+(((IkReal(-1.00000000000000))*(py)*(x12995)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x13012)))+(((IkReal(-0.0100000000000000))*(x12998)*(x13006)))+(((IkReal(-1.00000000000000))*(x13002)*(x13009)))+(((IkReal(-1.00000000000000))*(cj0)*(x13008)*(x13014)))+(((IkReal(-1.00000000000000))*(x13001)*(x13002)))+(((cj0)*(r12)*(x13001)))+(((IkReal(-1.00000000000000))*(x13004)*(x13018)))+(((IkReal(0.0100000000000000))*(x12998)*(x13004)))+(((x13006)*(x13018)))+(((sj0)*(x13008)*(x13012)))+(((IkReal(0.0100000000000000))*(cj0)*(x13000)))+(((px)*(sj0))));
42496 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x13008)*(x13012)))+(((IkReal(-1.00000000000000))*(py)*(x13003)))+(((IkReal(0.0100000000000000))*(x12998)*(x13016)))+(((IkReal(0.0100000000000000))*(x12998)*(x13013)))+(((IkReal(-1.00000000000000))*(x13013)*(x13018)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x13012)))+(((IkReal(-1.00000000000000))*(x13016)*(x13018)))+(((r12)*(sj0)*(x13001)))+(((x13001)*(x13010)))+(((IkReal(-1.00000000000000))*(px)*(x12995)))+(((IkReal(0.0100000000000000))*(sj0)*(x13000)))+(((x13009)*(x13010)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj0)*(x13008)*(x13014)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x13014))));
42497 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
42498 {
42499 {
42500 IkReal dummyeval[1];
42501 IkReal gconst11;
42502 gconst11=IKsign(sj1);
42503 dummyeval[0]=sj1;
42504 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
42505 {
42506 {
42507 IkReal dummyeval[1];
42508 dummyeval[0]=sj1;
42509 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
42510 {
42511 {
42512 IkReal dummyeval[1];
42513 dummyeval[0]=cj1;
42514 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
42515 {
42516 {
42517 IkReal evalcond[9];
42518 IkReal x13020=((IkReal(1.00000000000000))*(cj0));
42519 IkReal x13021=((cj4)*(sj6));
42520 IkReal x13022=((sj0)*(sj6));
42521 IkReal x13023=((cj5)*(sj4));
42522 IkReal x13024=((IkReal(0.374290000000000))*(sj5));
42523 IkReal x13025=((sj4)*(sj5));
42524 IkReal x13026=((cj0)*(cj6));
42525 IkReal x13027=((IkReal(0.0100000000000000))*(cj5));
42526 IkReal x13028=((cj4)*(sj5));
42527 IkReal x13029=((cj5)*(sj0));
42528 IkReal x13030=((IkReal(0.374290000000000))*(r02));
42529 IkReal x13031=((r20)*(sj6));
42530 IkReal x13032=((cj6)*(r21));
42531 IkReal x13033=((IkReal(1.00000000000000))*(sj0));
42532 IkReal x13034=((cj0)*(sj6));
42533 IkReal x13035=((cj4)*(cj6));
42534 IkReal x13036=((IkReal(0.374290000000000))*(r12));
42535 IkReal x13037=((cj0)*(cj5));
42536 IkReal x13038=((cj6)*(sj5));
42537 IkReal x13039=((cj6)*(r01));
42538 IkReal x13040=((r00)*(sj6));
42539 IkReal x13041=((IkReal(0.0100000000000000))*(sj5));
42540 IkReal x13042=((cj6)*(r11));
42541 IkReal x13043=((IkReal(1.00000000000000))*(r10));
42542 IkReal x13044=((r02)*(sj0));
42543 IkReal x13045=((cj6)*(sj4));
42544 IkReal x13046=((r12)*(x13033));
42545 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
42546 evalcond[1]=((((r22)*(x13025)))+(((IkReal(-1.00000000000000))*(r20)*(x13035)))+(((x13023)*(x13031)))+(((r21)*(x13021)))+(((x13023)*(x13032))));
42547 evalcond[2]=((IkReal(0.364420000000000))+(((x13024)*(x13031)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x13027)*(x13031)))+(pz)+(((IkReal(-1.00000000000000))*(x13027)*(x13032)))+(((x13024)*(x13032)))+(((IkReal(-1.00000000000000))*(r22)*(x13041))));
42548 evalcond[3]=((((r12)*(x13029)))+(((IkReal(-1.00000000000000))*(sj5)*(x13020)*(x13040)))+(((IkReal(-1.00000000000000))*(r11)*(x13033)*(x13038)))+(((r02)*(x13037)))+(((IkReal(-1.00000000000000))*(r01)*(x13020)*(x13038)))+(((IkReal(-1.00000000000000))*(sj5)*(x13022)*(x13043))));
42549 evalcond[4]=((((x13025)*(x13044)))+(((IkReal(-1.00000000000000))*(r11)*(x13020)*(x13021)))+(((cj4)*(r10)*(x13026)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x13020)*(x13023)))+(((r00)*(x13022)*(x13023)))+(((r01)*(sj0)*(x13021)))+(((IkReal(-1.00000000000000))*(x13020)*(x13023)*(x13042)))+(((IkReal(-1.00000000000000))*(r00)*(x13033)*(x13035)))+(((sj0)*(x13023)*(x13039)))+(((IkReal(-1.00000000000000))*(r12)*(x13020)*(x13025))));
42550 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x13020)*(x13023)*(x13040)))+(((IkReal(-1.00000000000000))*(x13025)*(x13046)))+(((IkReal(-1.00000000000000))*(r02)*(x13020)*(x13025)))+(((IkReal(-1.00000000000000))*(r01)*(x13020)*(x13021)))+(((cj4)*(r00)*(x13026)))+(((IkReal(-1.00000000000000))*(x13023)*(x13033)*(x13042)))+(((IkReal(-1.00000000000000))*(x13020)*(x13023)*(x13039)))+(((r10)*(sj0)*(x13035)))+(((IkReal(-1.00000000000000))*(x13022)*(x13023)*(x13043)))+(((IkReal(-1.00000000000000))*(r11)*(x13021)*(x13033))));
42551 evalcond[6]=((IkReal(0.0690000000000000))+(((r11)*(x13026)*(x13027)))+(((IkReal(-1.00000000000000))*(x13041)*(x13044)))+(((IkReal(-1.00000000000000))*(r00)*(x13022)*(x13027)))+(((IkReal(-1.00000000000000))*(r11)*(x13024)*(x13026)))+(((r00)*(x13022)*(x13024)))+(((IkReal(-1.00000000000000))*(sj0)*(x13027)*(x13039)))+(((IkReal(-1.00000000000000))*(r10)*(x13024)*(x13034)))+(((IkReal(-1.00000000000000))*(x13029)*(x13030)))+(((IkReal(-1.00000000000000))*(py)*(x13020)))+(((sj0)*(x13024)*(x13039)))+(((cj0)*(r12)*(x13041)))+(((x13036)*(x13037)))+(((r10)*(x13027)*(x13034)))+(((px)*(sj0))));
42552 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x13020)*(x13045)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x13020)*(x13021)))+(((r11)*(sj4)*(x13022)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x13020)*(x13035)))+(((IkReal(-1.00000000000000))*(x13021)*(x13029)*(x13043)))+(((IkReal(-1.00000000000000))*(r10)*(x13033)*(x13045)))+(((r01)*(sj4)*(x13034)))+(((IkReal(-1.00000000000000))*(r11)*(x13029)*(x13035)))+(((IkReal(-1.00000000000000))*(x13028)*(x13046)))+(((IkReal(-1.00000000000000))*(r02)*(x13020)*(x13028))));
42553 evalcond[8]=((IkReal(0.0690000000000000))+(((x13030)*(x13037)))+(((r00)*(x13027)*(x13034)))+(((r10)*(x13022)*(x13027)))+(((IkReal(-1.00000000000000))*(px)*(x13020)))+(((IkReal(-1.00000000000000))*(r00)*(x13024)*(x13034)))+(((IkReal(-1.00000000000000))*(r10)*(x13022)*(x13024)))+(((cj0)*(r02)*(x13041)))+(((x13029)*(x13036)))+(((r12)*(sj0)*(x13041)))+(((sj0)*(x13027)*(x13042)))+(((r01)*(x13026)*(x13027)))+(((IkReal(-1.00000000000000))*(sj0)*(x13024)*(x13042)))+(((IkReal(-1.00000000000000))*(r01)*(x13024)*(x13026)))+(((IkReal(-1.00000000000000))*(py)*(x13033))));
42554 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
42555 {
42556 {
42557 IkReal j3array[1], cj3array[1], sj3array[1];
42558 bool j3valid[1]={false};
42559 _nj3 = 1;
42560 IkReal x13047=((r20)*(sj6));
42561 IkReal x13048=((cj4)*(cj5));
42562 IkReal x13049=((cj6)*(r21));
42563 if( IKabs(((((x13047)*(x13048)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13048)*(x13049))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13047)))+(((sj5)*(x13049))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x13047)*(x13048)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13048)*(x13049)))))+IKsqr(((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13047)))+(((sj5)*(x13049)))))-1) <= IKFAST_SINCOS_THRESH )
42564     continue;
42565 j3array[0]=IKatan2(((((x13047)*(x13048)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13048)*(x13049)))), ((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13047)))+(((sj5)*(x13049)))));
42566 sj3array[0]=IKsin(j3array[0]);
42567 cj3array[0]=IKcos(j3array[0]);
42568 if( j3array[0] > IKPI )
42569 {
42570     j3array[0]-=IK2PI;
42571 }
42572 else if( j3array[0] < -IKPI )
42573 {    j3array[0]+=IK2PI;
42574 }
42575 j3valid[0] = true;
42576 for(int ij3 = 0; ij3 < 1; ++ij3)
42577 {
42578 if( !j3valid[ij3] )
42579 {
42580     continue;
42581 }
42582 _ij3[0] = ij3; _ij3[1] = -1;
42583 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42584 {
42585 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42586 {
42587     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42588 }
42589 }
42590 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42591 {
42592 IkReal evalcond[4];
42593 IkReal x13050=IKcos(j3);
42594 IkReal x13051=((sj0)*(sj5));
42595 IkReal x13052=((r00)*(sj6));
42596 IkReal x13053=((cj6)*(r01));
42597 IkReal x13054=((cj5)*(sj0));
42598 IkReal x13055=((cj0)*(cj5));
42599 IkReal x13056=((cj6)*(sj4));
42600 IkReal x13057=((sj4)*(sj6));
42601 IkReal x13058=((cj0)*(r11));
42602 IkReal x13059=((cj4)*(cj6));
42603 IkReal x13060=((cj4)*(sj6));
42604 IkReal x13061=((IkReal(1.00000000000000))*(cj0));
42605 IkReal x13062=((cj4)*(sj5));
42606 IkReal x13063=((sj5)*(sj6));
42607 IkReal x13064=((cj6)*(sj5));
42608 IkReal x13065=((IkReal(1.00000000000000))*(IKsin(j3)));
42609 evalcond[0]=((((IkReal(-1.00000000000000))*(x13050)))+(((r21)*(x13064)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x13063))));
42610 evalcond[1]=((((r22)*(x13062)))+(((IkReal(-1.00000000000000))*(r21)*(x13057)))+(((IkReal(-1.00000000000000))*(x13065)))+(((r20)*(x13056)))+(((cj5)*(r20)*(x13060)))+(((cj5)*(r21)*(x13059))));
42611 evalcond[2]=((((r12)*(x13055)))+(((x13051)*(x13052)))+(((IkReal(-1.00000000000000))*(x13058)*(x13064)))+(((x13051)*(x13053)))+(((IkReal(-1.00000000000000))*(x13065)))+(((IkReal(-1.00000000000000))*(r10)*(x13061)*(x13063)))+(((IkReal(-1.00000000000000))*(r02)*(x13054))));
42612 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x13057)))+(((x13057)*(x13058)))+(((r00)*(sj0)*(x13056)))+(((IkReal(-1.00000000000000))*(r10)*(x13056)*(x13061)))+(((IkReal(-1.00000000000000))*(r12)*(x13061)*(x13062)))+(((cj4)*(r02)*(x13051)))+(((IkReal(-1.00000000000000))*(r11)*(x13055)*(x13059)))+(((IkReal(-1.00000000000000))*(r10)*(x13055)*(x13060)))+(((cj4)*(x13053)*(x13054)))+(x13050)+(((cj4)*(x13052)*(x13054))));
42613 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
42614 {
42615 continue;
42616 }
42617 }
42618 
42619 {
42620 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42621 vinfos[0].jointtype = 1;
42622 vinfos[0].foffset = j0;
42623 vinfos[0].indices[0] = _ij0[0];
42624 vinfos[0].indices[1] = _ij0[1];
42625 vinfos[0].maxsolutions = _nj0;
42626 vinfos[1].jointtype = 1;
42627 vinfos[1].foffset = j1;
42628 vinfos[1].indices[0] = _ij1[0];
42629 vinfos[1].indices[1] = _ij1[1];
42630 vinfos[1].maxsolutions = _nj1;
42631 vinfos[2].jointtype = 1;
42632 vinfos[2].foffset = j2;
42633 vinfos[2].indices[0] = _ij2[0];
42634 vinfos[2].indices[1] = _ij2[1];
42635 vinfos[2].maxsolutions = _nj2;
42636 vinfos[3].jointtype = 1;
42637 vinfos[3].foffset = j3;
42638 vinfos[3].indices[0] = _ij3[0];
42639 vinfos[3].indices[1] = _ij3[1];
42640 vinfos[3].maxsolutions = _nj3;
42641 vinfos[4].jointtype = 1;
42642 vinfos[4].foffset = j4;
42643 vinfos[4].indices[0] = _ij4[0];
42644 vinfos[4].indices[1] = _ij4[1];
42645 vinfos[4].maxsolutions = _nj4;
42646 vinfos[5].jointtype = 1;
42647 vinfos[5].foffset = j5;
42648 vinfos[5].indices[0] = _ij5[0];
42649 vinfos[5].indices[1] = _ij5[1];
42650 vinfos[5].maxsolutions = _nj5;
42651 vinfos[6].jointtype = 1;
42652 vinfos[6].foffset = j6;
42653 vinfos[6].indices[0] = _ij6[0];
42654 vinfos[6].indices[1] = _ij6[1];
42655 vinfos[6].maxsolutions = _nj6;
42656 std::vector<int> vfree(0);
42657 solutions.AddSolution(vinfos,vfree);
42658 }
42659 }
42660 }
42661 
42662 } else
42663 {
42664 IkReal x13066=((IkReal(1.00000000000000))*(cj0));
42665 IkReal x13067=((cj4)*(sj6));
42666 IkReal x13068=((sj0)*(sj6));
42667 IkReal x13069=((cj5)*(sj4));
42668 IkReal x13070=((IkReal(0.374290000000000))*(sj5));
42669 IkReal x13071=((sj4)*(sj5));
42670 IkReal x13072=((cj0)*(cj6));
42671 IkReal x13073=((IkReal(0.0100000000000000))*(cj5));
42672 IkReal x13074=((cj4)*(sj5));
42673 IkReal x13075=((cj5)*(sj0));
42674 IkReal x13076=((IkReal(0.374290000000000))*(r02));
42675 IkReal x13077=((r20)*(sj6));
42676 IkReal x13078=((cj6)*(r21));
42677 IkReal x13079=((IkReal(1.00000000000000))*(sj0));
42678 IkReal x13080=((cj0)*(sj6));
42679 IkReal x13081=((cj4)*(cj6));
42680 IkReal x13082=((IkReal(0.374290000000000))*(r12));
42681 IkReal x13083=((cj0)*(cj5));
42682 IkReal x13084=((cj6)*(sj5));
42683 IkReal x13085=((cj6)*(r01));
42684 IkReal x13086=((r00)*(sj6));
42685 IkReal x13087=((IkReal(0.0100000000000000))*(sj5));
42686 IkReal x13088=((cj6)*(r11));
42687 IkReal x13089=((IkReal(1.00000000000000))*(r10));
42688 IkReal x13090=((r02)*(sj0));
42689 IkReal x13091=((cj6)*(sj4));
42690 IkReal x13092=((r12)*(x13079));
42691 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
42692 evalcond[1]=((((x13069)*(x13078)))+(((r22)*(x13071)))+(((IkReal(-1.00000000000000))*(r20)*(x13081)))+(((x13069)*(x13077)))+(((r21)*(x13067))));
42693 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x13073)*(x13077)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(r22)*(x13087)))+(((x13070)*(x13078)))+(((IkReal(-1.00000000000000))*(x13073)*(x13078)))+(pz)+(((x13070)*(x13077))));
42694 evalcond[3]=((((r02)*(x13083)))+(((IkReal(-1.00000000000000))*(sj5)*(x13066)*(x13086)))+(((IkReal(-1.00000000000000))*(r11)*(x13079)*(x13084)))+(((r12)*(x13075)))+(((IkReal(-1.00000000000000))*(r01)*(x13066)*(x13084)))+(((IkReal(-1.00000000000000))*(sj5)*(x13068)*(x13089))));
42695 evalcond[4]=((((IkReal(-1.00000000000000))*(x13066)*(x13069)*(x13088)))+(((r01)*(sj0)*(x13067)))+(((IkReal(-1.00000000000000))*(r11)*(x13066)*(x13067)))+(((sj0)*(x13069)*(x13085)))+(((x13071)*(x13090)))+(((IkReal(-1.00000000000000))*(r00)*(x13079)*(x13081)))+(((r00)*(x13068)*(x13069)))+(((IkReal(-1.00000000000000))*(r12)*(x13066)*(x13071)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x13066)*(x13069)))+(((cj4)*(r10)*(x13072))));
42696 evalcond[5]=((IkReal(-1.00000000000000))+(((r10)*(sj0)*(x13081)))+(((IkReal(-1.00000000000000))*(x13071)*(x13092)))+(((IkReal(-1.00000000000000))*(r11)*(x13067)*(x13079)))+(((IkReal(-1.00000000000000))*(x13068)*(x13069)*(x13089)))+(((cj4)*(r00)*(x13072)))+(((IkReal(-1.00000000000000))*(x13069)*(x13079)*(x13088)))+(((IkReal(-1.00000000000000))*(x13066)*(x13069)*(x13085)))+(((IkReal(-1.00000000000000))*(x13066)*(x13069)*(x13086)))+(((IkReal(-1.00000000000000))*(r01)*(x13066)*(x13067)))+(((IkReal(-1.00000000000000))*(r02)*(x13066)*(x13071))));
42697 evalcond[6]=((IkReal(0.0690000000000000))+(((r10)*(x13073)*(x13080)))+(((IkReal(-1.00000000000000))*(py)*(x13066)))+(((IkReal(-1.00000000000000))*(r10)*(x13070)*(x13080)))+(((IkReal(-1.00000000000000))*(sj0)*(x13073)*(x13085)))+(((IkReal(-1.00000000000000))*(x13075)*(x13076)))+(((IkReal(-1.00000000000000))*(r00)*(x13068)*(x13073)))+(((r11)*(x13072)*(x13073)))+(((IkReal(-1.00000000000000))*(x13087)*(x13090)))+(((x13082)*(x13083)))+(((cj0)*(r12)*(x13087)))+(((IkReal(-1.00000000000000))*(r11)*(x13070)*(x13072)))+(((r00)*(x13068)*(x13070)))+(((sj0)*(x13070)*(x13085)))+(((px)*(sj0))));
42698 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x13066)*(x13091)))+(((IkReal(-1.00000000000000))*(r11)*(x13075)*(x13081)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x13066)*(x13081)))+(((r11)*(sj4)*(x13068)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x13066)*(x13067)))+(((IkReal(-1.00000000000000))*(r10)*(x13079)*(x13091)))+(((IkReal(-1.00000000000000))*(r02)*(x13066)*(x13074)))+(((r01)*(sj4)*(x13080)))+(((IkReal(-1.00000000000000))*(x13067)*(x13075)*(x13089)))+(((IkReal(-1.00000000000000))*(x13074)*(x13092))));
42699 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(px)*(x13066)))+(((r00)*(x13073)*(x13080)))+(((r10)*(x13068)*(x13073)))+(((IkReal(-1.00000000000000))*(r00)*(x13070)*(x13080)))+(((cj0)*(r02)*(x13087)))+(((r01)*(x13072)*(x13073)))+(((x13075)*(x13082)))+(((IkReal(-1.00000000000000))*(sj0)*(x13070)*(x13088)))+(((r12)*(sj0)*(x13087)))+(((IkReal(-1.00000000000000))*(py)*(x13079)))+(((IkReal(-1.00000000000000))*(r01)*(x13070)*(x13072)))+(((x13076)*(x13083)))+(((IkReal(-1.00000000000000))*(r10)*(x13068)*(x13070)))+(((sj0)*(x13073)*(x13088))));
42700 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
42701 {
42702 {
42703 IkReal j3array[1], cj3array[1], sj3array[1];
42704 bool j3valid[1]={false};
42705 _nj3 = 1;
42706 IkReal x13093=((IkReal(1.00000000000000))*(sj5));
42707 IkReal x13094=((cj6)*(r21));
42708 IkReal x13095=((r20)*(sj6));
42709 IkReal x13096=((IkReal(1.00000000000000))*(cj4)*(cj5));
42710 if( IKabs(((((IkReal(-1.00000000000000))*(x13095)*(x13096)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x13094)*(x13096)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13093)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x13093)*(x13094)))+(((IkReal(-1.00000000000000))*(x13093)*(x13095)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x13095)*(x13096)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x13094)*(x13096)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13093)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x13093)*(x13094)))+(((IkReal(-1.00000000000000))*(x13093)*(x13095)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
42711     continue;
42712 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x13095)*(x13096)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x13094)*(x13096)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13093)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x13093)*(x13094)))+(((IkReal(-1.00000000000000))*(x13093)*(x13095)))+(((cj5)*(r22)))));
42713 sj3array[0]=IKsin(j3array[0]);
42714 cj3array[0]=IKcos(j3array[0]);
42715 if( j3array[0] > IKPI )
42716 {
42717     j3array[0]-=IK2PI;
42718 }
42719 else if( j3array[0] < -IKPI )
42720 {    j3array[0]+=IK2PI;
42721 }
42722 j3valid[0] = true;
42723 for(int ij3 = 0; ij3 < 1; ++ij3)
42724 {
42725 if( !j3valid[ij3] )
42726 {
42727     continue;
42728 }
42729 _ij3[0] = ij3; _ij3[1] = -1;
42730 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42731 {
42732 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42733 {
42734     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42735 }
42736 }
42737 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42738 {
42739 IkReal evalcond[4];
42740 IkReal x13097=IKsin(j3);
42741 IkReal x13098=IKcos(j3);
42742 IkReal x13099=((sj0)*(sj5));
42743 IkReal x13100=((r00)*(sj6));
42744 IkReal x13101=((cj6)*(r01));
42745 IkReal x13102=((cj5)*(sj0));
42746 IkReal x13103=((cj0)*(cj5));
42747 IkReal x13104=((cj6)*(sj4));
42748 IkReal x13105=((sj4)*(sj6));
42749 IkReal x13106=((cj0)*(r11));
42750 IkReal x13107=((cj4)*(cj6));
42751 IkReal x13108=((cj4)*(sj6));
42752 IkReal x13109=((IkReal(1.00000000000000))*(cj0));
42753 IkReal x13110=((cj4)*(sj5));
42754 IkReal x13111=((sj5)*(sj6));
42755 IkReal x13112=((cj6)*(sj5));
42756 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((r20)*(x13111)))+(x13098)+(((r21)*(x13112))));
42757 evalcond[1]=((((cj5)*(r21)*(x13107)))+(((IkReal(-1.00000000000000))*(r21)*(x13105)))+(((r22)*(x13110)))+(x13097)+(((cj5)*(r20)*(x13108)))+(((r20)*(x13104))));
42758 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x13102)))+(((IkReal(-1.00000000000000))*(x13106)*(x13112)))+(((x13099)*(x13100)))+(((IkReal(-1.00000000000000))*(r10)*(x13109)*(x13111)))+(((x13099)*(x13101)))+(((IkReal(-1.00000000000000))*(x13097)))+(((r12)*(x13103))));
42759 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x13103)*(x13108)))+(((cj4)*(r02)*(x13099)))+(((IkReal(-1.00000000000000))*(r11)*(x13103)*(x13107)))+(((IkReal(-1.00000000000000))*(r10)*(x13104)*(x13109)))+(((x13105)*(x13106)))+(((r00)*(sj0)*(x13104)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x13105)))+(((IkReal(-1.00000000000000))*(r12)*(x13109)*(x13110)))+(x13098)+(((cj4)*(x13100)*(x13102)))+(((cj4)*(x13101)*(x13102))));
42760 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
42761 {
42762 continue;
42763 }
42764 }
42765 
42766 {
42767 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42768 vinfos[0].jointtype = 1;
42769 vinfos[0].foffset = j0;
42770 vinfos[0].indices[0] = _ij0[0];
42771 vinfos[0].indices[1] = _ij0[1];
42772 vinfos[0].maxsolutions = _nj0;
42773 vinfos[1].jointtype = 1;
42774 vinfos[1].foffset = j1;
42775 vinfos[1].indices[0] = _ij1[0];
42776 vinfos[1].indices[1] = _ij1[1];
42777 vinfos[1].maxsolutions = _nj1;
42778 vinfos[2].jointtype = 1;
42779 vinfos[2].foffset = j2;
42780 vinfos[2].indices[0] = _ij2[0];
42781 vinfos[2].indices[1] = _ij2[1];
42782 vinfos[2].maxsolutions = _nj2;
42783 vinfos[3].jointtype = 1;
42784 vinfos[3].foffset = j3;
42785 vinfos[3].indices[0] = _ij3[0];
42786 vinfos[3].indices[1] = _ij3[1];
42787 vinfos[3].maxsolutions = _nj3;
42788 vinfos[4].jointtype = 1;
42789 vinfos[4].foffset = j4;
42790 vinfos[4].indices[0] = _ij4[0];
42791 vinfos[4].indices[1] = _ij4[1];
42792 vinfos[4].maxsolutions = _nj4;
42793 vinfos[5].jointtype = 1;
42794 vinfos[5].foffset = j5;
42795 vinfos[5].indices[0] = _ij5[0];
42796 vinfos[5].indices[1] = _ij5[1];
42797 vinfos[5].maxsolutions = _nj5;
42798 vinfos[6].jointtype = 1;
42799 vinfos[6].foffset = j6;
42800 vinfos[6].indices[0] = _ij6[0];
42801 vinfos[6].indices[1] = _ij6[1];
42802 vinfos[6].maxsolutions = _nj6;
42803 std::vector<int> vfree(0);
42804 solutions.AddSolution(vinfos,vfree);
42805 }
42806 }
42807 }
42808 
42809 } else
42810 {
42811 if( 1 )
42812 {
42813 continue;
42814 
42815 } else
42816 {
42817 }
42818 }
42819 }
42820 }
42821 
42822 } else
42823 {
42824 {
42825 IkReal j3array[1], cj3array[1], sj3array[1];
42826 bool j3valid[1]={false};
42827 _nj3 = 1;
42828 IkReal x13113=((cj0)*(cj5));
42829 IkReal x13114=((IkReal(1.00000000000000))*(cj0));
42830 IkReal x13115=((cj6)*(r11));
42831 IkReal x13116=((r10)*(sj6));
42832 IkReal x13117=((cj5)*(sj0));
42833 IkReal x13118=((r00)*(sj5)*(sj6));
42834 IkReal x13119=((cj6)*(r01)*(sj5));
42835 IkReal x13120=((IkReal(1.00000000000000))*(sj0)*(sj5));
42836 if( IKabs(((((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13115)))+(((r12)*(x13113)))+(((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13116)))+(((sj0)*(x13118)))+(((sj0)*(x13119)))+(((IkReal(-1.00000000000000))*(r02)*(x13117))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x13113)))+(((IkReal(-1.00000000000000))*(x13114)*(x13119)))+(((r12)*(x13117)))+(((IkReal(-1.00000000000000))*(x13114)*(x13118)))+(((IkReal(-1.00000000000000))*(x13115)*(x13120)))+(((IkReal(-1.00000000000000))*(x13116)*(x13120))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13115)))+(((r12)*(x13113)))+(((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13116)))+(((sj0)*(x13118)))+(((sj0)*(x13119)))+(((IkReal(-1.00000000000000))*(r02)*(x13117)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x13113)))+(((IkReal(-1.00000000000000))*(x13114)*(x13119)))+(((r12)*(x13117)))+(((IkReal(-1.00000000000000))*(x13114)*(x13118)))+(((IkReal(-1.00000000000000))*(x13115)*(x13120)))+(((IkReal(-1.00000000000000))*(x13116)*(x13120)))))))-1) <= IKFAST_SINCOS_THRESH )
42837     continue;
42838 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13115)))+(((r12)*(x13113)))+(((IkReal(-1.00000000000000))*(sj5)*(x13114)*(x13116)))+(((sj0)*(x13118)))+(((sj0)*(x13119)))+(((IkReal(-1.00000000000000))*(r02)*(x13117)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((r02)*(x13113)))+(((IkReal(-1.00000000000000))*(x13114)*(x13119)))+(((r12)*(x13117)))+(((IkReal(-1.00000000000000))*(x13114)*(x13118)))+(((IkReal(-1.00000000000000))*(x13115)*(x13120)))+(((IkReal(-1.00000000000000))*(x13116)*(x13120)))))));
42839 sj3array[0]=IKsin(j3array[0]);
42840 cj3array[0]=IKcos(j3array[0]);
42841 if( j3array[0] > IKPI )
42842 {
42843     j3array[0]-=IK2PI;
42844 }
42845 else if( j3array[0] < -IKPI )
42846 {    j3array[0]+=IK2PI;
42847 }
42848 j3valid[0] = true;
42849 for(int ij3 = 0; ij3 < 1; ++ij3)
42850 {
42851 if( !j3valid[ij3] )
42852 {
42853     continue;
42854 }
42855 _ij3[0] = ij3; _ij3[1] = -1;
42856 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42857 {
42858 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42859 {
42860     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42861 }
42862 }
42863 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42864 {
42865 IkReal evalcond[6];
42866 IkReal x13121=IKsin(j3);
42867 IkReal x13122=IKcos(j3);
42868 IkReal x13123=((sj0)*(sj5));
42869 IkReal x13124=((r00)*(sj6));
42870 IkReal x13125=((cj6)*(r01));
42871 IkReal x13126=((cj4)*(cj5));
42872 IkReal x13127=((IkReal(1.00000000000000))*(cj0));
42873 IkReal x13128=((cj5)*(r12));
42874 IkReal x13129=((IkReal(1.00000000000000))*(sj0));
42875 IkReal x13130=((cj6)*(r11));
42876 IkReal x13131=((cj5)*(r02));
42877 IkReal x13132=((IkReal(1.00000000000000))*(cj1));
42878 IkReal x13133=((cj6)*(sj4));
42879 IkReal x13134=((cj6)*(r21));
42880 IkReal x13135=((r20)*(sj6));
42881 IkReal x13136=((r10)*(sj6));
42882 IkReal x13137=((sj4)*(sj6));
42883 IkReal x13138=((cj4)*(r02));
42884 IkReal x13139=((IkReal(1.00000000000000))*(cj4)*(r12));
42885 IkReal x13140=((IkReal(1.00000000000000))*(x13121));
42886 IkReal x13141=((cj0)*(x13137));
42887 evalcond[0]=((((sj5)*(x13135)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x13122)))+(((sj5)*(x13134))));
42888 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x13137)))+(((cj4)*(r22)*(sj5)))+(((IkReal(-1.00000000000000))*(sj1)*(x13140)))+(((x13126)*(x13134)))+(((x13126)*(x13135)))+(((r20)*(x13133))));
42889 evalcond[2]=((((cj0)*(x13128)))+(((x13123)*(x13125)))+(((IkReal(-1.00000000000000))*(sj5)*(x13127)*(x13130)))+(((IkReal(-1.00000000000000))*(x13140)))+(((IkReal(-1.00000000000000))*(sj5)*(x13127)*(x13136)))+(((IkReal(-1.00000000000000))*(x13129)*(x13131)))+(((x13123)*(x13124))));
42890 evalcond[3]=((((IkReal(-1.00000000000000))*(x13123)*(x13130)))+(((IkReal(-1.00000000000000))*(sj5)*(x13125)*(x13127)))+(((sj0)*(x13128)))+(((IkReal(-1.00000000000000))*(x13123)*(x13136)))+(((cj0)*(x13131)))+(((IkReal(-1.00000000000000))*(sj5)*(x13124)*(x13127)))+(((IkReal(-1.00000000000000))*(x13122)*(x13132))));
42891 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x13127)*(x13133)))+(((r00)*(sj0)*(x13133)))+(((x13123)*(x13138)))+(((IkReal(-1.00000000000000))*(x13126)*(x13127)*(x13136)))+(((r11)*(x13141)))+(((IkReal(-1.00000000000000))*(x13126)*(x13127)*(x13130)))+(((sj0)*(x13125)*(x13126)))+(((sj0)*(x13124)*(x13126)))+(((IkReal(-1.00000000000000))*(r01)*(x13129)*(x13137)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x13127)))+(x13122));
42892 evalcond[5]=((((r11)*(sj0)*(x13137)))+(((IkReal(-1.00000000000000))*(x13121)*(x13132)))+(((r01)*(x13141)))+(((IkReal(-1.00000000000000))*(r10)*(x13129)*(x13133)))+(((IkReal(-1.00000000000000))*(x13126)*(x13129)*(x13136)))+(((IkReal(-1.00000000000000))*(x13125)*(x13126)*(x13127)))+(((IkReal(-1.00000000000000))*(x13124)*(x13126)*(x13127)))+(((IkReal(-1.00000000000000))*(x13126)*(x13129)*(x13130)))+(((IkReal(-1.00000000000000))*(sj5)*(x13127)*(x13138)))+(((IkReal(-1.00000000000000))*(x13123)*(x13139)))+(((IkReal(-1.00000000000000))*(r00)*(x13127)*(x13133))));
42893 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
42894 {
42895 continue;
42896 }
42897 }
42898 
42899 {
42900 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
42901 vinfos[0].jointtype = 1;
42902 vinfos[0].foffset = j0;
42903 vinfos[0].indices[0] = _ij0[0];
42904 vinfos[0].indices[1] = _ij0[1];
42905 vinfos[0].maxsolutions = _nj0;
42906 vinfos[1].jointtype = 1;
42907 vinfos[1].foffset = j1;
42908 vinfos[1].indices[0] = _ij1[0];
42909 vinfos[1].indices[1] = _ij1[1];
42910 vinfos[1].maxsolutions = _nj1;
42911 vinfos[2].jointtype = 1;
42912 vinfos[2].foffset = j2;
42913 vinfos[2].indices[0] = _ij2[0];
42914 vinfos[2].indices[1] = _ij2[1];
42915 vinfos[2].maxsolutions = _nj2;
42916 vinfos[3].jointtype = 1;
42917 vinfos[3].foffset = j3;
42918 vinfos[3].indices[0] = _ij3[0];
42919 vinfos[3].indices[1] = _ij3[1];
42920 vinfos[3].maxsolutions = _nj3;
42921 vinfos[4].jointtype = 1;
42922 vinfos[4].foffset = j4;
42923 vinfos[4].indices[0] = _ij4[0];
42924 vinfos[4].indices[1] = _ij4[1];
42925 vinfos[4].maxsolutions = _nj4;
42926 vinfos[5].jointtype = 1;
42927 vinfos[5].foffset = j5;
42928 vinfos[5].indices[0] = _ij5[0];
42929 vinfos[5].indices[1] = _ij5[1];
42930 vinfos[5].maxsolutions = _nj5;
42931 vinfos[6].jointtype = 1;
42932 vinfos[6].foffset = j6;
42933 vinfos[6].indices[0] = _ij6[0];
42934 vinfos[6].indices[1] = _ij6[1];
42935 vinfos[6].maxsolutions = _nj6;
42936 std::vector<int> vfree(0);
42937 solutions.AddSolution(vinfos,vfree);
42938 }
42939 }
42940 }
42941 
42942 }
42943 
42944 }
42945 
42946 } else
42947 {
42948 {
42949 IkReal j3array[1], cj3array[1], sj3array[1];
42950 bool j3valid[1]={false};
42951 _nj3 = 1;
42952 IkReal x13142=((sj5)*(sj6));
42953 IkReal x13143=((cj6)*(sj5));
42954 IkReal x13144=((IkReal(1.00000000000000))*(cj0));
42955 IkReal x13145=((IkReal(1.00000000000000))*(cj5));
42956 if( IKabs(((((IkReal(-1.00000000000000))*(r11)*(x13143)*(x13144)))+(((r01)*(sj0)*(x13143)))+(((r00)*(sj0)*(x13142)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x13145)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x13142)*(x13144))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13145)))+(((r21)*(x13143)))+(((r20)*(x13142))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r11)*(x13143)*(x13144)))+(((r01)*(sj0)*(x13143)))+(((r00)*(sj0)*(x13142)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x13145)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x13142)*(x13144)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13145)))+(((r21)*(x13143)))+(((r20)*(x13142)))))))-1) <= IKFAST_SINCOS_THRESH )
42957     continue;
42958 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r11)*(x13143)*(x13144)))+(((r01)*(sj0)*(x13143)))+(((r00)*(sj0)*(x13142)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x13145)))+(((cj0)*(cj5)*(r12)))+(((IkReal(-1.00000000000000))*(r10)*(x13142)*(x13144)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13145)))+(((r21)*(x13143)))+(((r20)*(x13142)))))));
42959 sj3array[0]=IKsin(j3array[0]);
42960 cj3array[0]=IKcos(j3array[0]);
42961 if( j3array[0] > IKPI )
42962 {
42963     j3array[0]-=IK2PI;
42964 }
42965 else if( j3array[0] < -IKPI )
42966 {    j3array[0]+=IK2PI;
42967 }
42968 j3valid[0] = true;
42969 for(int ij3 = 0; ij3 < 1; ++ij3)
42970 {
42971 if( !j3valid[ij3] )
42972 {
42973     continue;
42974 }
42975 _ij3[0] = ij3; _ij3[1] = -1;
42976 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
42977 {
42978 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
42979 {
42980     j3valid[iij3]=false; _ij3[1] = iij3; break; 
42981 }
42982 }
42983 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
42984 {
42985 IkReal evalcond[6];
42986 IkReal x13146=IKsin(j3);
42987 IkReal x13147=IKcos(j3);
42988 IkReal x13148=((sj0)*(sj5));
42989 IkReal x13149=((r00)*(sj6));
42990 IkReal x13150=((cj6)*(r01));
42991 IkReal x13151=((cj4)*(cj5));
42992 IkReal x13152=((IkReal(1.00000000000000))*(cj0));
42993 IkReal x13153=((cj5)*(r12));
42994 IkReal x13154=((IkReal(1.00000000000000))*(sj0));
42995 IkReal x13155=((cj6)*(r11));
42996 IkReal x13156=((cj5)*(r02));
42997 IkReal x13157=((IkReal(1.00000000000000))*(cj1));
42998 IkReal x13158=((cj6)*(sj4));
42999 IkReal x13159=((cj6)*(r21));
43000 IkReal x13160=((r20)*(sj6));
43001 IkReal x13161=((r10)*(sj6));
43002 IkReal x13162=((sj4)*(sj6));
43003 IkReal x13163=((cj4)*(r02));
43004 IkReal x13164=((IkReal(1.00000000000000))*(cj4)*(r12));
43005 IkReal x13165=((IkReal(1.00000000000000))*(x13146));
43006 IkReal x13166=((cj0)*(x13162));
43007 evalcond[0]=((((sj5)*(x13159)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(sj1)*(x13147)))+(((sj5)*(x13160))));
43008 evalcond[1]=((((x13151)*(x13159)))+(((r20)*(x13158)))+(((cj4)*(r22)*(sj5)))+(((x13151)*(x13160)))+(((IkReal(-1.00000000000000))*(sj1)*(x13165)))+(((IkReal(-1.00000000000000))*(r21)*(x13162))));
43009 evalcond[2]=((((IkReal(-1.00000000000000))*(x13165)))+(((IkReal(-1.00000000000000))*(sj5)*(x13152)*(x13161)))+(((cj0)*(x13153)))+(((x13148)*(x13150)))+(((x13148)*(x13149)))+(((IkReal(-1.00000000000000))*(sj5)*(x13152)*(x13155)))+(((IkReal(-1.00000000000000))*(x13154)*(x13156))));
43010 evalcond[3]=((((sj0)*(x13153)))+(((IkReal(-1.00000000000000))*(x13147)*(x13157)))+(((IkReal(-1.00000000000000))*(sj5)*(x13150)*(x13152)))+(((IkReal(-1.00000000000000))*(sj5)*(x13149)*(x13152)))+(((cj0)*(x13156)))+(((IkReal(-1.00000000000000))*(x13148)*(x13161)))+(((IkReal(-1.00000000000000))*(x13148)*(x13155))));
43011 evalcond[4]=((((r11)*(x13166)))+(((x13148)*(x13163)))+(((r00)*(sj0)*(x13158)))+(((sj0)*(x13149)*(x13151)))+(x13147)+(((IkReal(-1.00000000000000))*(x13151)*(x13152)*(x13155)))+(((IkReal(-1.00000000000000))*(r01)*(x13154)*(x13162)))+(((IkReal(-1.00000000000000))*(x13151)*(x13152)*(x13161)))+(((IkReal(-1.00000000000000))*(r10)*(x13152)*(x13158)))+(((sj0)*(x13150)*(x13151)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x13152))));
43012 evalcond[5]=((((r01)*(x13166)))+(((IkReal(-1.00000000000000))*(x13149)*(x13151)*(x13152)))+(((IkReal(-1.00000000000000))*(sj5)*(x13152)*(x13163)))+(((IkReal(-1.00000000000000))*(r00)*(x13152)*(x13158)))+(((IkReal(-1.00000000000000))*(x13150)*(x13151)*(x13152)))+(((IkReal(-1.00000000000000))*(r10)*(x13154)*(x13158)))+(((IkReal(-1.00000000000000))*(x13151)*(x13154)*(x13155)))+(((IkReal(-1.00000000000000))*(x13146)*(x13157)))+(((r11)*(sj0)*(x13162)))+(((IkReal(-1.00000000000000))*(x13148)*(x13164)))+(((IkReal(-1.00000000000000))*(x13151)*(x13154)*(x13161))));
43013 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43014 {
43015 continue;
43016 }
43017 }
43018 
43019 {
43020 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43021 vinfos[0].jointtype = 1;
43022 vinfos[0].foffset = j0;
43023 vinfos[0].indices[0] = _ij0[0];
43024 vinfos[0].indices[1] = _ij0[1];
43025 vinfos[0].maxsolutions = _nj0;
43026 vinfos[1].jointtype = 1;
43027 vinfos[1].foffset = j1;
43028 vinfos[1].indices[0] = _ij1[0];
43029 vinfos[1].indices[1] = _ij1[1];
43030 vinfos[1].maxsolutions = _nj1;
43031 vinfos[2].jointtype = 1;
43032 vinfos[2].foffset = j2;
43033 vinfos[2].indices[0] = _ij2[0];
43034 vinfos[2].indices[1] = _ij2[1];
43035 vinfos[2].maxsolutions = _nj2;
43036 vinfos[3].jointtype = 1;
43037 vinfos[3].foffset = j3;
43038 vinfos[3].indices[0] = _ij3[0];
43039 vinfos[3].indices[1] = _ij3[1];
43040 vinfos[3].maxsolutions = _nj3;
43041 vinfos[4].jointtype = 1;
43042 vinfos[4].foffset = j4;
43043 vinfos[4].indices[0] = _ij4[0];
43044 vinfos[4].indices[1] = _ij4[1];
43045 vinfos[4].maxsolutions = _nj4;
43046 vinfos[5].jointtype = 1;
43047 vinfos[5].foffset = j5;
43048 vinfos[5].indices[0] = _ij5[0];
43049 vinfos[5].indices[1] = _ij5[1];
43050 vinfos[5].maxsolutions = _nj5;
43051 vinfos[6].jointtype = 1;
43052 vinfos[6].foffset = j6;
43053 vinfos[6].indices[0] = _ij6[0];
43054 vinfos[6].indices[1] = _ij6[1];
43055 vinfos[6].maxsolutions = _nj6;
43056 std::vector<int> vfree(0);
43057 solutions.AddSolution(vinfos,vfree);
43058 }
43059 }
43060 }
43061 
43062 }
43063 
43064 }
43065 
43066 } else
43067 {
43068 {
43069 IkReal j3array[1], cj3array[1], sj3array[1];
43070 bool j3valid[1]={false};
43071 _nj3 = 1;
43072 IkReal x13167=((r20)*(sj6));
43073 IkReal x13168=((cj4)*(cj5));
43074 IkReal x13169=((cj6)*(r21));
43075 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13167)*(x13168)))+(((x13168)*(x13169))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((sj5)*(x13167)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13169))))))) < IKFAST_ATAN2_MAGTHRESH )
43076     continue;
43077 j3array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13167)*(x13168)))+(((x13168)*(x13169)))))), ((gconst11)*(((((sj5)*(x13167)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13169)))))));
43078 sj3array[0]=IKsin(j3array[0]);
43079 cj3array[0]=IKcos(j3array[0]);
43080 if( j3array[0] > IKPI )
43081 {
43082     j3array[0]-=IK2PI;
43083 }
43084 else if( j3array[0] < -IKPI )
43085 {    j3array[0]+=IK2PI;
43086 }
43087 j3valid[0] = true;
43088 for(int ij3 = 0; ij3 < 1; ++ij3)
43089 {
43090 if( !j3valid[ij3] )
43091 {
43092     continue;
43093 }
43094 _ij3[0] = ij3; _ij3[1] = -1;
43095 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43096 {
43097 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43098 {
43099     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43100 }
43101 }
43102 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43103 {
43104 IkReal evalcond[6];
43105 IkReal x13170=IKsin(j3);
43106 IkReal x13171=IKcos(j3);
43107 IkReal x13172=((sj0)*(sj5));
43108 IkReal x13173=((r00)*(sj6));
43109 IkReal x13174=((cj6)*(r01));
43110 IkReal x13175=((cj4)*(cj5));
43111 IkReal x13176=((IkReal(1.00000000000000))*(cj0));
43112 IkReal x13177=((cj5)*(r12));
43113 IkReal x13178=((IkReal(1.00000000000000))*(sj0));
43114 IkReal x13179=((cj6)*(r11));
43115 IkReal x13180=((cj5)*(r02));
43116 IkReal x13181=((IkReal(1.00000000000000))*(cj1));
43117 IkReal x13182=((cj6)*(sj4));
43118 IkReal x13183=((cj6)*(r21));
43119 IkReal x13184=((r20)*(sj6));
43120 IkReal x13185=((r10)*(sj6));
43121 IkReal x13186=((sj4)*(sj6));
43122 IkReal x13187=((cj4)*(r02));
43123 IkReal x13188=((IkReal(1.00000000000000))*(cj4)*(r12));
43124 IkReal x13189=((IkReal(1.00000000000000))*(x13170));
43125 IkReal x13190=((cj0)*(x13186));
43126 evalcond[0]=((((IkReal(-1.00000000000000))*(sj1)*(x13171)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13184)))+(((sj5)*(x13183))));
43127 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x13186)))+(((cj4)*(r22)*(sj5)))+(((x13175)*(x13184)))+(((x13175)*(x13183)))+(((r20)*(x13182)))+(((IkReal(-1.00000000000000))*(sj1)*(x13189))));
43128 evalcond[2]=((((IkReal(-1.00000000000000))*(x13178)*(x13180)))+(((x13172)*(x13173)))+(((IkReal(-1.00000000000000))*(x13189)))+(((cj0)*(x13177)))+(((IkReal(-1.00000000000000))*(sj5)*(x13176)*(x13185)))+(((IkReal(-1.00000000000000))*(sj5)*(x13176)*(x13179)))+(((x13172)*(x13174))));
43129 evalcond[3]=((((IkReal(-1.00000000000000))*(x13171)*(x13181)))+(((IkReal(-1.00000000000000))*(sj5)*(x13174)*(x13176)))+(((IkReal(-1.00000000000000))*(x13172)*(x13179)))+(((IkReal(-1.00000000000000))*(x13172)*(x13185)))+(((IkReal(-1.00000000000000))*(sj5)*(x13173)*(x13176)))+(((sj0)*(x13177)))+(((cj0)*(x13180))));
43130 evalcond[4]=((x13171)+(((r00)*(sj0)*(x13182)))+(((IkReal(-1.00000000000000))*(x13175)*(x13176)*(x13185)))+(((IkReal(-1.00000000000000))*(r10)*(x13176)*(x13182)))+(((IkReal(-1.00000000000000))*(r01)*(x13178)*(x13186)))+(((IkReal(-1.00000000000000))*(x13175)*(x13176)*(x13179)))+(((x13172)*(x13187)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(sj5)*(x13176)))+(((r11)*(x13190)))+(((sj0)*(x13173)*(x13175)))+(((sj0)*(x13174)*(x13175))));
43131 evalcond[5]=((((IkReal(-1.00000000000000))*(x13175)*(x13178)*(x13179)))+(((IkReal(-1.00000000000000))*(x13173)*(x13175)*(x13176)))+(((IkReal(-1.00000000000000))*(x13172)*(x13188)))+(((IkReal(-1.00000000000000))*(r00)*(x13176)*(x13182)))+(((IkReal(-1.00000000000000))*(x13174)*(x13175)*(x13176)))+(((r01)*(x13190)))+(((IkReal(-1.00000000000000))*(x13170)*(x13181)))+(((IkReal(-1.00000000000000))*(x13175)*(x13178)*(x13185)))+(((IkReal(-1.00000000000000))*(r10)*(x13178)*(x13182)))+(((r11)*(sj0)*(x13186)))+(((IkReal(-1.00000000000000))*(sj5)*(x13176)*(x13187))));
43132 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43133 {
43134 continue;
43135 }
43136 }
43137 
43138 {
43139 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43140 vinfos[0].jointtype = 1;
43141 vinfos[0].foffset = j0;
43142 vinfos[0].indices[0] = _ij0[0];
43143 vinfos[0].indices[1] = _ij0[1];
43144 vinfos[0].maxsolutions = _nj0;
43145 vinfos[1].jointtype = 1;
43146 vinfos[1].foffset = j1;
43147 vinfos[1].indices[0] = _ij1[0];
43148 vinfos[1].indices[1] = _ij1[1];
43149 vinfos[1].maxsolutions = _nj1;
43150 vinfos[2].jointtype = 1;
43151 vinfos[2].foffset = j2;
43152 vinfos[2].indices[0] = _ij2[0];
43153 vinfos[2].indices[1] = _ij2[1];
43154 vinfos[2].maxsolutions = _nj2;
43155 vinfos[3].jointtype = 1;
43156 vinfos[3].foffset = j3;
43157 vinfos[3].indices[0] = _ij3[0];
43158 vinfos[3].indices[1] = _ij3[1];
43159 vinfos[3].maxsolutions = _nj3;
43160 vinfos[4].jointtype = 1;
43161 vinfos[4].foffset = j4;
43162 vinfos[4].indices[0] = _ij4[0];
43163 vinfos[4].indices[1] = _ij4[1];
43164 vinfos[4].maxsolutions = _nj4;
43165 vinfos[5].jointtype = 1;
43166 vinfos[5].foffset = j5;
43167 vinfos[5].indices[0] = _ij5[0];
43168 vinfos[5].indices[1] = _ij5[1];
43169 vinfos[5].maxsolutions = _nj5;
43170 vinfos[6].jointtype = 1;
43171 vinfos[6].foffset = j6;
43172 vinfos[6].indices[0] = _ij6[0];
43173 vinfos[6].indices[1] = _ij6[1];
43174 vinfos[6].maxsolutions = _nj6;
43175 std::vector<int> vfree(0);
43176 solutions.AddSolution(vinfos,vfree);
43177 }
43178 }
43179 }
43180 
43181 }
43182 
43183 }
43184 
43185 } else
43186 {
43187 IkReal x13191=((IkReal(1.00000000000000))*(cj0));
43188 IkReal x13192=((cj4)*(sj6));
43189 IkReal x13193=((sj0)*(sj4));
43190 IkReal x13194=((cj5)*(sj6));
43191 IkReal x13195=((sj4)*(sj5));
43192 IkReal x13196=((r12)*(sj5));
43193 IkReal x13197=((IkReal(0.374290000000000))*(cj5));
43194 IkReal x13198=((r02)*(sj0));
43195 IkReal x13199=((IkReal(1.00000000000000))*(sj0));
43196 IkReal x13200=((cj0)*(r10));
43197 IkReal x13201=((cj4)*(cj6));
43198 IkReal x13202=((r00)*(sj0));
43199 IkReal x13203=((cj6)*(r21));
43200 IkReal x13204=((IkReal(0.374290000000000))*(sj5));
43201 IkReal x13205=((cj0)*(r00));
43202 IkReal x13206=((IkReal(0.0100000000000000))*(sj5));
43203 IkReal x13207=((cj0)*(r02));
43204 IkReal x13208=((cj5)*(sj4));
43205 IkReal x13209=((cj6)*(r01));
43206 IkReal x13210=((cj6)*(r11));
43207 IkReal x13211=((r01)*(sj0));
43208 IkReal x13212=((r10)*(sj0));
43209 IkReal x13213=((IkReal(0.0100000000000000))*(cj5)*(cj6));
43210 IkReal x13214=((sj6)*(x13204));
43211 IkReal x13215=((cj0)*(cj6)*(x13204));
43212 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j2)), IkReal(6.28318530717959))));
43213 evalcond[1]=((((r21)*(x13192)))+(((r22)*(x13195)))+(((IkReal(-1.00000000000000))*(r20)*(x13201)))+(((x13203)*(x13208)))+(cj1)+(((r20)*(sj4)*(x13194))));
43214 evalcond[2]=((((IkReal(-1.00000000000000))*(r22)*(x13197)))+(((IkReal(0.364420000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r22)*(x13206)))+(((r20)*(x13214)))+(((IkReal(-0.0100000000000000))*(cj5)*(x13203)))+(pz)+(((x13203)*(x13204)))+(((IkReal(-0.0100000000000000))*(r20)*(x13194))));
43215 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(sj4)*(x13191)*(x13194)))+(((IkReal(-1.00000000000000))*(r12)*(x13191)*(x13195)))+(((IkReal(-1.00000000000000))*(r00)*(x13199)*(x13201)))+(((IkReal(-1.00000000000000))*(x13191)*(x13208)*(x13210)))+(((r00)*(x13193)*(x13194)))+(((x13192)*(x13211)))+(((r02)*(sj5)*(x13193)))+(((IkReal(-1.00000000000000))*(r11)*(x13191)*(x13192)))+(((cj5)*(x13193)*(x13209)))+(((x13200)*(x13201))));
43216 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x13193)*(x13194)))+(((IkReal(-1.00000000000000))*(cj5)*(x13193)*(x13210)))+(((IkReal(-1.00000000000000))*(r01)*(x13191)*(x13192)))+(((x13201)*(x13212)))+(((IkReal(-1.00000000000000))*(r11)*(x13192)*(x13199)))+(((IkReal(-1.00000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(r02)*(x13191)*(x13195)))+(((IkReal(-1.00000000000000))*(x13191)*(x13208)*(x13209)))+(((IkReal(-1.00000000000000))*(r00)*(sj4)*(x13191)*(x13194)))+(((x13201)*(x13205)))+(((IkReal(-1.00000000000000))*(x13193)*(x13196))));
43217 evalcond[5]=((IkReal(-0.0690000000000000))+(((sj0)*(x13204)*(x13209)))+(((x13202)*(x13214)))+(((IkReal(-0.0100000000000000))*(x13194)*(x13202)))+(((IkReal(-1.00000000000000))*(cj0)*(x13204)*(x13210)))+(((IkReal(-1.00000000000000))*(py)*(x13191)))+(((cj0)*(r12)*(x13197)))+(((IkReal(-1.00000000000000))*(x13200)*(x13214)))+(((IkReal(0.0100000000000000))*(cj0)*(x13196)))+(((IkReal(-1.00000000000000))*(x13197)*(x13198)))+(((IkReal(0.0100000000000000))*(x13194)*(x13200)))+(((IkReal(-0.0100000000000000))*(cj5)*(sj0)*(x13209)))+(((IkReal(-1.00000000000000))*(x13198)*(x13206)))+(((px)*(sj0)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x13210))));
43218 evalcond[6]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(py)*(x13199)))+(((IkReal(0.0100000000000000))*(cj5)*(sj0)*(x13210)))+(((IkReal(-1.00000000000000))*(x13205)*(x13214)))+(((IkReal(-1.00000000000000))*(sj0)*(x13204)*(x13210)))+(((IkReal(0.0100000000000000))*(x13194)*(x13205)))+(((IkReal(0.0100000000000000))*(sj0)*(x13196)))+(((x13206)*(x13207)))+(((r12)*(sj0)*(x13197)))+(((IkReal(0.0100000000000000))*(cj0)*(cj5)*(x13209)))+(((IkReal(-1.00000000000000))*(x13212)*(x13214)))+(((x13197)*(x13207)))+(((IkReal(0.0100000000000000))*(x13194)*(x13212)))+(((IkReal(-1.00000000000000))*(cj0)*(x13204)*(x13209)))+(((IkReal(0.364420000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(px)*(x13191))));
43219 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  )
43220 {
43221 {
43222 IkReal dummyeval[1];
43223 IkReal gconst12;
43224 gconst12=IKsign(sj1);
43225 dummyeval[0]=sj1;
43226 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
43227 {
43228 {
43229 IkReal dummyeval[1];
43230 dummyeval[0]=sj1;
43231 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
43232 {
43233 {
43234 IkReal dummyeval[1];
43235 dummyeval[0]=cj1;
43236 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
43237 {
43238 {
43239 IkReal evalcond[9];
43240 IkReal x13216=((IkReal(1.00000000000000))*(cj0));
43241 IkReal x13217=((cj4)*(sj6));
43242 IkReal x13218=((sj0)*(sj6));
43243 IkReal x13219=((cj5)*(sj4));
43244 IkReal x13220=((IkReal(0.374290000000000))*(sj5));
43245 IkReal x13221=((sj4)*(sj5));
43246 IkReal x13222=((cj0)*(cj6));
43247 IkReal x13223=((IkReal(0.0100000000000000))*(cj5));
43248 IkReal x13224=((cj4)*(sj5));
43249 IkReal x13225=((cj5)*(sj0));
43250 IkReal x13226=((IkReal(0.374290000000000))*(r02));
43251 IkReal x13227=((r20)*(sj6));
43252 IkReal x13228=((cj6)*(r21));
43253 IkReal x13229=((IkReal(1.00000000000000))*(sj0));
43254 IkReal x13230=((cj0)*(sj6));
43255 IkReal x13231=((cj4)*(cj6));
43256 IkReal x13232=((IkReal(0.374290000000000))*(r12));
43257 IkReal x13233=((cj0)*(cj5));
43258 IkReal x13234=((cj6)*(sj5));
43259 IkReal x13235=((cj6)*(r01));
43260 IkReal x13236=((r00)*(sj6));
43261 IkReal x13237=((IkReal(0.0100000000000000))*(sj5));
43262 IkReal x13238=((cj6)*(r11));
43263 IkReal x13239=((IkReal(1.00000000000000))*(r10));
43264 IkReal x13240=((r02)*(sj0));
43265 IkReal x13241=((cj6)*(sj4));
43266 IkReal x13242=((r12)*(x13229));
43267 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j1)), IkReal(6.28318530717959))));
43268 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x13231)))+(((r22)*(x13221)))+(((x13219)*(x13227)))+(((x13219)*(x13228)))+(((r21)*(x13217))));
43269 evalcond[2]=((IkReal(0.364420000000000))+(((x13220)*(x13227)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x13223)*(x13227)))+(pz)+(((x13220)*(x13228)))+(((IkReal(-1.00000000000000))*(r22)*(x13237)))+(((IkReal(-1.00000000000000))*(x13223)*(x13228))));
43270 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x13216)*(x13236)))+(((IkReal(-1.00000000000000))*(r01)*(x13216)*(x13234)))+(((IkReal(-1.00000000000000))*(r11)*(x13229)*(x13234)))+(((r12)*(x13225)))+(((IkReal(-1.00000000000000))*(sj5)*(x13218)*(x13239)))+(((r02)*(x13233))));
43271 evalcond[4]=((((cj4)*(r10)*(x13222)))+(((IkReal(-1.00000000000000))*(r12)*(x13216)*(x13221)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x13216)*(x13219)))+(((sj0)*(x13219)*(x13235)))+(((r00)*(x13218)*(x13219)))+(((IkReal(-1.00000000000000))*(r11)*(x13216)*(x13217)))+(((x13221)*(x13240)))+(((IkReal(-1.00000000000000))*(r00)*(x13229)*(x13231)))+(((r01)*(sj0)*(x13217)))+(((IkReal(-1.00000000000000))*(x13216)*(x13219)*(x13238))));
43272 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x13219)*(x13229)*(x13238)))+(((cj4)*(r00)*(x13222)))+(((IkReal(-1.00000000000000))*(x13216)*(x13219)*(x13235)))+(((IkReal(-1.00000000000000))*(r11)*(x13217)*(x13229)))+(((r10)*(sj0)*(x13231)))+(((IkReal(-1.00000000000000))*(x13216)*(x13219)*(x13236)))+(((IkReal(-1.00000000000000))*(x13218)*(x13219)*(x13239)))+(((IkReal(-1.00000000000000))*(r01)*(x13216)*(x13217)))+(((IkReal(-1.00000000000000))*(x13221)*(x13242)))+(((IkReal(-1.00000000000000))*(r02)*(x13216)*(x13221))));
43273 evalcond[6]=((IkReal(-0.0690000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x13220)*(x13230)))+(((IkReal(-1.00000000000000))*(r00)*(x13218)*(x13223)))+(((r00)*(x13218)*(x13220)))+(((x13232)*(x13233)))+(((sj0)*(x13220)*(x13235)))+(((IkReal(-1.00000000000000))*(py)*(x13216)))+(((r10)*(x13223)*(x13230)))+(((IkReal(-1.00000000000000))*(r11)*(x13220)*(x13222)))+(((r11)*(x13222)*(x13223)))+(((IkReal(-1.00000000000000))*(sj0)*(x13223)*(x13235)))+(((cj0)*(r12)*(x13237)))+(((IkReal(-1.00000000000000))*(x13225)*(x13226)))+(((IkReal(-1.00000000000000))*(x13237)*(x13240)))+(((px)*(sj0))));
43274 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(x13216)*(x13241)))+(((IkReal(-1.00000000000000))*(r10)*(x13229)*(x13241)))+(((IkReal(-1.00000000000000))*(x13224)*(x13242)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x13216)*(x13217)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x13216)*(x13231)))+(((IkReal(-1.00000000000000))*(r11)*(x13225)*(x13231)))+(((r11)*(sj4)*(x13218)))+(((IkReal(-1.00000000000000))*(x13217)*(x13225)*(x13239)))+(((IkReal(-1.00000000000000))*(r02)*(x13216)*(x13224)))+(((r01)*(sj4)*(x13230))));
43275 evalcond[8]=((IkReal(0.0690000000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x13220)*(x13238)))+(((IkReal(-1.00000000000000))*(r01)*(x13220)*(x13222)))+(((sj0)*(x13223)*(x13238)))+(((r12)*(sj0)*(x13237)))+(((r10)*(x13218)*(x13223)))+(((IkReal(-1.00000000000000))*(py)*(x13229)))+(((cj0)*(r02)*(x13237)))+(((x13225)*(x13232)))+(((IkReal(-1.00000000000000))*(px)*(x13216)))+(((r01)*(x13222)*(x13223)))+(((IkReal(-1.00000000000000))*(r10)*(x13218)*(x13220)))+(((r00)*(x13223)*(x13230)))+(((x13226)*(x13233)))+(((IkReal(-1.00000000000000))*(r00)*(x13220)*(x13230))));
43276 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
43277 {
43278 {
43279 IkReal j3array[1], cj3array[1], sj3array[1];
43280 bool j3valid[1]={false};
43281 _nj3 = 1;
43282 IkReal x13243=((r20)*(sj6));
43283 IkReal x13244=((cj4)*(cj5));
43284 IkReal x13245=((cj6)*(r21));
43285 if( IKabs(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13244)*(x13245)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13243)*(x13244))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((sj5)*(x13243)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13245))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13244)*(x13245)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13243)*(x13244)))))+IKsqr(((((sj5)*(x13243)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13245)))))-1) <= IKFAST_SINCOS_THRESH )
43286     continue;
43287 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13244)*(x13245)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))+(((x13243)*(x13244)))), ((((sj5)*(x13243)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13245)))));
43288 sj3array[0]=IKsin(j3array[0]);
43289 cj3array[0]=IKcos(j3array[0]);
43290 if( j3array[0] > IKPI )
43291 {
43292     j3array[0]-=IK2PI;
43293 }
43294 else if( j3array[0] < -IKPI )
43295 {    j3array[0]+=IK2PI;
43296 }
43297 j3valid[0] = true;
43298 for(int ij3 = 0; ij3 < 1; ++ij3)
43299 {
43300 if( !j3valid[ij3] )
43301 {
43302     continue;
43303 }
43304 _ij3[0] = ij3; _ij3[1] = -1;
43305 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43306 {
43307 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43308 {
43309     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43310 }
43311 }
43312 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43313 {
43314 IkReal evalcond[4];
43315 IkReal x13246=IKsin(j3);
43316 IkReal x13247=((sj0)*(sj5));
43317 IkReal x13248=((r00)*(sj6));
43318 IkReal x13249=((cj6)*(r01));
43319 IkReal x13250=((cj5)*(sj0));
43320 IkReal x13251=((cj0)*(cj5));
43321 IkReal x13252=((cj6)*(sj4));
43322 IkReal x13253=((sj4)*(sj6));
43323 IkReal x13254=((cj0)*(r11));
43324 IkReal x13255=((cj4)*(cj6));
43325 IkReal x13256=((cj4)*(sj6));
43326 IkReal x13257=((IkReal(1.00000000000000))*(cj0));
43327 IkReal x13258=((cj4)*(sj5));
43328 IkReal x13259=((sj5)*(sj6));
43329 IkReal x13260=((cj6)*(sj5));
43330 IkReal x13261=((IkReal(1.00000000000000))*(IKcos(j3)));
43331 evalcond[0]=((((r21)*(x13260)))+(((IkReal(-1.00000000000000))*(x13261)))+(((r20)*(x13259)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
43332 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(x13253)))+(((r20)*(x13252)))+(((cj5)*(r20)*(x13256)))+(((IkReal(-1.00000000000000))*(x13246)))+(((r22)*(x13258)))+(((cj5)*(r21)*(x13255))));
43333 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x13250)))+(x13246)+(((x13247)*(x13249)))+(((IkReal(-1.00000000000000))*(r10)*(x13257)*(x13259)))+(((IkReal(-1.00000000000000))*(x13254)*(x13260)))+(((r12)*(x13251)))+(((x13247)*(x13248))));
43334 evalcond[3]=((((cj4)*(x13249)*(x13250)))+(((cj4)*(x13248)*(x13250)))+(((IkReal(-1.00000000000000))*(r11)*(x13251)*(x13255)))+(((IkReal(-1.00000000000000))*(r10)*(x13251)*(x13256)))+(((IkReal(-1.00000000000000))*(x13261)))+(((r00)*(sj0)*(x13252)))+(((IkReal(-1.00000000000000))*(r10)*(x13252)*(x13257)))+(((IkReal(-1.00000000000000))*(r12)*(x13257)*(x13258)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x13253)))+(((cj4)*(r02)*(x13247)))+(((x13253)*(x13254))));
43335 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
43336 {
43337 continue;
43338 }
43339 }
43340 
43341 {
43342 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43343 vinfos[0].jointtype = 1;
43344 vinfos[0].foffset = j0;
43345 vinfos[0].indices[0] = _ij0[0];
43346 vinfos[0].indices[1] = _ij0[1];
43347 vinfos[0].maxsolutions = _nj0;
43348 vinfos[1].jointtype = 1;
43349 vinfos[1].foffset = j1;
43350 vinfos[1].indices[0] = _ij1[0];
43351 vinfos[1].indices[1] = _ij1[1];
43352 vinfos[1].maxsolutions = _nj1;
43353 vinfos[2].jointtype = 1;
43354 vinfos[2].foffset = j2;
43355 vinfos[2].indices[0] = _ij2[0];
43356 vinfos[2].indices[1] = _ij2[1];
43357 vinfos[2].maxsolutions = _nj2;
43358 vinfos[3].jointtype = 1;
43359 vinfos[3].foffset = j3;
43360 vinfos[3].indices[0] = _ij3[0];
43361 vinfos[3].indices[1] = _ij3[1];
43362 vinfos[3].maxsolutions = _nj3;
43363 vinfos[4].jointtype = 1;
43364 vinfos[4].foffset = j4;
43365 vinfos[4].indices[0] = _ij4[0];
43366 vinfos[4].indices[1] = _ij4[1];
43367 vinfos[4].maxsolutions = _nj4;
43368 vinfos[5].jointtype = 1;
43369 vinfos[5].foffset = j5;
43370 vinfos[5].indices[0] = _ij5[0];
43371 vinfos[5].indices[1] = _ij5[1];
43372 vinfos[5].maxsolutions = _nj5;
43373 vinfos[6].jointtype = 1;
43374 vinfos[6].foffset = j6;
43375 vinfos[6].indices[0] = _ij6[0];
43376 vinfos[6].indices[1] = _ij6[1];
43377 vinfos[6].maxsolutions = _nj6;
43378 std::vector<int> vfree(0);
43379 solutions.AddSolution(vinfos,vfree);
43380 }
43381 }
43382 }
43383 
43384 } else
43385 {
43386 IkReal x13262=((IkReal(1.00000000000000))*(cj0));
43387 IkReal x13263=((cj4)*(sj6));
43388 IkReal x13264=((sj0)*(sj6));
43389 IkReal x13265=((cj5)*(sj4));
43390 IkReal x13266=((IkReal(0.374290000000000))*(sj5));
43391 IkReal x13267=((sj4)*(sj5));
43392 IkReal x13268=((cj0)*(cj6));
43393 IkReal x13269=((IkReal(0.0100000000000000))*(cj5));
43394 IkReal x13270=((cj4)*(sj5));
43395 IkReal x13271=((cj5)*(sj0));
43396 IkReal x13272=((IkReal(0.374290000000000))*(r02));
43397 IkReal x13273=((r20)*(sj6));
43398 IkReal x13274=((cj6)*(r21));
43399 IkReal x13275=((IkReal(1.00000000000000))*(sj0));
43400 IkReal x13276=((cj0)*(sj6));
43401 IkReal x13277=((cj4)*(cj6));
43402 IkReal x13278=((IkReal(0.374290000000000))*(r12));
43403 IkReal x13279=((cj0)*(cj5));
43404 IkReal x13280=((cj6)*(sj5));
43405 IkReal x13281=((cj6)*(r01));
43406 IkReal x13282=((r00)*(sj6));
43407 IkReal x13283=((IkReal(0.0100000000000000))*(sj5));
43408 IkReal x13284=((cj6)*(r11));
43409 IkReal x13285=((IkReal(1.00000000000000))*(r10));
43410 IkReal x13286=((r02)*(sj0));
43411 IkReal x13287=((cj6)*(sj4));
43412 IkReal x13288=((r12)*(x13275));
43413 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j1)), IkReal(6.28318530717959))));
43414 evalcond[1]=((((x13265)*(x13273)))+(((IkReal(-1.00000000000000))*(r20)*(x13277)))+(((r21)*(x13263)))+(((x13265)*(x13274)))+(((r22)*(x13267))));
43415 evalcond[2]=((IkReal(-0.364420000000000))+(((IkReal(-1.00000000000000))*(x13269)*(x13274)))+(((x13266)*(x13274)))+(((IkReal(-0.374290000000000))*(cj5)*(r22)))+(pz)+(((IkReal(-1.00000000000000))*(x13269)*(x13273)))+(((IkReal(-1.00000000000000))*(r22)*(x13283)))+(((x13266)*(x13273))));
43416 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x13262)*(x13282)))+(((r02)*(x13279)))+(((r12)*(x13271)))+(((IkReal(-1.00000000000000))*(r11)*(x13275)*(x13280)))+(((IkReal(-1.00000000000000))*(r01)*(x13262)*(x13280)))+(((IkReal(-1.00000000000000))*(sj5)*(x13264)*(x13285))));
43417 evalcond[4]=((((r01)*(sj0)*(x13263)))+(((IkReal(-1.00000000000000))*(r00)*(x13275)*(x13277)))+(((cj4)*(r10)*(x13268)))+(((sj0)*(x13265)*(x13281)))+(((IkReal(-1.00000000000000))*(r11)*(x13262)*(x13263)))+(((IkReal(-1.00000000000000))*(x13262)*(x13265)*(x13284)))+(((IkReal(-1.00000000000000))*(r10)*(sj6)*(x13262)*(x13265)))+(((IkReal(-1.00000000000000))*(r12)*(x13262)*(x13267)))+(((r00)*(x13264)*(x13265)))+(((x13267)*(x13286))));
43418 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r02)*(x13262)*(x13267)))+(((IkReal(-1.00000000000000))*(x13267)*(x13288)))+(((IkReal(-1.00000000000000))*(x13262)*(x13265)*(x13281)))+(((r10)*(sj0)*(x13277)))+(((IkReal(-1.00000000000000))*(x13264)*(x13265)*(x13285)))+(((cj4)*(r00)*(x13268)))+(((IkReal(-1.00000000000000))*(r11)*(x13263)*(x13275)))+(((IkReal(-1.00000000000000))*(x13265)*(x13275)*(x13284)))+(((IkReal(-1.00000000000000))*(r01)*(x13262)*(x13263)))+(((IkReal(-1.00000000000000))*(x13262)*(x13265)*(x13282))));
43419 evalcond[6]=((IkReal(-0.0690000000000000))+(((sj0)*(x13266)*(x13281)))+(((IkReal(-1.00000000000000))*(r10)*(x13266)*(x13276)))+(((IkReal(-1.00000000000000))*(sj0)*(x13269)*(x13281)))+(((IkReal(-1.00000000000000))*(x13283)*(x13286)))+(((r11)*(x13268)*(x13269)))+(((cj0)*(r12)*(x13283)))+(((IkReal(-1.00000000000000))*(r11)*(x13266)*(x13268)))+(((r10)*(x13269)*(x13276)))+(((IkReal(-1.00000000000000))*(r00)*(x13264)*(x13269)))+(((IkReal(-1.00000000000000))*(py)*(x13262)))+(((r00)*(x13264)*(x13266)))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(x13271)*(x13272)))+(((x13278)*(x13279))));
43420 evalcond[7]=((((r11)*(sj4)*(x13264)))+(((IkReal(-1.00000000000000))*(x13263)*(x13271)*(x13285)))+(((IkReal(-1.00000000000000))*(r02)*(x13262)*(x13270)))+(((IkReal(-1.00000000000000))*(x13270)*(x13288)))+(((IkReal(-1.00000000000000))*(r10)*(x13275)*(x13287)))+(((r01)*(sj4)*(x13276)))+(((IkReal(-1.00000000000000))*(r00)*(x13262)*(x13287)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x13262)*(x13277)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x13262)*(x13263)))+(((IkReal(-1.00000000000000))*(r11)*(x13271)*(x13277))));
43421 evalcond[8]=((IkReal(0.0690000000000000))+(((r12)*(sj0)*(x13283)))+(((r00)*(x13269)*(x13276)))+(((sj0)*(x13269)*(x13284)))+(((IkReal(-1.00000000000000))*(sj0)*(x13266)*(x13284)))+(((x13271)*(x13278)))+(((r01)*(x13268)*(x13269)))+(((IkReal(-1.00000000000000))*(r00)*(x13266)*(x13276)))+(((x13272)*(x13279)))+(((cj0)*(r02)*(x13283)))+(((r10)*(x13264)*(x13269)))+(((IkReal(-1.00000000000000))*(py)*(x13275)))+(((IkReal(-1.00000000000000))*(r01)*(x13266)*(x13268)))+(((IkReal(-1.00000000000000))*(r10)*(x13264)*(x13266)))+(((IkReal(-1.00000000000000))*(px)*(x13262))));
43422 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  && IKabs(evalcond[3]) < 0.0000010000000000  && IKabs(evalcond[4]) < 0.0000010000000000  && IKabs(evalcond[5]) < 0.0000010000000000  && IKabs(evalcond[6]) < 0.0000010000000000  && IKabs(evalcond[7]) < 0.0000010000000000  && IKabs(evalcond[8]) < 0.0000010000000000  )
43423 {
43424 {
43425 IkReal j3array[1], cj3array[1], sj3array[1];
43426 bool j3valid[1]={false};
43427 _nj3 = 1;
43428 IkReal x13289=((IkReal(1.00000000000000))*(sj5));
43429 IkReal x13290=((cj6)*(r21));
43430 IkReal x13291=((r20)*(sj6));
43431 IkReal x13292=((IkReal(1.00000000000000))*(cj4)*(cj5));
43432 if( IKabs(((((IkReal(-1.00000000000000))*(x13290)*(x13292)))+(((IkReal(-1.00000000000000))*(x13291)*(x13292)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13289)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(x13289)*(x13291)))+(((IkReal(-1.00000000000000))*(x13289)*(x13290)))+(((cj5)*(r22))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(x13290)*(x13292)))+(((IkReal(-1.00000000000000))*(x13291)*(x13292)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13289)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))))+IKsqr(((((IkReal(-1.00000000000000))*(x13289)*(x13291)))+(((IkReal(-1.00000000000000))*(x13289)*(x13290)))+(((cj5)*(r22)))))-1) <= IKFAST_SINCOS_THRESH )
43433     continue;
43434 j3array[0]=IKatan2(((((IkReal(-1.00000000000000))*(x13290)*(x13292)))+(((IkReal(-1.00000000000000))*(x13291)*(x13292)))+(((r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(cj4)*(r22)*(x13289)))+(((IkReal(-1.00000000000000))*(cj6)*(r20)*(sj4)))), ((((IkReal(-1.00000000000000))*(x13289)*(x13291)))+(((IkReal(-1.00000000000000))*(x13289)*(x13290)))+(((cj5)*(r22)))));
43435 sj3array[0]=IKsin(j3array[0]);
43436 cj3array[0]=IKcos(j3array[0]);
43437 if( j3array[0] > IKPI )
43438 {
43439     j3array[0]-=IK2PI;
43440 }
43441 else if( j3array[0] < -IKPI )
43442 {    j3array[0]+=IK2PI;
43443 }
43444 j3valid[0] = true;
43445 for(int ij3 = 0; ij3 < 1; ++ij3)
43446 {
43447 if( !j3valid[ij3] )
43448 {
43449     continue;
43450 }
43451 _ij3[0] = ij3; _ij3[1] = -1;
43452 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43453 {
43454 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43455 {
43456     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43457 }
43458 }
43459 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43460 {
43461 IkReal evalcond[4];
43462 IkReal x13293=IKsin(j3);
43463 IkReal x13294=IKcos(j3);
43464 IkReal x13295=((sj0)*(sj5));
43465 IkReal x13296=((r00)*(sj6));
43466 IkReal x13297=((cj6)*(r01));
43467 IkReal x13298=((cj0)*(cj5));
43468 IkReal x13299=((IkReal(1.00000000000000))*(cj5));
43469 IkReal x13300=((cj4)*(cj5));
43470 IkReal x13301=((cj6)*(sj4));
43471 IkReal x13302=((sj4)*(sj6));
43472 IkReal x13303=((cj0)*(r11));
43473 IkReal x13304=((IkReal(1.00000000000000))*(cj4));
43474 IkReal x13305=((cj6)*(r21));
43475 IkReal x13306=((r20)*(sj6));
43476 IkReal x13307=((cj0)*(sj5));
43477 IkReal x13308=((r10)*(sj6));
43478 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x13299)))+(((sj5)*(x13306)))+(((sj5)*(x13305)))+(x13294));
43479 evalcond[1]=((((r20)*(x13301)))+(((x13300)*(x13305)))+(((x13300)*(x13306)))+(((cj4)*(r22)*(sj5)))+(x13293)+(((IkReal(-1.00000000000000))*(r21)*(x13302))));
43480 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(sj0)*(x13299)))+(((x13295)*(x13296)))+(((r12)*(x13298)))+(((x13295)*(x13297)))+(((IkReal(-1.00000000000000))*(cj6)*(sj5)*(x13303)))+(((IkReal(-1.00000000000000))*(x13307)*(x13308)))+(x13293));
43481 evalcond[3]=((((IkReal(-1.00000000000000))*(x13298)*(x13304)*(x13308)))+(((sj0)*(x13296)*(x13300)))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(x13302)))+(((IkReal(-1.00000000000000))*(cj0)*(r10)*(x13301)))+(((sj0)*(x13297)*(x13300)))+(((cj4)*(r02)*(x13295)))+(((x13302)*(x13303)))+(((IkReal(-1.00000000000000))*(r12)*(x13304)*(x13307)))+(((IkReal(-1.00000000000000))*(cj6)*(r11)*(x13298)*(x13304)))+(((IkReal(-1.00000000000000))*(x13294)))+(((r00)*(sj0)*(x13301))));
43482 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
43483 {
43484 continue;
43485 }
43486 }
43487 
43488 {
43489 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43490 vinfos[0].jointtype = 1;
43491 vinfos[0].foffset = j0;
43492 vinfos[0].indices[0] = _ij0[0];
43493 vinfos[0].indices[1] = _ij0[1];
43494 vinfos[0].maxsolutions = _nj0;
43495 vinfos[1].jointtype = 1;
43496 vinfos[1].foffset = j1;
43497 vinfos[1].indices[0] = _ij1[0];
43498 vinfos[1].indices[1] = _ij1[1];
43499 vinfos[1].maxsolutions = _nj1;
43500 vinfos[2].jointtype = 1;
43501 vinfos[2].foffset = j2;
43502 vinfos[2].indices[0] = _ij2[0];
43503 vinfos[2].indices[1] = _ij2[1];
43504 vinfos[2].maxsolutions = _nj2;
43505 vinfos[3].jointtype = 1;
43506 vinfos[3].foffset = j3;
43507 vinfos[3].indices[0] = _ij3[0];
43508 vinfos[3].indices[1] = _ij3[1];
43509 vinfos[3].maxsolutions = _nj3;
43510 vinfos[4].jointtype = 1;
43511 vinfos[4].foffset = j4;
43512 vinfos[4].indices[0] = _ij4[0];
43513 vinfos[4].indices[1] = _ij4[1];
43514 vinfos[4].maxsolutions = _nj4;
43515 vinfos[5].jointtype = 1;
43516 vinfos[5].foffset = j5;
43517 vinfos[5].indices[0] = _ij5[0];
43518 vinfos[5].indices[1] = _ij5[1];
43519 vinfos[5].maxsolutions = _nj5;
43520 vinfos[6].jointtype = 1;
43521 vinfos[6].foffset = j6;
43522 vinfos[6].indices[0] = _ij6[0];
43523 vinfos[6].indices[1] = _ij6[1];
43524 vinfos[6].maxsolutions = _nj6;
43525 std::vector<int> vfree(0);
43526 solutions.AddSolution(vinfos,vfree);
43527 }
43528 }
43529 }
43530 
43531 } else
43532 {
43533 if( 1 )
43534 {
43535 continue;
43536 
43537 } else
43538 {
43539 }
43540 }
43541 }
43542 }
43543 
43544 } else
43545 {
43546 {
43547 IkReal j3array[1], cj3array[1], sj3array[1];
43548 bool j3valid[1]={false};
43549 _nj3 = 1;
43550 IkReal x13309=((cj5)*(r02));
43551 IkReal x13310=((cj0)*(sj5));
43552 IkReal x13311=((r10)*(sj6));
43553 IkReal x13312=((IkReal(1.00000000000000))*(cj6));
43554 IkReal x13313=((sj0)*(sj5));
43555 IkReal x13314=((cj5)*(r12));
43556 IkReal x13315=((IkReal(1.00000000000000))*(r00)*(sj6));
43557 if( IKabs(((((sj0)*(x13309)))+(((x13310)*(x13311)))+(((IkReal(-1.00000000000000))*(r01)*(x13312)*(x13313)))+(((cj6)*(r11)*(x13310)))+(((IkReal(-1.00000000000000))*(x13313)*(x13315)))+(((IkReal(-1.00000000000000))*(cj0)*(x13314))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x13310)*(x13312)))+(((sj0)*(x13314)))+(((IkReal(-1.00000000000000))*(r11)*(x13312)*(x13313)))+(((IkReal(-1.00000000000000))*(x13310)*(x13315)))+(((IkReal(-1.00000000000000))*(x13311)*(x13313)))+(((cj0)*(x13309))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((sj0)*(x13309)))+(((x13310)*(x13311)))+(((IkReal(-1.00000000000000))*(r01)*(x13312)*(x13313)))+(((cj6)*(r11)*(x13310)))+(((IkReal(-1.00000000000000))*(x13313)*(x13315)))+(((IkReal(-1.00000000000000))*(cj0)*(x13314)))))+IKsqr(((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x13310)*(x13312)))+(((sj0)*(x13314)))+(((IkReal(-1.00000000000000))*(r11)*(x13312)*(x13313)))+(((IkReal(-1.00000000000000))*(x13310)*(x13315)))+(((IkReal(-1.00000000000000))*(x13311)*(x13313)))+(((cj0)*(x13309)))))))-1) <= IKFAST_SINCOS_THRESH )
43558     continue;
43559 j3array[0]=IKatan2(((((sj0)*(x13309)))+(((x13310)*(x13311)))+(((IkReal(-1.00000000000000))*(r01)*(x13312)*(x13313)))+(((cj6)*(r11)*(x13310)))+(((IkReal(-1.00000000000000))*(x13313)*(x13315)))+(((IkReal(-1.00000000000000))*(cj0)*(x13314)))), ((((IKabs(cj1) != 0)?((IkReal)1/(cj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(x13310)*(x13312)))+(((sj0)*(x13314)))+(((IkReal(-1.00000000000000))*(r11)*(x13312)*(x13313)))+(((IkReal(-1.00000000000000))*(x13310)*(x13315)))+(((IkReal(-1.00000000000000))*(x13311)*(x13313)))+(((cj0)*(x13309)))))));
43560 sj3array[0]=IKsin(j3array[0]);
43561 cj3array[0]=IKcos(j3array[0]);
43562 if( j3array[0] > IKPI )
43563 {
43564     j3array[0]-=IK2PI;
43565 }
43566 else if( j3array[0] < -IKPI )
43567 {    j3array[0]+=IK2PI;
43568 }
43569 j3valid[0] = true;
43570 for(int ij3 = 0; ij3 < 1; ++ij3)
43571 {
43572 if( !j3valid[ij3] )
43573 {
43574     continue;
43575 }
43576 _ij3[0] = ij3; _ij3[1] = -1;
43577 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43578 {
43579 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43580 {
43581     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43582 }
43583 }
43584 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43585 {
43586 IkReal evalcond[6];
43587 IkReal x13316=IKsin(j3);
43588 IkReal x13317=IKcos(j3);
43589 IkReal x13318=((sj0)*(sj5));
43590 IkReal x13319=((r00)*(sj6));
43591 IkReal x13320=((IkReal(1.00000000000000))*(cj4));
43592 IkReal x13321=((cj6)*(r01));
43593 IkReal x13322=((cj0)*(cj5));
43594 IkReal x13323=((cj5)*(sj0));
43595 IkReal x13324=((cj6)*(r11));
43596 IkReal x13325=((cj0)*(sj5));
43597 IkReal x13326=((IkReal(1.00000000000000))*(cj1));
43598 IkReal x13327=((cj6)*(sj4));
43599 IkReal x13328=((IkReal(1.00000000000000))*(sj1));
43600 IkReal x13329=((cj4)*(cj5));
43601 IkReal x13330=((cj6)*(r21));
43602 IkReal x13331=((r20)*(sj6));
43603 IkReal x13332=((r10)*(sj6));
43604 IkReal x13333=((IkReal(1.00000000000000))*(cj0));
43605 IkReal x13334=((cj0)*(sj4)*(sj6));
43606 IkReal x13335=((sj0)*(sj4)*(sj6));
43607 evalcond[0]=((((IkReal(-1.00000000000000))*(x13317)*(x13328)))+(((sj5)*(x13331)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13330))));
43608 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(x13316)*(x13328)))+(((x13329)*(x13331)))+(((cj4)*(r22)*(sj5)))+(((x13329)*(x13330)))+(((r20)*(x13327))));
43609 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x13323)))+(((IkReal(-1.00000000000000))*(x13324)*(x13325)))+(((r12)*(x13322)))+(((x13318)*(x13321)))+(((x13318)*(x13319)))+(x13316)+(((IkReal(-1.00000000000000))*(x13325)*(x13332))));
43610 evalcond[3]=((((r12)*(x13323)))+(((IkReal(-1.00000000000000))*(x13321)*(x13325)))+(((IkReal(-1.00000000000000))*(x13317)*(x13326)))+(((IkReal(-1.00000000000000))*(x13319)*(x13325)))+(((r02)*(x13322)))+(((IkReal(-1.00000000000000))*(x13318)*(x13324)))+(((IkReal(-1.00000000000000))*(x13318)*(x13332))));
43611 evalcond[4]=((((IkReal(-1.00000000000000))*(x13320)*(x13322)*(x13332)))+(((cj4)*(x13321)*(x13323)))+(((cj4)*(x13319)*(x13323)))+(((r11)*(x13334)))+(((IkReal(-1.00000000000000))*(x13317)))+(((IkReal(-1.00000000000000))*(r01)*(x13335)))+(((IkReal(-1.00000000000000))*(x13320)*(x13322)*(x13324)))+(((IkReal(-1.00000000000000))*(r12)*(x13320)*(x13325)))+(((r00)*(sj0)*(x13327)))+(((cj4)*(r02)*(x13318)))+(((IkReal(-1.00000000000000))*(r10)*(x13327)*(x13333))));
43612 evalcond[5]=((((IkReal(-1.00000000000000))*(x13320)*(x13323)*(x13332)))+(((IkReal(-1.00000000000000))*(r12)*(x13318)*(x13320)))+(((IkReal(-1.00000000000000))*(x13316)*(x13326)))+(((IkReal(-1.00000000000000))*(r00)*(x13327)*(x13333)))+(((r11)*(x13335)))+(((IkReal(-1.00000000000000))*(r02)*(x13320)*(x13325)))+(((IkReal(-1.00000000000000))*(x13320)*(x13321)*(x13322)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13327)))+(((IkReal(-1.00000000000000))*(x13320)*(x13323)*(x13324)))+(((IkReal(-1.00000000000000))*(x13319)*(x13320)*(x13322)))+(((r01)*(x13334))));
43613 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43614 {
43615 continue;
43616 }
43617 }
43618 
43619 {
43620 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43621 vinfos[0].jointtype = 1;
43622 vinfos[0].foffset = j0;
43623 vinfos[0].indices[0] = _ij0[0];
43624 vinfos[0].indices[1] = _ij0[1];
43625 vinfos[0].maxsolutions = _nj0;
43626 vinfos[1].jointtype = 1;
43627 vinfos[1].foffset = j1;
43628 vinfos[1].indices[0] = _ij1[0];
43629 vinfos[1].indices[1] = _ij1[1];
43630 vinfos[1].maxsolutions = _nj1;
43631 vinfos[2].jointtype = 1;
43632 vinfos[2].foffset = j2;
43633 vinfos[2].indices[0] = _ij2[0];
43634 vinfos[2].indices[1] = _ij2[1];
43635 vinfos[2].maxsolutions = _nj2;
43636 vinfos[3].jointtype = 1;
43637 vinfos[3].foffset = j3;
43638 vinfos[3].indices[0] = _ij3[0];
43639 vinfos[3].indices[1] = _ij3[1];
43640 vinfos[3].maxsolutions = _nj3;
43641 vinfos[4].jointtype = 1;
43642 vinfos[4].foffset = j4;
43643 vinfos[4].indices[0] = _ij4[0];
43644 vinfos[4].indices[1] = _ij4[1];
43645 vinfos[4].maxsolutions = _nj4;
43646 vinfos[5].jointtype = 1;
43647 vinfos[5].foffset = j5;
43648 vinfos[5].indices[0] = _ij5[0];
43649 vinfos[5].indices[1] = _ij5[1];
43650 vinfos[5].maxsolutions = _nj5;
43651 vinfos[6].jointtype = 1;
43652 vinfos[6].foffset = j6;
43653 vinfos[6].indices[0] = _ij6[0];
43654 vinfos[6].indices[1] = _ij6[1];
43655 vinfos[6].maxsolutions = _nj6;
43656 std::vector<int> vfree(0);
43657 solutions.AddSolution(vinfos,vfree);
43658 }
43659 }
43660 }
43661 
43662 }
43663 
43664 }
43665 
43666 } else
43667 {
43668 {
43669 IkReal j3array[1], cj3array[1], sj3array[1];
43670 bool j3valid[1]={false};
43671 _nj3 = 1;
43672 IkReal x13336=((sj5)*(sj6));
43673 IkReal x13337=((IkReal(1.00000000000000))*(sj0));
43674 IkReal x13338=((cj6)*(sj5));
43675 IkReal x13339=((IkReal(1.00000000000000))*(cj5));
43676 if( IKabs(((((cj0)*(r10)*(x13336)))+(((cj0)*(r11)*(x13338)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x13339)))+(((IkReal(-1.00000000000000))*(r00)*(x13336)*(x13337)))+(((IkReal(-1.00000000000000))*(r01)*(x13337)*(x13338))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13339)))+(((r20)*(x13336)))+(((r21)*(x13338))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((cj0)*(r10)*(x13336)))+(((cj0)*(r11)*(x13338)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x13339)))+(((IkReal(-1.00000000000000))*(r00)*(x13336)*(x13337)))+(((IkReal(-1.00000000000000))*(r01)*(x13337)*(x13338)))))+IKsqr(((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13339)))+(((r20)*(x13336)))+(((r21)*(x13338)))))))-1) <= IKFAST_SINCOS_THRESH )
43677     continue;
43678 j3array[0]=IKatan2(((((cj0)*(r10)*(x13336)))+(((cj0)*(r11)*(x13338)))+(((cj5)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r12)*(x13339)))+(((IkReal(-1.00000000000000))*(r00)*(x13336)*(x13337)))+(((IkReal(-1.00000000000000))*(r01)*(x13337)*(x13338)))), ((((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r22)*(x13339)))+(((r20)*(x13336)))+(((r21)*(x13338)))))));
43679 sj3array[0]=IKsin(j3array[0]);
43680 cj3array[0]=IKcos(j3array[0]);
43681 if( j3array[0] > IKPI )
43682 {
43683     j3array[0]-=IK2PI;
43684 }
43685 else if( j3array[0] < -IKPI )
43686 {    j3array[0]+=IK2PI;
43687 }
43688 j3valid[0] = true;
43689 for(int ij3 = 0; ij3 < 1; ++ij3)
43690 {
43691 if( !j3valid[ij3] )
43692 {
43693     continue;
43694 }
43695 _ij3[0] = ij3; _ij3[1] = -1;
43696 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43697 {
43698 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43699 {
43700     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43701 }
43702 }
43703 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43704 {
43705 IkReal evalcond[6];
43706 IkReal x13340=IKsin(j3);
43707 IkReal x13341=IKcos(j3);
43708 IkReal x13342=((sj0)*(sj5));
43709 IkReal x13343=((r00)*(sj6));
43710 IkReal x13344=((IkReal(1.00000000000000))*(cj4));
43711 IkReal x13345=((cj6)*(r01));
43712 IkReal x13346=((cj0)*(cj5));
43713 IkReal x13347=((cj5)*(sj0));
43714 IkReal x13348=((cj6)*(r11));
43715 IkReal x13349=((cj0)*(sj5));
43716 IkReal x13350=((IkReal(1.00000000000000))*(cj1));
43717 IkReal x13351=((cj6)*(sj4));
43718 IkReal x13352=((IkReal(1.00000000000000))*(sj1));
43719 IkReal x13353=((cj4)*(cj5));
43720 IkReal x13354=((cj6)*(r21));
43721 IkReal x13355=((r20)*(sj6));
43722 IkReal x13356=((r10)*(sj6));
43723 IkReal x13357=((IkReal(1.00000000000000))*(cj0));
43724 IkReal x13358=((cj0)*(sj4)*(sj6));
43725 IkReal x13359=((sj0)*(sj4)*(sj6));
43726 evalcond[0]=((((IkReal(-1.00000000000000))*(x13341)*(x13352)))+(((sj5)*(x13355)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13354))));
43727 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13353)*(x13354)))+(((cj4)*(r22)*(sj5)))+(((x13353)*(x13355)))+(((IkReal(-1.00000000000000))*(x13340)*(x13352)))+(((r20)*(x13351))));
43728 evalcond[2]=((((IkReal(-1.00000000000000))*(x13349)*(x13356)))+(((r12)*(x13346)))+(((IkReal(-1.00000000000000))*(x13348)*(x13349)))+(((x13342)*(x13345)))+(x13340)+(((x13342)*(x13343)))+(((IkReal(-1.00000000000000))*(r02)*(x13347))));
43729 evalcond[3]=((((IkReal(-1.00000000000000))*(x13341)*(x13350)))+(((IkReal(-1.00000000000000))*(x13342)*(x13348)))+(((IkReal(-1.00000000000000))*(x13342)*(x13356)))+(((IkReal(-1.00000000000000))*(x13343)*(x13349)))+(((r12)*(x13347)))+(((r02)*(x13346)))+(((IkReal(-1.00000000000000))*(x13345)*(x13349))));
43730 evalcond[4]=((((IkReal(-1.00000000000000))*(x13344)*(x13346)*(x13348)))+(((IkReal(-1.00000000000000))*(x13341)))+(((IkReal(-1.00000000000000))*(r10)*(x13351)*(x13357)))+(((IkReal(-1.00000000000000))*(x13344)*(x13346)*(x13356)))+(((cj4)*(x13345)*(x13347)))+(((cj4)*(x13343)*(x13347)))+(((r11)*(x13358)))+(((IkReal(-1.00000000000000))*(r01)*(x13359)))+(((cj4)*(r02)*(x13342)))+(((IkReal(-1.00000000000000))*(r12)*(x13344)*(x13349)))+(((r00)*(sj0)*(x13351))));
43731 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13351)))+(((IkReal(-1.00000000000000))*(x13340)*(x13350)))+(((IkReal(-1.00000000000000))*(r12)*(x13342)*(x13344)))+(((IkReal(-1.00000000000000))*(x13344)*(x13345)*(x13346)))+(((IkReal(-1.00000000000000))*(x13344)*(x13347)*(x13348)))+(((IkReal(-1.00000000000000))*(r02)*(x13344)*(x13349)))+(((r01)*(x13358)))+(((r11)*(x13359)))+(((IkReal(-1.00000000000000))*(r00)*(x13351)*(x13357)))+(((IkReal(-1.00000000000000))*(x13344)*(x13347)*(x13356)))+(((IkReal(-1.00000000000000))*(x13343)*(x13344)*(x13346))));
43732 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43733 {
43734 continue;
43735 }
43736 }
43737 
43738 {
43739 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43740 vinfos[0].jointtype = 1;
43741 vinfos[0].foffset = j0;
43742 vinfos[0].indices[0] = _ij0[0];
43743 vinfos[0].indices[1] = _ij0[1];
43744 vinfos[0].maxsolutions = _nj0;
43745 vinfos[1].jointtype = 1;
43746 vinfos[1].foffset = j1;
43747 vinfos[1].indices[0] = _ij1[0];
43748 vinfos[1].indices[1] = _ij1[1];
43749 vinfos[1].maxsolutions = _nj1;
43750 vinfos[2].jointtype = 1;
43751 vinfos[2].foffset = j2;
43752 vinfos[2].indices[0] = _ij2[0];
43753 vinfos[2].indices[1] = _ij2[1];
43754 vinfos[2].maxsolutions = _nj2;
43755 vinfos[3].jointtype = 1;
43756 vinfos[3].foffset = j3;
43757 vinfos[3].indices[0] = _ij3[0];
43758 vinfos[3].indices[1] = _ij3[1];
43759 vinfos[3].maxsolutions = _nj3;
43760 vinfos[4].jointtype = 1;
43761 vinfos[4].foffset = j4;
43762 vinfos[4].indices[0] = _ij4[0];
43763 vinfos[4].indices[1] = _ij4[1];
43764 vinfos[4].maxsolutions = _nj4;
43765 vinfos[5].jointtype = 1;
43766 vinfos[5].foffset = j5;
43767 vinfos[5].indices[0] = _ij5[0];
43768 vinfos[5].indices[1] = _ij5[1];
43769 vinfos[5].maxsolutions = _nj5;
43770 vinfos[6].jointtype = 1;
43771 vinfos[6].foffset = j6;
43772 vinfos[6].indices[0] = _ij6[0];
43773 vinfos[6].indices[1] = _ij6[1];
43774 vinfos[6].maxsolutions = _nj6;
43775 std::vector<int> vfree(0);
43776 solutions.AddSolution(vinfos,vfree);
43777 }
43778 }
43779 }
43780 
43781 }
43782 
43783 }
43784 
43785 } else
43786 {
43787 {
43788 IkReal j3array[1], cj3array[1], sj3array[1];
43789 bool j3valid[1]={false};
43790 _nj3 = 1;
43791 IkReal x13360=((r20)*(sj6));
43792 IkReal x13361=((cj4)*(cj5));
43793 IkReal x13362=((cj6)*(r21));
43794 if( IKabs(((gconst12)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13360)*(x13361)))+(((x13361)*(x13362)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((sj5)*(x13360)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13362))))))) < IKFAST_ATAN2_MAGTHRESH )
43795     continue;
43796 j3array[0]=IKatan2(((gconst12)*(((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13360)*(x13361)))+(((x13361)*(x13362)))+(((cj6)*(r20)*(sj4)))+(((cj4)*(r22)*(sj5)))))), ((gconst12)*(((((sj5)*(x13360)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13362)))))));
43797 sj3array[0]=IKsin(j3array[0]);
43798 cj3array[0]=IKcos(j3array[0]);
43799 if( j3array[0] > IKPI )
43800 {
43801     j3array[0]-=IK2PI;
43802 }
43803 else if( j3array[0] < -IKPI )
43804 {    j3array[0]+=IK2PI;
43805 }
43806 j3valid[0] = true;
43807 for(int ij3 = 0; ij3 < 1; ++ij3)
43808 {
43809 if( !j3valid[ij3] )
43810 {
43811     continue;
43812 }
43813 _ij3[0] = ij3; _ij3[1] = -1;
43814 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43815 {
43816 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43817 {
43818     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43819 }
43820 }
43821 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43822 {
43823 IkReal evalcond[6];
43824 IkReal x13363=IKsin(j3);
43825 IkReal x13364=IKcos(j3);
43826 IkReal x13365=((sj0)*(sj5));
43827 IkReal x13366=((r00)*(sj6));
43828 IkReal x13367=((IkReal(1.00000000000000))*(cj4));
43829 IkReal x13368=((cj6)*(r01));
43830 IkReal x13369=((cj0)*(cj5));
43831 IkReal x13370=((cj5)*(sj0));
43832 IkReal x13371=((cj6)*(r11));
43833 IkReal x13372=((cj0)*(sj5));
43834 IkReal x13373=((IkReal(1.00000000000000))*(cj1));
43835 IkReal x13374=((cj6)*(sj4));
43836 IkReal x13375=((IkReal(1.00000000000000))*(sj1));
43837 IkReal x13376=((cj4)*(cj5));
43838 IkReal x13377=((cj6)*(r21));
43839 IkReal x13378=((r20)*(sj6));
43840 IkReal x13379=((r10)*(sj6));
43841 IkReal x13380=((IkReal(1.00000000000000))*(cj0));
43842 IkReal x13381=((cj0)*(sj4)*(sj6));
43843 IkReal x13382=((sj0)*(sj4)*(sj6));
43844 evalcond[0]=((((IkReal(-1.00000000000000))*(x13364)*(x13375)))+(((sj5)*(x13378)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13377))));
43845 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((cj4)*(r22)*(sj5)))+(((x13376)*(x13378)))+(((r20)*(x13374)))+(((x13376)*(x13377)))+(((IkReal(-1.00000000000000))*(x13363)*(x13375))));
43846 evalcond[2]=((((IkReal(-1.00000000000000))*(x13371)*(x13372)))+(((IkReal(-1.00000000000000))*(r02)*(x13370)))+(((r12)*(x13369)))+(((x13365)*(x13368)))+(((IkReal(-1.00000000000000))*(x13372)*(x13379)))+(x13363)+(((x13365)*(x13366))));
43847 evalcond[3]=((((IkReal(-1.00000000000000))*(x13365)*(x13379)))+(((r02)*(x13369)))+(((IkReal(-1.00000000000000))*(x13365)*(x13371)))+(((IkReal(-1.00000000000000))*(x13366)*(x13372)))+(((r12)*(x13370)))+(((IkReal(-1.00000000000000))*(x13368)*(x13372)))+(((IkReal(-1.00000000000000))*(x13364)*(x13373))));
43848 evalcond[4]=((((IkReal(-1.00000000000000))*(r01)*(x13382)))+(((cj4)*(x13368)*(x13370)))+(((cj4)*(x13366)*(x13370)))+(((IkReal(-1.00000000000000))*(r12)*(x13367)*(x13372)))+(((IkReal(-1.00000000000000))*(x13367)*(x13369)*(x13379)))+(((cj4)*(r02)*(x13365)))+(((r11)*(x13381)))+(((IkReal(-1.00000000000000))*(x13364)))+(((IkReal(-1.00000000000000))*(r10)*(x13374)*(x13380)))+(((r00)*(sj0)*(x13374)))+(((IkReal(-1.00000000000000))*(x13367)*(x13369)*(x13371))));
43849 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x13365)*(x13367)))+(((IkReal(-1.00000000000000))*(r00)*(x13374)*(x13380)))+(((IkReal(-1.00000000000000))*(x13367)*(x13370)*(x13379)))+(((IkReal(-1.00000000000000))*(x13366)*(x13367)*(x13369)))+(((IkReal(-1.00000000000000))*(r02)*(x13367)*(x13372)))+(((r11)*(x13382)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13374)))+(((IkReal(-1.00000000000000))*(x13367)*(x13370)*(x13371)))+(((IkReal(-1.00000000000000))*(x13367)*(x13368)*(x13369)))+(((IkReal(-1.00000000000000))*(x13363)*(x13373)))+(((r01)*(x13381))));
43850 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43851 {
43852 continue;
43853 }
43854 }
43855 
43856 {
43857 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
43858 vinfos[0].jointtype = 1;
43859 vinfos[0].foffset = j0;
43860 vinfos[0].indices[0] = _ij0[0];
43861 vinfos[0].indices[1] = _ij0[1];
43862 vinfos[0].maxsolutions = _nj0;
43863 vinfos[1].jointtype = 1;
43864 vinfos[1].foffset = j1;
43865 vinfos[1].indices[0] = _ij1[0];
43866 vinfos[1].indices[1] = _ij1[1];
43867 vinfos[1].maxsolutions = _nj1;
43868 vinfos[2].jointtype = 1;
43869 vinfos[2].foffset = j2;
43870 vinfos[2].indices[0] = _ij2[0];
43871 vinfos[2].indices[1] = _ij2[1];
43872 vinfos[2].maxsolutions = _nj2;
43873 vinfos[3].jointtype = 1;
43874 vinfos[3].foffset = j3;
43875 vinfos[3].indices[0] = _ij3[0];
43876 vinfos[3].indices[1] = _ij3[1];
43877 vinfos[3].maxsolutions = _nj3;
43878 vinfos[4].jointtype = 1;
43879 vinfos[4].foffset = j4;
43880 vinfos[4].indices[0] = _ij4[0];
43881 vinfos[4].indices[1] = _ij4[1];
43882 vinfos[4].maxsolutions = _nj4;
43883 vinfos[5].jointtype = 1;
43884 vinfos[5].foffset = j5;
43885 vinfos[5].indices[0] = _ij5[0];
43886 vinfos[5].indices[1] = _ij5[1];
43887 vinfos[5].maxsolutions = _nj5;
43888 vinfos[6].jointtype = 1;
43889 vinfos[6].foffset = j6;
43890 vinfos[6].indices[0] = _ij6[0];
43891 vinfos[6].indices[1] = _ij6[1];
43892 vinfos[6].maxsolutions = _nj6;
43893 std::vector<int> vfree(0);
43894 solutions.AddSolution(vinfos,vfree);
43895 }
43896 }
43897 }
43898 
43899 }
43900 
43901 }
43902 
43903 } else
43904 {
43905 if( 1 )
43906 {
43907 continue;
43908 
43909 } else
43910 {
43911 }
43912 }
43913 }
43914 }
43915 }
43916 }
43917 }
43918 }
43919 
43920 } else
43921 {
43922 {
43923 IkReal j3array[1], cj3array[1], sj3array[1];
43924 bool j3valid[1]={false};
43925 _nj3 = 1;
43926 IkReal x13383=((IKabs(sj2) != 0)?((IkReal)1/(sj2)):(IkReal)1.0e30);
43927 IkReal x13384=((sj5)*(sj6));
43928 IkReal x13385=((r00)*(sj0));
43929 IkReal x13386=((cj1)*(cj2));
43930 IkReal x13387=((cj0)*(r10));
43931 IkReal x13388=((cj6)*(sj5));
43932 IkReal x13389=((r01)*(sj0));
43933 IkReal x13390=((IkReal(1.00000000000000))*(cj0));
43934 IkReal x13391=((cj5)*(r12));
43935 IkReal x13392=((IkReal(1.00000000000000))*(cj5));
43936 IkReal x13393=((r02)*(sj0));
43937 if( IKabs(((x13383)*(((((x13384)*(x13385)))+(((cj0)*(x13391)))+(((IkReal(-1.00000000000000))*(r11)*(x13388)*(x13390)))+(((IkReal(-1.00000000000000))*(x13392)*(x13393)))+(((x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13384)*(x13387))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x13383)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13386)*(x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13386)*(x13390)*(x13391)))+(((IkReal(-1.00000000000000))*(x13384)*(x13385)*(x13386)))+(((cj0)*(r11)*(x13386)*(x13388)))+(((r20)*(sj2)*(x13384)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x13392)))+(((cj5)*(x13386)*(x13393)))+(((x13384)*(x13386)*(x13387)))+(((r21)*(sj2)*(x13388))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x13383)*(((((x13384)*(x13385)))+(((cj0)*(x13391)))+(((IkReal(-1.00000000000000))*(r11)*(x13388)*(x13390)))+(((IkReal(-1.00000000000000))*(x13392)*(x13393)))+(((x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13384)*(x13387)))))))+IKsqr(((x13383)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13386)*(x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13386)*(x13390)*(x13391)))+(((IkReal(-1.00000000000000))*(x13384)*(x13385)*(x13386)))+(((cj0)*(r11)*(x13386)*(x13388)))+(((r20)*(sj2)*(x13384)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x13392)))+(((cj5)*(x13386)*(x13393)))+(((x13384)*(x13386)*(x13387)))+(((r21)*(sj2)*(x13388)))))))-1) <= IKFAST_SINCOS_THRESH )
43938     continue;
43939 j3array[0]=IKatan2(((x13383)*(((((x13384)*(x13385)))+(((cj0)*(x13391)))+(((IkReal(-1.00000000000000))*(r11)*(x13388)*(x13390)))+(((IkReal(-1.00000000000000))*(x13392)*(x13393)))+(((x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13384)*(x13387)))))), ((x13383)*(((IKabs(sj1) != 0)?((IkReal)1/(sj1)):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13386)*(x13388)*(x13389)))+(((IkReal(-1.00000000000000))*(x13386)*(x13390)*(x13391)))+(((IkReal(-1.00000000000000))*(x13384)*(x13385)*(x13386)))+(((cj0)*(r11)*(x13386)*(x13388)))+(((r20)*(sj2)*(x13384)))+(((IkReal(-1.00000000000000))*(r22)*(sj2)*(x13392)))+(((cj5)*(x13386)*(x13393)))+(((x13384)*(x13386)*(x13387)))+(((r21)*(sj2)*(x13388)))))));
43940 sj3array[0]=IKsin(j3array[0]);
43941 cj3array[0]=IKcos(j3array[0]);
43942 if( j3array[0] > IKPI )
43943 {
43944     j3array[0]-=IK2PI;
43945 }
43946 else if( j3array[0] < -IKPI )
43947 {    j3array[0]+=IK2PI;
43948 }
43949 j3valid[0] = true;
43950 for(int ij3 = 0; ij3 < 1; ++ij3)
43951 {
43952 if( !j3valid[ij3] )
43953 {
43954     continue;
43955 }
43956 _ij3[0] = ij3; _ij3[1] = -1;
43957 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
43958 {
43959 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
43960 {
43961     j3valid[iij3]=false; _ij3[1] = iij3; break; 
43962 }
43963 }
43964 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
43965 {
43966 IkReal evalcond[6];
43967 IkReal x13394=IKcos(j3);
43968 IkReal x13395=IKsin(j3);
43969 IkReal x13396=((sj0)*(sj5));
43970 IkReal x13397=((r00)*(sj6));
43971 IkReal x13398=((IkReal(1.00000000000000))*(cj4));
43972 IkReal x13399=((cj6)*(r01));
43973 IkReal x13400=((cj0)*(cj5));
43974 IkReal x13401=((cj5)*(sj0));
43975 IkReal x13402=((cj6)*(r11));
43976 IkReal x13403=((cj6)*(sj4));
43977 IkReal x13404=((IkReal(1.00000000000000))*(cj1));
43978 IkReal x13405=((cj4)*(cj5));
43979 IkReal x13406=((cj6)*(r21));
43980 IkReal x13407=((r20)*(sj6));
43981 IkReal x13408=((r10)*(sj6));
43982 IkReal x13409=((cj0)*(sj5));
43983 IkReal x13410=((IkReal(1.00000000000000))*(cj0));
43984 IkReal x13411=((IkReal(1.00000000000000))*(x13409));
43985 IkReal x13412=((IkReal(1.00000000000000))*(x13395));
43986 IkReal x13413=((cj0)*(sj4)*(sj6));
43987 IkReal x13414=((cj2)*(x13395));
43988 IkReal x13415=((sj0)*(sj4)*(sj6));
43989 IkReal x13416=((IkReal(1.00000000000000))*(sj1)*(x13394));
43990 evalcond[0]=((((IkReal(-1.00000000000000))*(x13404)*(x13414)))+(((IkReal(-1.00000000000000))*(x13416)))+(((sj5)*(x13406)))+(((sj5)*(x13407)))+(((IkReal(-1.00000000000000))*(cj5)*(r22))));
43991 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13405)*(x13407)))+(((cj4)*(r22)*(sj5)))+(((cj1)*(cj2)*(x13394)))+(((r20)*(x13403)))+(((IkReal(-1.00000000000000))*(sj1)*(x13412)))+(((x13405)*(x13406))));
43992 evalcond[2]=((((x13396)*(x13399)))+(((r12)*(x13400)))+(((IkReal(-1.00000000000000))*(x13402)*(x13411)))+(((IkReal(-1.00000000000000))*(r02)*(x13401)))+(((IkReal(-1.00000000000000))*(x13408)*(x13411)))+(((x13396)*(x13397)))+(((IkReal(-1.00000000000000))*(sj2)*(x13412))));
43993 evalcond[3]=((((IkReal(-1.00000000000000))*(x13396)*(x13402)))+(((IkReal(-1.00000000000000))*(x13394)*(x13404)))+(((r12)*(x13401)))+(((IkReal(-1.00000000000000))*(x13399)*(x13411)))+(((IkReal(-1.00000000000000))*(x13396)*(x13408)))+(((r02)*(x13400)))+(((IkReal(-1.00000000000000))*(x13397)*(x13411)))+(((sj1)*(x13414))));
43994 evalcond[4]=((((IkReal(-1.00000000000000))*(x13398)*(x13400)*(x13402)))+(((cj4)*(x13399)*(x13401)))+(((cj4)*(r02)*(x13396)))+(((cj4)*(x13397)*(x13401)))+(((IkReal(-1.00000000000000))*(x13398)*(x13400)*(x13408)))+(((IkReal(-1.00000000000000))*(r01)*(x13415)))+(((sj2)*(x13394)))+(((IkReal(-1.00000000000000))*(r12)*(x13398)*(x13409)))+(((r00)*(sj0)*(x13403)))+(((IkReal(-1.00000000000000))*(r10)*(x13403)*(x13410)))+(((r11)*(x13413))));
43995 evalcond[5]=((((IkReal(-1.00000000000000))*(x13398)*(x13401)*(x13402)))+(((IkReal(-1.00000000000000))*(x13398)*(x13401)*(x13408)))+(((IkReal(-1.00000000000000))*(r00)*(x13403)*(x13410)))+(((r01)*(x13413)))+(((IkReal(-1.00000000000000))*(cj2)*(x13416)))+(((IkReal(-1.00000000000000))*(r02)*(x13398)*(x13409)))+(((IkReal(-1.00000000000000))*(x13395)*(x13404)))+(((IkReal(-1.00000000000000))*(r12)*(x13396)*(x13398)))+(((IkReal(-1.00000000000000))*(x13397)*(x13398)*(x13400)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13403)))+(((r11)*(x13415)))+(((IkReal(-1.00000000000000))*(x13398)*(x13399)*(x13400))));
43996 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
43997 {
43998 continue;
43999 }
44000 }
44001 
44002 {
44003 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
44004 vinfos[0].jointtype = 1;
44005 vinfos[0].foffset = j0;
44006 vinfos[0].indices[0] = _ij0[0];
44007 vinfos[0].indices[1] = _ij0[1];
44008 vinfos[0].maxsolutions = _nj0;
44009 vinfos[1].jointtype = 1;
44010 vinfos[1].foffset = j1;
44011 vinfos[1].indices[0] = _ij1[0];
44012 vinfos[1].indices[1] = _ij1[1];
44013 vinfos[1].maxsolutions = _nj1;
44014 vinfos[2].jointtype = 1;
44015 vinfos[2].foffset = j2;
44016 vinfos[2].indices[0] = _ij2[0];
44017 vinfos[2].indices[1] = _ij2[1];
44018 vinfos[2].maxsolutions = _nj2;
44019 vinfos[3].jointtype = 1;
44020 vinfos[3].foffset = j3;
44021 vinfos[3].indices[0] = _ij3[0];
44022 vinfos[3].indices[1] = _ij3[1];
44023 vinfos[3].maxsolutions = _nj3;
44024 vinfos[4].jointtype = 1;
44025 vinfos[4].foffset = j4;
44026 vinfos[4].indices[0] = _ij4[0];
44027 vinfos[4].indices[1] = _ij4[1];
44028 vinfos[4].maxsolutions = _nj4;
44029 vinfos[5].jointtype = 1;
44030 vinfos[5].foffset = j5;
44031 vinfos[5].indices[0] = _ij5[0];
44032 vinfos[5].indices[1] = _ij5[1];
44033 vinfos[5].maxsolutions = _nj5;
44034 vinfos[6].jointtype = 1;
44035 vinfos[6].foffset = j6;
44036 vinfos[6].indices[0] = _ij6[0];
44037 vinfos[6].indices[1] = _ij6[1];
44038 vinfos[6].maxsolutions = _nj6;
44039 std::vector<int> vfree(0);
44040 solutions.AddSolution(vinfos,vfree);
44041 }
44042 }
44043 }
44044 
44045 }
44046 
44047 }
44048 
44049 } else
44050 {
44051 {
44052 IkReal j3array[1], cj3array[1], sj3array[1];
44053 bool j3valid[1]={false};
44054 _nj3 = 1;
44055 IkReal x13417=(cj1)*(cj1);
44056 IkReal x13418=(sj1)*(sj1);
44057 IkReal x13419=((r00)*(sj6));
44058 IkReal x13420=((cj6)*(r01));
44059 IkReal x13421=((IkReal(1.00000000000000))*(cj1));
44060 IkReal x13422=((cj5)*(r22));
44061 IkReal x13423=((sj5)*(sj6));
44062 IkReal x13424=((r10)*(sj0));
44063 IkReal x13425=((cj1)*(cj5));
44064 IkReal x13426=((cj0)*(r02));
44065 IkReal x13427=((r12)*(sj0));
44066 IkReal x13428=((IkReal(1.00000000000000))*(sj1));
44067 IkReal x13429=((cj6)*(sj5));
44068 IkReal x13430=((cj0)*(sj5));
44069 IkReal x13431=((r11)*(sj0));
44070 IkReal x13432=((sj1)*(x13430));
44071 if( IKabs(((((IKabs(((((cj2)*(x13418)))+(((cj2)*(x13417))))) != 0)?((IkReal)1/(((((cj2)*(x13418)))+(((cj2)*(x13417)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x13426)*(x13428)))+(((cj1)*(r21)*(x13429)))+(((x13420)*(x13432)))+(((sj1)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13421)*(x13422)))+(((sj1)*(x13423)*(x13424)))+(((cj1)*(r20)*(x13423)))+(((x13419)*(x13432)))+(((IkReal(-1.00000000000000))*(cj5)*(x13427)*(x13428))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((x13417)+(x13418))) != 0)?((IkReal)1/(((x13417)+(x13418)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13419)*(x13421)*(x13430)))+(((r20)*(sj1)*(x13423)))+(((x13425)*(x13427)))+(((r21)*(sj1)*(x13429)))+(((IkReal(-1.00000000000000))*(x13421)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13420)*(x13421)*(x13430)))+(((x13425)*(x13426)))+(((IkReal(-1.00000000000000))*(x13421)*(x13423)*(x13424)))+(((IkReal(-1.00000000000000))*(x13422)*(x13428))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(((((cj2)*(x13418)))+(((cj2)*(x13417))))) != 0)?((IkReal)1/(((((cj2)*(x13418)))+(((cj2)*(x13417)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x13426)*(x13428)))+(((cj1)*(r21)*(x13429)))+(((x13420)*(x13432)))+(((sj1)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13421)*(x13422)))+(((sj1)*(x13423)*(x13424)))+(((cj1)*(r20)*(x13423)))+(((x13419)*(x13432)))+(((IkReal(-1.00000000000000))*(cj5)*(x13427)*(x13428)))))))+IKsqr(((((IKabs(((x13417)+(x13418))) != 0)?((IkReal)1/(((x13417)+(x13418)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13419)*(x13421)*(x13430)))+(((r20)*(sj1)*(x13423)))+(((x13425)*(x13427)))+(((r21)*(sj1)*(x13429)))+(((IkReal(-1.00000000000000))*(x13421)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13420)*(x13421)*(x13430)))+(((x13425)*(x13426)))+(((IkReal(-1.00000000000000))*(x13421)*(x13423)*(x13424)))+(((IkReal(-1.00000000000000))*(x13422)*(x13428)))))))-1) <= IKFAST_SINCOS_THRESH )
44072     continue;
44073 j3array[0]=IKatan2(((((IKabs(((((cj2)*(x13418)))+(((cj2)*(x13417))))) != 0)?((IkReal)1/(((((cj2)*(x13418)))+(((cj2)*(x13417)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(cj5)*(x13426)*(x13428)))+(((cj1)*(r21)*(x13429)))+(((x13420)*(x13432)))+(((sj1)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13421)*(x13422)))+(((sj1)*(x13423)*(x13424)))+(((cj1)*(r20)*(x13423)))+(((x13419)*(x13432)))+(((IkReal(-1.00000000000000))*(cj5)*(x13427)*(x13428)))))), ((((IKabs(((x13417)+(x13418))) != 0)?((IkReal)1/(((x13417)+(x13418)))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(x13419)*(x13421)*(x13430)))+(((r20)*(sj1)*(x13423)))+(((x13425)*(x13427)))+(((r21)*(sj1)*(x13429)))+(((IkReal(-1.00000000000000))*(x13421)*(x13429)*(x13431)))+(((IkReal(-1.00000000000000))*(x13420)*(x13421)*(x13430)))+(((x13425)*(x13426)))+(((IkReal(-1.00000000000000))*(x13421)*(x13423)*(x13424)))+(((IkReal(-1.00000000000000))*(x13422)*(x13428)))))));
44074 sj3array[0]=IKsin(j3array[0]);
44075 cj3array[0]=IKcos(j3array[0]);
44076 if( j3array[0] > IKPI )
44077 {
44078     j3array[0]-=IK2PI;
44079 }
44080 else if( j3array[0] < -IKPI )
44081 {    j3array[0]+=IK2PI;
44082 }
44083 j3valid[0] = true;
44084 for(int ij3 = 0; ij3 < 1; ++ij3)
44085 {
44086 if( !j3valid[ij3] )
44087 {
44088     continue;
44089 }
44090 _ij3[0] = ij3; _ij3[1] = -1;
44091 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
44092 {
44093 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
44094 {
44095     j3valid[iij3]=false; _ij3[1] = iij3; break; 
44096 }
44097 }
44098 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
44099 {
44100 IkReal evalcond[6];
44101 IkReal x13433=IKcos(j3);
44102 IkReal x13434=IKsin(j3);
44103 IkReal x13435=((sj0)*(sj5));
44104 IkReal x13436=((r00)*(sj6));
44105 IkReal x13437=((IkReal(1.00000000000000))*(cj4));
44106 IkReal x13438=((cj6)*(r01));
44107 IkReal x13439=((cj0)*(cj5));
44108 IkReal x13440=((cj5)*(sj0));
44109 IkReal x13441=((cj6)*(r11));
44110 IkReal x13442=((cj6)*(sj4));
44111 IkReal x13443=((IkReal(1.00000000000000))*(cj1));
44112 IkReal x13444=((cj4)*(cj5));
44113 IkReal x13445=((cj6)*(r21));
44114 IkReal x13446=((r20)*(sj6));
44115 IkReal x13447=((r10)*(sj6));
44116 IkReal x13448=((cj0)*(sj5));
44117 IkReal x13449=((IkReal(1.00000000000000))*(cj0));
44118 IkReal x13450=((IkReal(1.00000000000000))*(x13448));
44119 IkReal x13451=((IkReal(1.00000000000000))*(x13434));
44120 IkReal x13452=((cj0)*(sj4)*(sj6));
44121 IkReal x13453=((cj2)*(x13434));
44122 IkReal x13454=((sj0)*(sj4)*(sj6));
44123 IkReal x13455=((IkReal(1.00000000000000))*(sj1)*(x13433));
44124 evalcond[0]=((((IkReal(-1.00000000000000))*(x13455)))+(((sj5)*(x13445)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((IkReal(-1.00000000000000))*(x13443)*(x13453)))+(((sj5)*(x13446))));
44125 evalcond[1]=((((r20)*(x13442)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((IkReal(-1.00000000000000))*(sj1)*(x13451)))+(((cj4)*(r22)*(sj5)))+(((cj1)*(cj2)*(x13433)))+(((x13444)*(x13446)))+(((x13444)*(x13445))));
44126 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x13440)))+(((IkReal(-1.00000000000000))*(sj2)*(x13451)))+(((r12)*(x13439)))+(((IkReal(-1.00000000000000))*(x13447)*(x13450)))+(((IkReal(-1.00000000000000))*(x13441)*(x13450)))+(((x13435)*(x13436)))+(((x13435)*(x13438))));
44127 evalcond[3]=((((sj1)*(x13453)))+(((IkReal(-1.00000000000000))*(x13438)*(x13450)))+(((r02)*(x13439)))+(((IkReal(-1.00000000000000))*(x13433)*(x13443)))+(((IkReal(-1.00000000000000))*(x13436)*(x13450)))+(((IkReal(-1.00000000000000))*(x13435)*(x13441)))+(((r12)*(x13440)))+(((IkReal(-1.00000000000000))*(x13435)*(x13447))));
44128 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x13442)*(x13449)))+(((cj4)*(r02)*(x13435)))+(((sj2)*(x13433)))+(((r11)*(x13452)))+(((cj4)*(x13436)*(x13440)))+(((IkReal(-1.00000000000000))*(x13437)*(x13439)*(x13441)))+(((IkReal(-1.00000000000000))*(r01)*(x13454)))+(((r00)*(sj0)*(x13442)))+(((IkReal(-1.00000000000000))*(r12)*(x13437)*(x13448)))+(((cj4)*(x13438)*(x13440)))+(((IkReal(-1.00000000000000))*(x13437)*(x13439)*(x13447))));
44129 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x13437)*(x13448)))+(((IkReal(-1.00000000000000))*(x13434)*(x13443)))+(((IkReal(-1.00000000000000))*(r12)*(x13435)*(x13437)))+(((IkReal(-1.00000000000000))*(x13436)*(x13437)*(x13439)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13442)))+(((IkReal(-1.00000000000000))*(x13437)*(x13438)*(x13439)))+(((IkReal(-1.00000000000000))*(x13437)*(x13440)*(x13447)))+(((r01)*(x13452)))+(((IkReal(-1.00000000000000))*(cj2)*(x13455)))+(((IkReal(-1.00000000000000))*(r00)*(x13442)*(x13449)))+(((IkReal(-1.00000000000000))*(x13437)*(x13440)*(x13441)))+(((r11)*(x13454))));
44130 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
44131 {
44132 continue;
44133 }
44134 }
44135 
44136 {
44137 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
44138 vinfos[0].jointtype = 1;
44139 vinfos[0].foffset = j0;
44140 vinfos[0].indices[0] = _ij0[0];
44141 vinfos[0].indices[1] = _ij0[1];
44142 vinfos[0].maxsolutions = _nj0;
44143 vinfos[1].jointtype = 1;
44144 vinfos[1].foffset = j1;
44145 vinfos[1].indices[0] = _ij1[0];
44146 vinfos[1].indices[1] = _ij1[1];
44147 vinfos[1].maxsolutions = _nj1;
44148 vinfos[2].jointtype = 1;
44149 vinfos[2].foffset = j2;
44150 vinfos[2].indices[0] = _ij2[0];
44151 vinfos[2].indices[1] = _ij2[1];
44152 vinfos[2].maxsolutions = _nj2;
44153 vinfos[3].jointtype = 1;
44154 vinfos[3].foffset = j3;
44155 vinfos[3].indices[0] = _ij3[0];
44156 vinfos[3].indices[1] = _ij3[1];
44157 vinfos[3].maxsolutions = _nj3;
44158 vinfos[4].jointtype = 1;
44159 vinfos[4].foffset = j4;
44160 vinfos[4].indices[0] = _ij4[0];
44161 vinfos[4].indices[1] = _ij4[1];
44162 vinfos[4].maxsolutions = _nj4;
44163 vinfos[5].jointtype = 1;
44164 vinfos[5].foffset = j5;
44165 vinfos[5].indices[0] = _ij5[0];
44166 vinfos[5].indices[1] = _ij5[1];
44167 vinfos[5].maxsolutions = _nj5;
44168 vinfos[6].jointtype = 1;
44169 vinfos[6].foffset = j6;
44170 vinfos[6].indices[0] = _ij6[0];
44171 vinfos[6].indices[1] = _ij6[1];
44172 vinfos[6].maxsolutions = _nj6;
44173 std::vector<int> vfree(0);
44174 solutions.AddSolution(vinfos,vfree);
44175 }
44176 }
44177 }
44178 
44179 }
44180 
44181 }
44182 
44183 } else
44184 {
44185 {
44186 IkReal j3array[1], cj3array[1], sj3array[1];
44187 bool j3valid[1]={false};
44188 _nj3 = 1;
44189 IkReal x13456=((sj1)*(sj6));
44190 IkReal x13457=((r20)*(sj5));
44191 IkReal x13458=((IkReal(1.00000000000000))*(r21));
44192 IkReal x13459=((cj5)*(cj6));
44193 IkReal x13460=((r22)*(sj5));
44194 IkReal x13461=((cj4)*(sj1));
44195 IkReal x13462=((cj1)*(cj2));
44196 IkReal x13463=((cj5)*(r20));
44197 IkReal x13464=((cj4)*(x13462));
44198 IkReal x13465=((IkReal(1.00000000000000))*(cj5)*(r22));
44199 IkReal x13466=((cj6)*(r20)*(sj4));
44200 IkReal x13467=((cj6)*(r21)*(sj5));
44201 if( IKabs(((gconst4)*(((((sj1)*(x13466)))+(((IkReal(-1.00000000000000))*(sj4)*(x13456)*(x13458)))+(((x13460)*(x13461)))+(((cj4)*(x13456)*(x13463)))+(((r21)*(x13459)*(x13461)))+(((x13462)*(x13467)))+(((IkReal(-1.00000000000000))*(x13462)*(x13465)))+(((sj6)*(x13457)*(x13462))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((sj1)*(x13467)))+(((IkReal(-1.00000000000000))*(x13460)*(x13464)))+(((x13456)*(x13457)))+(((IkReal(-1.00000000000000))*(x13458)*(x13459)*(x13464)))+(((IkReal(-1.00000000000000))*(sj6)*(x13463)*(x13464)))+(((IkReal(-1.00000000000000))*(x13462)*(x13466)))+(((IkReal(-1.00000000000000))*(sj1)*(x13465)))+(((r21)*(sj4)*(sj6)*(x13462))))))) < IKFAST_ATAN2_MAGTHRESH )
44202     continue;
44203 j3array[0]=IKatan2(((gconst4)*(((((sj1)*(x13466)))+(((IkReal(-1.00000000000000))*(sj4)*(x13456)*(x13458)))+(((x13460)*(x13461)))+(((cj4)*(x13456)*(x13463)))+(((r21)*(x13459)*(x13461)))+(((x13462)*(x13467)))+(((IkReal(-1.00000000000000))*(x13462)*(x13465)))+(((sj6)*(x13457)*(x13462)))))), ((gconst4)*(((((sj1)*(x13467)))+(((IkReal(-1.00000000000000))*(x13460)*(x13464)))+(((x13456)*(x13457)))+(((IkReal(-1.00000000000000))*(x13458)*(x13459)*(x13464)))+(((IkReal(-1.00000000000000))*(sj6)*(x13463)*(x13464)))+(((IkReal(-1.00000000000000))*(x13462)*(x13466)))+(((IkReal(-1.00000000000000))*(sj1)*(x13465)))+(((r21)*(sj4)*(sj6)*(x13462)))))));
44204 sj3array[0]=IKsin(j3array[0]);
44205 cj3array[0]=IKcos(j3array[0]);
44206 if( j3array[0] > IKPI )
44207 {
44208     j3array[0]-=IK2PI;
44209 }
44210 else if( j3array[0] < -IKPI )
44211 {    j3array[0]+=IK2PI;
44212 }
44213 j3valid[0] = true;
44214 for(int ij3 = 0; ij3 < 1; ++ij3)
44215 {
44216 if( !j3valid[ij3] )
44217 {
44218     continue;
44219 }
44220 _ij3[0] = ij3; _ij3[1] = -1;
44221 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
44222 {
44223 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
44224 {
44225     j3valid[iij3]=false; _ij3[1] = iij3; break; 
44226 }
44227 }
44228 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
44229 {
44230 IkReal evalcond[6];
44231 IkReal x13468=IKcos(j3);
44232 IkReal x13469=IKsin(j3);
44233 IkReal x13470=((sj0)*(sj5));
44234 IkReal x13471=((r00)*(sj6));
44235 IkReal x13472=((IkReal(1.00000000000000))*(cj4));
44236 IkReal x13473=((cj6)*(r01));
44237 IkReal x13474=((cj0)*(cj5));
44238 IkReal x13475=((cj5)*(sj0));
44239 IkReal x13476=((cj6)*(r11));
44240 IkReal x13477=((cj6)*(sj4));
44241 IkReal x13478=((IkReal(1.00000000000000))*(cj1));
44242 IkReal x13479=((cj4)*(cj5));
44243 IkReal x13480=((cj6)*(r21));
44244 IkReal x13481=((r20)*(sj6));
44245 IkReal x13482=((r10)*(sj6));
44246 IkReal x13483=((cj0)*(sj5));
44247 IkReal x13484=((IkReal(1.00000000000000))*(cj0));
44248 IkReal x13485=((IkReal(1.00000000000000))*(x13483));
44249 IkReal x13486=((IkReal(1.00000000000000))*(x13469));
44250 IkReal x13487=((cj0)*(sj4)*(sj6));
44251 IkReal x13488=((cj2)*(x13469));
44252 IkReal x13489=((sj0)*(sj4)*(sj6));
44253 IkReal x13490=((IkReal(1.00000000000000))*(sj1)*(x13468));
44254 evalcond[0]=((((IkReal(-1.00000000000000))*(x13490)))+(((sj5)*(x13480)))+(((IkReal(-1.00000000000000))*(cj5)*(r22)))+(((sj5)*(x13481)))+(((IkReal(-1.00000000000000))*(x13478)*(x13488))));
44255 evalcond[1]=((((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj6)))+(((x13479)*(x13480)))+(((cj1)*(cj2)*(x13468)))+(((IkReal(-1.00000000000000))*(sj1)*(x13486)))+(((cj4)*(r22)*(sj5)))+(((r20)*(x13477)))+(((x13479)*(x13481))));
44256 evalcond[2]=((((x13470)*(x13471)))+(((IkReal(-1.00000000000000))*(x13482)*(x13485)))+(((x13470)*(x13473)))+(((IkReal(-1.00000000000000))*(sj2)*(x13486)))+(((r12)*(x13474)))+(((IkReal(-1.00000000000000))*(x13476)*(x13485)))+(((IkReal(-1.00000000000000))*(r02)*(x13475))));
44257 evalcond[3]=((((sj1)*(x13488)))+(((IkReal(-1.00000000000000))*(x13470)*(x13476)))+(((IkReal(-1.00000000000000))*(x13468)*(x13478)))+(((r02)*(x13474)))+(((IkReal(-1.00000000000000))*(x13471)*(x13485)))+(((IkReal(-1.00000000000000))*(x13470)*(x13482)))+(((IkReal(-1.00000000000000))*(x13473)*(x13485)))+(((r12)*(x13475))));
44258 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x13477)*(x13484)))+(((IkReal(-1.00000000000000))*(r12)*(x13472)*(x13483)))+(((cj4)*(x13471)*(x13475)))+(((IkReal(-1.00000000000000))*(x13472)*(x13474)*(x13476)))+(((IkReal(-1.00000000000000))*(x13472)*(x13474)*(x13482)))+(((r00)*(sj0)*(x13477)))+(((r11)*(x13487)))+(((sj2)*(x13468)))+(((cj4)*(x13473)*(x13475)))+(((IkReal(-1.00000000000000))*(r01)*(x13489)))+(((cj4)*(r02)*(x13470))));
44259 evalcond[5]=((((IkReal(-1.00000000000000))*(x13471)*(x13472)*(x13474)))+(((IkReal(-1.00000000000000))*(cj2)*(x13490)))+(((r11)*(x13489)))+(((IkReal(-1.00000000000000))*(x13472)*(x13475)*(x13482)))+(((IkReal(-1.00000000000000))*(x13469)*(x13478)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x13477)))+(((IkReal(-1.00000000000000))*(r02)*(x13472)*(x13483)))+(((r01)*(x13487)))+(((IkReal(-1.00000000000000))*(x13472)*(x13475)*(x13476)))+(((IkReal(-1.00000000000000))*(r12)*(x13470)*(x13472)))+(((IkReal(-1.00000000000000))*(r00)*(x13477)*(x13484)))+(((IkReal(-1.00000000000000))*(x13472)*(x13473)*(x13474))));
44260 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
44261 {
44262 continue;
44263 }
44264 }
44265 
44266 {
44267 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(7);
44268 vinfos[0].jointtype = 1;
44269 vinfos[0].foffset = j0;
44270 vinfos[0].indices[0] = _ij0[0];
44271 vinfos[0].indices[1] = _ij0[1];
44272 vinfos[0].maxsolutions = _nj0;
44273 vinfos[1].jointtype = 1;
44274 vinfos[1].foffset = j1;
44275 vinfos[1].indices[0] = _ij1[0];
44276 vinfos[1].indices[1] = _ij1[1];
44277 vinfos[1].maxsolutions = _nj1;
44278 vinfos[2].jointtype = 1;
44279 vinfos[2].foffset = j2;
44280 vinfos[2].indices[0] = _ij2[0];
44281 vinfos[2].indices[1] = _ij2[1];
44282 vinfos[2].maxsolutions = _nj2;
44283 vinfos[3].jointtype = 1;
44284 vinfos[3].foffset = j3;
44285 vinfos[3].indices[0] = _ij3[0];
44286 vinfos[3].indices[1] = _ij3[1];
44287 vinfos[3].maxsolutions = _nj3;
44288 vinfos[4].jointtype = 1;
44289 vinfos[4].foffset = j4;
44290 vinfos[4].indices[0] = _ij4[0];
44291 vinfos[4].indices[1] = _ij4[1];
44292 vinfos[4].maxsolutions = _nj4;
44293 vinfos[5].jointtype = 1;
44294 vinfos[5].foffset = j5;
44295 vinfos[5].indices[0] = _ij5[0];
44296 vinfos[5].indices[1] = _ij5[1];
44297 vinfos[5].maxsolutions = _nj5;
44298 vinfos[6].jointtype = 1;
44299 vinfos[6].foffset = j6;
44300 vinfos[6].indices[0] = _ij6[0];
44301 vinfos[6].indices[1] = _ij6[1];
44302 vinfos[6].maxsolutions = _nj6;
44303 std::vector<int> vfree(0);
44304 solutions.AddSolution(vinfos,vfree);
44305 }
44306 }
44307 }
44308 
44309 }
44310 
44311 }
44312 }
44313 }
44314 
44315 }
44316 
44317 }
44318 }
44319 }
44320 
44321 }
44322 
44323 }
44324     }
44325 }
44326 return solutions.GetNumSolutions()>0;
44327 }
44328 
44329 static inline bool checkconsistency8(const IkReal* Breal)
44330 {
44331     IkReal norm = 0.1;
44332     for(int i = 0; i < 7; ++i) {
44333         norm += IKabs(Breal[i]);
44334     }
44335     IkReal tol = 1e-5*norm; // have to increase the threshold since many computations are involved
44336     return IKabs(Breal[0]*Breal[1]-Breal[2]) < tol && IKabs(Breal[1]*Breal[1]-Breal[3]) < tol && IKabs(Breal[0]*Breal[3]-Breal[4]) < tol && IKabs(Breal[1]*Breal[3]-Breal[5]) < tol && IKabs(Breal[0]*Breal[5]-Breal[6]) < tol;
44337 }
44341 static inline void solvedialyticpoly8qep(const IkReal* matcoeffs, IkReal* rawroots, int& numroots)
44342 {
44343     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
44344     IkReal IKFAST_ALIGNED16(M[16*16]) = {0};
44345     IkReal IKFAST_ALIGNED16(A[8*8]);
44346     IkReal IKFAST_ALIGNED16(work[16*16*15]);
44347     int ipiv[8];
44348     int info, coeffindex;
44349     const int worksize=16*16*15;
44350     const int matrixdim = 8;
44351     const int matrixdim2 = 16;
44352     numroots = 0;
44353     // first setup M = [0 I; -C -B] and A
44354     coeffindex = 0;
44355     for(int j = 0; j < 4; ++j) {
44356         for(int k = 0; k < 6; ++k) {
44357             M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -matcoeffs[coeffindex++];
44358         }
44359     }
44360     for(int j = 0; j < 4; ++j) {
44361         for(int k = 0; k < 6; ++k) {
44362             M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -matcoeffs[coeffindex++];
44363         }
44364     }
44365     for(int j = 0; j < 4; ++j) {
44366         for(int k = 0; k < 6; ++k) {
44367             A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = matcoeffs[coeffindex++];
44368         }
44369         for(int k = 0; k < 2; ++k) {
44370             A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
44371         }
44372     }
44373     const IkReal lfpossibilities[4][4] = {{1,-1,1,1},{1,0,-2,1},{1,1,2,0},{1,-1,4,1}};
44374     int lfindex = -1;
44375     bool bsingular = true;
44376     do {
44377         dgetrf_(&matrixdim,&matrixdim,A,&matrixdim,&ipiv[0],&info);
44378         if( info == 0 ) {
44379             bsingular = false;
44380             for(int j = 0; j < matrixdim; ++j) {
44381                 if( IKabs(A[j*matrixdim+j]) < 100*tol ) {
44382                     bsingular = true;
44383                     break;
44384                 }
44385             }
44386             if( !bsingular ) {
44387                 break;
44388             }
44389         }
44390         if( lfindex == 3 ) {
44391             break;
44392         }
44393         // transform by the linear functional
44394         lfindex++;
44395         const IkReal* lf = lfpossibilities[lfindex];
44396         // have to reinitialize A
44397         coeffindex = 0;
44398         for(int j = 0; j < 4; ++j) {
44399             for(int k = 0; k < 6; ++k) {
44400                 IkReal a = matcoeffs[coeffindex+48], b = matcoeffs[coeffindex+24], c = matcoeffs[coeffindex];
44401                 A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = lf[0]*lf[0]*a+lf[0]*lf[2]*b+lf[2]*lf[2]*c;
44402                 M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -(lf[1]*lf[1]*a + lf[1]*lf[3]*b + lf[3]*lf[3]*c);
44403                 M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -(2*lf[0]*lf[1]*a + (lf[0]*lf[3]+lf[1]*lf[2])*b + 2*lf[2]*lf[3]*c);
44404                 coeffindex++;
44405             }
44406             for(int k = 0; k < 2; ++k) {
44407                 A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
44408             }
44409         }
44410     } while(lfindex<4);
44411 
44412     if( bsingular ) {
44413         return;
44414     }
44415     dgetrs_("No transpose", &matrixdim, &matrixdim2, A, &matrixdim, &ipiv[0], &M[matrixdim], &matrixdim2, &info);
44416     if( info != 0 ) {
44417         return;
44418     }
44419 
44420     // set identity in upper corner
44421     for(int j = 0; j < matrixdim; ++j) {
44422         M[matrixdim*2*matrixdim+j+matrixdim*2*j] = 1;
44423     }
44424     IkReal IKFAST_ALIGNED16(wr[16]);
44425     IkReal IKFAST_ALIGNED16(wi[16]);
44426     IkReal IKFAST_ALIGNED16(vr[16*16]);
44427     int one=1;
44428     dgeev_("N", "V", &matrixdim2, M, &matrixdim2, wr, wi,NULL, &one, vr, &matrixdim2, work, &worksize, &info);
44429     if( info != 0 ) {
44430         return;
44431     }
44432     IkReal Breal[matrixdim-1];
44433     for(int i = 0; i < matrixdim2; ++i) {
44434         if( IKabs(wi[i]) < tol*100 ) {
44435             IkReal* ev = vr+matrixdim2*i;
44436             if( IKabs(wr[i]) > 1 ) {
44437                 ev += matrixdim;
44438             }
44439             // consistency has to be checked!!
44440             if( IKabs(ev[0]) < tol ) {
44441                 continue;
44442             }
44443             IkReal iconst = 1/ev[0];
44444             for(int j = 1; j < matrixdim; ++j) {
44445                 Breal[j-1] = ev[j]*iconst;
44446             }
44447             if( checkconsistency8(Breal) ) {
44448                 if( lfindex >= 0 ) {
44449                     const IkReal* lf = lfpossibilities[lfindex];
44450                     rawroots[numroots++] = (wr[i]*lf[0]+lf[1])/(wr[i]*lf[2]+lf[3]);
44451                 }
44452                 else {
44453                     rawroots[numroots++] = wr[i];
44454                 }
44455                 bool bsmall0=IKabs(ev[0]) > IKabs(ev[2]);
44456                 bool bsmall1=IKabs(ev[0]) > IKabs(ev[1]);
44457                 if( bsmall0 && bsmall1 ) {
44458                     rawroots[numroots++] = ev[2]/ev[0];
44459                     rawroots[numroots++] = ev[1]/ev[0];
44460                 }
44461                 else if( bsmall0 && !bsmall1 ) {
44462                     rawroots[numroots++] = ev[3]/ev[1];
44463                     rawroots[numroots++] = ev[1]/ev[0];
44464                 }
44465                 else if( !bsmall0 && bsmall1 ) {
44466                     rawroots[numroots++] = ev[6]/ev[4];
44467                     rawroots[numroots++] = ev[7]/ev[6];
44468                 }
44469                 else if( !bsmall0 && !bsmall1 ) {
44470                     rawroots[numroots++] = ev[7]/ev[5];
44471                     rawroots[numroots++] = ev[7]/ev[6];
44472                 }
44473             }
44474         }
44475     }
44476 }};
44477 
44478 
44481 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
44482 IKSolver solver;
44483 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
44484 }
44485 
44486 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - baxter (92388cabb79ce4a7e4498b08e3e28901)>"; }
44487 
44488 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
44489 
44490 #ifdef IKFAST_NAMESPACE
44491 } // end namespace
44492 #endif
44493 
44494 #ifndef IKFAST_NO_MAIN
44495 #include <stdio.h>
44496 #include <stdlib.h>
44497 #ifdef IKFAST_NAMESPACE
44498 using namespace IKFAST_NAMESPACE;
44499 #endif
44500 int main(int argc, char** argv)
44501 {
44502     if( argc != 12+GetNumFreeParameters()+1 ) {
44503         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
44504                "Returns the ik solutions given the transformation of the end effector specified by\n"
44505                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
44506                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
44507         return 1;
44508     }
44509 
44510     IkSolutionList<IkReal> solutions;
44511     std::vector<IkReal> vfree(GetNumFreeParameters());
44512     IkReal eerot[9],eetrans[3];
44513     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
44514     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
44515     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
44516     for(std::size_t i = 0; i < vfree.size(); ++i)
44517         vfree[i] = atof(argv[13+i]);
44518     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
44519 
44520     if( !bSuccess ) {
44521         fprintf(stderr,"Failed to get ik solution\n");
44522         return -1;
44523     }
44524 
44525     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
44526     std::vector<IkReal> solvalues(GetNumJoints());
44527     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
44528         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
44529         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
44530         std::vector<IkReal> vsolfree(sol.GetFree().size());
44531         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
44532         for( std::size_t j = 0; j < solvalues.size(); ++j)
44533             printf("%.15f, ", solvalues[j]);
44534         printf("\n");
44535     }
44536     return 0;
44537 }
44538 
44539 #endif


baxter_ikfast_left_arm_plugin
Author(s): Rethink Robotics Inc.
autogenerated on Fri Aug 28 2015 12:01:00