robotican_manipulator_h_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==62);
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;
00212 x0=IKcos(j[0]);
00213 x1=IKcos(j[2]);
00214 x2=IKcos(j[1]);
00215 x3=IKsin(j[1]);
00216 x4=IKsin(j[2]);
00217 x5=IKcos(j[4]);
00218 x6=IKsin(j[4]);
00219 x7=IKsin(j[3]);
00220 x8=IKcos(j[3]);
00221 x9=IKsin(j[0]);
00222 x10=IKcos(j[5]);
00223 x11=IKsin(j[5]);
00224 x12=((IkReal(0.707109999985348))*(x0));
00225 x13=((IkReal(1.00000000000000))*(x7));
00226 x14=((IkReal(0.203650865777126))*(x9));
00227 x15=((IkReal(0.00424262137423857))*(x9));
00228 x16=((IkReal(1.00000000000000))*(x5));
00229 x17=((IkReal(0.177000000000000))*(x7));
00230 x18=((IkReal(0.125158469997407))*(x9));
00231 x19=((IkReal(0.125157330540038))*(x9));
00232 x20=((IkReal(0.707103562373095))*(x9));
00233 x21=((IkReal(0.161221074999524))*(x9));
00234 x22=((IkReal(0.00600000000000000))*(x0));
00235 x23=((IkReal(0.00424265999991209))*(x9));
00236 x24=((IkReal(0.00600000000000000))*(x9));
00237 x25=((IkReal(0.125158469997407))*(x0));
00238 x26=((IkReal(0.0300000000000000))*(x2));
00239 x27=((IkReal(0.707103562373095))*(x0));
00240 x28=((IkReal(1.00000000000000))*(x6));
00241 x29=((IkReal(0.00424265999991209))*(x0));
00242 x30=((IkReal(0.707109999985348))*(x9));
00243 x31=((IkReal(0.161221074999524))*(x0));
00244 x32=((IkReal(0.00424262137423857))*(x0));
00245 x33=((IkReal(0.203650865777126))*(x0));
00246 x34=((IkReal(0.264000000000000))*(x3));
00247 x35=((IkReal(0.125157330540038))*(x0));
00248 x36=((IkReal(0.177000000000000))*(x8));
00249 x37=((x2)*(x4));
00250 x38=((x1)*(x3));
00251 x39=((x3)*(x4));
00252 x40=((x1)*(x2));
00253 x41=((x6)*(x8));
00254 x42=((x0)*(x8));
00255 x43=((IkReal(1.00000000000000))*(x8)*(x9));
00256 x44=((IkReal(0.707109999985348))*(x39));
00257 x45=((IkReal(0.707103562373095))*(x40));
00258 x46=((x12)*(x39));
00259 x47=((x27)*(x40));
00260 x48=((x20)*(x40));
00261 x49=((x30)*(x39));
00262 x50=((((IkReal(0.707109999985348))*(x40)))+(((IkReal(0.707103562373095))*(x37)))+(((IkReal(0.707103562373095))*(x38))));
00263 x51=((((IkReal(0.707109999985348))*(x38)))+(((IkReal(0.707109999985348))*(x37)))+(((IkReal(0.707103562373095))*(x39))));
00264 x52=((x44)+(((IkReal(-1.00000000000000))*(x50))));
00265 x53=((((x27)*(((x38)+(x37)))))+(((x12)*(x40))));
00266 x54=((((x27)*(x39)))+(((x12)*(((x38)+(x37))))));
00267 x55=((((x20)*(x39)))+(((x30)*(((x38)+(x37))))));
00268 x56=((((x20)*(((x38)+(x37)))))+(((x30)*(x40))));
00269 x57=((x52)*(x8));
00270 x58=((((IkReal(-1.00000000000000))*(x47)))+(x54));
00271 x59=((x47)+(((IkReal(-1.00000000000000))*(x54))));
00272 x60=((((IkReal(-1.00000000000000))*(x48)))+(x55));
00273 x61=((x48)+(((IkReal(-1.00000000000000))*(x55))));
00274 x62=((((x59)*(x8)))+(((IkReal(-1.00000000000000))*(x13)*(x9))));
00275 x63=((((x0)*(x7)))+(((x61)*(x8))));
00276 x64=((((x28)*(((x45)+(((IkReal(-1.00000000000000))*(x51)))))))+(((IkReal(-1.00000000000000))*(x16)*(x57))));
00277 x65=((((IkReal(-1.00000000000000))*(x16)*(x62)))+(((x28)*(((((IkReal(-1.00000000000000))*(x46)))+(x53))))));
00278 x66=((((x28)*(((((IkReal(-1.00000000000000))*(x49)))+(x56)))))+(((IkReal(-1.00000000000000))*(x16)*(x63))));
00279 eerot[0]=((((x6)*(x62)))+(((x5)*(((((IkReal(-1.00000000000000))*(x46)))+(x53))))));
00280 eerot[1]=((((x11)*(x65)))+(((x10)*(((((IkReal(-1.00000000000000))*(x43)))+(((x58)*(x7))))))));
00281 eerot[2]=((((x11)*(((x43)+(((IkReal(-1.00000000000000))*(x13)*(x58)))))))+(((x10)*(x65))));
00282 IkReal x67=((IkReal(1.00000000000000))*(x24));
00283 IkReal x68=((IkReal(1.00000000000000))*(x39));
00284 eetrans[0]=((((x0)*(x26)))+(((x5)*(((((x35)*(x38)))+(((x35)*(x37)))+(((IkReal(-1.00000000000000))*(x25)*(x68)))+(((x25)*(x40)))))))+(((IkReal(-1.00000000000000))*(x31)*(x68)))+(((IkReal(-1.00000000000000))*(x67)*(x8)))+(((x7)*(((((x29)*(x37)))+(((x29)*(x38)))+(((x32)*(x39)))+(((IkReal(-1.00000000000000))*(x32)*(x40)))))))+(((x31)*(x40)))+(((IkReal(-1.00000000000000))*(x67)))+(((x0)*(x34)))+(((x6)*(((((x36)*(x59)))+(((IkReal(-1.00000000000000))*(x17)*(x9)))))))+(((x33)*(x37)))+(((x33)*(x38))));
00285 eerot[3]=((((x6)*(x63)))+(((x5)*(((((IkReal(-1.00000000000000))*(x49)))+(x56))))));
00286 eerot[4]=((((x11)*(x66)))+(((x10)*(((((x60)*(x7)))+(x42))))));
00287 eerot[5]=((((x11)*(((((IkReal(-1.00000000000000))*(x42)))+(((IkReal(-1.00000000000000))*(x13)*(x60)))))))+(((x10)*(x66))));
00288 IkReal x69=((IkReal(1.00000000000000))*(x39));
00289 eetrans[1]=((((x22)*(x8)))+(((x34)*(x9)))+(((x7)*(((((IkReal(-1.00000000000000))*(x15)*(x40)))+(((x23)*(x37)))+(((x23)*(x38)))+(((x15)*(x39)))))))+(((x21)*(x40)))+(((x14)*(x37)))+(((x14)*(x38)))+(((IkReal(-1.00000000000000))*(x21)*(x69)))+(x22)+(((x26)*(x9)))+(((x6)*(((((x0)*(x17)))+(((x36)*(x61)))))))+(((x5)*(((((x19)*(x38)))+(((x19)*(x37)))+(((x18)*(x40)))+(((IkReal(-1.00000000000000))*(x18)*(x69))))))));
00290 eerot[6]=((((x41)*(x52)))+(((x5)*(((x45)+(((IkReal(-1.00000000000000))*(x51))))))));
00291 eerot[7]=((((x10)*(x7)*(((((IkReal(-1.00000000000000))*(x44)))+(x50)))))+(((x11)*(x64))));
00292 eerot[8]=((((x11)*(x52)*(x7)))+(((x10)*(x64))));
00293 eetrans[2]=((IkReal(0.0690000000000000))+(((x41)*(((((IkReal(0.125158469997407))*(x39)))+(((IkReal(-0.125158469997407))*(x40)))+(((IkReal(-0.125157330540038))*(x38)))+(((IkReal(-0.125157330540038))*(x37)))))))+(((IkReal(0.264000000000000))*(x2)))+(((IkReal(0.203650865777126))*(x40)))+(((IkReal(-0.0300000000000000))*(x3)))+(((IkReal(-0.203650865777126))*(x39)))+(((x7)*(((((IkReal(0.00424265999991209))*(x40)))+(((IkReal(0.00424262137423857))*(x38)))+(((IkReal(0.00424262137423857))*(x37)))+(((IkReal(-0.00424265999991209))*(x39)))))))+(((x5)*(((((IkReal(0.125157330540038))*(x40)))+(((IkReal(-0.125158469997407))*(x37)))+(((IkReal(-0.125158469997407))*(x38)))+(((IkReal(-0.125157330540038))*(x39)))))))+(((IkReal(-0.161221074999524))*(x37)))+(((IkReal(-0.161221074999524))*(x38))));
00294 }
00295 
00296 IKFAST_API int GetNumFreeParameters() { return 0; }
00297 IKFAST_API int* GetFreeParameters() { return NULL; }
00298 IKFAST_API int GetNumJoints() { return 6; }
00299 
00300 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00301 
00302 IKFAST_API int GetIkType() { return 0x67000001; }
00303 
00304 class IKSolver {
00305 public:
00306 IkReal j0,cj0,sj0,htj0,j1,cj1,sj1,htj1,j2,cj2,sj2,htj2,j3,cj3,sj3,htj3,j4,cj4,sj4,htj4,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;
00307 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5;
00308 
00309 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00310 j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; j5=numeric_limits<IkReal>::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1; 
00311 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00312     solutions.Clear();
00313 r00 = eerot[0*3+0];
00314 r01 = eerot[0*3+1];
00315 r02 = eerot[0*3+2];
00316 r10 = eerot[1*3+0];
00317 r11 = eerot[1*3+1];
00318 r12 = eerot[1*3+2];
00319 r20 = eerot[2*3+0];
00320 r21 = eerot[2*3+1];
00321 r22 = eerot[2*3+2];
00322 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00323 
00324 new_r00=((IkReal(-1.00000000000000))*(r02));
00325 new_r01=r01;
00326 new_r02=r00;
00327 new_px=((((IkReal(-0.177000000000000))*(r00)))+(px));
00328 new_r10=((IkReal(-1.00000000000000))*(r12));
00329 new_r11=r11;
00330 new_r12=r10;
00331 new_py=((((IkReal(-0.177000000000000))*(r10)))+(py));
00332 new_r20=((IkReal(-1.00000000000000))*(r22));
00333 new_r21=r21;
00334 new_r22=r20;
00335 new_pz=((IkReal(-0.0690000000000000))+(((IkReal(-0.177000000000000))*(r20)))+(pz));
00336 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;
00337 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
00338 npx=((((px)*(r00)))+(((py)*(r10)))+(((pz)*(r20))));
00339 npy=((((px)*(r01)))+(((py)*(r11)))+(((pz)*(r21))));
00340 npz=((((px)*(r02)))+(((py)*(r12)))+(((pz)*(r22))));
00341 rxp0_0=((((IkReal(-1.00000000000000))*(py)*(r20)))+(((pz)*(r10))));
00342 rxp0_1=((((px)*(r20)))+(((IkReal(-1.00000000000000))*(pz)*(r00))));
00343 rxp0_2=((((IkReal(-1.00000000000000))*(px)*(r10)))+(((py)*(r00))));
00344 rxp1_0=((((IkReal(-1.00000000000000))*(py)*(r21)))+(((pz)*(r11))));
00345 rxp1_1=((((px)*(r21)))+(((IkReal(-1.00000000000000))*(pz)*(r01))));
00346 rxp1_2=((((IkReal(-1.00000000000000))*(px)*(r11)))+(((py)*(r01))));
00347 rxp2_0=((((IkReal(-1.00000000000000))*(py)*(r22)))+(((pz)*(r12))));
00348 rxp2_1=((((px)*(r22)))+(((IkReal(-1.00000000000000))*(pz)*(r02))));
00349 rxp2_2=((((IkReal(-1.00000000000000))*(px)*(r12)))+(((py)*(r02))));
00350 IkReal op[72], zeror[48];
00351 int numroots;
00352 IkReal x70=((IkReal(0.516006574023843))*(npz));
00353 IkReal x71=((IkReal(0.0600071344697922))*(npx));
00354 IkReal x72=((IkReal(0.0120000000000000))*(npy));
00355 IkReal x73=((IkReal(1.00000000000000))*(pp));
00356 IkReal x74=((IkReal(0.0600071344697922))*(npy));
00357 IkReal x75=((IkReal(0.120014268939584))*(npx));
00358 IkReal x76=((IkReal(0.0240000000000000))*(npx));
00359 IkReal x77=((IkReal(0.120014268939584))*(npy));
00360 IkReal x78=((IkReal(0.0120000000000000))*(r20));
00361 IkReal x79=((IkReal(0.00600000000000000))*(r21));
00362 IkReal x80=((IkReal(1.03201314804769))*(npx));
00363 IkReal x81=((IkReal(0.120014268939584))*(npz));
00364 IkReal x82=((IkReal(2.06402629609537))*(npy));
00365 IkReal x83=((IkReal(2.00000000000000))*(rxp0_2));
00366 IkReal x84=((IkReal(0.0240000000000000))*(r22));
00367 IkReal x85=((IkReal(4.00000000000000))*(rxp1_2));
00368 IkReal x86=((IkReal(-0.000720085613637506))+(((IkReal(-1.00000000000000))*(x74))));
00369 IkReal x87=((IkReal(1.00000000000000))*(rxp2_2));
00370 IkReal x88=((IkReal(-0.00600000000000000))*(r21));
00371 IkReal x89=((IkReal(-0.0120000000000000))*(r20));
00372 IkReal x90=((((IkReal(-1.00000000000000))*(x77)))+(x76));
00373 IkReal x91=((IkReal(-0.0600071344697922))*(npy));
00374 IkReal x92=((IkReal(-0.000720085613637506))+(x74));
00375 IkReal x93=((IkReal(-1.00000000000000))*(rxp2_2));
00376 IkReal x94=((IkReal(0.00313008984422510))+(x70));
00377 IkReal x95=((x80)+(x81));
00378 IkReal x96=((x77)+(x76));
00379 IkReal x97=((x73)+(x71));
00380 IkReal x98=((x72)+(x71));
00381 IkReal x99=((x73)+(x72));
00382 op[0]=((x72)+(x94)+(((IkReal(-1.00000000000000))*(x97))));
00383 op[1]=x74;
00384 op[2]=x96;
00385 op[3]=x75;
00386 op[4]=((x71)+(x94)+(((IkReal(-1.00000000000000))*(x99))));
00387 op[5]=x91;
00388 op[6]=x92;
00389 op[7]=((((IkReal(-1.00000000000000))*(x73)))+(x98)+(x94));
00390 op[8]=x75;
00391 op[9]=x90;
00392 op[10]=x86;
00393 op[11]=((((IkReal(-1.00000000000000))*(x72)))+(x94)+(((IkReal(-1.00000000000000))*(x97))));
00394 op[12]=((rxp2_2)+(x78));
00395 op[13]=x88;
00396 op[14]=((IkReal(-0.0240000000000000))*(r21));
00397 op[15]=x89;
00398 op[16]=((((IkReal(-1.00000000000000))*(x78)))+(rxp2_2));
00399 op[17]=x79;
00400 op[18]=x88;
00401 op[19]=rxp2_2;
00402 op[20]=x89;
00403 op[21]=IkReal(0);
00404 op[22]=x79;
00405 op[23]=rxp2_2;
00406 op[24]=((IkReal(-1.00000000000000))*(x95));
00407 op[25]=IkReal(0);
00408 op[26]=x82;
00409 op[27]=IkReal(0);
00410 op[28]=((x80)+(((IkReal(-1.00000000000000))*(x81))));
00411 op[29]=IkReal(0);
00412 op[30]=IkReal(0);
00413 op[31]=((x81)+(((IkReal(-1.00000000000000))*(x80))));
00414 op[32]=IkReal(0);
00415 op[33]=x82;
00416 op[34]=IkReal(0);
00417 op[35]=x95;
00418 op[36]=((x84)+(((IkReal(-1.00000000000000))*(x83))));
00419 op[37]=IkReal(0);
00420 op[38]=x85;
00421 op[39]=IkReal(0);
00422 op[40]=((x83)+(x84));
00423 op[41]=IkReal(0);
00424 op[42]=IkReal(0);
00425 op[43]=((IkReal(-2.00000000000000))*(rxp0_2));
00426 op[44]=IkReal(0);
00427 op[45]=x85;
00428 op[46]=IkReal(0);
00429 op[47]=x83;
00430 op[48]=((IkReal(0.00313008984422510))+(((IkReal(-1.00000000000000))*(x73)))+(((IkReal(-1.00000000000000))*(x70)))+(x98));
00431 op[49]=x74;
00432 op[50]=x90;
00433 op[51]=x75;
00434 op[52]=((IkReal(0.00313008984422510))+(((IkReal(-1.00000000000000))*(x72)))+(((IkReal(-1.00000000000000))*(x70)))+(((IkReal(-1.00000000000000))*(x97))));
00435 op[53]=x91;
00436 op[54]=x92;
00437 op[55]=((IkReal(0.00313008984422510))+(((IkReal(-1.00000000000000))*(x70)))+(x72)+(((IkReal(-1.00000000000000))*(x97))));
00438 op[56]=x75;
00439 op[57]=x96;
00440 op[58]=x86;
00441 op[59]=((IkReal(0.00313008984422510))+(((IkReal(-1.00000000000000))*(x70)))+(x71)+(((IkReal(-1.00000000000000))*(x99))));
00442 op[60]=((((IkReal(-1.00000000000000))*(x78)))+(((IkReal(-1.00000000000000))*(x87))));
00443 op[61]=x88;
00444 op[62]=((IkReal(0.0240000000000000))*(r21));
00445 op[63]=x89;
00446 op[64]=((x78)+(((IkReal(-1.00000000000000))*(x87))));
00447 op[65]=x79;
00448 op[66]=x88;
00449 op[67]=x93;
00450 op[68]=x89;
00451 op[69]=IkReal(0);
00452 op[70]=x79;
00453 op[71]=x93;
00454 solvedialyticpoly8qep(op,zeror,numroots);
00455 IkReal j4array[16], cj4array[16], sj4array[16], j5array[16], cj5array[16], sj5array[16], j3array[16], cj3array[16], sj3array[16];
00456 int numsolutions = 0;
00457 for(int ij4 = 0; ij4 < numroots; ij4 += 3)
00458 {
00459 IkReal htj4 = zeror[ij4+0], htj5 = zeror[ij4+1], htj3 = zeror[ij4+2];
00460 j4array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj4)));
00461 j5array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj5)));
00462 j3array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj3)));
00463 IkReal x100=(htj4)*(htj4);
00464 IkReal x101=(htj5)*(htj5);
00465 IkReal x102=(htj3)*(htj3);
00466 cj4array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x100))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x100)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x100))))));
00467 cj5array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x101))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x101)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x101))))));
00468 cj3array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x102))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x102)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x102))))));
00469 sj4array[numsolutions]=((IkReal(2.00000000000000))*(htj4)*(((IKabs(((IkReal(1.00000000000000))+((htj4)*(htj4)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj4)*(htj4))))):(IkReal)1.0e30)));
00470 sj5array[numsolutions]=((IkReal(2.00000000000000))*(htj5)*(((IKabs(((IkReal(1.00000000000000))+((htj5)*(htj5)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj5)*(htj5))))):(IkReal)1.0e30)));
00471 sj3array[numsolutions]=((IkReal(2.00000000000000))*(htj3)*(((IKabs(((IkReal(1.00000000000000))+((htj3)*(htj3)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj3)*(htj3))))):(IkReal)1.0e30)));
00472 if( j4array[numsolutions] > IKPI )
00473 {
00474     j4array[numsolutions]-=IK2PI;
00475 }
00476 else if( j4array[numsolutions] < -IKPI )
00477 {
00478     j4array[numsolutions]+=IK2PI;
00479 }
00480 if( j5array[numsolutions] > IKPI )
00481 {
00482     j5array[numsolutions]-=IK2PI;
00483 }
00484 else if( j5array[numsolutions] < -IKPI )
00485 {
00486     j5array[numsolutions]+=IK2PI;
00487 }
00488 if( j3array[numsolutions] > IKPI )
00489 {
00490     j3array[numsolutions]-=IK2PI;
00491 }
00492 else if( j3array[numsolutions] < -IKPI )
00493 {
00494     j3array[numsolutions]+=IK2PI;
00495 }
00496 numsolutions++;
00497 }
00498 bool j4valid[16]={true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true};
00499 _nj4 = 16;
00500 _nj5 = 1;
00501 _nj3 = 1;
00502 for(int ij4 = 0; ij4 < numsolutions; ++ij4)
00503     {
00504 if( !j4valid[ij4] )
00505 {
00506     continue;
00507 }
00508 _ij4[0] = ij4; _ij4[1] = -1;
00509 _ij5[0] = 0; _ij5[1] = -1;
00510 _ij3[0] = 0; _ij3[1] = -1;
00511 for(int iij4 = ij4+1; iij4 < numsolutions; ++iij4)
00512 {
00513 if( !j4valid[iij4] ) { continue; }
00514 if( IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(cj5array[ij4]-cj5array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij4]-sj5array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(cj3array[ij4]-cj3array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij4]-sj3array[iij4]) < IKFAST_SOLUTION_THRESH &&  1 )
00515 {
00516     j4valid[iij4]=false; _ij4[1] = iij4; _ij5[1] = 0; _ij3[1] = 0;  break; 
00517 }
00518 }
00519     j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
00520 
00521     j5 = j5array[ij4]; cj5 = cj5array[ij4]; sj5 = sj5array[ij4];
00522 
00523     j3 = j3array[ij4]; cj3 = cj3array[ij4]; sj3 = sj3array[ij4];
00524 
00525 {
00526 IkReal dummyeval[1];
00527 IkReal gconst0;
00528 IkReal x103=(cj5)*(cj5);
00529 IkReal x104=(sj5)*(sj5);
00530 IkReal x105=((IkReal(1.00000000000000))*(r10));
00531 IkReal x106=((cj4)*(sj5));
00532 IkReal x107=((r00)*(r11));
00533 IkReal x108=((cj4)*(cj5));
00534 IkReal x109=((sj4)*(x103));
00535 IkReal x110=((sj4)*(x104));
00536 gconst0=IKsign(((((x107)*(x109)))+(((r00)*(r12)*(x106)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x108)))+(((IkReal(-1.00000000000000))*(r02)*(x105)*(x106)))+(((IkReal(-1.00000000000000))*(r01)*(x105)*(x109)))+(((IkReal(-1.00000000000000))*(r01)*(x105)*(x110)))+(((r01)*(r12)*(x108)))+(((x107)*(x110)))));
00537 IkReal x111=(cj5)*(cj5);
00538 IkReal x112=(sj5)*(sj5);
00539 IkReal x113=((IkReal(1.00000000000000))*(r10));
00540 IkReal x114=((cj4)*(sj5));
00541 IkReal x115=((r00)*(r11));
00542 IkReal x116=((cj4)*(cj5));
00543 IkReal x117=((sj4)*(x111));
00544 IkReal x118=((sj4)*(x112));
00545 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(x113)*(x114)))+(((r00)*(r12)*(x114)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x116)))+(((r01)*(r12)*(x116)))+(((IkReal(-1.00000000000000))*(r01)*(x113)*(x117)))+(((IkReal(-1.00000000000000))*(r01)*(x113)*(x118)))+(((x115)*(x118)))+(((x115)*(x117))));
00546 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00547 {
00548 {
00549 IkReal dummyeval[1];
00550 IkReal gconst1;
00551 IkReal x119=(cj5)*(cj5);
00552 IkReal x120=(sj5)*(sj5);
00553 IkReal x121=((IkReal(1.00000000000000))*(r11));
00554 IkReal x122=((cj4)*(r00));
00555 IkReal x123=((r02)*(sj4));
00556 IkReal x124=((r12)*(sj4));
00557 IkReal x125=((cj4)*(r01)*(r10));
00558 gconst1=IKsign(((((IkReal(-1.00000000000000))*(x120)*(x121)*(x122)))+(((x120)*(x125)))+(((IkReal(-1.00000000000000))*(cj5)*(x121)*(x123)))+(((IkReal(-1.00000000000000))*(x119)*(x121)*(x122)))+(((r00)*(sj5)*(x124)))+(((x119)*(x125)))+(((cj5)*(r01)*(x124)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x123)))));
00559 IkReal x126=(cj5)*(cj5);
00560 IkReal x127=(sj5)*(sj5);
00561 IkReal x128=((IkReal(1.00000000000000))*(r11));
00562 IkReal x129=((cj4)*(r00));
00563 IkReal x130=((r02)*(sj4));
00564 IkReal x131=((r12)*(sj4));
00565 IkReal x132=((cj4)*(r01)*(r10));
00566 dummyeval[0]=((((x127)*(x132)))+(((cj5)*(r01)*(x131)))+(((IkReal(-1.00000000000000))*(x126)*(x128)*(x129)))+(((IkReal(-1.00000000000000))*(cj5)*(x128)*(x130)))+(((x126)*(x132)))+(((IkReal(-1.00000000000000))*(x127)*(x128)*(x129)))+(((r00)*(sj5)*(x131)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x130))));
00567 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00568 {
00569 {
00570 IkReal dummyeval[1];
00571 IkReal gconst2;
00572 gconst2=IKsign(sj3);
00573 dummyeval[0]=sj3;
00574 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00575 {
00576 {
00577 IkReal evalcond[3];
00578 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959))));
00579 evalcond[1]=((IkReal(-0.0120000000000000))+(((npx)*(sj5)))+(((cj5)*(npy))));
00580 evalcond[2]=((((cj5)*(r21)))+(((r20)*(sj5))));
00581 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  )
00582 {
00583 {
00584 IkReal j2array[1], cj2array[1], sj2array[1];
00585 bool j2valid[1]={false};
00586 _nj2 = 1;
00587 IkReal x133=((IkReal(2.34381456633434))*(cj4));
00588 IkReal x134=((npy)*(sj5));
00589 IkReal x135=((IkReal(2.94476514910275))*(cj4));
00590 IkReal x136=((IkReal(2.34381456633434))*(sj4));
00591 IkReal x137=((cj5)*(npx));
00592 IkReal x138=((IkReal(2.94476514910275))*(sj4));
00593 if( IKabs(((IkReal(0.516358403118598))+(((IkReal(-1.00000000000000))*(x135)*(x137)))+(((IkReal(-1.00000000000000))*(x134)*(x136)))+(((IkReal(-1.00000000000000))*(npz)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x133)))+(((x136)*(x137)))+(((x134)*(x135))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.830081885873801))+(((IkReal(-1.00000000000000))*(x137)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x136)))+(((IkReal(-1.00000000000000))*(x133)*(x137)))+(((x134)*(x138)))+(((x133)*(x134)))+(((npz)*(x135))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.516358403118598))+(((IkReal(-1.00000000000000))*(x135)*(x137)))+(((IkReal(-1.00000000000000))*(x134)*(x136)))+(((IkReal(-1.00000000000000))*(npz)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x133)))+(((x136)*(x137)))+(((x134)*(x135)))))+IKsqr(((IkReal(-0.830081885873801))+(((IkReal(-1.00000000000000))*(x137)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x136)))+(((IkReal(-1.00000000000000))*(x133)*(x137)))+(((x134)*(x138)))+(((x133)*(x134)))+(((npz)*(x135)))))-1) <= IKFAST_SINCOS_THRESH )
00594     continue;
00595 j2array[0]=IKatan2(((IkReal(0.516358403118598))+(((IkReal(-1.00000000000000))*(x135)*(x137)))+(((IkReal(-1.00000000000000))*(x134)*(x136)))+(((IkReal(-1.00000000000000))*(npz)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x133)))+(((x136)*(x137)))+(((x134)*(x135)))), ((IkReal(-0.830081885873801))+(((IkReal(-1.00000000000000))*(x137)*(x138)))+(((IkReal(-1.00000000000000))*(npz)*(x136)))+(((IkReal(-1.00000000000000))*(x133)*(x137)))+(((x134)*(x138)))+(((x133)*(x134)))+(((npz)*(x135)))));
00596 sj2array[0]=IKsin(j2array[0]);
00597 cj2array[0]=IKcos(j2array[0]);
00598 if( j2array[0] > IKPI )
00599 {
00600     j2array[0]-=IK2PI;
00601 }
00602 else if( j2array[0] < -IKPI )
00603 {    j2array[0]+=IK2PI;
00604 }
00605 j2valid[0] = true;
00606 for(int ij2 = 0; ij2 < 1; ++ij2)
00607 {
00608 if( !j2valid[ij2] )
00609 {
00610     continue;
00611 }
00612 _ij2[0] = ij2; _ij2[1] = -1;
00613 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00614 {
00615 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00616 {
00617     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00618 }
00619 }
00620 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00621 {
00622 IkReal evalcond[2];
00623 IkReal x139=IKcos(j2);
00624 IkReal x140=IKsin(j2);
00625 IkReal x141=((npy)*(sj5));
00626 IkReal x142=((cj5)*(npx));
00627 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(0.165463933124939))*(x140)))+(((sj4)*(x141)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x142)))+(((IkReal(-0.207888640466058))*(x139))));
00628 evalcond[1]=((IkReal(0.0300035672348961))+(((IkReal(0.165463933124939))*(x139)))+(((IkReal(-1.00000000000000))*(cj4)*(x141)))+(((npz)*(sj4)))+(((IkReal(0.207888640466058))*(x140)))+(((cj4)*(x142))));
00629 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00630 {
00631 continue;
00632 }
00633 }
00634 
00635 {
00636 IkReal dummyeval[1];
00637 IkReal gconst56;
00638 IkReal x143=(cj5)*(cj5);
00639 IkReal x144=(sj5)*(sj5);
00640 IkReal x145=((IkReal(2.00000000000000))*(cj5)*(sj5));
00641 gconst56=IKsign(((((r00)*(r01)*(x145)))+(((x143)*((r11)*(r11))))+(((x144)*((r00)*(r00))))+(((r10)*(r11)*(x145)))+(((x143)*((r01)*(r01))))+(((x144)*((r10)*(r10))))));
00642 IkReal x146=(cj5)*(cj5);
00643 IkReal x147=(sj5)*(sj5);
00644 IkReal x148=((IkReal(2.00000000000000))*(cj5)*(sj5));
00645 dummyeval[0]=((((r00)*(r01)*(x148)))+(((x147)*((r10)*(r10))))+(((x147)*((r00)*(r00))))+(((x146)*((r01)*(r01))))+(((r10)*(r11)*(x148)))+(((x146)*((r11)*(r11)))));
00646 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00647 {
00648 {
00649 IkReal dummyeval[1];
00650 IkReal gconst57;
00651 IkReal x149=(cj5)*(cj5);
00652 IkReal x150=(sj5)*(sj5);
00653 IkReal x151=((IkReal(1.00000000000000))*(r10));
00654 IkReal x152=((cj4)*(sj5));
00655 IkReal x153=((r00)*(r11));
00656 IkReal x154=((cj4)*(cj5));
00657 IkReal x155=((sj4)*(x149));
00658 IkReal x156=((sj4)*(x150));
00659 gconst57=IKsign(((((x153)*(x156)))+(((x153)*(x155)))+(((IkReal(-1.00000000000000))*(r01)*(x151)*(x155)))+(((IkReal(-1.00000000000000))*(r01)*(x151)*(x156)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x154)))+(((IkReal(-1.00000000000000))*(r02)*(x151)*(x152)))+(((r00)*(r12)*(x152)))+(((r01)*(r12)*(x154)))));
00660 IkReal x157=(cj5)*(cj5);
00661 IkReal x158=(sj5)*(sj5);
00662 IkReal x159=((IkReal(1.00000000000000))*(r10));
00663 IkReal x160=((cj4)*(sj5));
00664 IkReal x161=((r00)*(r11));
00665 IkReal x162=((cj4)*(cj5));
00666 IkReal x163=((sj4)*(x157));
00667 IkReal x164=((sj4)*(x158));
00668 dummyeval[0]=((((x161)*(x163)))+(((x161)*(x164)))+(((IkReal(-1.00000000000000))*(r02)*(x159)*(x160)))+(((r01)*(r12)*(x162)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x162)))+(((IkReal(-1.00000000000000))*(r01)*(x159)*(x163)))+(((IkReal(-1.00000000000000))*(r01)*(x159)*(x164)))+(((r00)*(r12)*(x160))));
00669 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00670 {
00671 {
00672 IkReal dummyeval[1];
00673 IkReal gconst58;
00674 gconst58=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
00675 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
00676 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00677 {
00678 continue;
00679 
00680 } else
00681 {
00682 {
00683 IkReal j1array[1], cj1array[1], sj1array[1];
00684 bool j1valid[1]={false};
00685 _nj1 = 1;
00686 IkReal x165=((IkReal(0.707109999985348))*(sj4));
00687 IkReal x166=((r22)*(sj2));
00688 IkReal x167=((cj5)*(r20));
00689 IkReal x168=((r21)*(sj5));
00690 IkReal x169=((IkReal(0.707109999985348))*(cj4));
00691 IkReal x170=((cj2)*(r22));
00692 IkReal x171=((IkReal(0.707103562373095))*(sj4));
00693 IkReal x172=((IkReal(0.707103562373095))*(cj4));
00694 IkReal x173=((sj2)*(x172));
00695 IkReal x174=((cj2)*(x172));
00696 if( IKabs(((gconst58)*(((((IkReal(-1.00000000000000))*(cj2)*(x165)*(x167)))+(((x169)*(x170)))+(((IkReal(-1.00000000000000))*(sj2)*(x167)*(x171)))+(((IkReal(-1.00000000000000))*(sj2)*(x167)*(x169)))+(((x166)*(x172)))+(((x167)*(x174)))+(((x170)*(x171)))+(((IkReal(-1.00000000000000))*(x168)*(x174)))+(((sj2)*(x168)*(x171)))+(((cj2)*(x165)*(x168)))+(((IkReal(-1.00000000000000))*(x165)*(x166)))+(((sj2)*(x168)*(x169))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst58)*(((((IkReal(-1.00000000000000))*(sj2)*(x165)*(x167)))+(((IkReal(-1.00000000000000))*(cj2)*(x168)*(x171)))+(((IkReal(-1.00000000000000))*(cj2)*(x168)*(x169)))+(((x166)*(x171)))+(((x167)*(x173)))+(((IkReal(-1.00000000000000))*(x170)*(x172)))+(((x166)*(x169)))+(((x165)*(x170)))+(((IkReal(-1.00000000000000))*(x168)*(x173)))+(((cj2)*(x167)*(x169)))+(((cj2)*(x167)*(x171)))+(((sj2)*(x165)*(x168))))))) < IKFAST_ATAN2_MAGTHRESH )
00697     continue;
00698 j1array[0]=IKatan2(((gconst58)*(((((IkReal(-1.00000000000000))*(cj2)*(x165)*(x167)))+(((x169)*(x170)))+(((IkReal(-1.00000000000000))*(sj2)*(x167)*(x171)))+(((IkReal(-1.00000000000000))*(sj2)*(x167)*(x169)))+(((x166)*(x172)))+(((x167)*(x174)))+(((x170)*(x171)))+(((IkReal(-1.00000000000000))*(x168)*(x174)))+(((sj2)*(x168)*(x171)))+(((cj2)*(x165)*(x168)))+(((IkReal(-1.00000000000000))*(x165)*(x166)))+(((sj2)*(x168)*(x169)))))), ((gconst58)*(((((IkReal(-1.00000000000000))*(sj2)*(x165)*(x167)))+(((IkReal(-1.00000000000000))*(cj2)*(x168)*(x171)))+(((IkReal(-1.00000000000000))*(cj2)*(x168)*(x169)))+(((x166)*(x171)))+(((x167)*(x173)))+(((IkReal(-1.00000000000000))*(x170)*(x172)))+(((x166)*(x169)))+(((x165)*(x170)))+(((IkReal(-1.00000000000000))*(x168)*(x173)))+(((cj2)*(x167)*(x169)))+(((cj2)*(x167)*(x171)))+(((sj2)*(x165)*(x168)))))));
00699 sj1array[0]=IKsin(j1array[0]);
00700 cj1array[0]=IKcos(j1array[0]);
00701 if( j1array[0] > IKPI )
00702 {
00703     j1array[0]-=IK2PI;
00704 }
00705 else if( j1array[0] < -IKPI )
00706 {    j1array[0]+=IK2PI;
00707 }
00708 j1valid[0] = true;
00709 for(int ij1 = 0; ij1 < 1; ++ij1)
00710 {
00711 if( !j1valid[ij1] )
00712 {
00713     continue;
00714 }
00715 _ij1[0] = ij1; _ij1[1] = -1;
00716 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
00717 {
00718 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00719 {
00720     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00721 }
00722 }
00723 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00724 {
00725 IkReal evalcond[2];
00726 IkReal x175=IKsin(j1);
00727 IkReal x176=IKcos(j1);
00728 IkReal x177=((cj5)*(r20));
00729 IkReal x178=((r21)*(sj5));
00730 IkReal x179=((IkReal(0.707103562373095))*(x175));
00731 IkReal x180=((IkReal(0.707109999985348))*(x175));
00732 IkReal x181=((IkReal(0.707103562373095))*(x176));
00733 IkReal x182=((IkReal(0.707109999985348))*(x176));
00734 evalcond[0]=((((sj2)*(x179)))+(((sj2)*(x182)))+(((cj4)*(r22)))+(((sj4)*(x178)))+(((cj2)*(x180)))+(((IkReal(-1.00000000000000))*(sj4)*(x177)))+(((IkReal(-1.00000000000000))*(cj2)*(x181))));
00735 evalcond[1]=((((sj2)*(x181)))+(((cj4)*(x177)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(x178)))+(((cj2)*(x182)))+(((cj2)*(x179)))+(((IkReal(-1.00000000000000))*(sj2)*(x180))));
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 gconst59;
00745 IkReal x183=(cj5)*(cj5);
00746 IkReal x184=(sj5)*(sj5);
00747 IkReal x185=((IkReal(2.00000000000000))*(cj5)*(sj5));
00748 gconst59=IKsign(((((x184)*((r00)*(r00))))+(((r10)*(r11)*(x185)))+(((x184)*((r10)*(r10))))+(((r00)*(r01)*(x185)))+(((x183)*((r11)*(r11))))+(((x183)*((r01)*(r01))))));
00749 IkReal x186=(cj5)*(cj5);
00750 IkReal x187=(sj5)*(sj5);
00751 IkReal x188=((IkReal(2.00000000000000))*(cj5)*(sj5));
00752 dummyeval[0]=((((r10)*(r11)*(x188)))+(((r00)*(r01)*(x188)))+(((x186)*((r11)*(r11))))+(((x186)*((r01)*(r01))))+(((x187)*((r00)*(r00))))+(((x187)*((r10)*(r10)))));
00753 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00754 {
00755 {
00756 IkReal dummyeval[1];
00757 IkReal gconst60;
00758 IkReal x189=(cj5)*(cj5);
00759 IkReal x190=(sj5)*(sj5);
00760 IkReal x191=((IkReal(1.00000000000000))*(r10));
00761 IkReal x192=((cj4)*(sj5));
00762 IkReal x193=((r00)*(r11));
00763 IkReal x194=((cj4)*(cj5));
00764 IkReal x195=((sj4)*(x189));
00765 IkReal x196=((sj4)*(x190));
00766 gconst60=IKsign(((((x193)*(x195)))+(((x193)*(x196)))+(((r00)*(r12)*(x192)))+(((r01)*(r12)*(x194)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x194)))+(((IkReal(-1.00000000000000))*(r01)*(x191)*(x195)))+(((IkReal(-1.00000000000000))*(r01)*(x191)*(x196)))+(((IkReal(-1.00000000000000))*(r02)*(x191)*(x192)))));
00767 IkReal x197=(cj5)*(cj5);
00768 IkReal x198=(sj5)*(sj5);
00769 IkReal x199=((IkReal(1.00000000000000))*(r10));
00770 IkReal x200=((cj4)*(sj5));
00771 IkReal x201=((r00)*(r11));
00772 IkReal x202=((cj4)*(cj5));
00773 IkReal x203=((sj4)*(x197));
00774 IkReal x204=((sj4)*(x198));
00775 dummyeval[0]=((((IkReal(-1.00000000000000))*(r01)*(x199)*(x203)))+(((IkReal(-1.00000000000000))*(r01)*(x199)*(x204)))+(((x201)*(x204)))+(((x201)*(x203)))+(((r01)*(r12)*(x202)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x202)))+(((r00)*(r12)*(x200)))+(((IkReal(-1.00000000000000))*(r02)*(x199)*(x200))));
00776 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00777 {
00778 continue;
00779 
00780 } else
00781 {
00782 {
00783 IkReal j0array[1], cj0array[1], sj0array[1];
00784 bool j0valid[1]={false};
00785 _nj0 = 1;
00786 IkReal x205=((cj5)*(sj4));
00787 IkReal x206=((IkReal(1.00000000000000))*(cj4));
00788 IkReal x207=((IkReal(1.00000000000000))*(sj4)*(sj5));
00789 if( IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(r11)*(x207)))+(((IkReal(-1.00000000000000))*(r12)*(x206)))+(((r10)*(x205))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(r02)*(x206)))+(((r00)*(x205)))+(((IkReal(-1.00000000000000))*(r01)*(x207))))))) < IKFAST_ATAN2_MAGTHRESH )
00790     continue;
00791 j0array[0]=IKatan2(((gconst60)*(((((IkReal(-1.00000000000000))*(r11)*(x207)))+(((IkReal(-1.00000000000000))*(r12)*(x206)))+(((r10)*(x205)))))), ((gconst60)*(((((IkReal(-1.00000000000000))*(r02)*(x206)))+(((r00)*(x205)))+(((IkReal(-1.00000000000000))*(r01)*(x207)))))));
00792 sj0array[0]=IKsin(j0array[0]);
00793 cj0array[0]=IKcos(j0array[0]);
00794 if( j0array[0] > IKPI )
00795 {
00796     j0array[0]-=IK2PI;
00797 }
00798 else if( j0array[0] < -IKPI )
00799 {    j0array[0]+=IK2PI;
00800 }
00801 j0valid[0] = true;
00802 for(int ij0 = 0; ij0 < 1; ++ij0)
00803 {
00804 if( !j0valid[ij0] )
00805 {
00806     continue;
00807 }
00808 _ij0[0] = ij0; _ij0[1] = -1;
00809 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
00810 {
00811 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00812 {
00813     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00814 }
00815 }
00816 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00817 {
00818 IkReal evalcond[6];
00819 IkReal x208=IKsin(j0);
00820 IkReal x209=IKcos(j0);
00821 IkReal x210=((IkReal(0.707103562373095))*(cj2));
00822 IkReal x211=((cj5)*(sj4));
00823 IkReal x212=((IkReal(1.00000000000000))*(sj4));
00824 IkReal x213=((IkReal(1.00000000000000))*(r10));
00825 IkReal x214=((IkReal(1.00000000000000))*(cj5));
00826 IkReal x215=((IkReal(1.00000000000000))*(cj4));
00827 IkReal x216=((sj1)*(sj2));
00828 IkReal x217=((IkReal(0.707109999985348))*(cj1));
00829 IkReal x218=((cj4)*(r11));
00830 IkReal x219=((sj5)*(x208));
00831 IkReal x220=((r10)*(x208));
00832 IkReal x221=((r01)*(x209));
00833 IkReal x222=((r00)*(x209));
00834 IkReal x223=((r02)*(x209));
00835 IkReal x224=((r12)*(x209));
00836 IkReal x225=((cj5)*(x208));
00837 IkReal x226=((r12)*(x208));
00838 IkReal x227=((sj5)*(x209));
00839 IkReal x228=((r02)*(x208));
00840 evalcond[0]=((IkReal(1.00000000000000))+(((r01)*(x225)))+(((IkReal(-1.00000000000000))*(x213)*(x227)))+(((r00)*(x219)))+(((IkReal(-1.00000000000000))*(r11)*(x209)*(x214))));
00841 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x212)*(x227)))+(((r01)*(sj4)*(x219)))+(((IkReal(-1.00000000000000))*(x215)*(x224)))+(((cj4)*(x228)))+(((IkReal(-1.00000000000000))*(r00)*(x208)*(x211)))+(((r10)*(x209)*(x211))));
00842 evalcond[2]=((((sj4)*(x228)))+(((cj4)*(r00)*(x225)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x209)*(x213)))+(((x218)*(x227)))+(((IkReal(-1.00000000000000))*(x212)*(x224)))+(((IkReal(-1.00000000000000))*(r01)*(x215)*(x219))));
00843 evalcond[3]=((((IkReal(-1.00000000000000))*(x214)*(x221)))+(((IkReal(-1.00000000000000))*(r11)*(x208)*(x214)))+(((IkReal(-1.00000000000000))*(x213)*(x219)))+(((IkReal(-1.00000000000000))*(sj5)*(x222))));
00844 evalcond[4]=((((IkReal(-1.00000000000000))*(x215)*(x223)))+(((IkReal(-1.00000000000000))*(x215)*(x226)))+(((IkReal(-0.707109999985348))*(x216)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((cj2)*(x217)))+(((IkReal(-1.00000000000000))*(sj5)*(x212)*(x221)))+(((sj1)*(x210)))+(((IkReal(-1.00000000000000))*(r11)*(x212)*(x219)))+(((x211)*(x220)))+(((x211)*(x222))));
00845 evalcond[5]=((((x218)*(x219)))+(((IkReal(-1.00000000000000))*(cj4)*(x213)*(x225)))+(((IkReal(-1.00000000000000))*(cj4)*(x214)*(x222)))+(((IkReal(-0.707109999985348))*(cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(sj2)*(x217)))+(((IkReal(-1.00000000000000))*(x212)*(x223)))+(((IkReal(-1.00000000000000))*(x212)*(x226)))+(((cj1)*(x210)))+(((cj4)*(sj5)*(x221)))+(((IkReal(-0.707103562373095))*(x216))));
00846 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  )
00847 {
00848 continue;
00849 }
00850 }
00851 
00852 {
00853 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00854 vinfos[0].jointtype = 1;
00855 vinfos[0].foffset = j0;
00856 vinfos[0].indices[0] = _ij0[0];
00857 vinfos[0].indices[1] = _ij0[1];
00858 vinfos[0].maxsolutions = _nj0;
00859 vinfos[1].jointtype = 1;
00860 vinfos[1].foffset = j1;
00861 vinfos[1].indices[0] = _ij1[0];
00862 vinfos[1].indices[1] = _ij1[1];
00863 vinfos[1].maxsolutions = _nj1;
00864 vinfos[2].jointtype = 1;
00865 vinfos[2].foffset = j2;
00866 vinfos[2].indices[0] = _ij2[0];
00867 vinfos[2].indices[1] = _ij2[1];
00868 vinfos[2].maxsolutions = _nj2;
00869 vinfos[3].jointtype = 1;
00870 vinfos[3].foffset = j3;
00871 vinfos[3].indices[0] = _ij3[0];
00872 vinfos[3].indices[1] = _ij3[1];
00873 vinfos[3].maxsolutions = _nj3;
00874 vinfos[4].jointtype = 1;
00875 vinfos[4].foffset = j4;
00876 vinfos[4].indices[0] = _ij4[0];
00877 vinfos[4].indices[1] = _ij4[1];
00878 vinfos[4].maxsolutions = _nj4;
00879 vinfos[5].jointtype = 1;
00880 vinfos[5].foffset = j5;
00881 vinfos[5].indices[0] = _ij5[0];
00882 vinfos[5].indices[1] = _ij5[1];
00883 vinfos[5].maxsolutions = _nj5;
00884 std::vector<int> vfree(0);
00885 solutions.AddSolution(vinfos,vfree);
00886 }
00887 }
00888 }
00889 
00890 }
00891 
00892 }
00893 
00894 } else
00895 {
00896 {
00897 IkReal j0array[1], cj0array[1], sj0array[1];
00898 bool j0valid[1]={false};
00899 _nj0 = 1;
00900 if( IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
00901     continue;
00902 j0array[0]=IKatan2(((gconst59)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst59)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
00903 sj0array[0]=IKsin(j0array[0]);
00904 cj0array[0]=IKcos(j0array[0]);
00905 if( j0array[0] > IKPI )
00906 {
00907     j0array[0]-=IK2PI;
00908 }
00909 else if( j0array[0] < -IKPI )
00910 {    j0array[0]+=IK2PI;
00911 }
00912 j0valid[0] = true;
00913 for(int ij0 = 0; ij0 < 1; ++ij0)
00914 {
00915 if( !j0valid[ij0] )
00916 {
00917     continue;
00918 }
00919 _ij0[0] = ij0; _ij0[1] = -1;
00920 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
00921 {
00922 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00923 {
00924     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00925 }
00926 }
00927 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00928 {
00929 IkReal evalcond[6];
00930 IkReal x229=IKsin(j0);
00931 IkReal x230=IKcos(j0);
00932 IkReal x231=((IkReal(0.707103562373095))*(cj2));
00933 IkReal x232=((cj5)*(sj4));
00934 IkReal x233=((IkReal(1.00000000000000))*(sj4));
00935 IkReal x234=((IkReal(1.00000000000000))*(r10));
00936 IkReal x235=((IkReal(1.00000000000000))*(cj5));
00937 IkReal x236=((IkReal(1.00000000000000))*(cj4));
00938 IkReal x237=((sj1)*(sj2));
00939 IkReal x238=((IkReal(0.707109999985348))*(cj1));
00940 IkReal x239=((cj4)*(r11));
00941 IkReal x240=((sj5)*(x229));
00942 IkReal x241=((r10)*(x229));
00943 IkReal x242=((r01)*(x230));
00944 IkReal x243=((r00)*(x230));
00945 IkReal x244=((r02)*(x230));
00946 IkReal x245=((r12)*(x230));
00947 IkReal x246=((cj5)*(x229));
00948 IkReal x247=((r12)*(x229));
00949 IkReal x248=((sj5)*(x230));
00950 IkReal x249=((r02)*(x229));
00951 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x234)*(x248)))+(((IkReal(-1.00000000000000))*(r11)*(x230)*(x235)))+(((r01)*(x246)))+(((r00)*(x240))));
00952 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x229)*(x232)))+(((cj4)*(x249)))+(((r01)*(sj4)*(x240)))+(((r10)*(x230)*(x232)))+(((IkReal(-1.00000000000000))*(x236)*(x245)))+(((IkReal(-1.00000000000000))*(r11)*(x233)*(x248))));
00953 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x236)*(x240)))+(((cj4)*(r00)*(x246)))+(((IkReal(-1.00000000000000))*(x233)*(x245)))+(((x239)*(x248)))+(((sj4)*(x249)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x230)*(x234))));
00954 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x243)))+(((IkReal(-1.00000000000000))*(x234)*(x240)))+(((IkReal(-1.00000000000000))*(x235)*(x242)))+(((IkReal(-1.00000000000000))*(r11)*(x229)*(x235))));
00955 evalcond[4]=((((sj1)*(x231)))+(((cj2)*(x238)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x236)*(x247)))+(((IkReal(-1.00000000000000))*(x236)*(x244)))+(((IkReal(-1.00000000000000))*(r11)*(x233)*(x240)))+(((x232)*(x243)))+(((x232)*(x241)))+(((IkReal(-0.707109999985348))*(x237)))+(((IkReal(-1.00000000000000))*(sj5)*(x233)*(x242))));
00956 evalcond[5]=((((cj1)*(x231)))+(((IkReal(-0.707109999985348))*(cj2)*(sj1)))+(((IkReal(-0.707103562373095))*(x237)))+(((IkReal(-1.00000000000000))*(cj4)*(x234)*(x246)))+(((IkReal(-1.00000000000000))*(x233)*(x244)))+(((IkReal(-1.00000000000000))*(x233)*(x247)))+(((x239)*(x240)))+(((cj4)*(sj5)*(x242)))+(((IkReal(-1.00000000000000))*(sj2)*(x238)))+(((IkReal(-1.00000000000000))*(cj4)*(x235)*(x243))));
00957 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  )
00958 {
00959 continue;
00960 }
00961 }
00962 
00963 {
00964 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00965 vinfos[0].jointtype = 1;
00966 vinfos[0].foffset = j0;
00967 vinfos[0].indices[0] = _ij0[0];
00968 vinfos[0].indices[1] = _ij0[1];
00969 vinfos[0].maxsolutions = _nj0;
00970 vinfos[1].jointtype = 1;
00971 vinfos[1].foffset = j1;
00972 vinfos[1].indices[0] = _ij1[0];
00973 vinfos[1].indices[1] = _ij1[1];
00974 vinfos[1].maxsolutions = _nj1;
00975 vinfos[2].jointtype = 1;
00976 vinfos[2].foffset = j2;
00977 vinfos[2].indices[0] = _ij2[0];
00978 vinfos[2].indices[1] = _ij2[1];
00979 vinfos[2].maxsolutions = _nj2;
00980 vinfos[3].jointtype = 1;
00981 vinfos[3].foffset = j3;
00982 vinfos[3].indices[0] = _ij3[0];
00983 vinfos[3].indices[1] = _ij3[1];
00984 vinfos[3].maxsolutions = _nj3;
00985 vinfos[4].jointtype = 1;
00986 vinfos[4].foffset = j4;
00987 vinfos[4].indices[0] = _ij4[0];
00988 vinfos[4].indices[1] = _ij4[1];
00989 vinfos[4].maxsolutions = _nj4;
00990 vinfos[5].jointtype = 1;
00991 vinfos[5].foffset = j5;
00992 vinfos[5].indices[0] = _ij5[0];
00993 vinfos[5].indices[1] = _ij5[1];
00994 vinfos[5].maxsolutions = _nj5;
00995 std::vector<int> vfree(0);
00996 solutions.AddSolution(vinfos,vfree);
00997 }
00998 }
00999 }
01000 
01001 }
01002 
01003 }
01004 }
01005 }
01006 
01007 }
01008 
01009 }
01010 
01011 } else
01012 {
01013 {
01014 IkReal j0array[1], cj0array[1], sj0array[1];
01015 bool j0valid[1]={false};
01016 _nj0 = 1;
01017 IkReal x250=((cj5)*(sj4));
01018 IkReal x251=((IkReal(1.00000000000000))*(cj4));
01019 IkReal x252=((IkReal(1.00000000000000))*(sj4)*(sj5));
01020 if( IKabs(((gconst57)*(((((r10)*(x250)))+(((IkReal(-1.00000000000000))*(r12)*(x251)))+(((IkReal(-1.00000000000000))*(r11)*(x252))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst57)*(((((r00)*(x250)))+(((IkReal(-1.00000000000000))*(r02)*(x251)))+(((IkReal(-1.00000000000000))*(r01)*(x252))))))) < IKFAST_ATAN2_MAGTHRESH )
01021     continue;
01022 j0array[0]=IKatan2(((gconst57)*(((((r10)*(x250)))+(((IkReal(-1.00000000000000))*(r12)*(x251)))+(((IkReal(-1.00000000000000))*(r11)*(x252)))))), ((gconst57)*(((((r00)*(x250)))+(((IkReal(-1.00000000000000))*(r02)*(x251)))+(((IkReal(-1.00000000000000))*(r01)*(x252)))))));
01023 sj0array[0]=IKsin(j0array[0]);
01024 cj0array[0]=IKcos(j0array[0]);
01025 if( j0array[0] > IKPI )
01026 {
01027     j0array[0]-=IK2PI;
01028 }
01029 else if( j0array[0] < -IKPI )
01030 {    j0array[0]+=IK2PI;
01031 }
01032 j0valid[0] = true;
01033 for(int ij0 = 0; ij0 < 1; ++ij0)
01034 {
01035 if( !j0valid[ij0] )
01036 {
01037     continue;
01038 }
01039 _ij0[0] = ij0; _ij0[1] = -1;
01040 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
01041 {
01042 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
01043 {
01044     j0valid[iij0]=false; _ij0[1] = iij0; break; 
01045 }
01046 }
01047 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
01048 {
01049 IkReal evalcond[4];
01050 IkReal x253=IKsin(j0);
01051 IkReal x254=IKcos(j0);
01052 IkReal x255=((IkReal(1.00000000000000))*(cj5));
01053 IkReal x256=((r01)*(sj5));
01054 IkReal x257=((IkReal(1.00000000000000))*(r12));
01055 IkReal x258=((r11)*(sj5));
01056 IkReal x259=((IkReal(1.00000000000000))*(r10));
01057 IkReal x260=((cj4)*(x253));
01058 IkReal x261=((sj4)*(x253));
01059 IkReal x262=((sj4)*(x254));
01060 IkReal x263=((sj5)*(x253));
01061 IkReal x264=((cj4)*(x254));
01062 IkReal x265=((sj5)*(x254));
01063 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x259)*(x265)))+(((cj5)*(r01)*(x253)))+(((r00)*(x263)))+(((IkReal(-1.00000000000000))*(r11)*(x254)*(x255))));
01064 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x255)*(x261)))+(((IkReal(-1.00000000000000))*(x258)*(x262)))+(((r02)*(x260)))+(((cj5)*(r10)*(x262)))+(((x256)*(x261)))+(((IkReal(-1.00000000000000))*(x257)*(x264))));
01065 evalcond[2]=((((x258)*(x264)))+(((IkReal(-1.00000000000000))*(r10)*(x255)*(x264)))+(((r02)*(x261)))+(((cj5)*(r00)*(x260)))+(((IkReal(-1.00000000000000))*(x256)*(x260)))+(((IkReal(-1.00000000000000))*(x257)*(x262))));
01066 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x253)*(x255)))+(((IkReal(-1.00000000000000))*(x259)*(x263)))+(((IkReal(-1.00000000000000))*(r01)*(x254)*(x255)))+(((IkReal(-1.00000000000000))*(r00)*(x265))));
01067 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01068 {
01069 continue;
01070 }
01071 }
01072 
01073 {
01074 IkReal dummyeval[1];
01075 IkReal gconst61;
01076 gconst61=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
01077 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
01078 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01079 {
01080 {
01081 IkReal dummyeval[1];
01082 IkReal gconst62;
01083 gconst62=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
01084 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
01085 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01086 {
01087 continue;
01088 
01089 } else
01090 {
01091 {
01092 IkReal j1array[1], cj1array[1], sj1array[1];
01093 bool j1valid[1]={false};
01094 _nj1 = 1;
01095 IkReal x266=((sj4)*(sj5));
01096 IkReal x267=((IkReal(0.707103562373095))*(sj0));
01097 IkReal x268=((r11)*(sj2));
01098 IkReal x269=((cj2)*(cj4));
01099 IkReal x270=((IkReal(0.707103562373095))*(r22));
01100 IkReal x271=((IkReal(0.707109999985348))*(cj0));
01101 IkReal x272=((cj2)*(r01));
01102 IkReal x273=((IkReal(0.707109999985348))*(cj2));
01103 IkReal x274=((IkReal(0.707109999985348))*(sj0));
01104 IkReal x275=((r21)*(sj2));
01105 IkReal x276=((IkReal(0.707103562373095))*(cj2));
01106 IkReal x277=((IkReal(0.707103562373095))*(sj2));
01107 IkReal x278=((cj5)*(sj4));
01108 IkReal x279=((r10)*(sj2));
01109 IkReal x280=((cj0)*(r00));
01110 IkReal x281=((IkReal(0.707103562373095))*(cj0));
01111 IkReal x282=((cj4)*(sj2));
01112 IkReal x283=((IkReal(0.707109999985348))*(r22));
01113 IkReal x284=((r02)*(x282));
01114 IkReal x285=((r20)*(x278));
01115 if( IKabs(((gconst62)*(((((IkReal(-1.00000000000000))*(x266)*(x272)*(x281)))+(((IkReal(-1.00000000000000))*(x277)*(x285)))+(((cj2)*(r10)*(x267)*(x278)))+(((x269)*(x283)))+(((r01)*(sj2)*(x266)*(x271)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x266)*(x267)))+(((x271)*(x284)))+(((x266)*(x268)*(x274)))+(((r21)*(x266)*(x273)))+(((IkReal(-1.00000000000000))*(r12)*(x267)*(x269)))+(((r12)*(x274)*(x282)))+(((IkReal(-1.00000000000000))*(x273)*(x285)))+(((IkReal(-1.00000000000000))*(x274)*(x278)*(x279)))+(((IkReal(0.707103562373095))*(x266)*(x275)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x271)*(x278)))+(((x270)*(x282)))+(((x276)*(x278)*(x280)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x281))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((IkReal(-1.00000000000000))*(r21)*(x266)*(x276)))+(((IkReal(-0.707109999985348))*(sj2)*(x285)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x271)))+(((x277)*(x278)*(x280)))+(((IkReal(-1.00000000000000))*(x266)*(x271)*(x272)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x266)*(x273)))+(((IkReal(-1.00000000000000))*(x266)*(x267)*(x268)))+(((x267)*(x278)*(x279)))+(((IkReal(-1.00000000000000))*(x269)*(x270)))+(((IkReal(-1.00000000000000))*(r12)*(x269)*(x274)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x266)*(x277)))+(((r10)*(sj0)*(x273)*(x278)))+(((cj2)*(r00)*(x271)*(x278)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x277)))+(((IkReal(0.707109999985348))*(x266)*(x275)))+(((x276)*(x285)))+(((x282)*(x283)))+(((IkReal(-1.00000000000000))*(r12)*(x267)*(x282))))))) < IKFAST_ATAN2_MAGTHRESH )
01116     continue;
01117 j1array[0]=IKatan2(((gconst62)*(((((IkReal(-1.00000000000000))*(x266)*(x272)*(x281)))+(((IkReal(-1.00000000000000))*(x277)*(x285)))+(((cj2)*(r10)*(x267)*(x278)))+(((x269)*(x283)))+(((r01)*(sj2)*(x266)*(x271)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x266)*(x267)))+(((x271)*(x284)))+(((x266)*(x268)*(x274)))+(((r21)*(x266)*(x273)))+(((IkReal(-1.00000000000000))*(r12)*(x267)*(x269)))+(((r12)*(x274)*(x282)))+(((IkReal(-1.00000000000000))*(x273)*(x285)))+(((IkReal(-1.00000000000000))*(x274)*(x278)*(x279)))+(((IkReal(0.707103562373095))*(x266)*(x275)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x271)*(x278)))+(((x270)*(x282)))+(((x276)*(x278)*(x280)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x281)))))), ((gconst62)*(((((IkReal(-1.00000000000000))*(r21)*(x266)*(x276)))+(((IkReal(-0.707109999985348))*(sj2)*(x285)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x271)))+(((x277)*(x278)*(x280)))+(((IkReal(-1.00000000000000))*(x266)*(x271)*(x272)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x266)*(x273)))+(((IkReal(-1.00000000000000))*(x266)*(x267)*(x268)))+(((x267)*(x278)*(x279)))+(((IkReal(-1.00000000000000))*(x269)*(x270)))+(((IkReal(-1.00000000000000))*(r12)*(x269)*(x274)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x266)*(x277)))+(((r10)*(sj0)*(x273)*(x278)))+(((cj2)*(r00)*(x271)*(x278)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x277)))+(((IkReal(0.707109999985348))*(x266)*(x275)))+(((x276)*(x285)))+(((x282)*(x283)))+(((IkReal(-1.00000000000000))*(r12)*(x267)*(x282)))))));
01118 sj1array[0]=IKsin(j1array[0]);
01119 cj1array[0]=IKcos(j1array[0]);
01120 if( j1array[0] > IKPI )
01121 {
01122     j1array[0]-=IK2PI;
01123 }
01124 else if( j1array[0] < -IKPI )
01125 {    j1array[0]+=IK2PI;
01126 }
01127 j1valid[0] = true;
01128 for(int ij1 = 0; ij1 < 1; ++ij1)
01129 {
01130 if( !j1valid[ij1] )
01131 {
01132     continue;
01133 }
01134 _ij1[0] = ij1; _ij1[1] = -1;
01135 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01136 {
01137 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01138 {
01139     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01140 }
01141 }
01142 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01143 {
01144 IkReal evalcond[4];
01145 IkReal x286=IKsin(j1);
01146 IkReal x287=IKcos(j1);
01147 IkReal x288=((IkReal(0.707109999985348))*(cj2));
01148 IkReal x289=((IkReal(1.00000000000000))*(sj4));
01149 IkReal x290=((cj5)*(r00));
01150 IkReal x291=((IkReal(0.707109999985348))*(sj2));
01151 IkReal x292=((cj5)*(r20));
01152 IkReal x293=((r12)*(sj0));
01153 IkReal x294=((r21)*(sj5));
01154 IkReal x295=((IkReal(1.00000000000000))*(cj4));
01155 IkReal x296=((IkReal(0.707103562373095))*(x287));
01156 IkReal x297=((r11)*(sj0)*(sj5));
01157 IkReal x298=((cj0)*(x295));
01158 IkReal x299=((IkReal(0.707103562373095))*(x286));
01159 IkReal x300=((cj0)*(r01)*(sj5));
01160 IkReal x301=((cj5)*(r10)*(sj0));
01161 IkReal x302=((sj2)*(x296));
01162 IkReal x303=((cj2)*(x299));
01163 IkReal x304=((x287)*(x288));
01164 IkReal x305=((x286)*(x291));
01165 IkReal x306=((cj2)*(x296));
01166 IkReal x307=((x286)*(x288));
01167 IkReal x308=((sj2)*(x299));
01168 IkReal x309=((x287)*(x291));
01169 IkReal x310=((x304)+(x302)+(x303));
01170 IkReal x311=((x308)+(x309)+(x307));
01171 evalcond[0]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x289)*(x292)))+(((sj4)*(x294)))+(x311)+(((IkReal(-1.00000000000000))*(x306))));
01172 evalcond[1]=((((r22)*(sj4)))+(((cj4)*(x292)))+(x310)+(((IkReal(-1.00000000000000))*(x305)))+(((IkReal(-1.00000000000000))*(x294)*(x295))));
01173 evalcond[2]=((((IkReal(-1.00000000000000))*(x289)*(x297)))+(((IkReal(-1.00000000000000))*(x293)*(x295)))+(((IkReal(-1.00000000000000))*(r02)*(x298)))+(x310)+(((cj0)*(sj4)*(x290)))+(((sj4)*(x301)))+(((IkReal(-1.00000000000000))*(x289)*(x300)))+(((IkReal(-1.00000000000000))*(x305))));
01174 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x289)))+(((IkReal(-1.00000000000000))*(x290)*(x298)))+(((IkReal(-1.00000000000000))*(x289)*(x293)))+(((cj4)*(x297)))+(((IkReal(-1.00000000000000))*(x295)*(x301)))+(x306)+(((IkReal(-1.00000000000000))*(x311)))+(((cj4)*(x300))));
01175 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01176 {
01177 continue;
01178 }
01179 }
01180 
01181 {
01182 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01183 vinfos[0].jointtype = 1;
01184 vinfos[0].foffset = j0;
01185 vinfos[0].indices[0] = _ij0[0];
01186 vinfos[0].indices[1] = _ij0[1];
01187 vinfos[0].maxsolutions = _nj0;
01188 vinfos[1].jointtype = 1;
01189 vinfos[1].foffset = j1;
01190 vinfos[1].indices[0] = _ij1[0];
01191 vinfos[1].indices[1] = _ij1[1];
01192 vinfos[1].maxsolutions = _nj1;
01193 vinfos[2].jointtype = 1;
01194 vinfos[2].foffset = j2;
01195 vinfos[2].indices[0] = _ij2[0];
01196 vinfos[2].indices[1] = _ij2[1];
01197 vinfos[2].maxsolutions = _nj2;
01198 vinfos[3].jointtype = 1;
01199 vinfos[3].foffset = j3;
01200 vinfos[3].indices[0] = _ij3[0];
01201 vinfos[3].indices[1] = _ij3[1];
01202 vinfos[3].maxsolutions = _nj3;
01203 vinfos[4].jointtype = 1;
01204 vinfos[4].foffset = j4;
01205 vinfos[4].indices[0] = _ij4[0];
01206 vinfos[4].indices[1] = _ij4[1];
01207 vinfos[4].maxsolutions = _nj4;
01208 vinfos[5].jointtype = 1;
01209 vinfos[5].foffset = j5;
01210 vinfos[5].indices[0] = _ij5[0];
01211 vinfos[5].indices[1] = _ij5[1];
01212 vinfos[5].maxsolutions = _nj5;
01213 std::vector<int> vfree(0);
01214 solutions.AddSolution(vinfos,vfree);
01215 }
01216 }
01217 }
01218 
01219 }
01220 
01221 }
01222 
01223 } else
01224 {
01225 {
01226 IkReal j1array[1], cj1array[1], sj1array[1];
01227 bool j1valid[1]={false};
01228 _nj1 = 1;
01229 IkReal x312=((IkReal(0.707109999985348))*(sj4));
01230 IkReal x313=((r22)*(sj2));
01231 IkReal x314=((cj5)*(r20));
01232 IkReal x315=((r21)*(sj5));
01233 IkReal x316=((IkReal(0.707109999985348))*(cj4));
01234 IkReal x317=((cj2)*(r22));
01235 IkReal x318=((IkReal(0.707103562373095))*(sj4));
01236 IkReal x319=((IkReal(0.707103562373095))*(cj4));
01237 IkReal x320=((sj2)*(x319));
01238 IkReal x321=((cj2)*(x319));
01239 if( IKabs(((gconst61)*(((((x317)*(x318)))+(((IkReal(-1.00000000000000))*(x312)*(x313)))+(((IkReal(-1.00000000000000))*(cj2)*(x312)*(x314)))+(((IkReal(-1.00000000000000))*(x315)*(x321)))+(((x314)*(x321)))+(((IkReal(-1.00000000000000))*(sj2)*(x314)*(x318)))+(((IkReal(-1.00000000000000))*(sj2)*(x314)*(x316)))+(((cj2)*(x312)*(x315)))+(((sj2)*(x315)*(x318)))+(((sj2)*(x315)*(x316)))+(((x316)*(x317)))+(((x313)*(x319))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((IkReal(-1.00000000000000))*(sj2)*(x312)*(x314)))+(((cj2)*(x314)*(x316)))+(((cj2)*(x314)*(x318)))+(((x312)*(x317)))+(((IkReal(-1.00000000000000))*(x315)*(x320)))+(((sj2)*(x312)*(x315)))+(((x314)*(x320)))+(((IkReal(-1.00000000000000))*(cj2)*(x315)*(x318)))+(((IkReal(-1.00000000000000))*(cj2)*(x315)*(x316)))+(((IkReal(-1.00000000000000))*(x317)*(x319)))+(((x313)*(x318)))+(((x313)*(x316))))))) < IKFAST_ATAN2_MAGTHRESH )
01240     continue;
01241 j1array[0]=IKatan2(((gconst61)*(((((x317)*(x318)))+(((IkReal(-1.00000000000000))*(x312)*(x313)))+(((IkReal(-1.00000000000000))*(cj2)*(x312)*(x314)))+(((IkReal(-1.00000000000000))*(x315)*(x321)))+(((x314)*(x321)))+(((IkReal(-1.00000000000000))*(sj2)*(x314)*(x318)))+(((IkReal(-1.00000000000000))*(sj2)*(x314)*(x316)))+(((cj2)*(x312)*(x315)))+(((sj2)*(x315)*(x318)))+(((sj2)*(x315)*(x316)))+(((x316)*(x317)))+(((x313)*(x319)))))), ((gconst61)*(((((IkReal(-1.00000000000000))*(sj2)*(x312)*(x314)))+(((cj2)*(x314)*(x316)))+(((cj2)*(x314)*(x318)))+(((x312)*(x317)))+(((IkReal(-1.00000000000000))*(x315)*(x320)))+(((sj2)*(x312)*(x315)))+(((x314)*(x320)))+(((IkReal(-1.00000000000000))*(cj2)*(x315)*(x318)))+(((IkReal(-1.00000000000000))*(cj2)*(x315)*(x316)))+(((IkReal(-1.00000000000000))*(x317)*(x319)))+(((x313)*(x318)))+(((x313)*(x316)))))));
01242 sj1array[0]=IKsin(j1array[0]);
01243 cj1array[0]=IKcos(j1array[0]);
01244 if( j1array[0] > IKPI )
01245 {
01246     j1array[0]-=IK2PI;
01247 }
01248 else if( j1array[0] < -IKPI )
01249 {    j1array[0]+=IK2PI;
01250 }
01251 j1valid[0] = true;
01252 for(int ij1 = 0; ij1 < 1; ++ij1)
01253 {
01254 if( !j1valid[ij1] )
01255 {
01256     continue;
01257 }
01258 _ij1[0] = ij1; _ij1[1] = -1;
01259 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01260 {
01261 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01262 {
01263     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01264 }
01265 }
01266 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01267 {
01268 IkReal evalcond[4];
01269 IkReal x322=IKsin(j1);
01270 IkReal x323=IKcos(j1);
01271 IkReal x324=((IkReal(0.707109999985348))*(cj2));
01272 IkReal x325=((IkReal(1.00000000000000))*(sj4));
01273 IkReal x326=((cj5)*(r00));
01274 IkReal x327=((IkReal(0.707109999985348))*(sj2));
01275 IkReal x328=((cj5)*(r20));
01276 IkReal x329=((r12)*(sj0));
01277 IkReal x330=((r21)*(sj5));
01278 IkReal x331=((IkReal(1.00000000000000))*(cj4));
01279 IkReal x332=((IkReal(0.707103562373095))*(x323));
01280 IkReal x333=((r11)*(sj0)*(sj5));
01281 IkReal x334=((cj0)*(x331));
01282 IkReal x335=((IkReal(0.707103562373095))*(x322));
01283 IkReal x336=((cj0)*(r01)*(sj5));
01284 IkReal x337=((cj5)*(r10)*(sj0));
01285 IkReal x338=((sj2)*(x332));
01286 IkReal x339=((cj2)*(x335));
01287 IkReal x340=((x323)*(x324));
01288 IkReal x341=((x322)*(x327));
01289 IkReal x342=((cj2)*(x332));
01290 IkReal x343=((x322)*(x324));
01291 IkReal x344=((sj2)*(x335));
01292 IkReal x345=((x323)*(x327));
01293 IkReal x346=((x339)+(x338)+(x340));
01294 IkReal x347=((x343)+(x344)+(x345));
01295 evalcond[0]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x325)*(x328)))+(x347)+(((sj4)*(x330)))+(((IkReal(-1.00000000000000))*(x342))));
01296 evalcond[1]=((((r22)*(sj4)))+(x346)+(((IkReal(-1.00000000000000))*(x330)*(x331)))+(((cj4)*(x328)))+(((IkReal(-1.00000000000000))*(x341))));
01297 evalcond[2]=((((cj0)*(sj4)*(x326)))+(((IkReal(-1.00000000000000))*(x329)*(x331)))+(x346)+(((IkReal(-1.00000000000000))*(r02)*(x334)))+(((sj4)*(x337)))+(((IkReal(-1.00000000000000))*(x341)))+(((IkReal(-1.00000000000000))*(x325)*(x336)))+(((IkReal(-1.00000000000000))*(x325)*(x333))));
01298 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x325)))+(((IkReal(-1.00000000000000))*(x325)*(x329)))+(x342)+(((IkReal(-1.00000000000000))*(x331)*(x337)))+(((cj4)*(x336)))+(((cj4)*(x333)))+(((IkReal(-1.00000000000000))*(x347)))+(((IkReal(-1.00000000000000))*(x326)*(x334))));
01299 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01300 {
01301 continue;
01302 }
01303 }
01304 
01305 {
01306 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01307 vinfos[0].jointtype = 1;
01308 vinfos[0].foffset = j0;
01309 vinfos[0].indices[0] = _ij0[0];
01310 vinfos[0].indices[1] = _ij0[1];
01311 vinfos[0].maxsolutions = _nj0;
01312 vinfos[1].jointtype = 1;
01313 vinfos[1].foffset = j1;
01314 vinfos[1].indices[0] = _ij1[0];
01315 vinfos[1].indices[1] = _ij1[1];
01316 vinfos[1].maxsolutions = _nj1;
01317 vinfos[2].jointtype = 1;
01318 vinfos[2].foffset = j2;
01319 vinfos[2].indices[0] = _ij2[0];
01320 vinfos[2].indices[1] = _ij2[1];
01321 vinfos[2].maxsolutions = _nj2;
01322 vinfos[3].jointtype = 1;
01323 vinfos[3].foffset = j3;
01324 vinfos[3].indices[0] = _ij3[0];
01325 vinfos[3].indices[1] = _ij3[1];
01326 vinfos[3].maxsolutions = _nj3;
01327 vinfos[4].jointtype = 1;
01328 vinfos[4].foffset = j4;
01329 vinfos[4].indices[0] = _ij4[0];
01330 vinfos[4].indices[1] = _ij4[1];
01331 vinfos[4].maxsolutions = _nj4;
01332 vinfos[5].jointtype = 1;
01333 vinfos[5].foffset = j5;
01334 vinfos[5].indices[0] = _ij5[0];
01335 vinfos[5].indices[1] = _ij5[1];
01336 vinfos[5].maxsolutions = _nj5;
01337 std::vector<int> vfree(0);
01338 solutions.AddSolution(vinfos,vfree);
01339 }
01340 }
01341 }
01342 
01343 }
01344 
01345 }
01346 }
01347 }
01348 
01349 }
01350 
01351 }
01352 
01353 } else
01354 {
01355 {
01356 IkReal j0array[1], cj0array[1], sj0array[1];
01357 bool j0valid[1]={false};
01358 _nj0 = 1;
01359 if( IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
01360     continue;
01361 j0array[0]=IKatan2(((gconst56)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst56)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
01362 sj0array[0]=IKsin(j0array[0]);
01363 cj0array[0]=IKcos(j0array[0]);
01364 if( j0array[0] > IKPI )
01365 {
01366     j0array[0]-=IK2PI;
01367 }
01368 else if( j0array[0] < -IKPI )
01369 {    j0array[0]+=IK2PI;
01370 }
01371 j0valid[0] = true;
01372 for(int ij0 = 0; ij0 < 1; ++ij0)
01373 {
01374 if( !j0valid[ij0] )
01375 {
01376     continue;
01377 }
01378 _ij0[0] = ij0; _ij0[1] = -1;
01379 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
01380 {
01381 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
01382 {
01383     j0valid[iij0]=false; _ij0[1] = iij0; break; 
01384 }
01385 }
01386 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
01387 {
01388 IkReal evalcond[4];
01389 IkReal x348=IKsin(j0);
01390 IkReal x349=IKcos(j0);
01391 IkReal x350=((IkReal(1.00000000000000))*(cj5));
01392 IkReal x351=((r01)*(sj5));
01393 IkReal x352=((IkReal(1.00000000000000))*(r12));
01394 IkReal x353=((r11)*(sj5));
01395 IkReal x354=((IkReal(1.00000000000000))*(r10));
01396 IkReal x355=((cj4)*(x348));
01397 IkReal x356=((sj4)*(x348));
01398 IkReal x357=((sj4)*(x349));
01399 IkReal x358=((sj5)*(x348));
01400 IkReal x359=((cj4)*(x349));
01401 IkReal x360=((sj5)*(x349));
01402 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x354)*(x360)))+(((r00)*(x358)))+(((cj5)*(r01)*(x348)))+(((IkReal(-1.00000000000000))*(r11)*(x349)*(x350))));
01403 evalcond[1]=((((IkReal(-1.00000000000000))*(x353)*(x357)))+(((x351)*(x356)))+(((IkReal(-1.00000000000000))*(r00)*(x350)*(x356)))+(((IkReal(-1.00000000000000))*(x352)*(x359)))+(((r02)*(x355)))+(((cj5)*(r10)*(x357))));
01404 evalcond[2]=((((x353)*(x359)))+(((IkReal(-1.00000000000000))*(x351)*(x355)))+(((IkReal(-1.00000000000000))*(r10)*(x350)*(x359)))+(((IkReal(-1.00000000000000))*(x352)*(x357)))+(((cj5)*(r00)*(x355)))+(((r02)*(x356))));
01405 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x349)*(x350)))+(((IkReal(-1.00000000000000))*(r00)*(x360)))+(((IkReal(-1.00000000000000))*(r11)*(x348)*(x350)))+(((IkReal(-1.00000000000000))*(x354)*(x358))));
01406 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01407 {
01408 continue;
01409 }
01410 }
01411 
01412 {
01413 IkReal dummyeval[1];
01414 IkReal gconst61;
01415 gconst61=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
01416 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
01417 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01418 {
01419 {
01420 IkReal dummyeval[1];
01421 IkReal gconst62;
01422 gconst62=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
01423 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
01424 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01425 {
01426 continue;
01427 
01428 } else
01429 {
01430 {
01431 IkReal j1array[1], cj1array[1], sj1array[1];
01432 bool j1valid[1]={false};
01433 _nj1 = 1;
01434 IkReal x361=((sj4)*(sj5));
01435 IkReal x362=((IkReal(0.707103562373095))*(sj0));
01436 IkReal x363=((r11)*(sj2));
01437 IkReal x364=((cj2)*(cj4));
01438 IkReal x365=((IkReal(0.707103562373095))*(r22));
01439 IkReal x366=((IkReal(0.707109999985348))*(cj0));
01440 IkReal x367=((cj2)*(r01));
01441 IkReal x368=((IkReal(0.707109999985348))*(cj2));
01442 IkReal x369=((IkReal(0.707109999985348))*(sj0));
01443 IkReal x370=((r21)*(sj2));
01444 IkReal x371=((IkReal(0.707103562373095))*(cj2));
01445 IkReal x372=((IkReal(0.707103562373095))*(sj2));
01446 IkReal x373=((cj5)*(sj4));
01447 IkReal x374=((r10)*(sj2));
01448 IkReal x375=((cj0)*(r00));
01449 IkReal x376=((IkReal(0.707103562373095))*(cj0));
01450 IkReal x377=((cj4)*(sj2));
01451 IkReal x378=((IkReal(0.707109999985348))*(r22));
01452 IkReal x379=((r02)*(x377));
01453 IkReal x380=((r20)*(x373));
01454 if( IKabs(((gconst62)*(((((IkReal(0.707103562373095))*(x361)*(x370)))+(((IkReal(-1.00000000000000))*(r12)*(x362)*(x364)))+(((r12)*(x369)*(x377)))+(((x364)*(x378)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x361)*(x362)))+(((IkReal(-1.00000000000000))*(r02)*(x364)*(x376)))+(((x365)*(x377)))+(((IkReal(-1.00000000000000))*(x369)*(x373)*(x374)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x366)*(x373)))+(((x366)*(x379)))+(((r21)*(x361)*(x368)))+(((x361)*(x363)*(x369)))+(((IkReal(-1.00000000000000))*(x368)*(x380)))+(((cj2)*(r10)*(x362)*(x373)))+(((x371)*(x373)*(x375)))+(((r01)*(sj2)*(x361)*(x366)))+(((IkReal(-1.00000000000000))*(x372)*(x380)))+(((IkReal(-1.00000000000000))*(x361)*(x367)*(x376))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((IkReal(-0.707109999985348))*(sj2)*(x380)))+(((IkReal(0.707109999985348))*(x361)*(x370)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x372)))+(((x372)*(x373)*(x375)))+(((IkReal(-1.00000000000000))*(r12)*(x362)*(x377)))+(((IkReal(-1.00000000000000))*(x361)*(x366)*(x367)))+(((IkReal(-1.00000000000000))*(r12)*(x364)*(x369)))+(((cj2)*(r00)*(x366)*(x373)))+(((IkReal(-1.00000000000000))*(r21)*(x361)*(x371)))+(((IkReal(-1.00000000000000))*(r02)*(x364)*(x366)))+(((x371)*(x380)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x361)*(x372)))+(((IkReal(-1.00000000000000))*(x361)*(x362)*(x363)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x361)*(x368)))+(((x377)*(x378)))+(((IkReal(-1.00000000000000))*(x364)*(x365)))+(((r10)*(sj0)*(x368)*(x373)))+(((x362)*(x373)*(x374))))))) < IKFAST_ATAN2_MAGTHRESH )
01455     continue;
01456 j1array[0]=IKatan2(((gconst62)*(((((IkReal(0.707103562373095))*(x361)*(x370)))+(((IkReal(-1.00000000000000))*(r12)*(x362)*(x364)))+(((r12)*(x369)*(x377)))+(((x364)*(x378)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x361)*(x362)))+(((IkReal(-1.00000000000000))*(r02)*(x364)*(x376)))+(((x365)*(x377)))+(((IkReal(-1.00000000000000))*(x369)*(x373)*(x374)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x366)*(x373)))+(((x366)*(x379)))+(((r21)*(x361)*(x368)))+(((x361)*(x363)*(x369)))+(((IkReal(-1.00000000000000))*(x368)*(x380)))+(((cj2)*(r10)*(x362)*(x373)))+(((x371)*(x373)*(x375)))+(((r01)*(sj2)*(x361)*(x366)))+(((IkReal(-1.00000000000000))*(x372)*(x380)))+(((IkReal(-1.00000000000000))*(x361)*(x367)*(x376)))))), ((gconst62)*(((((IkReal(-0.707109999985348))*(sj2)*(x380)))+(((IkReal(0.707109999985348))*(x361)*(x370)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x372)))+(((x372)*(x373)*(x375)))+(((IkReal(-1.00000000000000))*(r12)*(x362)*(x377)))+(((IkReal(-1.00000000000000))*(x361)*(x366)*(x367)))+(((IkReal(-1.00000000000000))*(r12)*(x364)*(x369)))+(((cj2)*(r00)*(x366)*(x373)))+(((IkReal(-1.00000000000000))*(r21)*(x361)*(x371)))+(((IkReal(-1.00000000000000))*(r02)*(x364)*(x366)))+(((x371)*(x380)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x361)*(x372)))+(((IkReal(-1.00000000000000))*(x361)*(x362)*(x363)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x361)*(x368)))+(((x377)*(x378)))+(((IkReal(-1.00000000000000))*(x364)*(x365)))+(((r10)*(sj0)*(x368)*(x373)))+(((x362)*(x373)*(x374)))))));
01457 sj1array[0]=IKsin(j1array[0]);
01458 cj1array[0]=IKcos(j1array[0]);
01459 if( j1array[0] > IKPI )
01460 {
01461     j1array[0]-=IK2PI;
01462 }
01463 else if( j1array[0] < -IKPI )
01464 {    j1array[0]+=IK2PI;
01465 }
01466 j1valid[0] = true;
01467 for(int ij1 = 0; ij1 < 1; ++ij1)
01468 {
01469 if( !j1valid[ij1] )
01470 {
01471     continue;
01472 }
01473 _ij1[0] = ij1; _ij1[1] = -1;
01474 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01475 {
01476 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01477 {
01478     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01479 }
01480 }
01481 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01482 {
01483 IkReal evalcond[4];
01484 IkReal x381=IKsin(j1);
01485 IkReal x382=IKcos(j1);
01486 IkReal x383=((IkReal(0.707109999985348))*(cj2));
01487 IkReal x384=((IkReal(1.00000000000000))*(sj4));
01488 IkReal x385=((cj5)*(r00));
01489 IkReal x386=((IkReal(0.707109999985348))*(sj2));
01490 IkReal x387=((cj5)*(r20));
01491 IkReal x388=((r12)*(sj0));
01492 IkReal x389=((r21)*(sj5));
01493 IkReal x390=((IkReal(1.00000000000000))*(cj4));
01494 IkReal x391=((IkReal(0.707103562373095))*(x382));
01495 IkReal x392=((r11)*(sj0)*(sj5));
01496 IkReal x393=((cj0)*(x390));
01497 IkReal x394=((IkReal(0.707103562373095))*(x381));
01498 IkReal x395=((cj0)*(r01)*(sj5));
01499 IkReal x396=((cj5)*(r10)*(sj0));
01500 IkReal x397=((sj2)*(x391));
01501 IkReal x398=((cj2)*(x394));
01502 IkReal x399=((x382)*(x383));
01503 IkReal x400=((x381)*(x386));
01504 IkReal x401=((cj2)*(x391));
01505 IkReal x402=((x381)*(x383));
01506 IkReal x403=((sj2)*(x394));
01507 IkReal x404=((x382)*(x386));
01508 IkReal x405=((x397)+(x399)+(x398));
01509 IkReal x406=((x403)+(x402)+(x404));
01510 evalcond[0]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x384)*(x387)))+(((sj4)*(x389)))+(x406)+(((IkReal(-1.00000000000000))*(x401))));
01511 evalcond[1]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x389)*(x390)))+(x405)+(((cj4)*(x387)))+(((IkReal(-1.00000000000000))*(x400))));
01512 evalcond[2]=((((IkReal(-1.00000000000000))*(x384)*(x395)))+(((IkReal(-1.00000000000000))*(x384)*(x392)))+(((IkReal(-1.00000000000000))*(r02)*(x393)))+(((cj0)*(sj4)*(x385)))+(((IkReal(-1.00000000000000))*(x388)*(x390)))+(x405)+(((IkReal(-1.00000000000000))*(x400)))+(((sj4)*(x396))));
01513 evalcond[3]=((((IkReal(-1.00000000000000))*(x385)*(x393)))+(((cj4)*(x392)))+(((cj4)*(x395)))+(((IkReal(-1.00000000000000))*(x384)*(x388)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x384)))+(x401)+(((IkReal(-1.00000000000000))*(x390)*(x396)))+(((IkReal(-1.00000000000000))*(x406))));
01514 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01515 {
01516 continue;
01517 }
01518 }
01519 
01520 {
01521 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01522 vinfos[0].jointtype = 1;
01523 vinfos[0].foffset = j0;
01524 vinfos[0].indices[0] = _ij0[0];
01525 vinfos[0].indices[1] = _ij0[1];
01526 vinfos[0].maxsolutions = _nj0;
01527 vinfos[1].jointtype = 1;
01528 vinfos[1].foffset = j1;
01529 vinfos[1].indices[0] = _ij1[0];
01530 vinfos[1].indices[1] = _ij1[1];
01531 vinfos[1].maxsolutions = _nj1;
01532 vinfos[2].jointtype = 1;
01533 vinfos[2].foffset = j2;
01534 vinfos[2].indices[0] = _ij2[0];
01535 vinfos[2].indices[1] = _ij2[1];
01536 vinfos[2].maxsolutions = _nj2;
01537 vinfos[3].jointtype = 1;
01538 vinfos[3].foffset = j3;
01539 vinfos[3].indices[0] = _ij3[0];
01540 vinfos[3].indices[1] = _ij3[1];
01541 vinfos[3].maxsolutions = _nj3;
01542 vinfos[4].jointtype = 1;
01543 vinfos[4].foffset = j4;
01544 vinfos[4].indices[0] = _ij4[0];
01545 vinfos[4].indices[1] = _ij4[1];
01546 vinfos[4].maxsolutions = _nj4;
01547 vinfos[5].jointtype = 1;
01548 vinfos[5].foffset = j5;
01549 vinfos[5].indices[0] = _ij5[0];
01550 vinfos[5].indices[1] = _ij5[1];
01551 vinfos[5].maxsolutions = _nj5;
01552 std::vector<int> vfree(0);
01553 solutions.AddSolution(vinfos,vfree);
01554 }
01555 }
01556 }
01557 
01558 }
01559 
01560 }
01561 
01562 } else
01563 {
01564 {
01565 IkReal j1array[1], cj1array[1], sj1array[1];
01566 bool j1valid[1]={false};
01567 _nj1 = 1;
01568 IkReal x407=((IkReal(0.707109999985348))*(sj4));
01569 IkReal x408=((r22)*(sj2));
01570 IkReal x409=((cj5)*(r20));
01571 IkReal x410=((r21)*(sj5));
01572 IkReal x411=((IkReal(0.707109999985348))*(cj4));
01573 IkReal x412=((cj2)*(r22));
01574 IkReal x413=((IkReal(0.707103562373095))*(sj4));
01575 IkReal x414=((IkReal(0.707103562373095))*(cj4));
01576 IkReal x415=((sj2)*(x414));
01577 IkReal x416=((cj2)*(x414));
01578 if( IKabs(((gconst61)*(((((x411)*(x412)))+(((IkReal(-1.00000000000000))*(cj2)*(x407)*(x409)))+(((sj2)*(x410)*(x413)))+(((sj2)*(x410)*(x411)))+(((x408)*(x414)))+(((x409)*(x416)))+(((cj2)*(x407)*(x410)))+(((IkReal(-1.00000000000000))*(x407)*(x408)))+(((x412)*(x413)))+(((IkReal(-1.00000000000000))*(x410)*(x416)))+(((IkReal(-1.00000000000000))*(sj2)*(x409)*(x413)))+(((IkReal(-1.00000000000000))*(sj2)*(x409)*(x411))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((x407)*(x412)))+(((IkReal(-1.00000000000000))*(x412)*(x414)))+(((IkReal(-1.00000000000000))*(cj2)*(x410)*(x413)))+(((IkReal(-1.00000000000000))*(cj2)*(x410)*(x411)))+(((IkReal(-1.00000000000000))*(sj2)*(x407)*(x409)))+(((x408)*(x411)))+(((x408)*(x413)))+(((x409)*(x415)))+(((cj2)*(x409)*(x411)))+(((cj2)*(x409)*(x413)))+(((IkReal(-1.00000000000000))*(x410)*(x415)))+(((sj2)*(x407)*(x410))))))) < IKFAST_ATAN2_MAGTHRESH )
01579     continue;
01580 j1array[0]=IKatan2(((gconst61)*(((((x411)*(x412)))+(((IkReal(-1.00000000000000))*(cj2)*(x407)*(x409)))+(((sj2)*(x410)*(x413)))+(((sj2)*(x410)*(x411)))+(((x408)*(x414)))+(((x409)*(x416)))+(((cj2)*(x407)*(x410)))+(((IkReal(-1.00000000000000))*(x407)*(x408)))+(((x412)*(x413)))+(((IkReal(-1.00000000000000))*(x410)*(x416)))+(((IkReal(-1.00000000000000))*(sj2)*(x409)*(x413)))+(((IkReal(-1.00000000000000))*(sj2)*(x409)*(x411)))))), ((gconst61)*(((((x407)*(x412)))+(((IkReal(-1.00000000000000))*(x412)*(x414)))+(((IkReal(-1.00000000000000))*(cj2)*(x410)*(x413)))+(((IkReal(-1.00000000000000))*(cj2)*(x410)*(x411)))+(((IkReal(-1.00000000000000))*(sj2)*(x407)*(x409)))+(((x408)*(x411)))+(((x408)*(x413)))+(((x409)*(x415)))+(((cj2)*(x409)*(x411)))+(((cj2)*(x409)*(x413)))+(((IkReal(-1.00000000000000))*(x410)*(x415)))+(((sj2)*(x407)*(x410)))))));
01581 sj1array[0]=IKsin(j1array[0]);
01582 cj1array[0]=IKcos(j1array[0]);
01583 if( j1array[0] > IKPI )
01584 {
01585     j1array[0]-=IK2PI;
01586 }
01587 else if( j1array[0] < -IKPI )
01588 {    j1array[0]+=IK2PI;
01589 }
01590 j1valid[0] = true;
01591 for(int ij1 = 0; ij1 < 1; ++ij1)
01592 {
01593 if( !j1valid[ij1] )
01594 {
01595     continue;
01596 }
01597 _ij1[0] = ij1; _ij1[1] = -1;
01598 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01599 {
01600 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01601 {
01602     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01603 }
01604 }
01605 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01606 {
01607 IkReal evalcond[4];
01608 IkReal x417=IKsin(j1);
01609 IkReal x418=IKcos(j1);
01610 IkReal x419=((IkReal(0.707109999985348))*(cj2));
01611 IkReal x420=((IkReal(1.00000000000000))*(sj4));
01612 IkReal x421=((cj5)*(r00));
01613 IkReal x422=((IkReal(0.707109999985348))*(sj2));
01614 IkReal x423=((cj5)*(r20));
01615 IkReal x424=((r12)*(sj0));
01616 IkReal x425=((r21)*(sj5));
01617 IkReal x426=((IkReal(1.00000000000000))*(cj4));
01618 IkReal x427=((IkReal(0.707103562373095))*(x418));
01619 IkReal x428=((r11)*(sj0)*(sj5));
01620 IkReal x429=((cj0)*(x426));
01621 IkReal x430=((IkReal(0.707103562373095))*(x417));
01622 IkReal x431=((cj0)*(r01)*(sj5));
01623 IkReal x432=((cj5)*(r10)*(sj0));
01624 IkReal x433=((sj2)*(x427));
01625 IkReal x434=((cj2)*(x430));
01626 IkReal x435=((x418)*(x419));
01627 IkReal x436=((x417)*(x422));
01628 IkReal x437=((cj2)*(x427));
01629 IkReal x438=((x417)*(x419));
01630 IkReal x439=((sj2)*(x430));
01631 IkReal x440=((x418)*(x422));
01632 IkReal x441=((x433)+(x434)+(x435));
01633 IkReal x442=((x438)+(x439)+(x440));
01634 evalcond[0]=((((IkReal(-1.00000000000000))*(x437)))+(((IkReal(-1.00000000000000))*(x420)*(x423)))+(((cj4)*(r22)))+(((sj4)*(x425)))+(x442));
01635 evalcond[1]=((((IkReal(-1.00000000000000))*(x436)))+(((r22)*(sj4)))+(((cj4)*(x423)))+(x441)+(((IkReal(-1.00000000000000))*(x425)*(x426))));
01636 evalcond[2]=((((sj4)*(x432)))+(((IkReal(-1.00000000000000))*(x436)))+(((IkReal(-1.00000000000000))*(x420)*(x428)))+(((IkReal(-1.00000000000000))*(x420)*(x431)))+(((IkReal(-1.00000000000000))*(r02)*(x429)))+(x441)+(((IkReal(-1.00000000000000))*(x424)*(x426)))+(((cj0)*(sj4)*(x421))));
01637 evalcond[3]=((((IkReal(-1.00000000000000))*(x442)))+(((IkReal(-1.00000000000000))*(x421)*(x429)))+(((IkReal(-1.00000000000000))*(x420)*(x424)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x420)))+(((cj4)*(x431)))+(((cj4)*(x428)))+(x437)+(((IkReal(-1.00000000000000))*(x426)*(x432))));
01638 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01639 {
01640 continue;
01641 }
01642 }
01643 
01644 {
01645 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01646 vinfos[0].jointtype = 1;
01647 vinfos[0].foffset = j0;
01648 vinfos[0].indices[0] = _ij0[0];
01649 vinfos[0].indices[1] = _ij0[1];
01650 vinfos[0].maxsolutions = _nj0;
01651 vinfos[1].jointtype = 1;
01652 vinfos[1].foffset = j1;
01653 vinfos[1].indices[0] = _ij1[0];
01654 vinfos[1].indices[1] = _ij1[1];
01655 vinfos[1].maxsolutions = _nj1;
01656 vinfos[2].jointtype = 1;
01657 vinfos[2].foffset = j2;
01658 vinfos[2].indices[0] = _ij2[0];
01659 vinfos[2].indices[1] = _ij2[1];
01660 vinfos[2].maxsolutions = _nj2;
01661 vinfos[3].jointtype = 1;
01662 vinfos[3].foffset = j3;
01663 vinfos[3].indices[0] = _ij3[0];
01664 vinfos[3].indices[1] = _ij3[1];
01665 vinfos[3].maxsolutions = _nj3;
01666 vinfos[4].jointtype = 1;
01667 vinfos[4].foffset = j4;
01668 vinfos[4].indices[0] = _ij4[0];
01669 vinfos[4].indices[1] = _ij4[1];
01670 vinfos[4].maxsolutions = _nj4;
01671 vinfos[5].jointtype = 1;
01672 vinfos[5].foffset = j5;
01673 vinfos[5].indices[0] = _ij5[0];
01674 vinfos[5].indices[1] = _ij5[1];
01675 vinfos[5].maxsolutions = _nj5;
01676 std::vector<int> vfree(0);
01677 solutions.AddSolution(vinfos,vfree);
01678 }
01679 }
01680 }
01681 
01682 }
01683 
01684 }
01685 }
01686 }
01687 
01688 }
01689 
01690 }
01691 }
01692 }
01693 
01694 } else
01695 {
01696 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959))));
01697 evalcond[1]=((((npx)*(sj5)))+(((cj5)*(npy))));
01698 evalcond[2]=((((cj5)*(r21)))+(((r20)*(sj5))));
01699 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  )
01700 {
01701 {
01702 IkReal j2array[1], cj2array[1], sj2array[1];
01703 bool j2valid[1]={false};
01704 _nj2 = 1;
01705 IkReal x443=((IkReal(2.34381456633434))*(cj4));
01706 IkReal x444=((npy)*(sj5));
01707 IkReal x445=((IkReal(2.94476514910275))*(cj4));
01708 IkReal x446=((IkReal(2.34381456633434))*(sj4));
01709 IkReal x447=((cj5)*(npx));
01710 IkReal x448=((IkReal(2.94476514910275))*(sj4));
01711 if( IKabs(((IkReal(0.516358403118598))+(((x446)*(x447)))+(((IkReal(-1.00000000000000))*(x444)*(x446)))+(((IkReal(-1.00000000000000))*(x444)*(x445)))+(((IkReal(-1.00000000000000))*(npz)*(x443)))+(((npz)*(x448)))+(((x445)*(x447))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.830081885873801))+(((npz)*(x446)))+(((npz)*(x445)))+(((IkReal(-1.00000000000000))*(x443)*(x444)))+(((x444)*(x448)))+(((IkReal(-1.00000000000000))*(x447)*(x448)))+(((x443)*(x447))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.516358403118598))+(((x446)*(x447)))+(((IkReal(-1.00000000000000))*(x444)*(x446)))+(((IkReal(-1.00000000000000))*(x444)*(x445)))+(((IkReal(-1.00000000000000))*(npz)*(x443)))+(((npz)*(x448)))+(((x445)*(x447)))))+IKsqr(((IkReal(-0.830081885873801))+(((npz)*(x446)))+(((npz)*(x445)))+(((IkReal(-1.00000000000000))*(x443)*(x444)))+(((x444)*(x448)))+(((IkReal(-1.00000000000000))*(x447)*(x448)))+(((x443)*(x447)))))-1) <= IKFAST_SINCOS_THRESH )
01712     continue;
01713 j2array[0]=IKatan2(((IkReal(0.516358403118598))+(((x446)*(x447)))+(((IkReal(-1.00000000000000))*(x444)*(x446)))+(((IkReal(-1.00000000000000))*(x444)*(x445)))+(((IkReal(-1.00000000000000))*(npz)*(x443)))+(((npz)*(x448)))+(((x445)*(x447)))), ((IkReal(-0.830081885873801))+(((npz)*(x446)))+(((npz)*(x445)))+(((IkReal(-1.00000000000000))*(x443)*(x444)))+(((x444)*(x448)))+(((IkReal(-1.00000000000000))*(x447)*(x448)))+(((x443)*(x447)))));
01714 sj2array[0]=IKsin(j2array[0]);
01715 cj2array[0]=IKcos(j2array[0]);
01716 if( j2array[0] > IKPI )
01717 {
01718     j2array[0]-=IK2PI;
01719 }
01720 else if( j2array[0] < -IKPI )
01721 {    j2array[0]+=IK2PI;
01722 }
01723 j2valid[0] = true;
01724 for(int ij2 = 0; ij2 < 1; ++ij2)
01725 {
01726 if( !j2valid[ij2] )
01727 {
01728     continue;
01729 }
01730 _ij2[0] = ij2; _ij2[1] = -1;
01731 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01732 {
01733 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01734 {
01735     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01736 }
01737 }
01738 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01739 {
01740 IkReal evalcond[2];
01741 IkReal x449=IKcos(j2);
01742 IkReal x450=IKsin(j2);
01743 IkReal x451=((npy)*(sj5));
01744 IkReal x452=((cj5)*(npx));
01745 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(x449)))+(((sj4)*(x451)))+(((IkReal(0.165463933124939))*(x450)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x452))));
01746 evalcond[1]=((IkReal(-0.0300035672348961))+(((IkReal(-0.207888640466058))*(x450)))+(((cj4)*(x452)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(x451)))+(((IkReal(-0.165463933124939))*(x449))));
01747 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
01748 {
01749 continue;
01750 }
01751 }
01752 
01753 {
01754 IkReal dummyeval[1];
01755 IkReal gconst65;
01756 IkReal x453=(cj5)*(cj5);
01757 IkReal x454=(sj5)*(sj5);
01758 IkReal x455=((IkReal(1.00000000000000))*(x454));
01759 IkReal x456=((IkReal(2.00000000000000))*(cj5)*(sj5));
01760 IkReal x457=((IkReal(1.00000000000000))*(x453));
01761 gconst65=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x456)))+(((IkReal(-1.00000000000000))*(x457)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x456)))+(((IkReal(-1.00000000000000))*(x455)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x455)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x457)*((r01)*(r01))))));
01762 IkReal x458=(cj5)*(cj5);
01763 IkReal x459=(sj5)*(sj5);
01764 IkReal x460=((IkReal(1.00000000000000))*(x459));
01765 IkReal x461=((IkReal(2.00000000000000))*(cj5)*(sj5));
01766 IkReal x462=((IkReal(1.00000000000000))*(x458));
01767 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(r11)*(x461)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x461)))+(((IkReal(-1.00000000000000))*(x460)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x460)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x462)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x462)*((r11)*(r11)))));
01768 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01769 {
01770 {
01771 IkReal dummyeval[1];
01772 IkReal gconst66;
01773 IkReal x463=(sj5)*(sj5);
01774 IkReal x464=(cj5)*(cj5);
01775 IkReal x465=((cj4)*(cj5));
01776 IkReal x466=((IkReal(1.00000000000000))*(r12));
01777 IkReal x467=((cj4)*(sj5));
01778 IkReal x468=((r01)*(r10));
01779 IkReal x469=((sj4)*(x464));
01780 IkReal x470=((IkReal(1.00000000000000))*(r00)*(r11));
01781 IkReal x471=((sj4)*(x463));
01782 gconst66=IKsign(((((x468)*(x469)))+(((IkReal(-1.00000000000000))*(r00)*(x466)*(x467)))+(((IkReal(-1.00000000000000))*(x469)*(x470)))+(((r02)*(r11)*(x465)))+(((r02)*(r10)*(x467)))+(((IkReal(-1.00000000000000))*(r01)*(x465)*(x466)))+(((IkReal(-1.00000000000000))*(x470)*(x471)))+(((x468)*(x471)))));
01783 IkReal x472=(sj5)*(sj5);
01784 IkReal x473=(cj5)*(cj5);
01785 IkReal x474=((cj4)*(cj5));
01786 IkReal x475=((IkReal(1.00000000000000))*(r12));
01787 IkReal x476=((cj4)*(sj5));
01788 IkReal x477=((r01)*(r10));
01789 IkReal x478=((sj4)*(x473));
01790 IkReal x479=((IkReal(1.00000000000000))*(r00)*(r11));
01791 IkReal x480=((sj4)*(x472));
01792 dummyeval[0]=((((IkReal(-1.00000000000000))*(x478)*(x479)))+(((r02)*(r10)*(x476)))+(((r02)*(r11)*(x474)))+(((IkReal(-1.00000000000000))*(x479)*(x480)))+(((x477)*(x478)))+(((IkReal(-1.00000000000000))*(r01)*(x474)*(x475)))+(((IkReal(-1.00000000000000))*(r00)*(x475)*(x476)))+(((x477)*(x480))));
01793 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01794 {
01795 {
01796 IkReal dummyeval[1];
01797 IkReal gconst67;
01798 gconst67=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
01799 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
01800 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01801 {
01802 continue;
01803 
01804 } else
01805 {
01806 {
01807 IkReal j1array[1], cj1array[1], sj1array[1];
01808 bool j1valid[1]={false};
01809 _nj1 = 1;
01810 IkReal x481=((IkReal(0.707109999985348))*(sj4));
01811 IkReal x482=((r22)*(sj2));
01812 IkReal x483=((cj5)*(r20));
01813 IkReal x484=((r21)*(sj5));
01814 IkReal x485=((IkReal(0.707109999985348))*(cj4));
01815 IkReal x486=((IkReal(0.707103562373095))*(sj4));
01816 IkReal x487=((cj2)*(r22));
01817 IkReal x488=((IkReal(0.707103562373095))*(cj4));
01818 IkReal x489=((sj2)*(x488));
01819 IkReal x490=((cj2)*(x488));
01820 if( IKabs(((gconst67)*(((((cj2)*(x481)*(x483)))+(((IkReal(-1.00000000000000))*(sj2)*(x484)*(x486)))+(((x483)*(x490)))+(((IkReal(-1.00000000000000))*(cj2)*(x481)*(x484)))+(((IkReal(-1.00000000000000))*(x481)*(x482)))+(((sj2)*(x483)*(x486)))+(((x486)*(x487)))+(((IkReal(-1.00000000000000))*(sj2)*(x483)*(x485)))+(((IkReal(-1.00000000000000))*(x484)*(x490)))+(((IkReal(-1.00000000000000))*(x482)*(x488)))+(((sj2)*(x484)*(x485)))+(((IkReal(-1.00000000000000))*(x485)*(x487))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(x484)*(x489)))+(((IkReal(-1.00000000000000))*(cj2)*(x483)*(x486)))+(((cj2)*(x484)*(x486)))+(((IkReal(-1.00000000000000))*(sj2)*(x481)*(x484)))+(((x483)*(x489)))+(((x481)*(x487)))+(((sj2)*(x481)*(x483)))+(((x482)*(x486)))+(((IkReal(-1.00000000000000))*(x482)*(x485)))+(((IkReal(-1.00000000000000))*(cj2)*(x484)*(x485)))+(((x487)*(x488)))+(((cj2)*(x483)*(x485))))))) < IKFAST_ATAN2_MAGTHRESH )
01821     continue;
01822 j1array[0]=IKatan2(((gconst67)*(((((cj2)*(x481)*(x483)))+(((IkReal(-1.00000000000000))*(sj2)*(x484)*(x486)))+(((x483)*(x490)))+(((IkReal(-1.00000000000000))*(cj2)*(x481)*(x484)))+(((IkReal(-1.00000000000000))*(x481)*(x482)))+(((sj2)*(x483)*(x486)))+(((x486)*(x487)))+(((IkReal(-1.00000000000000))*(sj2)*(x483)*(x485)))+(((IkReal(-1.00000000000000))*(x484)*(x490)))+(((IkReal(-1.00000000000000))*(x482)*(x488)))+(((sj2)*(x484)*(x485)))+(((IkReal(-1.00000000000000))*(x485)*(x487)))))), ((gconst67)*(((((IkReal(-1.00000000000000))*(x484)*(x489)))+(((IkReal(-1.00000000000000))*(cj2)*(x483)*(x486)))+(((cj2)*(x484)*(x486)))+(((IkReal(-1.00000000000000))*(sj2)*(x481)*(x484)))+(((x483)*(x489)))+(((x481)*(x487)))+(((sj2)*(x481)*(x483)))+(((x482)*(x486)))+(((IkReal(-1.00000000000000))*(x482)*(x485)))+(((IkReal(-1.00000000000000))*(cj2)*(x484)*(x485)))+(((x487)*(x488)))+(((cj2)*(x483)*(x485)))))));
01823 sj1array[0]=IKsin(j1array[0]);
01824 cj1array[0]=IKcos(j1array[0]);
01825 if( j1array[0] > IKPI )
01826 {
01827     j1array[0]-=IK2PI;
01828 }
01829 else if( j1array[0] < -IKPI )
01830 {    j1array[0]+=IK2PI;
01831 }
01832 j1valid[0] = true;
01833 for(int ij1 = 0; ij1 < 1; ++ij1)
01834 {
01835 if( !j1valid[ij1] )
01836 {
01837     continue;
01838 }
01839 _ij1[0] = ij1; _ij1[1] = -1;
01840 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01841 {
01842 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01843 {
01844     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01845 }
01846 }
01847 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01848 {
01849 IkReal evalcond[2];
01850 IkReal x491=IKsin(j1);
01851 IkReal x492=IKcos(j1);
01852 IkReal x493=((cj5)*(r20));
01853 IkReal x494=((r21)*(sj5));
01854 IkReal x495=((IkReal(0.707103562373095))*(x491));
01855 IkReal x496=((IkReal(0.707109999985348))*(x491));
01856 IkReal x497=((IkReal(0.707103562373095))*(x492));
01857 IkReal x498=((IkReal(0.707109999985348))*(x492));
01858 evalcond[0]=((((sj4)*(x494)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(cj2)*(x497)))+(((IkReal(-1.00000000000000))*(sj4)*(x493)))+(((sj2)*(x498)))+(((sj2)*(x495)))+(((cj2)*(x496))));
01859 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(x494)))+(((IkReal(-1.00000000000000))*(sj2)*(x497)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj2)*(x495)))+(((IkReal(-1.00000000000000))*(cj2)*(x498)))+(((cj4)*(x493)))+(((sj2)*(x496))));
01860 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
01861 {
01862 continue;
01863 }
01864 }
01865 
01866 {
01867 IkReal dummyeval[1];
01868 IkReal gconst68;
01869 IkReal x499=(cj5)*(cj5);
01870 IkReal x500=(sj5)*(sj5);
01871 IkReal x501=((IkReal(1.00000000000000))*(x500));
01872 IkReal x502=((IkReal(2.00000000000000))*(cj5)*(sj5));
01873 IkReal x503=((IkReal(1.00000000000000))*(x499));
01874 gconst68=IKsign(((((IkReal(-1.00000000000000))*(r00)*(r01)*(x502)))+(((IkReal(-1.00000000000000))*(x503)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x501)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x503)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x502)))+(((IkReal(-1.00000000000000))*(x501)*((r00)*(r00))))));
01875 IkReal x504=(cj5)*(cj5);
01876 IkReal x505=(sj5)*(sj5);
01877 IkReal x506=((IkReal(1.00000000000000))*(x505));
01878 IkReal x507=((IkReal(2.00000000000000))*(cj5)*(sj5));
01879 IkReal x508=((IkReal(1.00000000000000))*(x504));
01880 dummyeval[0]=((((IkReal(-1.00000000000000))*(x508)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x508)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x507)))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x507)))+(((IkReal(-1.00000000000000))*(x506)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x506)*((r00)*(r00)))));
01881 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01882 {
01883 {
01884 IkReal dummyeval[1];
01885 IkReal gconst69;
01886 IkReal x509=(sj5)*(sj5);
01887 IkReal x510=(cj5)*(cj5);
01888 IkReal x511=((cj4)*(cj5));
01889 IkReal x512=((IkReal(1.00000000000000))*(r12));
01890 IkReal x513=((cj4)*(sj5));
01891 IkReal x514=((r01)*(r10));
01892 IkReal x515=((sj4)*(x510));
01893 IkReal x516=((IkReal(1.00000000000000))*(r00)*(r11));
01894 IkReal x517=((sj4)*(x509));
01895 gconst69=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x511)*(x512)))+(((r02)*(r11)*(x511)))+(((x514)*(x515)))+(((x514)*(x517)))+(((IkReal(-1.00000000000000))*(x516)*(x517)))+(((IkReal(-1.00000000000000))*(r00)*(x512)*(x513)))+(((IkReal(-1.00000000000000))*(x515)*(x516)))+(((r02)*(r10)*(x513)))));
01896 IkReal x518=(sj5)*(sj5);
01897 IkReal x519=(cj5)*(cj5);
01898 IkReal x520=((cj4)*(cj5));
01899 IkReal x521=((IkReal(1.00000000000000))*(r12));
01900 IkReal x522=((cj4)*(sj5));
01901 IkReal x523=((r01)*(r10));
01902 IkReal x524=((sj4)*(x519));
01903 IkReal x525=((IkReal(1.00000000000000))*(r00)*(r11));
01904 IkReal x526=((sj4)*(x518));
01905 dummyeval[0]=((((r02)*(r10)*(x522)))+(((IkReal(-1.00000000000000))*(x524)*(x525)))+(((IkReal(-1.00000000000000))*(r01)*(x520)*(x521)))+(((IkReal(-1.00000000000000))*(x525)*(x526)))+(((IkReal(-1.00000000000000))*(r00)*(x521)*(x522)))+(((x523)*(x524)))+(((x523)*(x526)))+(((r02)*(r11)*(x520))));
01906 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01907 {
01908 continue;
01909 
01910 } else
01911 {
01912 {
01913 IkReal j0array[1], cj0array[1], sj0array[1];
01914 bool j0valid[1]={false};
01915 _nj0 = 1;
01916 IkReal x527=((cj5)*(sj4));
01917 IkReal x528=((IkReal(1.00000000000000))*(cj4));
01918 IkReal x529=((IkReal(1.00000000000000))*(sj4)*(sj5));
01919 if( IKabs(((gconst69)*(((((r10)*(x527)))+(((IkReal(-1.00000000000000))*(r11)*(x529)))+(((IkReal(-1.00000000000000))*(r12)*(x528))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst69)*(((((IkReal(-1.00000000000000))*(r01)*(x529)))+(((IkReal(-1.00000000000000))*(r02)*(x528)))+(((r00)*(x527))))))) < IKFAST_ATAN2_MAGTHRESH )
01920     continue;
01921 j0array[0]=IKatan2(((gconst69)*(((((r10)*(x527)))+(((IkReal(-1.00000000000000))*(r11)*(x529)))+(((IkReal(-1.00000000000000))*(r12)*(x528)))))), ((gconst69)*(((((IkReal(-1.00000000000000))*(r01)*(x529)))+(((IkReal(-1.00000000000000))*(r02)*(x528)))+(((r00)*(x527)))))));
01922 sj0array[0]=IKsin(j0array[0]);
01923 cj0array[0]=IKcos(j0array[0]);
01924 if( j0array[0] > IKPI )
01925 {
01926     j0array[0]-=IK2PI;
01927 }
01928 else if( j0array[0] < -IKPI )
01929 {    j0array[0]+=IK2PI;
01930 }
01931 j0valid[0] = true;
01932 for(int ij0 = 0; ij0 < 1; ++ij0)
01933 {
01934 if( !j0valid[ij0] )
01935 {
01936     continue;
01937 }
01938 _ij0[0] = ij0; _ij0[1] = -1;
01939 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
01940 {
01941 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
01942 {
01943     j0valid[iij0]=false; _ij0[1] = iij0; break; 
01944 }
01945 }
01946 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
01947 {
01948 IkReal evalcond[6];
01949 IkReal x530=IKsin(j0);
01950 IkReal x531=IKcos(j0);
01951 IkReal x532=((IkReal(0.707103562373095))*(cj2));
01952 IkReal x533=((cj5)*(sj4));
01953 IkReal x534=((IkReal(1.00000000000000))*(sj4));
01954 IkReal x535=((IkReal(1.00000000000000))*(r10));
01955 IkReal x536=((IkReal(1.00000000000000))*(cj5));
01956 IkReal x537=((IkReal(1.00000000000000))*(cj4));
01957 IkReal x538=((sj1)*(sj2));
01958 IkReal x539=((IkReal(0.707109999985348))*(cj1));
01959 IkReal x540=((cj4)*(r11));
01960 IkReal x541=((sj5)*(x530));
01961 IkReal x542=((r10)*(x530));
01962 IkReal x543=((r01)*(x531));
01963 IkReal x544=((r00)*(x531));
01964 IkReal x545=((r02)*(x531));
01965 IkReal x546=((r12)*(x531));
01966 IkReal x547=((cj5)*(x530));
01967 IkReal x548=((r12)*(x530));
01968 IkReal x549=((sj5)*(x531));
01969 IkReal x550=((r02)*(x530));
01970 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x531)*(x536)))+(((IkReal(-1.00000000000000))*(x535)*(x549)))+(((r00)*(x541)))+(((r01)*(x547))));
01971 evalcond[1]=((((IkReal(-1.00000000000000))*(x537)*(x546)))+(((cj4)*(x550)))+(((r10)*(x531)*(x533)))+(((IkReal(-1.00000000000000))*(r11)*(x534)*(x549)))+(((IkReal(-1.00000000000000))*(r00)*(x530)*(x533)))+(((r01)*(sj4)*(x541))));
01972 evalcond[2]=((((sj4)*(x550)))+(((IkReal(-1.00000000000000))*(x534)*(x546)))+(((x540)*(x549)))+(((cj4)*(r00)*(x547)))+(((IkReal(-1.00000000000000))*(r01)*(x537)*(x541)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x531)*(x535))));
01973 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x544)))+(((IkReal(-1.00000000000000))*(x535)*(x541)))+(((IkReal(-1.00000000000000))*(r11)*(x530)*(x536)))+(((IkReal(-1.00000000000000))*(x536)*(x543))));
01974 evalcond[4]=((((IkReal(-1.00000000000000))*(x537)*(x545)))+(((IkReal(-1.00000000000000))*(x537)*(x548)))+(((sj1)*(x532)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(sj5)*(x534)*(x543)))+(((IkReal(-0.707109999985348))*(x538)))+(((cj2)*(x539)))+(((x533)*(x544)))+(((x533)*(x542)))+(((IkReal(-1.00000000000000))*(r11)*(x534)*(x541))));
01975 evalcond[5]=((((IkReal(-1.00000000000000))*(x534)*(x545)))+(((IkReal(-1.00000000000000))*(x534)*(x548)))+(((sj2)*(x539)))+(((IkReal(-1.00000000000000))*(cj1)*(x532)))+(((x540)*(x541)))+(((IkReal(-1.00000000000000))*(cj4)*(x535)*(x547)))+(((IkReal(0.707103562373095))*(x538)))+(((IkReal(-1.00000000000000))*(cj4)*(x536)*(x544)))+(((IkReal(0.707109999985348))*(cj2)*(sj1)))+(((cj4)*(sj5)*(x543))));
01976 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  )
01977 {
01978 continue;
01979 }
01980 }
01981 
01982 {
01983 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01984 vinfos[0].jointtype = 1;
01985 vinfos[0].foffset = j0;
01986 vinfos[0].indices[0] = _ij0[0];
01987 vinfos[0].indices[1] = _ij0[1];
01988 vinfos[0].maxsolutions = _nj0;
01989 vinfos[1].jointtype = 1;
01990 vinfos[1].foffset = j1;
01991 vinfos[1].indices[0] = _ij1[0];
01992 vinfos[1].indices[1] = _ij1[1];
01993 vinfos[1].maxsolutions = _nj1;
01994 vinfos[2].jointtype = 1;
01995 vinfos[2].foffset = j2;
01996 vinfos[2].indices[0] = _ij2[0];
01997 vinfos[2].indices[1] = _ij2[1];
01998 vinfos[2].maxsolutions = _nj2;
01999 vinfos[3].jointtype = 1;
02000 vinfos[3].foffset = j3;
02001 vinfos[3].indices[0] = _ij3[0];
02002 vinfos[3].indices[1] = _ij3[1];
02003 vinfos[3].maxsolutions = _nj3;
02004 vinfos[4].jointtype = 1;
02005 vinfos[4].foffset = j4;
02006 vinfos[4].indices[0] = _ij4[0];
02007 vinfos[4].indices[1] = _ij4[1];
02008 vinfos[4].maxsolutions = _nj4;
02009 vinfos[5].jointtype = 1;
02010 vinfos[5].foffset = j5;
02011 vinfos[5].indices[0] = _ij5[0];
02012 vinfos[5].indices[1] = _ij5[1];
02013 vinfos[5].maxsolutions = _nj5;
02014 std::vector<int> vfree(0);
02015 solutions.AddSolution(vinfos,vfree);
02016 }
02017 }
02018 }
02019 
02020 }
02021 
02022 }
02023 
02024 } else
02025 {
02026 {
02027 IkReal j0array[1], cj0array[1], sj0array[1];
02028 bool j0valid[1]={false};
02029 _nj0 = 1;
02030 if( IKabs(((gconst68)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst68)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
02031     continue;
02032 j0array[0]=IKatan2(((gconst68)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst68)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
02033 sj0array[0]=IKsin(j0array[0]);
02034 cj0array[0]=IKcos(j0array[0]);
02035 if( j0array[0] > IKPI )
02036 {
02037     j0array[0]-=IK2PI;
02038 }
02039 else if( j0array[0] < -IKPI )
02040 {    j0array[0]+=IK2PI;
02041 }
02042 j0valid[0] = true;
02043 for(int ij0 = 0; ij0 < 1; ++ij0)
02044 {
02045 if( !j0valid[ij0] )
02046 {
02047     continue;
02048 }
02049 _ij0[0] = ij0; _ij0[1] = -1;
02050 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02051 {
02052 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02053 {
02054     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02055 }
02056 }
02057 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02058 {
02059 IkReal evalcond[6];
02060 IkReal x551=IKsin(j0);
02061 IkReal x552=IKcos(j0);
02062 IkReal x553=((IkReal(0.707103562373095))*(cj2));
02063 IkReal x554=((cj5)*(sj4));
02064 IkReal x555=((IkReal(1.00000000000000))*(sj4));
02065 IkReal x556=((IkReal(1.00000000000000))*(r10));
02066 IkReal x557=((IkReal(1.00000000000000))*(cj5));
02067 IkReal x558=((IkReal(1.00000000000000))*(cj4));
02068 IkReal x559=((sj1)*(sj2));
02069 IkReal x560=((IkReal(0.707109999985348))*(cj1));
02070 IkReal x561=((cj4)*(r11));
02071 IkReal x562=((sj5)*(x551));
02072 IkReal x563=((r10)*(x551));
02073 IkReal x564=((r01)*(x552));
02074 IkReal x565=((r00)*(x552));
02075 IkReal x566=((r02)*(x552));
02076 IkReal x567=((r12)*(x552));
02077 IkReal x568=((cj5)*(x551));
02078 IkReal x569=((r12)*(x551));
02079 IkReal x570=((sj5)*(x552));
02080 IkReal x571=((r02)*(x551));
02081 evalcond[0]=((IkReal(-1.00000000000000))+(((r01)*(x568)))+(((r00)*(x562)))+(((IkReal(-1.00000000000000))*(r11)*(x552)*(x557)))+(((IkReal(-1.00000000000000))*(x556)*(x570))));
02082 evalcond[1]=((((r01)*(sj4)*(x562)))+(((IkReal(-1.00000000000000))*(x558)*(x567)))+(((IkReal(-1.00000000000000))*(r11)*(x555)*(x570)))+(((IkReal(-1.00000000000000))*(r00)*(x551)*(x554)))+(((r10)*(x552)*(x554)))+(((cj4)*(x571))));
02083 evalcond[2]=((((x561)*(x570)))+(((sj4)*(x571)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x552)*(x556)))+(((IkReal(-1.00000000000000))*(x555)*(x567)))+(((IkReal(-1.00000000000000))*(r01)*(x558)*(x562)))+(((cj4)*(r00)*(x568))));
02084 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x565)))+(((IkReal(-1.00000000000000))*(x556)*(x562)))+(((IkReal(-1.00000000000000))*(x557)*(x564)))+(((IkReal(-1.00000000000000))*(r11)*(x551)*(x557))));
02085 evalcond[4]=((((sj1)*(x553)))+(((IkReal(-1.00000000000000))*(r11)*(x555)*(x562)))+(((IkReal(-1.00000000000000))*(x558)*(x569)))+(((IkReal(-1.00000000000000))*(x558)*(x566)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((cj2)*(x560)))+(((IkReal(-0.707109999985348))*(x559)))+(((IkReal(-1.00000000000000))*(sj5)*(x555)*(x564)))+(((x554)*(x563)))+(((x554)*(x565))));
02086 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(x557)*(x565)))+(((IkReal(-1.00000000000000))*(cj1)*(x553)))+(((IkReal(0.707103562373095))*(x559)))+(((IkReal(-1.00000000000000))*(x555)*(x566)))+(((IkReal(-1.00000000000000))*(x555)*(x569)))+(((x561)*(x562)))+(((cj4)*(sj5)*(x564)))+(((IkReal(0.707109999985348))*(cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(cj4)*(x556)*(x568)))+(((sj2)*(x560))));
02087 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  )
02088 {
02089 continue;
02090 }
02091 }
02092 
02093 {
02094 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02095 vinfos[0].jointtype = 1;
02096 vinfos[0].foffset = j0;
02097 vinfos[0].indices[0] = _ij0[0];
02098 vinfos[0].indices[1] = _ij0[1];
02099 vinfos[0].maxsolutions = _nj0;
02100 vinfos[1].jointtype = 1;
02101 vinfos[1].foffset = j1;
02102 vinfos[1].indices[0] = _ij1[0];
02103 vinfos[1].indices[1] = _ij1[1];
02104 vinfos[1].maxsolutions = _nj1;
02105 vinfos[2].jointtype = 1;
02106 vinfos[2].foffset = j2;
02107 vinfos[2].indices[0] = _ij2[0];
02108 vinfos[2].indices[1] = _ij2[1];
02109 vinfos[2].maxsolutions = _nj2;
02110 vinfos[3].jointtype = 1;
02111 vinfos[3].foffset = j3;
02112 vinfos[3].indices[0] = _ij3[0];
02113 vinfos[3].indices[1] = _ij3[1];
02114 vinfos[3].maxsolutions = _nj3;
02115 vinfos[4].jointtype = 1;
02116 vinfos[4].foffset = j4;
02117 vinfos[4].indices[0] = _ij4[0];
02118 vinfos[4].indices[1] = _ij4[1];
02119 vinfos[4].maxsolutions = _nj4;
02120 vinfos[5].jointtype = 1;
02121 vinfos[5].foffset = j5;
02122 vinfos[5].indices[0] = _ij5[0];
02123 vinfos[5].indices[1] = _ij5[1];
02124 vinfos[5].maxsolutions = _nj5;
02125 std::vector<int> vfree(0);
02126 solutions.AddSolution(vinfos,vfree);
02127 }
02128 }
02129 }
02130 
02131 }
02132 
02133 }
02134 }
02135 }
02136 
02137 }
02138 
02139 }
02140 
02141 } else
02142 {
02143 {
02144 IkReal j0array[1], cj0array[1], sj0array[1];
02145 bool j0valid[1]={false};
02146 _nj0 = 1;
02147 IkReal x572=((cj5)*(sj4));
02148 IkReal x573=((IkReal(1.00000000000000))*(cj4));
02149 IkReal x574=((IkReal(1.00000000000000))*(sj4)*(sj5));
02150 if( IKabs(((gconst66)*(((((IkReal(-1.00000000000000))*(r11)*(x574)))+(((IkReal(-1.00000000000000))*(r12)*(x573)))+(((r10)*(x572))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst66)*(((((r00)*(x572)))+(((IkReal(-1.00000000000000))*(r01)*(x574)))+(((IkReal(-1.00000000000000))*(r02)*(x573))))))) < IKFAST_ATAN2_MAGTHRESH )
02151     continue;
02152 j0array[0]=IKatan2(((gconst66)*(((((IkReal(-1.00000000000000))*(r11)*(x574)))+(((IkReal(-1.00000000000000))*(r12)*(x573)))+(((r10)*(x572)))))), ((gconst66)*(((((r00)*(x572)))+(((IkReal(-1.00000000000000))*(r01)*(x574)))+(((IkReal(-1.00000000000000))*(r02)*(x573)))))));
02153 sj0array[0]=IKsin(j0array[0]);
02154 cj0array[0]=IKcos(j0array[0]);
02155 if( j0array[0] > IKPI )
02156 {
02157     j0array[0]-=IK2PI;
02158 }
02159 else if( j0array[0] < -IKPI )
02160 {    j0array[0]+=IK2PI;
02161 }
02162 j0valid[0] = true;
02163 for(int ij0 = 0; ij0 < 1; ++ij0)
02164 {
02165 if( !j0valid[ij0] )
02166 {
02167     continue;
02168 }
02169 _ij0[0] = ij0; _ij0[1] = -1;
02170 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02171 {
02172 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02173 {
02174     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02175 }
02176 }
02177 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02178 {
02179 IkReal evalcond[4];
02180 IkReal x575=IKsin(j0);
02181 IkReal x576=IKcos(j0);
02182 IkReal x577=((IkReal(1.00000000000000))*(cj5));
02183 IkReal x578=((r01)*(sj5));
02184 IkReal x579=((IkReal(1.00000000000000))*(r12));
02185 IkReal x580=((r11)*(sj5));
02186 IkReal x581=((IkReal(1.00000000000000))*(r10));
02187 IkReal x582=((cj4)*(x575));
02188 IkReal x583=((sj4)*(x575));
02189 IkReal x584=((sj4)*(x576));
02190 IkReal x585=((sj5)*(x575));
02191 IkReal x586=((cj4)*(x576));
02192 IkReal x587=((sj5)*(x576));
02193 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x576)*(x577)))+(((r00)*(x585)))+(((cj5)*(r01)*(x575)))+(((IkReal(-1.00000000000000))*(x581)*(x587))));
02194 evalcond[1]=((((x578)*(x583)))+(((IkReal(-1.00000000000000))*(x580)*(x584)))+(((IkReal(-1.00000000000000))*(r00)*(x577)*(x583)))+(((r02)*(x582)))+(((IkReal(-1.00000000000000))*(x579)*(x586)))+(((cj5)*(r10)*(x584))));
02195 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x577)*(x586)))+(((x580)*(x586)))+(((r02)*(x583)))+(((IkReal(-1.00000000000000))*(x579)*(x584)))+(((IkReal(-1.00000000000000))*(x578)*(x582)))+(((cj5)*(r00)*(x582))));
02196 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x576)*(x577)))+(((IkReal(-1.00000000000000))*(r11)*(x575)*(x577)))+(((IkReal(-1.00000000000000))*(r00)*(x587)))+(((IkReal(-1.00000000000000))*(x581)*(x585))));
02197 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02198 {
02199 continue;
02200 }
02201 }
02202 
02203 {
02204 IkReal dummyeval[1];
02205 IkReal gconst70;
02206 gconst70=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
02207 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
02208 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02209 {
02210 {
02211 IkReal dummyeval[1];
02212 IkReal gconst71;
02213 gconst71=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
02214 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
02215 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02216 {
02217 continue;
02218 
02219 } else
02220 {
02221 {
02222 IkReal j1array[1], cj1array[1], sj1array[1];
02223 bool j1valid[1]={false};
02224 _nj1 = 1;
02225 IkReal x588=((sj4)*(sj5));
02226 IkReal x589=((IkReal(0.707103562373095))*(sj0));
02227 IkReal x590=((r11)*(sj2));
02228 IkReal x591=((cj2)*(cj4));
02229 IkReal x592=((IkReal(0.707103562373095))*(r22));
02230 IkReal x593=((IkReal(0.707109999985348))*(cj0));
02231 IkReal x594=((cj2)*(r01));
02232 IkReal x595=((IkReal(0.707109999985348))*(cj2));
02233 IkReal x596=((IkReal(0.707109999985348))*(sj0));
02234 IkReal x597=((r21)*(sj2));
02235 IkReal x598=((IkReal(0.707103562373095))*(cj2));
02236 IkReal x599=((IkReal(0.707103562373095))*(sj2));
02237 IkReal x600=((cj5)*(sj4));
02238 IkReal x601=((r10)*(sj2));
02239 IkReal x602=((cj0)*(r00));
02240 IkReal x603=((IkReal(0.707103562373095))*(cj0));
02241 IkReal x604=((cj4)*(sj2));
02242 IkReal x605=((IkReal(0.707109999985348))*(r22));
02243 IkReal x606=((r02)*(x604));
02244 IkReal x607=((r20)*(x600));
02245 if( IKabs(((gconst71)*(((((IkReal(0.707103562373095))*(x588)*(x597)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x588)*(x589)))+(((IkReal(-1.00000000000000))*(r02)*(x591)*(x603)))+(((r12)*(x596)*(x604)))+(((r21)*(x588)*(x595)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x593)*(x600)))+(((x593)*(x606)))+(((x592)*(x604)))+(((x591)*(x605)))+(((IkReal(-1.00000000000000))*(x599)*(x607)))+(((IkReal(-1.00000000000000))*(x588)*(x594)*(x603)))+(((x598)*(x600)*(x602)))+(((r01)*(sj2)*(x588)*(x593)))+(((x588)*(x590)*(x596)))+(((IkReal(-1.00000000000000))*(x596)*(x600)*(x601)))+(((cj2)*(r10)*(x589)*(x600)))+(((IkReal(-1.00000000000000))*(r12)*(x589)*(x591)))+(((IkReal(-1.00000000000000))*(x595)*(x607))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst71)*(((((r10)*(sj0)*(x595)*(x600)))+(((x589)*(x600)*(x601)))+(((x599)*(x600)*(x602)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x588)*(x595)))+(((IkReal(-1.00000000000000))*(r12)*(x591)*(x596)))+(((x604)*(x605)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x599)))+(((IkReal(-1.00000000000000))*(r12)*(x589)*(x604)))+(((IkReal(-1.00000000000000))*(x588)*(x589)*(x590)))+(((IkReal(-1.00000000000000))*(r02)*(x591)*(x593)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x588)*(x599)))+(((IkReal(-1.00000000000000))*(r21)*(x588)*(x598)))+(((IkReal(-1.00000000000000))*(x591)*(x592)))+(((cj2)*(r00)*(x593)*(x600)))+(((IkReal(-0.707109999985348))*(sj2)*(x607)))+(((x598)*(x607)))+(((IkReal(-1.00000000000000))*(x588)*(x593)*(x594)))+(((IkReal(0.707109999985348))*(x588)*(x597))))))) < IKFAST_ATAN2_MAGTHRESH )
02246     continue;
02247 j1array[0]=IKatan2(((gconst71)*(((((IkReal(0.707103562373095))*(x588)*(x597)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x588)*(x589)))+(((IkReal(-1.00000000000000))*(r02)*(x591)*(x603)))+(((r12)*(x596)*(x604)))+(((r21)*(x588)*(x595)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x593)*(x600)))+(((x593)*(x606)))+(((x592)*(x604)))+(((x591)*(x605)))+(((IkReal(-1.00000000000000))*(x599)*(x607)))+(((IkReal(-1.00000000000000))*(x588)*(x594)*(x603)))+(((x598)*(x600)*(x602)))+(((r01)*(sj2)*(x588)*(x593)))+(((x588)*(x590)*(x596)))+(((IkReal(-1.00000000000000))*(x596)*(x600)*(x601)))+(((cj2)*(r10)*(x589)*(x600)))+(((IkReal(-1.00000000000000))*(r12)*(x589)*(x591)))+(((IkReal(-1.00000000000000))*(x595)*(x607)))))), ((gconst71)*(((((r10)*(sj0)*(x595)*(x600)))+(((x589)*(x600)*(x601)))+(((x599)*(x600)*(x602)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x588)*(x595)))+(((IkReal(-1.00000000000000))*(r12)*(x591)*(x596)))+(((x604)*(x605)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x599)))+(((IkReal(-1.00000000000000))*(r12)*(x589)*(x604)))+(((IkReal(-1.00000000000000))*(x588)*(x589)*(x590)))+(((IkReal(-1.00000000000000))*(r02)*(x591)*(x593)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x588)*(x599)))+(((IkReal(-1.00000000000000))*(r21)*(x588)*(x598)))+(((IkReal(-1.00000000000000))*(x591)*(x592)))+(((cj2)*(r00)*(x593)*(x600)))+(((IkReal(-0.707109999985348))*(sj2)*(x607)))+(((x598)*(x607)))+(((IkReal(-1.00000000000000))*(x588)*(x593)*(x594)))+(((IkReal(0.707109999985348))*(x588)*(x597)))))));
02248 sj1array[0]=IKsin(j1array[0]);
02249 cj1array[0]=IKcos(j1array[0]);
02250 if( j1array[0] > IKPI )
02251 {
02252     j1array[0]-=IK2PI;
02253 }
02254 else if( j1array[0] < -IKPI )
02255 {    j1array[0]+=IK2PI;
02256 }
02257 j1valid[0] = true;
02258 for(int ij1 = 0; ij1 < 1; ++ij1)
02259 {
02260 if( !j1valid[ij1] )
02261 {
02262     continue;
02263 }
02264 _ij1[0] = ij1; _ij1[1] = -1;
02265 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02266 {
02267 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02268 {
02269     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02270 }
02271 }
02272 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02273 {
02274 IkReal evalcond[4];
02275 IkReal x608=IKsin(j1);
02276 IkReal x609=IKcos(j1);
02277 IkReal x610=((IkReal(0.707109999985348))*(cj2));
02278 IkReal x611=((IkReal(1.00000000000000))*(sj4));
02279 IkReal x612=((cj5)*(r00));
02280 IkReal x613=((IkReal(0.707109999985348))*(sj2));
02281 IkReal x614=((cj5)*(r20));
02282 IkReal x615=((r12)*(sj0));
02283 IkReal x616=((r21)*(sj5));
02284 IkReal x617=((IkReal(1.00000000000000))*(cj4));
02285 IkReal x618=((IkReal(0.707103562373095))*(x609));
02286 IkReal x619=((r11)*(sj0)*(sj5));
02287 IkReal x620=((cj0)*(x617));
02288 IkReal x621=((IkReal(0.707103562373095))*(x608));
02289 IkReal x622=((cj0)*(r01)*(sj5));
02290 IkReal x623=((cj5)*(r10)*(sj0));
02291 IkReal x624=((sj2)*(x618));
02292 IkReal x625=((cj2)*(x621));
02293 IkReal x626=((x609)*(x610));
02294 IkReal x627=((x608)*(x613));
02295 IkReal x628=((x608)*(x610));
02296 IkReal x629=((sj2)*(x621));
02297 IkReal x630=((x609)*(x613));
02298 IkReal x631=((cj2)*(x618));
02299 IkReal x632=((x625)+(x624)+(x626));
02300 IkReal x633=((x629)+(x628)+(x630));
02301 evalcond[0]=((((cj4)*(r22)))+(((sj4)*(x616)))+(((IkReal(-1.00000000000000))*(x611)*(x614)))+(((IkReal(-1.00000000000000))*(x631)))+(x633));
02302 evalcond[1]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x632)))+(x627)+(((IkReal(-1.00000000000000))*(x616)*(x617)))+(((cj4)*(x614))));
02303 evalcond[2]=((((sj4)*(x623)))+(((cj0)*(sj4)*(x612)))+(((IkReal(-1.00000000000000))*(x611)*(x619)))+(((IkReal(-1.00000000000000))*(r02)*(x620)))+(((IkReal(-1.00000000000000))*(x627)))+(((IkReal(-1.00000000000000))*(x611)*(x622)))+(x632)+(((IkReal(-1.00000000000000))*(x615)*(x617))));
02304 evalcond[3]=((((IkReal(-1.00000000000000))*(x611)*(x615)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x611)))+(((cj4)*(x622)))+(((IkReal(-1.00000000000000))*(x631)))+(((IkReal(-1.00000000000000))*(x617)*(x623)))+(((IkReal(-1.00000000000000))*(x612)*(x620)))+(x633)+(((cj4)*(x619))));
02305 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02306 {
02307 continue;
02308 }
02309 }
02310 
02311 {
02312 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02313 vinfos[0].jointtype = 1;
02314 vinfos[0].foffset = j0;
02315 vinfos[0].indices[0] = _ij0[0];
02316 vinfos[0].indices[1] = _ij0[1];
02317 vinfos[0].maxsolutions = _nj0;
02318 vinfos[1].jointtype = 1;
02319 vinfos[1].foffset = j1;
02320 vinfos[1].indices[0] = _ij1[0];
02321 vinfos[1].indices[1] = _ij1[1];
02322 vinfos[1].maxsolutions = _nj1;
02323 vinfos[2].jointtype = 1;
02324 vinfos[2].foffset = j2;
02325 vinfos[2].indices[0] = _ij2[0];
02326 vinfos[2].indices[1] = _ij2[1];
02327 vinfos[2].maxsolutions = _nj2;
02328 vinfos[3].jointtype = 1;
02329 vinfos[3].foffset = j3;
02330 vinfos[3].indices[0] = _ij3[0];
02331 vinfos[3].indices[1] = _ij3[1];
02332 vinfos[3].maxsolutions = _nj3;
02333 vinfos[4].jointtype = 1;
02334 vinfos[4].foffset = j4;
02335 vinfos[4].indices[0] = _ij4[0];
02336 vinfos[4].indices[1] = _ij4[1];
02337 vinfos[4].maxsolutions = _nj4;
02338 vinfos[5].jointtype = 1;
02339 vinfos[5].foffset = j5;
02340 vinfos[5].indices[0] = _ij5[0];
02341 vinfos[5].indices[1] = _ij5[1];
02342 vinfos[5].maxsolutions = _nj5;
02343 std::vector<int> vfree(0);
02344 solutions.AddSolution(vinfos,vfree);
02345 }
02346 }
02347 }
02348 
02349 }
02350 
02351 }
02352 
02353 } else
02354 {
02355 {
02356 IkReal j1array[1], cj1array[1], sj1array[1];
02357 bool j1valid[1]={false};
02358 _nj1 = 1;
02359 IkReal x634=((IkReal(0.707109999985348))*(sj4));
02360 IkReal x635=((r22)*(sj2));
02361 IkReal x636=((cj5)*(r20));
02362 IkReal x637=((r21)*(sj5));
02363 IkReal x638=((IkReal(0.707109999985348))*(cj4));
02364 IkReal x639=((cj2)*(r22));
02365 IkReal x640=((IkReal(0.707103562373095))*(sj4));
02366 IkReal x641=((IkReal(0.707103562373095))*(cj4));
02367 IkReal x642=((sj2)*(x641));
02368 IkReal x643=((cj2)*(x641));
02369 if( IKabs(((gconst70)*(((((x636)*(x643)))+(((x639)*(x640)))+(((IkReal(-1.00000000000000))*(cj2)*(x634)*(x637)))+(((IkReal(-1.00000000000000))*(x634)*(x635)))+(((IkReal(-1.00000000000000))*(x638)*(x639)))+(((IkReal(-1.00000000000000))*(sj2)*(x637)*(x640)))+(((sj2)*(x636)*(x640)))+(((IkReal(-1.00000000000000))*(x635)*(x641)))+(((IkReal(-1.00000000000000))*(sj2)*(x636)*(x638)))+(((IkReal(-1.00000000000000))*(x637)*(x643)))+(((sj2)*(x637)*(x638)))+(((cj2)*(x634)*(x636))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((x635)*(x640)))+(((x634)*(x639)))+(((x636)*(x642)))+(((x639)*(x641)))+(((cj2)*(x636)*(x638)))+(((IkReal(-1.00000000000000))*(sj2)*(x634)*(x637)))+(((IkReal(-1.00000000000000))*(cj2)*(x637)*(x638)))+(((cj2)*(x637)*(x640)))+(((IkReal(-1.00000000000000))*(x635)*(x638)))+(((IkReal(-1.00000000000000))*(cj2)*(x636)*(x640)))+(((IkReal(-1.00000000000000))*(x637)*(x642)))+(((sj2)*(x634)*(x636))))))) < IKFAST_ATAN2_MAGTHRESH )
02370     continue;
02371 j1array[0]=IKatan2(((gconst70)*(((((x636)*(x643)))+(((x639)*(x640)))+(((IkReal(-1.00000000000000))*(cj2)*(x634)*(x637)))+(((IkReal(-1.00000000000000))*(x634)*(x635)))+(((IkReal(-1.00000000000000))*(x638)*(x639)))+(((IkReal(-1.00000000000000))*(sj2)*(x637)*(x640)))+(((sj2)*(x636)*(x640)))+(((IkReal(-1.00000000000000))*(x635)*(x641)))+(((IkReal(-1.00000000000000))*(sj2)*(x636)*(x638)))+(((IkReal(-1.00000000000000))*(x637)*(x643)))+(((sj2)*(x637)*(x638)))+(((cj2)*(x634)*(x636)))))), ((gconst70)*(((((x635)*(x640)))+(((x634)*(x639)))+(((x636)*(x642)))+(((x639)*(x641)))+(((cj2)*(x636)*(x638)))+(((IkReal(-1.00000000000000))*(sj2)*(x634)*(x637)))+(((IkReal(-1.00000000000000))*(cj2)*(x637)*(x638)))+(((cj2)*(x637)*(x640)))+(((IkReal(-1.00000000000000))*(x635)*(x638)))+(((IkReal(-1.00000000000000))*(cj2)*(x636)*(x640)))+(((IkReal(-1.00000000000000))*(x637)*(x642)))+(((sj2)*(x634)*(x636)))))));
02372 sj1array[0]=IKsin(j1array[0]);
02373 cj1array[0]=IKcos(j1array[0]);
02374 if( j1array[0] > IKPI )
02375 {
02376     j1array[0]-=IK2PI;
02377 }
02378 else if( j1array[0] < -IKPI )
02379 {    j1array[0]+=IK2PI;
02380 }
02381 j1valid[0] = true;
02382 for(int ij1 = 0; ij1 < 1; ++ij1)
02383 {
02384 if( !j1valid[ij1] )
02385 {
02386     continue;
02387 }
02388 _ij1[0] = ij1; _ij1[1] = -1;
02389 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02390 {
02391 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02392 {
02393     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02394 }
02395 }
02396 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02397 {
02398 IkReal evalcond[4];
02399 IkReal x644=IKsin(j1);
02400 IkReal x645=IKcos(j1);
02401 IkReal x646=((IkReal(0.707109999985348))*(cj2));
02402 IkReal x647=((IkReal(1.00000000000000))*(sj4));
02403 IkReal x648=((cj5)*(r00));
02404 IkReal x649=((IkReal(0.707109999985348))*(sj2));
02405 IkReal x650=((cj5)*(r20));
02406 IkReal x651=((r12)*(sj0));
02407 IkReal x652=((r21)*(sj5));
02408 IkReal x653=((IkReal(1.00000000000000))*(cj4));
02409 IkReal x654=((IkReal(0.707103562373095))*(x645));
02410 IkReal x655=((r11)*(sj0)*(sj5));
02411 IkReal x656=((cj0)*(x653));
02412 IkReal x657=((IkReal(0.707103562373095))*(x644));
02413 IkReal x658=((cj0)*(r01)*(sj5));
02414 IkReal x659=((cj5)*(r10)*(sj0));
02415 IkReal x660=((sj2)*(x654));
02416 IkReal x661=((cj2)*(x657));
02417 IkReal x662=((x645)*(x646));
02418 IkReal x663=((x644)*(x649));
02419 IkReal x664=((x644)*(x646));
02420 IkReal x665=((sj2)*(x657));
02421 IkReal x666=((x645)*(x649));
02422 IkReal x667=((cj2)*(x654));
02423 IkReal x668=((x661)+(x660)+(x662));
02424 IkReal x669=((x665)+(x664)+(x666));
02425 evalcond[0]=((((sj4)*(x652)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x647)*(x650)))+(((IkReal(-1.00000000000000))*(x667)))+(x669));
02426 evalcond[1]=((((cj4)*(x650)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x668)))+(x663)+(((IkReal(-1.00000000000000))*(x652)*(x653))));
02427 evalcond[2]=((((sj4)*(x659)))+(((IkReal(-1.00000000000000))*(x651)*(x653)))+(((IkReal(-1.00000000000000))*(x647)*(x658)))+(((IkReal(-1.00000000000000))*(x647)*(x655)))+(((IkReal(-1.00000000000000))*(x663)))+(((cj0)*(sj4)*(x648)))+(((IkReal(-1.00000000000000))*(r02)*(x656)))+(x668));
02428 evalcond[3]=((((cj4)*(x658)))+(((cj4)*(x655)))+(((IkReal(-1.00000000000000))*(x647)*(x651)))+(((IkReal(-1.00000000000000))*(x667)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x647)))+(x669)+(((IkReal(-1.00000000000000))*(x648)*(x656)))+(((IkReal(-1.00000000000000))*(x653)*(x659))));
02429 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02430 {
02431 continue;
02432 }
02433 }
02434 
02435 {
02436 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02437 vinfos[0].jointtype = 1;
02438 vinfos[0].foffset = j0;
02439 vinfos[0].indices[0] = _ij0[0];
02440 vinfos[0].indices[1] = _ij0[1];
02441 vinfos[0].maxsolutions = _nj0;
02442 vinfos[1].jointtype = 1;
02443 vinfos[1].foffset = j1;
02444 vinfos[1].indices[0] = _ij1[0];
02445 vinfos[1].indices[1] = _ij1[1];
02446 vinfos[1].maxsolutions = _nj1;
02447 vinfos[2].jointtype = 1;
02448 vinfos[2].foffset = j2;
02449 vinfos[2].indices[0] = _ij2[0];
02450 vinfos[2].indices[1] = _ij2[1];
02451 vinfos[2].maxsolutions = _nj2;
02452 vinfos[3].jointtype = 1;
02453 vinfos[3].foffset = j3;
02454 vinfos[3].indices[0] = _ij3[0];
02455 vinfos[3].indices[1] = _ij3[1];
02456 vinfos[3].maxsolutions = _nj3;
02457 vinfos[4].jointtype = 1;
02458 vinfos[4].foffset = j4;
02459 vinfos[4].indices[0] = _ij4[0];
02460 vinfos[4].indices[1] = _ij4[1];
02461 vinfos[4].maxsolutions = _nj4;
02462 vinfos[5].jointtype = 1;
02463 vinfos[5].foffset = j5;
02464 vinfos[5].indices[0] = _ij5[0];
02465 vinfos[5].indices[1] = _ij5[1];
02466 vinfos[5].maxsolutions = _nj5;
02467 std::vector<int> vfree(0);
02468 solutions.AddSolution(vinfos,vfree);
02469 }
02470 }
02471 }
02472 
02473 }
02474 
02475 }
02476 }
02477 }
02478 
02479 }
02480 
02481 }
02482 
02483 } else
02484 {
02485 {
02486 IkReal j0array[1], cj0array[1], sj0array[1];
02487 bool j0valid[1]={false};
02488 _nj0 = 1;
02489 if( IKabs(((gconst65)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst65)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
02490     continue;
02491 j0array[0]=IKatan2(((gconst65)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst65)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
02492 sj0array[0]=IKsin(j0array[0]);
02493 cj0array[0]=IKcos(j0array[0]);
02494 if( j0array[0] > IKPI )
02495 {
02496     j0array[0]-=IK2PI;
02497 }
02498 else if( j0array[0] < -IKPI )
02499 {    j0array[0]+=IK2PI;
02500 }
02501 j0valid[0] = true;
02502 for(int ij0 = 0; ij0 < 1; ++ij0)
02503 {
02504 if( !j0valid[ij0] )
02505 {
02506     continue;
02507 }
02508 _ij0[0] = ij0; _ij0[1] = -1;
02509 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02510 {
02511 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02512 {
02513     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02514 }
02515 }
02516 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02517 {
02518 IkReal evalcond[4];
02519 IkReal x670=IKsin(j0);
02520 IkReal x671=IKcos(j0);
02521 IkReal x672=((IkReal(1.00000000000000))*(cj5));
02522 IkReal x673=((r01)*(sj5));
02523 IkReal x674=((IkReal(1.00000000000000))*(r12));
02524 IkReal x675=((r11)*(sj5));
02525 IkReal x676=((IkReal(1.00000000000000))*(r10));
02526 IkReal x677=((cj4)*(x670));
02527 IkReal x678=((sj4)*(x670));
02528 IkReal x679=((sj4)*(x671));
02529 IkReal x680=((sj5)*(x670));
02530 IkReal x681=((cj4)*(x671));
02531 IkReal x682=((sj5)*(x671));
02532 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x671)*(x672)))+(((r00)*(x680)))+(((IkReal(-1.00000000000000))*(x676)*(x682)))+(((cj5)*(r01)*(x670))));
02533 evalcond[1]=((((cj5)*(r10)*(x679)))+(((x673)*(x678)))+(((r02)*(x677)))+(((IkReal(-1.00000000000000))*(x675)*(x679)))+(((IkReal(-1.00000000000000))*(r00)*(x672)*(x678)))+(((IkReal(-1.00000000000000))*(x674)*(x681))));
02534 evalcond[2]=((((cj5)*(r00)*(x677)))+(((r02)*(x678)))+(((IkReal(-1.00000000000000))*(x673)*(x677)))+(((IkReal(-1.00000000000000))*(r10)*(x672)*(x681)))+(((IkReal(-1.00000000000000))*(x674)*(x679)))+(((x675)*(x681))));
02535 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x670)*(x672)))+(((IkReal(-1.00000000000000))*(r00)*(x682)))+(((IkReal(-1.00000000000000))*(r01)*(x671)*(x672)))+(((IkReal(-1.00000000000000))*(x676)*(x680))));
02536 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02537 {
02538 continue;
02539 }
02540 }
02541 
02542 {
02543 IkReal dummyeval[1];
02544 IkReal gconst70;
02545 gconst70=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
02546 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
02547 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02548 {
02549 {
02550 IkReal dummyeval[1];
02551 IkReal gconst71;
02552 gconst71=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
02553 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
02554 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02555 {
02556 continue;
02557 
02558 } else
02559 {
02560 {
02561 IkReal j1array[1], cj1array[1], sj1array[1];
02562 bool j1valid[1]={false};
02563 _nj1 = 1;
02564 IkReal x683=((sj4)*(sj5));
02565 IkReal x684=((IkReal(0.707103562373095))*(sj0));
02566 IkReal x685=((r11)*(sj2));
02567 IkReal x686=((cj2)*(cj4));
02568 IkReal x687=((IkReal(0.707103562373095))*(r22));
02569 IkReal x688=((IkReal(0.707109999985348))*(cj0));
02570 IkReal x689=((cj2)*(r01));
02571 IkReal x690=((IkReal(0.707109999985348))*(cj2));
02572 IkReal x691=((IkReal(0.707109999985348))*(sj0));
02573 IkReal x692=((r21)*(sj2));
02574 IkReal x693=((IkReal(0.707103562373095))*(cj2));
02575 IkReal x694=((IkReal(0.707103562373095))*(sj2));
02576 IkReal x695=((cj5)*(sj4));
02577 IkReal x696=((r10)*(sj2));
02578 IkReal x697=((cj0)*(r00));
02579 IkReal x698=((IkReal(0.707103562373095))*(cj0));
02580 IkReal x699=((cj4)*(sj2));
02581 IkReal x700=((IkReal(0.707109999985348))*(r22));
02582 IkReal x701=((r02)*(x699));
02583 IkReal x702=((r20)*(x695));
02584 if( IKabs(((gconst71)*(((((x687)*(x699)))+(((IkReal(-1.00000000000000))*(r12)*(x684)*(x686)))+(((cj2)*(r10)*(x684)*(x695)))+(((IkReal(-1.00000000000000))*(x683)*(x689)*(x698)))+(((IkReal(-1.00000000000000))*(x690)*(x702)))+(((r12)*(x691)*(x699)))+(((IkReal(-1.00000000000000))*(x694)*(x702)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x688)*(x695)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x683)*(x684)))+(((x683)*(x685)*(x691)))+(((r21)*(x683)*(x690)))+(((IkReal(-1.00000000000000))*(x691)*(x695)*(x696)))+(((IkReal(0.707103562373095))*(x683)*(x692)))+(((x688)*(x701)))+(((x686)*(x700)))+(((IkReal(-1.00000000000000))*(r02)*(x686)*(x698)))+(((r01)*(sj2)*(x683)*(x688)))+(((x693)*(x695)*(x697))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst71)*(((((IkReal(-1.00000000000000))*(x683)*(x688)*(x689)))+(((x684)*(x695)*(x696)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x683)*(x690)))+(((IkReal(-1.00000000000000))*(r12)*(x684)*(x699)))+(((IkReal(-1.00000000000000))*(r02)*(x686)*(x688)))+(((r10)*(sj0)*(x690)*(x695)))+(((IkReal(-1.00000000000000))*(x686)*(x687)))+(((IkReal(-1.00000000000000))*(r12)*(x686)*(x691)))+(((cj2)*(r00)*(x688)*(x695)))+(((x694)*(x695)*(x697)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x694)))+(((IkReal(-0.707109999985348))*(sj2)*(x702)))+(((IkReal(-1.00000000000000))*(r21)*(x683)*(x693)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x683)*(x694)))+(((IkReal(0.707109999985348))*(x683)*(x692)))+(((x693)*(x702)))+(((IkReal(-1.00000000000000))*(x683)*(x684)*(x685)))+(((x699)*(x700))))))) < IKFAST_ATAN2_MAGTHRESH )
02585     continue;
02586 j1array[0]=IKatan2(((gconst71)*(((((x687)*(x699)))+(((IkReal(-1.00000000000000))*(r12)*(x684)*(x686)))+(((cj2)*(r10)*(x684)*(x695)))+(((IkReal(-1.00000000000000))*(x683)*(x689)*(x698)))+(((IkReal(-1.00000000000000))*(x690)*(x702)))+(((r12)*(x691)*(x699)))+(((IkReal(-1.00000000000000))*(x694)*(x702)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x688)*(x695)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x683)*(x684)))+(((x683)*(x685)*(x691)))+(((r21)*(x683)*(x690)))+(((IkReal(-1.00000000000000))*(x691)*(x695)*(x696)))+(((IkReal(0.707103562373095))*(x683)*(x692)))+(((x688)*(x701)))+(((x686)*(x700)))+(((IkReal(-1.00000000000000))*(r02)*(x686)*(x698)))+(((r01)*(sj2)*(x683)*(x688)))+(((x693)*(x695)*(x697)))))), ((gconst71)*(((((IkReal(-1.00000000000000))*(x683)*(x688)*(x689)))+(((x684)*(x695)*(x696)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x683)*(x690)))+(((IkReal(-1.00000000000000))*(r12)*(x684)*(x699)))+(((IkReal(-1.00000000000000))*(r02)*(x686)*(x688)))+(((r10)*(sj0)*(x690)*(x695)))+(((IkReal(-1.00000000000000))*(x686)*(x687)))+(((IkReal(-1.00000000000000))*(r12)*(x686)*(x691)))+(((cj2)*(r00)*(x688)*(x695)))+(((x694)*(x695)*(x697)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x694)))+(((IkReal(-0.707109999985348))*(sj2)*(x702)))+(((IkReal(-1.00000000000000))*(r21)*(x683)*(x693)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x683)*(x694)))+(((IkReal(0.707109999985348))*(x683)*(x692)))+(((x693)*(x702)))+(((IkReal(-1.00000000000000))*(x683)*(x684)*(x685)))+(((x699)*(x700)))))));
02587 sj1array[0]=IKsin(j1array[0]);
02588 cj1array[0]=IKcos(j1array[0]);
02589 if( j1array[0] > IKPI )
02590 {
02591     j1array[0]-=IK2PI;
02592 }
02593 else if( j1array[0] < -IKPI )
02594 {    j1array[0]+=IK2PI;
02595 }
02596 j1valid[0] = true;
02597 for(int ij1 = 0; ij1 < 1; ++ij1)
02598 {
02599 if( !j1valid[ij1] )
02600 {
02601     continue;
02602 }
02603 _ij1[0] = ij1; _ij1[1] = -1;
02604 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02605 {
02606 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02607 {
02608     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02609 }
02610 }
02611 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02612 {
02613 IkReal evalcond[4];
02614 IkReal x703=IKsin(j1);
02615 IkReal x704=IKcos(j1);
02616 IkReal x705=((IkReal(0.707109999985348))*(cj2));
02617 IkReal x706=((IkReal(1.00000000000000))*(sj4));
02618 IkReal x707=((cj5)*(r00));
02619 IkReal x708=((IkReal(0.707109999985348))*(sj2));
02620 IkReal x709=((cj5)*(r20));
02621 IkReal x710=((r12)*(sj0));
02622 IkReal x711=((r21)*(sj5));
02623 IkReal x712=((IkReal(1.00000000000000))*(cj4));
02624 IkReal x713=((IkReal(0.707103562373095))*(x704));
02625 IkReal x714=((r11)*(sj0)*(sj5));
02626 IkReal x715=((cj0)*(x712));
02627 IkReal x716=((IkReal(0.707103562373095))*(x703));
02628 IkReal x717=((cj0)*(r01)*(sj5));
02629 IkReal x718=((cj5)*(r10)*(sj0));
02630 IkReal x719=((sj2)*(x713));
02631 IkReal x720=((cj2)*(x716));
02632 IkReal x721=((x704)*(x705));
02633 IkReal x722=((x703)*(x708));
02634 IkReal x723=((x703)*(x705));
02635 IkReal x724=((sj2)*(x716));
02636 IkReal x725=((x704)*(x708));
02637 IkReal x726=((cj2)*(x713));
02638 IkReal x727=((x719)+(x720)+(x721));
02639 IkReal x728=((x723)+(x724)+(x725));
02640 evalcond[0]=((((sj4)*(x711)))+(((IkReal(-1.00000000000000))*(x706)*(x709)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x726)))+(x728));
02641 evalcond[1]=((((IkReal(-1.00000000000000))*(x711)*(x712)))+(((cj4)*(x709)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x727)))+(x722));
02642 evalcond[2]=((((sj4)*(x718)))+(((IkReal(-1.00000000000000))*(r02)*(x715)))+(((IkReal(-1.00000000000000))*(x706)*(x714)))+(((IkReal(-1.00000000000000))*(x706)*(x717)))+(((IkReal(-1.00000000000000))*(x710)*(x712)))+(((IkReal(-1.00000000000000))*(x722)))+(((cj0)*(sj4)*(x707)))+(x727));
02643 evalcond[3]=((((IkReal(-1.00000000000000))*(x707)*(x715)))+(((IkReal(-1.00000000000000))*(x706)*(x710)))+(((cj4)*(x714)))+(((cj4)*(x717)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x706)))+(((IkReal(-1.00000000000000))*(x726)))+(((IkReal(-1.00000000000000))*(x712)*(x718)))+(x728));
02644 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02645 {
02646 continue;
02647 }
02648 }
02649 
02650 {
02651 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02652 vinfos[0].jointtype = 1;
02653 vinfos[0].foffset = j0;
02654 vinfos[0].indices[0] = _ij0[0];
02655 vinfos[0].indices[1] = _ij0[1];
02656 vinfos[0].maxsolutions = _nj0;
02657 vinfos[1].jointtype = 1;
02658 vinfos[1].foffset = j1;
02659 vinfos[1].indices[0] = _ij1[0];
02660 vinfos[1].indices[1] = _ij1[1];
02661 vinfos[1].maxsolutions = _nj1;
02662 vinfos[2].jointtype = 1;
02663 vinfos[2].foffset = j2;
02664 vinfos[2].indices[0] = _ij2[0];
02665 vinfos[2].indices[1] = _ij2[1];
02666 vinfos[2].maxsolutions = _nj2;
02667 vinfos[3].jointtype = 1;
02668 vinfos[3].foffset = j3;
02669 vinfos[3].indices[0] = _ij3[0];
02670 vinfos[3].indices[1] = _ij3[1];
02671 vinfos[3].maxsolutions = _nj3;
02672 vinfos[4].jointtype = 1;
02673 vinfos[4].foffset = j4;
02674 vinfos[4].indices[0] = _ij4[0];
02675 vinfos[4].indices[1] = _ij4[1];
02676 vinfos[4].maxsolutions = _nj4;
02677 vinfos[5].jointtype = 1;
02678 vinfos[5].foffset = j5;
02679 vinfos[5].indices[0] = _ij5[0];
02680 vinfos[5].indices[1] = _ij5[1];
02681 vinfos[5].maxsolutions = _nj5;
02682 std::vector<int> vfree(0);
02683 solutions.AddSolution(vinfos,vfree);
02684 }
02685 }
02686 }
02687 
02688 }
02689 
02690 }
02691 
02692 } else
02693 {
02694 {
02695 IkReal j1array[1], cj1array[1], sj1array[1];
02696 bool j1valid[1]={false};
02697 _nj1 = 1;
02698 IkReal x729=((IkReal(0.707109999985348))*(sj4));
02699 IkReal x730=((r22)*(sj2));
02700 IkReal x731=((cj5)*(r20));
02701 IkReal x732=((r21)*(sj5));
02702 IkReal x733=((IkReal(0.707109999985348))*(cj4));
02703 IkReal x734=((cj2)*(r22));
02704 IkReal x735=((IkReal(0.707103562373095))*(sj4));
02705 IkReal x736=((IkReal(0.707103562373095))*(cj4));
02706 IkReal x737=((sj2)*(x736));
02707 IkReal x738=((cj2)*(x736));
02708 if( IKabs(((gconst70)*(((((sj2)*(x732)*(x733)))+(((x731)*(x738)))+(((IkReal(-1.00000000000000))*(x732)*(x738)))+(((IkReal(-1.00000000000000))*(sj2)*(x731)*(x733)))+(((x734)*(x735)))+(((IkReal(-1.00000000000000))*(x733)*(x734)))+(((cj2)*(x729)*(x731)))+(((IkReal(-1.00000000000000))*(x730)*(x736)))+(((IkReal(-1.00000000000000))*(cj2)*(x729)*(x732)))+(((sj2)*(x731)*(x735)))+(((IkReal(-1.00000000000000))*(sj2)*(x732)*(x735)))+(((IkReal(-1.00000000000000))*(x729)*(x730))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((x731)*(x737)))+(((IkReal(-1.00000000000000))*(x732)*(x737)))+(((x734)*(x736)))+(((IkReal(-1.00000000000000))*(sj2)*(x729)*(x732)))+(((x729)*(x734)))+(((sj2)*(x729)*(x731)))+(((IkReal(-1.00000000000000))*(cj2)*(x732)*(x733)))+(((cj2)*(x731)*(x733)))+(((IkReal(-1.00000000000000))*(x730)*(x733)))+(((IkReal(-1.00000000000000))*(cj2)*(x731)*(x735)))+(((cj2)*(x732)*(x735)))+(((x730)*(x735))))))) < IKFAST_ATAN2_MAGTHRESH )
02709     continue;
02710 j1array[0]=IKatan2(((gconst70)*(((((sj2)*(x732)*(x733)))+(((x731)*(x738)))+(((IkReal(-1.00000000000000))*(x732)*(x738)))+(((IkReal(-1.00000000000000))*(sj2)*(x731)*(x733)))+(((x734)*(x735)))+(((IkReal(-1.00000000000000))*(x733)*(x734)))+(((cj2)*(x729)*(x731)))+(((IkReal(-1.00000000000000))*(x730)*(x736)))+(((IkReal(-1.00000000000000))*(cj2)*(x729)*(x732)))+(((sj2)*(x731)*(x735)))+(((IkReal(-1.00000000000000))*(sj2)*(x732)*(x735)))+(((IkReal(-1.00000000000000))*(x729)*(x730)))))), ((gconst70)*(((((x731)*(x737)))+(((IkReal(-1.00000000000000))*(x732)*(x737)))+(((x734)*(x736)))+(((IkReal(-1.00000000000000))*(sj2)*(x729)*(x732)))+(((x729)*(x734)))+(((sj2)*(x729)*(x731)))+(((IkReal(-1.00000000000000))*(cj2)*(x732)*(x733)))+(((cj2)*(x731)*(x733)))+(((IkReal(-1.00000000000000))*(x730)*(x733)))+(((IkReal(-1.00000000000000))*(cj2)*(x731)*(x735)))+(((cj2)*(x732)*(x735)))+(((x730)*(x735)))))));
02711 sj1array[0]=IKsin(j1array[0]);
02712 cj1array[0]=IKcos(j1array[0]);
02713 if( j1array[0] > IKPI )
02714 {
02715     j1array[0]-=IK2PI;
02716 }
02717 else if( j1array[0] < -IKPI )
02718 {    j1array[0]+=IK2PI;
02719 }
02720 j1valid[0] = true;
02721 for(int ij1 = 0; ij1 < 1; ++ij1)
02722 {
02723 if( !j1valid[ij1] )
02724 {
02725     continue;
02726 }
02727 _ij1[0] = ij1; _ij1[1] = -1;
02728 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02729 {
02730 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02731 {
02732     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02733 }
02734 }
02735 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02736 {
02737 IkReal evalcond[4];
02738 IkReal x739=IKsin(j1);
02739 IkReal x740=IKcos(j1);
02740 IkReal x741=((IkReal(0.707109999985348))*(cj2));
02741 IkReal x742=((IkReal(1.00000000000000))*(sj4));
02742 IkReal x743=((cj5)*(r00));
02743 IkReal x744=((IkReal(0.707109999985348))*(sj2));
02744 IkReal x745=((cj5)*(r20));
02745 IkReal x746=((r12)*(sj0));
02746 IkReal x747=((r21)*(sj5));
02747 IkReal x748=((IkReal(1.00000000000000))*(cj4));
02748 IkReal x749=((IkReal(0.707103562373095))*(x740));
02749 IkReal x750=((r11)*(sj0)*(sj5));
02750 IkReal x751=((cj0)*(x748));
02751 IkReal x752=((IkReal(0.707103562373095))*(x739));
02752 IkReal x753=((cj0)*(r01)*(sj5));
02753 IkReal x754=((cj5)*(r10)*(sj0));
02754 IkReal x755=((sj2)*(x749));
02755 IkReal x756=((cj2)*(x752));
02756 IkReal x757=((x740)*(x741));
02757 IkReal x758=((x739)*(x744));
02758 IkReal x759=((x739)*(x741));
02759 IkReal x760=((sj2)*(x752));
02760 IkReal x761=((x740)*(x744));
02761 IkReal x762=((cj2)*(x749));
02762 IkReal x763=((x755)+(x757)+(x756));
02763 IkReal x764=((x759)+(x760)+(x761));
02764 evalcond[0]=((((sj4)*(x747)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x742)*(x745)))+(((IkReal(-1.00000000000000))*(x762)))+(x764));
02765 evalcond[1]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x763)))+(((IkReal(-1.00000000000000))*(x747)*(x748)))+(x758)+(((cj4)*(x745))));
02766 evalcond[2]=((((cj0)*(sj4)*(x743)))+(((IkReal(-1.00000000000000))*(x742)*(x750)))+(((IkReal(-1.00000000000000))*(x742)*(x753)))+(((IkReal(-1.00000000000000))*(x746)*(x748)))+(((sj4)*(x754)))+(((IkReal(-1.00000000000000))*(r02)*(x751)))+(x763)+(((IkReal(-1.00000000000000))*(x758))));
02767 evalcond[3]=((((IkReal(-1.00000000000000))*(x742)*(x746)))+(((IkReal(-1.00000000000000))*(x762)))+(((IkReal(-1.00000000000000))*(x743)*(x751)))+(x764)+(((IkReal(-1.00000000000000))*(x748)*(x754)))+(((cj4)*(x753)))+(((cj4)*(x750)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x742))));
02768 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02769 {
02770 continue;
02771 }
02772 }
02773 
02774 {
02775 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02776 vinfos[0].jointtype = 1;
02777 vinfos[0].foffset = j0;
02778 vinfos[0].indices[0] = _ij0[0];
02779 vinfos[0].indices[1] = _ij0[1];
02780 vinfos[0].maxsolutions = _nj0;
02781 vinfos[1].jointtype = 1;
02782 vinfos[1].foffset = j1;
02783 vinfos[1].indices[0] = _ij1[0];
02784 vinfos[1].indices[1] = _ij1[1];
02785 vinfos[1].maxsolutions = _nj1;
02786 vinfos[2].jointtype = 1;
02787 vinfos[2].foffset = j2;
02788 vinfos[2].indices[0] = _ij2[0];
02789 vinfos[2].indices[1] = _ij2[1];
02790 vinfos[2].maxsolutions = _nj2;
02791 vinfos[3].jointtype = 1;
02792 vinfos[3].foffset = j3;
02793 vinfos[3].indices[0] = _ij3[0];
02794 vinfos[3].indices[1] = _ij3[1];
02795 vinfos[3].maxsolutions = _nj3;
02796 vinfos[4].jointtype = 1;
02797 vinfos[4].foffset = j4;
02798 vinfos[4].indices[0] = _ij4[0];
02799 vinfos[4].indices[1] = _ij4[1];
02800 vinfos[4].maxsolutions = _nj4;
02801 vinfos[5].jointtype = 1;
02802 vinfos[5].foffset = j5;
02803 vinfos[5].indices[0] = _ij5[0];
02804 vinfos[5].indices[1] = _ij5[1];
02805 vinfos[5].maxsolutions = _nj5;
02806 std::vector<int> vfree(0);
02807 solutions.AddSolution(vinfos,vfree);
02808 }
02809 }
02810 }
02811 
02812 }
02813 
02814 }
02815 }
02816 }
02817 
02818 }
02819 
02820 }
02821 }
02822 }
02823 
02824 } else
02825 {
02826 if( 1 )
02827 {
02828 continue;
02829 
02830 } else
02831 {
02832 }
02833 }
02834 }
02835 }
02836 
02837 } else
02838 {
02839 {
02840 IkReal j2array[1], cj2array[1], sj2array[1];
02841 bool j2valid[1]={false};
02842 _nj2 = 1;
02843 IkReal x765=((IkReal(8.66210554726807e+23))*(cj5));
02844 IkReal x766=((IkReal(8.66210554726807e+23))*(sj5));
02845 IkReal x767=((IkReal(6.89439331452234e+23))*(cj5));
02846 IkReal x768=((IkReal(6.89439331452234e+23))*(sj5));
02847 IkReal x769=((npx)*(sj3)*(sj4));
02848 IkReal x770=((cj4)*(npz)*(sj3));
02849 IkReal x771=((npy)*(sj3)*(sj4));
02850 if( IKabs(((gconst2)*(((IkReal(-5.19726332836084e+21))+(((npy)*(x765)))+(((IkReal(-1.00000000000000))*(x768)*(x771)))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((IkReal(-6.89439331452234e+23))*(x770)))+(((npx)*(x766)))+(((x767)*(x769))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((IkReal(-4.13663598871341e+21))+(((npy)*(x767)))+(((IkReal(-1.00000000000000))*(x765)*(x769)))+(((IkReal(8.66210554726807e+23))*(x770)))+(((x766)*(x771)))+(((npx)*(x768)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3))))))) < IKFAST_ATAN2_MAGTHRESH )
02851     continue;
02852 j2array[0]=IKatan2(((gconst2)*(((IkReal(-5.19726332836084e+21))+(((npy)*(x765)))+(((IkReal(-1.00000000000000))*(x768)*(x771)))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((IkReal(-6.89439331452234e+23))*(x770)))+(((npx)*(x766)))+(((x767)*(x769)))))), ((gconst2)*(((IkReal(-4.13663598871341e+21))+(((npy)*(x767)))+(((IkReal(-1.00000000000000))*(x765)*(x769)))+(((IkReal(8.66210554726807e+23))*(x770)))+(((x766)*(x771)))+(((npx)*(x768)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3)))))));
02853 sj2array[0]=IKsin(j2array[0]);
02854 cj2array[0]=IKcos(j2array[0]);
02855 if( j2array[0] > IKPI )
02856 {
02857     j2array[0]-=IK2PI;
02858 }
02859 else if( j2array[0] < -IKPI )
02860 {    j2array[0]+=IK2PI;
02861 }
02862 j2valid[0] = true;
02863 for(int ij2 = 0; ij2 < 1; ++ij2)
02864 {
02865 if( !j2valid[ij2] )
02866 {
02867     continue;
02868 }
02869 _ij2[0] = ij2; _ij2[1] = -1;
02870 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02871 {
02872 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02873 {
02874     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02875 }
02876 }
02877 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02878 {
02879 IkReal evalcond[3];
02880 IkReal x772=IKsin(j2);
02881 IkReal x773=IKcos(j2);
02882 IkReal x774=((cj5)*(npx));
02883 IkReal x775=((npy)*(sj5));
02884 IkReal x776=((IkReal(0.165463933124939))*(x773));
02885 IkReal x777=((IkReal(0.207888640466058))*(x772));
02886 evalcond[0]=((IkReal(-0.258003287011922))+(((sj4)*(x775)))+(((IkReal(-1.00000000000000))*(sj4)*(x774)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(x772)))+(((IkReal(-0.207888640466058))*(x773))));
02887 evalcond[1]=((IkReal(-0.00600000000000000))+(((IkReal(-0.0300035672348961))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x776)))+(((IkReal(-1.00000000000000))*(sj3)*(x777)))+(((npx)*(sj5)))+(((IkReal(-0.00600000000000000))*(cj3)))+(((cj5)*(npy))));
02888 evalcond[2]=((((npz)*(sj4)))+(((IkReal(-0.00600000000000000))*(sj3)))+(((cj3)*(x777)))+(((cj3)*(x776)))+(((IkReal(-1.00000000000000))*(cj4)*(x775)))+(((cj4)*(x774)))+(((IkReal(0.0300035672348961))*(cj3))));
02889 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
02890 {
02891 continue;
02892 }
02893 }
02894 
02895 {
02896 IkReal dummyeval[1];
02897 IkReal gconst4;
02898 IkReal x778=(cj5)*(cj5);
02899 IkReal x779=(sj5)*(sj5);
02900 IkReal x780=((IkReal(1.00000000000000))*(r10));
02901 IkReal x781=((cj4)*(sj5));
02902 IkReal x782=((r00)*(r11));
02903 IkReal x783=((cj4)*(cj5));
02904 IkReal x784=((sj4)*(x778));
02905 IkReal x785=((sj4)*(x779));
02906 gconst4=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x780)*(x784)))+(((IkReal(-1.00000000000000))*(r01)*(x780)*(x785)))+(((r01)*(r12)*(x783)))+(((x782)*(x784)))+(((x782)*(x785)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x783)))+(((r00)*(r12)*(x781)))+(((IkReal(-1.00000000000000))*(r02)*(x780)*(x781)))));
02907 IkReal x786=(cj5)*(cj5);
02908 IkReal x787=(sj5)*(sj5);
02909 IkReal x788=((IkReal(1.00000000000000))*(r10));
02910 IkReal x789=((cj4)*(sj5));
02911 IkReal x790=((r00)*(r11));
02912 IkReal x791=((cj4)*(cj5));
02913 IkReal x792=((sj4)*(x786));
02914 IkReal x793=((sj4)*(x787));
02915 dummyeval[0]=((((r01)*(r12)*(x791)))+(((x790)*(x793)))+(((x790)*(x792)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x791)))+(((r00)*(r12)*(x789)))+(((IkReal(-1.00000000000000))*(r02)*(x788)*(x789)))+(((IkReal(-1.00000000000000))*(r01)*(x788)*(x793)))+(((IkReal(-1.00000000000000))*(r01)*(x788)*(x792))));
02916 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02917 {
02918 {
02919 IkReal dummyeval[1];
02920 IkReal gconst5;
02921 IkReal x794=(cj5)*(cj5);
02922 IkReal x795=(sj5)*(sj5);
02923 IkReal x796=((IkReal(1.00000000000000))*(r11));
02924 IkReal x797=((cj4)*(r00));
02925 IkReal x798=((r02)*(sj4));
02926 IkReal x799=((r12)*(sj4));
02927 IkReal x800=((cj4)*(r01)*(r10));
02928 gconst5=IKsign(((((IkReal(-1.00000000000000))*(x794)*(x796)*(x797)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x798)))+(((r00)*(sj5)*(x799)))+(((x795)*(x800)))+(((x794)*(x800)))+(((IkReal(-1.00000000000000))*(cj5)*(x796)*(x798)))+(((cj5)*(r01)*(x799)))+(((IkReal(-1.00000000000000))*(x795)*(x796)*(x797)))));
02929 IkReal x801=(cj5)*(cj5);
02930 IkReal x802=(sj5)*(sj5);
02931 IkReal x803=((IkReal(1.00000000000000))*(r11));
02932 IkReal x804=((cj4)*(r00));
02933 IkReal x805=((r02)*(sj4));
02934 IkReal x806=((r12)*(sj4));
02935 IkReal x807=((cj4)*(r01)*(r10));
02936 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(sj5)*(x805)))+(((r00)*(sj5)*(x806)))+(((IkReal(-1.00000000000000))*(x801)*(x803)*(x804)))+(((x801)*(x807)))+(((IkReal(-1.00000000000000))*(x802)*(x803)*(x804)))+(((IkReal(-1.00000000000000))*(cj5)*(x803)*(x805)))+(((cj5)*(r01)*(x806)))+(((x802)*(x807))));
02937 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02938 {
02939 {
02940 IkReal dummyeval[1];
02941 IkReal gconst6;
02942 IkReal x808=((IkReal(1.00000000000000))*(sj3));
02943 gconst6=IKsign(((((IkReal(-1.00000000000000))*(x808)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x808)*((sj2)*(sj2))))));
02944 IkReal x809=((IkReal(1.00000000000000))*(sj3));
02945 dummyeval[0]=((((IkReal(-1.00000000000000))*(x809)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x809)*((cj2)*(cj2)))));
02946 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02947 {
02948 {
02949 IkReal evalcond[5];
02950 IkReal x810=((cj5)*(npx));
02951 IkReal x811=((npy)*(sj5));
02952 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959))));
02953 evalcond[1]=((IkReal(-0.258003287011922))+(((sj4)*(x811)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x810)))+(((IkReal(0.165463933124939))*(sj2))));
02954 evalcond[2]=((IkReal(-0.0120000000000000))+(((npx)*(sj5)))+(((cj5)*(npy))));
02955 evalcond[3]=((IkReal(0.0300035672348961))+(((npz)*(sj4)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj4)*(x810)))+(((IkReal(-1.00000000000000))*(cj4)*(x811)))+(((IkReal(0.165463933124939))*(cj2))));
02956 evalcond[4]=((((cj5)*(r21)))+(((r20)*(sj5))));
02957 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  )
02958 {
02959 {
02960 IkReal dummyeval[1];
02961 IkReal gconst20;
02962 IkReal x812=(cj5)*(cj5);
02963 IkReal x813=(sj5)*(sj5);
02964 IkReal x814=((IkReal(2.00000000000000))*(cj5)*(sj5));
02965 gconst20=IKsign(((((x813)*((r00)*(r00))))+(((x812)*((r11)*(r11))))+(((x812)*((r01)*(r01))))+(((x813)*((r10)*(r10))))+(((r10)*(r11)*(x814)))+(((r00)*(r01)*(x814)))));
02966 IkReal x815=(cj5)*(cj5);
02967 IkReal x816=(sj5)*(sj5);
02968 IkReal x817=((IkReal(2.00000000000000))*(cj5)*(sj5));
02969 dummyeval[0]=((((x815)*((r11)*(r11))))+(((r10)*(r11)*(x817)))+(((x816)*((r10)*(r10))))+(((r00)*(r01)*(x817)))+(((x816)*((r00)*(r00))))+(((x815)*((r01)*(r01)))));
02970 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02971 {
02972 {
02973 IkReal dummyeval[1];
02974 IkReal gconst21;
02975 IkReal x818=(cj5)*(cj5);
02976 IkReal x819=(sj5)*(sj5);
02977 IkReal x820=((IkReal(1.00000000000000))*(r10));
02978 IkReal x821=((cj4)*(sj5));
02979 IkReal x822=((r00)*(r11));
02980 IkReal x823=((cj4)*(cj5));
02981 IkReal x824=((sj4)*(x818));
02982 IkReal x825=((sj4)*(x819));
02983 gconst21=IKsign(((((r00)*(r12)*(x821)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x823)))+(((IkReal(-1.00000000000000))*(r01)*(x820)*(x824)))+(((IkReal(-1.00000000000000))*(r01)*(x820)*(x825)))+(((r01)*(r12)*(x823)))+(((IkReal(-1.00000000000000))*(r02)*(x820)*(x821)))+(((x822)*(x825)))+(((x822)*(x824)))));
02984 IkReal x826=(cj5)*(cj5);
02985 IkReal x827=(sj5)*(sj5);
02986 IkReal x828=((IkReal(1.00000000000000))*(r10));
02987 IkReal x829=((cj4)*(sj5));
02988 IkReal x830=((r00)*(r11));
02989 IkReal x831=((cj4)*(cj5));
02990 IkReal x832=((sj4)*(x826));
02991 IkReal x833=((sj4)*(x827));
02992 dummyeval[0]=((((r00)*(r12)*(x829)))+(((r01)*(r12)*(x831)))+(((IkReal(-1.00000000000000))*(r01)*(x828)*(x832)))+(((IkReal(-1.00000000000000))*(r01)*(x828)*(x833)))+(((x830)*(x832)))+(((x830)*(x833)))+(((IkReal(-1.00000000000000))*(r02)*(x828)*(x829)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x831))));
02993 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02994 {
02995 {
02996 IkReal dummyeval[1];
02997 IkReal gconst22;
02998 gconst22=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
02999 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
03000 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03001 {
03002 continue;
03003 
03004 } else
03005 {
03006 {
03007 IkReal j1array[1], cj1array[1], sj1array[1];
03008 bool j1valid[1]={false};
03009 _nj1 = 1;
03010 IkReal x834=((IkReal(0.707109999985348))*(sj4));
03011 IkReal x835=((r22)*(sj2));
03012 IkReal x836=((cj5)*(r20));
03013 IkReal x837=((r21)*(sj5));
03014 IkReal x838=((IkReal(0.707109999985348))*(cj4));
03015 IkReal x839=((cj2)*(r22));
03016 IkReal x840=((IkReal(0.707103562373095))*(sj4));
03017 IkReal x841=((IkReal(0.707103562373095))*(cj4));
03018 IkReal x842=((sj2)*(x841));
03019 if( IKabs(((gconst22)*(((((x838)*(x839)))+(((IkReal(-1.00000000000000))*(sj2)*(x836)*(x838)))+(((x839)*(x840)))+(((x835)*(x841)))+(((IkReal(-1.00000000000000))*(sj2)*(x836)*(x840)))+(((cj2)*(x834)*(x837)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x841)))+(((cj2)*(x836)*(x841)))+(((IkReal(-1.00000000000000))*(x834)*(x835)))+(((sj2)*(x837)*(x838)))+(((IkReal(-1.00000000000000))*(cj2)*(x834)*(x836)))+(((sj2)*(x837)*(x840))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst22)*(((((sj2)*(x834)*(x837)))+(((x835)*(x840)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x838)))+(((x835)*(x838)))+(((cj2)*(x836)*(x838)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x840)))+(((IkReal(-1.00000000000000))*(x837)*(x842)))+(((cj2)*(x836)*(x840)))+(((x836)*(x842)))+(((x834)*(x839)))+(((IkReal(-1.00000000000000))*(x839)*(x841)))+(((IkReal(-1.00000000000000))*(sj2)*(x834)*(x836))))))) < IKFAST_ATAN2_MAGTHRESH )
03020     continue;
03021 j1array[0]=IKatan2(((gconst22)*(((((x838)*(x839)))+(((IkReal(-1.00000000000000))*(sj2)*(x836)*(x838)))+(((x839)*(x840)))+(((x835)*(x841)))+(((IkReal(-1.00000000000000))*(sj2)*(x836)*(x840)))+(((cj2)*(x834)*(x837)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x841)))+(((cj2)*(x836)*(x841)))+(((IkReal(-1.00000000000000))*(x834)*(x835)))+(((sj2)*(x837)*(x838)))+(((IkReal(-1.00000000000000))*(cj2)*(x834)*(x836)))+(((sj2)*(x837)*(x840)))))), ((gconst22)*(((((sj2)*(x834)*(x837)))+(((x835)*(x840)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x838)))+(((x835)*(x838)))+(((cj2)*(x836)*(x838)))+(((IkReal(-1.00000000000000))*(cj2)*(x837)*(x840)))+(((IkReal(-1.00000000000000))*(x837)*(x842)))+(((cj2)*(x836)*(x840)))+(((x836)*(x842)))+(((x834)*(x839)))+(((IkReal(-1.00000000000000))*(x839)*(x841)))+(((IkReal(-1.00000000000000))*(sj2)*(x834)*(x836)))))));
03022 sj1array[0]=IKsin(j1array[0]);
03023 cj1array[0]=IKcos(j1array[0]);
03024 if( j1array[0] > IKPI )
03025 {
03026     j1array[0]-=IK2PI;
03027 }
03028 else if( j1array[0] < -IKPI )
03029 {    j1array[0]+=IK2PI;
03030 }
03031 j1valid[0] = true;
03032 for(int ij1 = 0; ij1 < 1; ++ij1)
03033 {
03034 if( !j1valid[ij1] )
03035 {
03036     continue;
03037 }
03038 _ij1[0] = ij1; _ij1[1] = -1;
03039 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03040 {
03041 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03042 {
03043     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03044 }
03045 }
03046 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03047 {
03048 IkReal evalcond[2];
03049 IkReal x843=IKsin(j1);
03050 IkReal x844=IKcos(j1);
03051 IkReal x845=((cj5)*(r20));
03052 IkReal x846=((r21)*(sj5));
03053 IkReal x847=((IkReal(0.707103562373095))*(x843));
03054 IkReal x848=((IkReal(0.707109999985348))*(x843));
03055 IkReal x849=((IkReal(0.707103562373095))*(x844));
03056 IkReal x850=((IkReal(0.707109999985348))*(x844));
03057 evalcond[0]=((((cj4)*(r22)))+(((sj2)*(x850)))+(((sj4)*(x846)))+(((IkReal(-1.00000000000000))*(sj4)*(x845)))+(((sj2)*(x847)))+(((cj2)*(x848)))+(((IkReal(-1.00000000000000))*(cj2)*(x849))));
03058 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)*(x848)))+(((IkReal(-1.00000000000000))*(cj4)*(x846)))+(((r22)*(sj4)))+(((cj2)*(x850)))+(((cj4)*(x845)))+(((sj2)*(x849)))+(((cj2)*(x847))));
03059 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
03060 {
03061 continue;
03062 }
03063 }
03064 
03065 {
03066 IkReal dummyeval[1];
03067 IkReal gconst23;
03068 IkReal x851=(cj5)*(cj5);
03069 IkReal x852=(sj5)*(sj5);
03070 IkReal x853=((IkReal(2.00000000000000))*(cj5)*(sj5));
03071 gconst23=IKsign(((((r00)*(r01)*(x853)))+(((x852)*((r10)*(r10))))+(((x851)*((r01)*(r01))))+(((r10)*(r11)*(x853)))+(((x851)*((r11)*(r11))))+(((x852)*((r00)*(r00))))));
03072 IkReal x854=(cj5)*(cj5);
03073 IkReal x855=(sj5)*(sj5);
03074 IkReal x856=((IkReal(2.00000000000000))*(cj5)*(sj5));
03075 dummyeval[0]=((((r00)*(r01)*(x856)))+(((x854)*((r11)*(r11))))+(((x855)*((r00)*(r00))))+(((x854)*((r01)*(r01))))+(((r10)*(r11)*(x856)))+(((x855)*((r10)*(r10)))));
03076 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03077 {
03078 {
03079 IkReal dummyeval[1];
03080 IkReal gconst24;
03081 IkReal x857=(cj5)*(cj5);
03082 IkReal x858=(sj5)*(sj5);
03083 IkReal x859=((IkReal(1.00000000000000))*(r10));
03084 IkReal x860=((cj4)*(sj5));
03085 IkReal x861=((r00)*(r11));
03086 IkReal x862=((cj4)*(cj5));
03087 IkReal x863=((sj4)*(x857));
03088 IkReal x864=((sj4)*(x858));
03089 gconst24=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x859)*(x864)))+(((IkReal(-1.00000000000000))*(r01)*(x859)*(x863)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x862)))+(((IkReal(-1.00000000000000))*(r02)*(x859)*(x860)))+(((r01)*(r12)*(x862)))+(((x861)*(x863)))+(((x861)*(x864)))+(((r00)*(r12)*(x860)))));
03090 IkReal x865=(cj5)*(cj5);
03091 IkReal x866=(sj5)*(sj5);
03092 IkReal x867=((IkReal(1.00000000000000))*(r10));
03093 IkReal x868=((cj4)*(sj5));
03094 IkReal x869=((r00)*(r11));
03095 IkReal x870=((cj4)*(cj5));
03096 IkReal x871=((sj4)*(x865));
03097 IkReal x872=((sj4)*(x866));
03098 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(r11)*(x870)))+(((r01)*(r12)*(x870)))+(((x869)*(x871)))+(((x869)*(x872)))+(((r00)*(r12)*(x868)))+(((IkReal(-1.00000000000000))*(r01)*(x867)*(x871)))+(((IkReal(-1.00000000000000))*(r01)*(x867)*(x872)))+(((IkReal(-1.00000000000000))*(r02)*(x867)*(x868))));
03099 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03100 {
03101 continue;
03102 
03103 } else
03104 {
03105 {
03106 IkReal j0array[1], cj0array[1], sj0array[1];
03107 bool j0valid[1]={false};
03108 _nj0 = 1;
03109 IkReal x873=((cj5)*(sj4));
03110 IkReal x874=((IkReal(1.00000000000000))*(cj4));
03111 IkReal x875=((IkReal(1.00000000000000))*(sj4)*(sj5));
03112 if( IKabs(((gconst24)*(((((IkReal(-1.00000000000000))*(r12)*(x874)))+(((r10)*(x873)))+(((IkReal(-1.00000000000000))*(r11)*(x875))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst24)*(((((r00)*(x873)))+(((IkReal(-1.00000000000000))*(r01)*(x875)))+(((IkReal(-1.00000000000000))*(r02)*(x874))))))) < IKFAST_ATAN2_MAGTHRESH )
03113     continue;
03114 j0array[0]=IKatan2(((gconst24)*(((((IkReal(-1.00000000000000))*(r12)*(x874)))+(((r10)*(x873)))+(((IkReal(-1.00000000000000))*(r11)*(x875)))))), ((gconst24)*(((((r00)*(x873)))+(((IkReal(-1.00000000000000))*(r01)*(x875)))+(((IkReal(-1.00000000000000))*(r02)*(x874)))))));
03115 sj0array[0]=IKsin(j0array[0]);
03116 cj0array[0]=IKcos(j0array[0]);
03117 if( j0array[0] > IKPI )
03118 {
03119     j0array[0]-=IK2PI;
03120 }
03121 else if( j0array[0] < -IKPI )
03122 {    j0array[0]+=IK2PI;
03123 }
03124 j0valid[0] = true;
03125 for(int ij0 = 0; ij0 < 1; ++ij0)
03126 {
03127 if( !j0valid[ij0] )
03128 {
03129     continue;
03130 }
03131 _ij0[0] = ij0; _ij0[1] = -1;
03132 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03133 {
03134 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03135 {
03136     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03137 }
03138 }
03139 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03140 {
03141 IkReal evalcond[6];
03142 IkReal x876=IKsin(j0);
03143 IkReal x877=IKcos(j0);
03144 IkReal x878=((IkReal(0.707103562373095))*(cj2));
03145 IkReal x879=((cj5)*(sj4));
03146 IkReal x880=((IkReal(1.00000000000000))*(sj4));
03147 IkReal x881=((IkReal(1.00000000000000))*(r10));
03148 IkReal x882=((IkReal(1.00000000000000))*(cj5));
03149 IkReal x883=((IkReal(1.00000000000000))*(cj4));
03150 IkReal x884=((sj1)*(sj2));
03151 IkReal x885=((IkReal(0.707109999985348))*(cj1));
03152 IkReal x886=((cj4)*(r11));
03153 IkReal x887=((sj5)*(x876));
03154 IkReal x888=((r10)*(x876));
03155 IkReal x889=((r01)*(x877));
03156 IkReal x890=((r00)*(x877));
03157 IkReal x891=((r02)*(x877));
03158 IkReal x892=((r12)*(x877));
03159 IkReal x893=((cj5)*(x876));
03160 IkReal x894=((r12)*(x876));
03161 IkReal x895=((sj5)*(x877));
03162 IkReal x896=((r02)*(x876));
03163 evalcond[0]=((IkReal(1.00000000000000))+(((r00)*(x887)))+(((r01)*(x893)))+(((IkReal(-1.00000000000000))*(x881)*(x895)))+(((IkReal(-1.00000000000000))*(r11)*(x877)*(x882))));
03164 evalcond[1]=((((IkReal(-1.00000000000000))*(x883)*(x892)))+(((r10)*(x877)*(x879)))+(((r01)*(sj4)*(x887)))+(((IkReal(-1.00000000000000))*(r11)*(x880)*(x895)))+(((cj4)*(x896)))+(((IkReal(-1.00000000000000))*(r00)*(x876)*(x879))));
03165 evalcond[2]=((((x886)*(x895)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x877)*(x881)))+(((sj4)*(x896)))+(((cj4)*(r00)*(x893)))+(((IkReal(-1.00000000000000))*(r01)*(x883)*(x887)))+(((IkReal(-1.00000000000000))*(x880)*(x892))));
03166 evalcond[3]=((((IkReal(-1.00000000000000))*(x882)*(x889)))+(((IkReal(-1.00000000000000))*(x881)*(x887)))+(((IkReal(-1.00000000000000))*(r11)*(x876)*(x882)))+(((IkReal(-1.00000000000000))*(sj5)*(x890))));
03167 evalcond[4]=((((cj2)*(x885)))+(((x879)*(x888)))+(((IkReal(-1.00000000000000))*(x883)*(x891)))+(((IkReal(-1.00000000000000))*(x883)*(x894)))+(((x879)*(x890)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r11)*(x880)*(x887)))+(((sj1)*(x878)))+(((IkReal(-0.707109999985348))*(x884)))+(((IkReal(-1.00000000000000))*(sj5)*(x880)*(x889))));
03168 evalcond[5]=((((x886)*(x887)))+(((IkReal(-1.00000000000000))*(cj4)*(x882)*(x890)))+(((IkReal(-0.707109999985348))*(cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(cj4)*(x881)*(x893)))+(((cj4)*(sj5)*(x889)))+(((cj1)*(x878)))+(((IkReal(-1.00000000000000))*(sj2)*(x885)))+(((IkReal(-1.00000000000000))*(x880)*(x894)))+(((IkReal(-1.00000000000000))*(x880)*(x891)))+(((IkReal(-0.707103562373095))*(x884))));
03169 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  )
03170 {
03171 continue;
03172 }
03173 }
03174 
03175 {
03176 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03177 vinfos[0].jointtype = 1;
03178 vinfos[0].foffset = j0;
03179 vinfos[0].indices[0] = _ij0[0];
03180 vinfos[0].indices[1] = _ij0[1];
03181 vinfos[0].maxsolutions = _nj0;
03182 vinfos[1].jointtype = 1;
03183 vinfos[1].foffset = j1;
03184 vinfos[1].indices[0] = _ij1[0];
03185 vinfos[1].indices[1] = _ij1[1];
03186 vinfos[1].maxsolutions = _nj1;
03187 vinfos[2].jointtype = 1;
03188 vinfos[2].foffset = j2;
03189 vinfos[2].indices[0] = _ij2[0];
03190 vinfos[2].indices[1] = _ij2[1];
03191 vinfos[2].maxsolutions = _nj2;
03192 vinfos[3].jointtype = 1;
03193 vinfos[3].foffset = j3;
03194 vinfos[3].indices[0] = _ij3[0];
03195 vinfos[3].indices[1] = _ij3[1];
03196 vinfos[3].maxsolutions = _nj3;
03197 vinfos[4].jointtype = 1;
03198 vinfos[4].foffset = j4;
03199 vinfos[4].indices[0] = _ij4[0];
03200 vinfos[4].indices[1] = _ij4[1];
03201 vinfos[4].maxsolutions = _nj4;
03202 vinfos[5].jointtype = 1;
03203 vinfos[5].foffset = j5;
03204 vinfos[5].indices[0] = _ij5[0];
03205 vinfos[5].indices[1] = _ij5[1];
03206 vinfos[5].maxsolutions = _nj5;
03207 std::vector<int> vfree(0);
03208 solutions.AddSolution(vinfos,vfree);
03209 }
03210 }
03211 }
03212 
03213 }
03214 
03215 }
03216 
03217 } else
03218 {
03219 {
03220 IkReal j0array[1], cj0array[1], sj0array[1];
03221 bool j0valid[1]={false};
03222 _nj0 = 1;
03223 if( IKabs(((gconst23)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst23)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
03224     continue;
03225 j0array[0]=IKatan2(((gconst23)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst23)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
03226 sj0array[0]=IKsin(j0array[0]);
03227 cj0array[0]=IKcos(j0array[0]);
03228 if( j0array[0] > IKPI )
03229 {
03230     j0array[0]-=IK2PI;
03231 }
03232 else if( j0array[0] < -IKPI )
03233 {    j0array[0]+=IK2PI;
03234 }
03235 j0valid[0] = true;
03236 for(int ij0 = 0; ij0 < 1; ++ij0)
03237 {
03238 if( !j0valid[ij0] )
03239 {
03240     continue;
03241 }
03242 _ij0[0] = ij0; _ij0[1] = -1;
03243 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03244 {
03245 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03246 {
03247     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03248 }
03249 }
03250 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03251 {
03252 IkReal evalcond[6];
03253 IkReal x897=IKsin(j0);
03254 IkReal x898=IKcos(j0);
03255 IkReal x899=((IkReal(0.707103562373095))*(cj2));
03256 IkReal x900=((cj5)*(sj4));
03257 IkReal x901=((IkReal(1.00000000000000))*(sj4));
03258 IkReal x902=((IkReal(1.00000000000000))*(r10));
03259 IkReal x903=((IkReal(1.00000000000000))*(cj5));
03260 IkReal x904=((IkReal(1.00000000000000))*(cj4));
03261 IkReal x905=((sj1)*(sj2));
03262 IkReal x906=((IkReal(0.707109999985348))*(cj1));
03263 IkReal x907=((cj4)*(r11));
03264 IkReal x908=((sj5)*(x897));
03265 IkReal x909=((r10)*(x897));
03266 IkReal x910=((r01)*(x898));
03267 IkReal x911=((r00)*(x898));
03268 IkReal x912=((r02)*(x898));
03269 IkReal x913=((r12)*(x898));
03270 IkReal x914=((cj5)*(x897));
03271 IkReal x915=((r12)*(x897));
03272 IkReal x916=((sj5)*(x898));
03273 IkReal x917=((r02)*(x897));
03274 evalcond[0]=((IkReal(1.00000000000000))+(((r00)*(x908)))+(((IkReal(-1.00000000000000))*(r11)*(x898)*(x903)))+(((IkReal(-1.00000000000000))*(x902)*(x916)))+(((r01)*(x914))));
03275 evalcond[1]=((((r01)*(sj4)*(x908)))+(((r10)*(x898)*(x900)))+(((cj4)*(x917)))+(((IkReal(-1.00000000000000))*(x904)*(x913)))+(((IkReal(-1.00000000000000))*(r11)*(x901)*(x916)))+(((IkReal(-1.00000000000000))*(r00)*(x897)*(x900))));
03276 evalcond[2]=((((x907)*(x916)))+(((IkReal(-1.00000000000000))*(r01)*(x904)*(x908)))+(((cj4)*(r00)*(x914)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x898)*(x902)))+(((sj4)*(x917)))+(((IkReal(-1.00000000000000))*(x901)*(x913))));
03277 evalcond[3]=((((IkReal(-1.00000000000000))*(x902)*(x908)))+(((IkReal(-1.00000000000000))*(sj5)*(x911)))+(((IkReal(-1.00000000000000))*(r11)*(x897)*(x903)))+(((IkReal(-1.00000000000000))*(x903)*(x910))));
03278 evalcond[4]=((((IkReal(-1.00000000000000))*(sj5)*(x901)*(x910)))+(((sj1)*(x899)))+(((IkReal(-0.707109999985348))*(x905)))+(((cj2)*(x906)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((x900)*(x909)))+(((x900)*(x911)))+(((IkReal(-1.00000000000000))*(x904)*(x912)))+(((IkReal(-1.00000000000000))*(x904)*(x915)))+(((IkReal(-1.00000000000000))*(r11)*(x901)*(x908))));
03279 evalcond[5]=((((cj4)*(sj5)*(x910)))+(((IkReal(-0.707109999985348))*(cj2)*(sj1)))+(((x907)*(x908)))+(((IkReal(-1.00000000000000))*(sj2)*(x906)))+(((IkReal(-0.707103562373095))*(x905)))+(((cj1)*(x899)))+(((IkReal(-1.00000000000000))*(cj4)*(x902)*(x914)))+(((IkReal(-1.00000000000000))*(cj4)*(x903)*(x911)))+(((IkReal(-1.00000000000000))*(x901)*(x915)))+(((IkReal(-1.00000000000000))*(x901)*(x912))));
03280 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  )
03281 {
03282 continue;
03283 }
03284 }
03285 
03286 {
03287 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03288 vinfos[0].jointtype = 1;
03289 vinfos[0].foffset = j0;
03290 vinfos[0].indices[0] = _ij0[0];
03291 vinfos[0].indices[1] = _ij0[1];
03292 vinfos[0].maxsolutions = _nj0;
03293 vinfos[1].jointtype = 1;
03294 vinfos[1].foffset = j1;
03295 vinfos[1].indices[0] = _ij1[0];
03296 vinfos[1].indices[1] = _ij1[1];
03297 vinfos[1].maxsolutions = _nj1;
03298 vinfos[2].jointtype = 1;
03299 vinfos[2].foffset = j2;
03300 vinfos[2].indices[0] = _ij2[0];
03301 vinfos[2].indices[1] = _ij2[1];
03302 vinfos[2].maxsolutions = _nj2;
03303 vinfos[3].jointtype = 1;
03304 vinfos[3].foffset = j3;
03305 vinfos[3].indices[0] = _ij3[0];
03306 vinfos[3].indices[1] = _ij3[1];
03307 vinfos[3].maxsolutions = _nj3;
03308 vinfos[4].jointtype = 1;
03309 vinfos[4].foffset = j4;
03310 vinfos[4].indices[0] = _ij4[0];
03311 vinfos[4].indices[1] = _ij4[1];
03312 vinfos[4].maxsolutions = _nj4;
03313 vinfos[5].jointtype = 1;
03314 vinfos[5].foffset = j5;
03315 vinfos[5].indices[0] = _ij5[0];
03316 vinfos[5].indices[1] = _ij5[1];
03317 vinfos[5].maxsolutions = _nj5;
03318 std::vector<int> vfree(0);
03319 solutions.AddSolution(vinfos,vfree);
03320 }
03321 }
03322 }
03323 
03324 }
03325 
03326 }
03327 }
03328 }
03329 
03330 }
03331 
03332 }
03333 
03334 } else
03335 {
03336 {
03337 IkReal j0array[1], cj0array[1], sj0array[1];
03338 bool j0valid[1]={false};
03339 _nj0 = 1;
03340 IkReal x918=((IkReal(1.00000000000000))*(cj4));
03341 IkReal x919=((cj5)*(sj4));
03342 IkReal x920=((IkReal(1.00000000000000))*(sj4)*(sj5));
03343 if( IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(r11)*(x920)))+(((r10)*(x919)))+(((IkReal(-1.00000000000000))*(r12)*(x918))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(r02)*(x918)))+(((IkReal(-1.00000000000000))*(r01)*(x920)))+(((r00)*(x919))))))) < IKFAST_ATAN2_MAGTHRESH )
03344     continue;
03345 j0array[0]=IKatan2(((gconst21)*(((((IkReal(-1.00000000000000))*(r11)*(x920)))+(((r10)*(x919)))+(((IkReal(-1.00000000000000))*(r12)*(x918)))))), ((gconst21)*(((((IkReal(-1.00000000000000))*(r02)*(x918)))+(((IkReal(-1.00000000000000))*(r01)*(x920)))+(((r00)*(x919)))))));
03346 sj0array[0]=IKsin(j0array[0]);
03347 cj0array[0]=IKcos(j0array[0]);
03348 if( j0array[0] > IKPI )
03349 {
03350     j0array[0]-=IK2PI;
03351 }
03352 else if( j0array[0] < -IKPI )
03353 {    j0array[0]+=IK2PI;
03354 }
03355 j0valid[0] = true;
03356 for(int ij0 = 0; ij0 < 1; ++ij0)
03357 {
03358 if( !j0valid[ij0] )
03359 {
03360     continue;
03361 }
03362 _ij0[0] = ij0; _ij0[1] = -1;
03363 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03364 {
03365 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03366 {
03367     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03368 }
03369 }
03370 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03371 {
03372 IkReal evalcond[4];
03373 IkReal x921=IKsin(j0);
03374 IkReal x922=IKcos(j0);
03375 IkReal x923=((IkReal(1.00000000000000))*(cj5));
03376 IkReal x924=((r01)*(sj5));
03377 IkReal x925=((IkReal(1.00000000000000))*(r12));
03378 IkReal x926=((r11)*(sj5));
03379 IkReal x927=((IkReal(1.00000000000000))*(r10));
03380 IkReal x928=((cj4)*(x921));
03381 IkReal x929=((sj4)*(x921));
03382 IkReal x930=((sj4)*(x922));
03383 IkReal x931=((sj5)*(x921));
03384 IkReal x932=((cj4)*(x922));
03385 IkReal x933=((sj5)*(x922));
03386 evalcond[0]=((IkReal(1.00000000000000))+(((cj5)*(r01)*(x921)))+(((IkReal(-1.00000000000000))*(r11)*(x922)*(x923)))+(((IkReal(-1.00000000000000))*(x927)*(x933)))+(((r00)*(x931))));
03387 evalcond[1]=((((IkReal(-1.00000000000000))*(x925)*(x932)))+(((x924)*(x929)))+(((IkReal(-1.00000000000000))*(r00)*(x923)*(x929)))+(((cj5)*(r10)*(x930)))+(((IkReal(-1.00000000000000))*(x926)*(x930)))+(((r02)*(x928))));
03388 evalcond[2]=((((IkReal(-1.00000000000000))*(x925)*(x930)))+(((cj5)*(r00)*(x928)))+(((IkReal(-1.00000000000000))*(r10)*(x923)*(x932)))+(((x926)*(x932)))+(((r02)*(x929)))+(((IkReal(-1.00000000000000))*(x924)*(x928))));
03389 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x922)*(x923)))+(((IkReal(-1.00000000000000))*(r11)*(x921)*(x923)))+(((IkReal(-1.00000000000000))*(x927)*(x931)))+(((IkReal(-1.00000000000000))*(r00)*(x933))));
03390 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03391 {
03392 continue;
03393 }
03394 }
03395 
03396 {
03397 IkReal dummyeval[1];
03398 IkReal gconst25;
03399 gconst25=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
03400 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
03401 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03402 {
03403 {
03404 IkReal dummyeval[1];
03405 IkReal gconst26;
03406 gconst26=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
03407 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
03408 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03409 {
03410 continue;
03411 
03412 } else
03413 {
03414 {
03415 IkReal j1array[1], cj1array[1], sj1array[1];
03416 bool j1valid[1]={false};
03417 _nj1 = 1;
03418 IkReal x934=((sj4)*(sj5));
03419 IkReal x935=((IkReal(0.707103562373095))*(sj0));
03420 IkReal x936=((r11)*(sj2));
03421 IkReal x937=((cj2)*(cj4));
03422 IkReal x938=((IkReal(0.707103562373095))*(r22));
03423 IkReal x939=((IkReal(0.707109999985348))*(cj0));
03424 IkReal x940=((cj2)*(r01));
03425 IkReal x941=((IkReal(0.707109999985348))*(cj2));
03426 IkReal x942=((IkReal(0.707109999985348))*(sj0));
03427 IkReal x943=((r21)*(sj2));
03428 IkReal x944=((IkReal(0.707103562373095))*(cj2));
03429 IkReal x945=((IkReal(0.707103562373095))*(sj2));
03430 IkReal x946=((cj5)*(sj4));
03431 IkReal x947=((r10)*(sj2));
03432 IkReal x948=((cj0)*(r00));
03433 IkReal x949=((IkReal(0.707103562373095))*(cj0));
03434 IkReal x950=((cj4)*(sj2));
03435 IkReal x951=((IkReal(0.707109999985348))*(r22));
03436 IkReal x952=((r02)*(x950));
03437 IkReal x953=((r20)*(x946));
03438 if( IKabs(((gconst26)*(((((r01)*(sj2)*(x934)*(x939)))+(((IkReal(-1.00000000000000))*(x942)*(x946)*(x947)))+(((x934)*(x936)*(x942)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x934)*(x935)))+(((r12)*(x942)*(x950)))+(((IkReal(-1.00000000000000))*(r12)*(x935)*(x937)))+(((IkReal(-1.00000000000000))*(x941)*(x953)))+(((x944)*(x946)*(x948)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x939)*(x946)))+(((IkReal(0.707103562373095))*(x934)*(x943)))+(((cj2)*(r10)*(x935)*(x946)))+(((IkReal(-1.00000000000000))*(x945)*(x953)))+(((x938)*(x950)))+(((r21)*(x934)*(x941)))+(((x939)*(x952)))+(((IkReal(-1.00000000000000))*(r02)*(x937)*(x949)))+(((IkReal(-1.00000000000000))*(x934)*(x940)*(x949)))+(((x937)*(x951))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(r21)*(x934)*(x944)))+(((x945)*(x946)*(x948)))+(((x944)*(x953)))+(((cj2)*(r00)*(x939)*(x946)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x945)))+(((IkReal(-1.00000000000000))*(x934)*(x935)*(x936)))+(((IkReal(0.707109999985348))*(x934)*(x943)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x934)*(x941)))+(((IkReal(-1.00000000000000))*(x934)*(x939)*(x940)))+(((IkReal(-1.00000000000000))*(r12)*(x937)*(x942)))+(((r10)*(sj0)*(x941)*(x946)))+(((IkReal(-0.707109999985348))*(sj2)*(x953)))+(((x935)*(x946)*(x947)))+(((IkReal(-1.00000000000000))*(x937)*(x938)))+(((x950)*(x951)))+(((IkReal(-1.00000000000000))*(r02)*(x937)*(x939)))+(((IkReal(-1.00000000000000))*(r12)*(x935)*(x950)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x934)*(x945))))))) < IKFAST_ATAN2_MAGTHRESH )
03439     continue;
03440 j1array[0]=IKatan2(((gconst26)*(((((r01)*(sj2)*(x934)*(x939)))+(((IkReal(-1.00000000000000))*(x942)*(x946)*(x947)))+(((x934)*(x936)*(x942)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x934)*(x935)))+(((r12)*(x942)*(x950)))+(((IkReal(-1.00000000000000))*(r12)*(x935)*(x937)))+(((IkReal(-1.00000000000000))*(x941)*(x953)))+(((x944)*(x946)*(x948)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x939)*(x946)))+(((IkReal(0.707103562373095))*(x934)*(x943)))+(((cj2)*(r10)*(x935)*(x946)))+(((IkReal(-1.00000000000000))*(x945)*(x953)))+(((x938)*(x950)))+(((r21)*(x934)*(x941)))+(((x939)*(x952)))+(((IkReal(-1.00000000000000))*(r02)*(x937)*(x949)))+(((IkReal(-1.00000000000000))*(x934)*(x940)*(x949)))+(((x937)*(x951)))))), ((gconst26)*(((((IkReal(-1.00000000000000))*(r21)*(x934)*(x944)))+(((x945)*(x946)*(x948)))+(((x944)*(x953)))+(((cj2)*(r00)*(x939)*(x946)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x945)))+(((IkReal(-1.00000000000000))*(x934)*(x935)*(x936)))+(((IkReal(0.707109999985348))*(x934)*(x943)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x934)*(x941)))+(((IkReal(-1.00000000000000))*(x934)*(x939)*(x940)))+(((IkReal(-1.00000000000000))*(r12)*(x937)*(x942)))+(((r10)*(sj0)*(x941)*(x946)))+(((IkReal(-0.707109999985348))*(sj2)*(x953)))+(((x935)*(x946)*(x947)))+(((IkReal(-1.00000000000000))*(x937)*(x938)))+(((x950)*(x951)))+(((IkReal(-1.00000000000000))*(r02)*(x937)*(x939)))+(((IkReal(-1.00000000000000))*(r12)*(x935)*(x950)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x934)*(x945)))))));
03441 sj1array[0]=IKsin(j1array[0]);
03442 cj1array[0]=IKcos(j1array[0]);
03443 if( j1array[0] > IKPI )
03444 {
03445     j1array[0]-=IK2PI;
03446 }
03447 else if( j1array[0] < -IKPI )
03448 {    j1array[0]+=IK2PI;
03449 }
03450 j1valid[0] = true;
03451 for(int ij1 = 0; ij1 < 1; ++ij1)
03452 {
03453 if( !j1valid[ij1] )
03454 {
03455     continue;
03456 }
03457 _ij1[0] = ij1; _ij1[1] = -1;
03458 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03459 {
03460 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03461 {
03462     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03463 }
03464 }
03465 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03466 {
03467 IkReal evalcond[4];
03468 IkReal x954=IKsin(j1);
03469 IkReal x955=IKcos(j1);
03470 IkReal x956=((IkReal(0.707109999985348))*(cj2));
03471 IkReal x957=((IkReal(1.00000000000000))*(sj4));
03472 IkReal x958=((cj5)*(r00));
03473 IkReal x959=((IkReal(0.707109999985348))*(sj2));
03474 IkReal x960=((cj5)*(r20));
03475 IkReal x961=((r12)*(sj0));
03476 IkReal x962=((r21)*(sj5));
03477 IkReal x963=((IkReal(1.00000000000000))*(cj4));
03478 IkReal x964=((IkReal(0.707103562373095))*(x955));
03479 IkReal x965=((r11)*(sj0)*(sj5));
03480 IkReal x966=((cj0)*(x963));
03481 IkReal x967=((IkReal(0.707103562373095))*(x954));
03482 IkReal x968=((cj0)*(r01)*(sj5));
03483 IkReal x969=((cj5)*(r10)*(sj0));
03484 IkReal x970=((sj2)*(x964));
03485 IkReal x971=((cj2)*(x967));
03486 IkReal x972=((x955)*(x956));
03487 IkReal x973=((x954)*(x959));
03488 IkReal x974=((cj2)*(x964));
03489 IkReal x975=((x954)*(x956));
03490 IkReal x976=((sj2)*(x967));
03491 IkReal x977=((x955)*(x959));
03492 IkReal x978=((x971)+(x970)+(x972));
03493 IkReal x979=((x975)+(x977)+(x976));
03494 evalcond[0]=((((cj4)*(r22)))+(((sj4)*(x962)))+(((IkReal(-1.00000000000000))*(x957)*(x960)))+(x979)+(((IkReal(-1.00000000000000))*(x974))));
03495 evalcond[1]=((((IkReal(-1.00000000000000))*(x962)*(x963)))+(((r22)*(sj4)))+(x978)+(((IkReal(-1.00000000000000))*(x973)))+(((cj4)*(x960))));
03496 evalcond[2]=((((IkReal(-1.00000000000000))*(x961)*(x963)))+(((sj4)*(x969)))+(((IkReal(-1.00000000000000))*(x957)*(x968)))+(((IkReal(-1.00000000000000))*(x957)*(x965)))+(((cj0)*(sj4)*(x958)))+(x978)+(((IkReal(-1.00000000000000))*(x973)))+(((IkReal(-1.00000000000000))*(r02)*(x966))));
03497 evalcond[3]=((((IkReal(-1.00000000000000))*(x963)*(x969)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x957)))+(((IkReal(-1.00000000000000))*(x958)*(x966)))+(((IkReal(-1.00000000000000))*(x957)*(x961)))+(x974)+(((IkReal(-1.00000000000000))*(x979)))+(((cj4)*(x965)))+(((cj4)*(x968))));
03498 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03499 {
03500 continue;
03501 }
03502 }
03503 
03504 {
03505 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03506 vinfos[0].jointtype = 1;
03507 vinfos[0].foffset = j0;
03508 vinfos[0].indices[0] = _ij0[0];
03509 vinfos[0].indices[1] = _ij0[1];
03510 vinfos[0].maxsolutions = _nj0;
03511 vinfos[1].jointtype = 1;
03512 vinfos[1].foffset = j1;
03513 vinfos[1].indices[0] = _ij1[0];
03514 vinfos[1].indices[1] = _ij1[1];
03515 vinfos[1].maxsolutions = _nj1;
03516 vinfos[2].jointtype = 1;
03517 vinfos[2].foffset = j2;
03518 vinfos[2].indices[0] = _ij2[0];
03519 vinfos[2].indices[1] = _ij2[1];
03520 vinfos[2].maxsolutions = _nj2;
03521 vinfos[3].jointtype = 1;
03522 vinfos[3].foffset = j3;
03523 vinfos[3].indices[0] = _ij3[0];
03524 vinfos[3].indices[1] = _ij3[1];
03525 vinfos[3].maxsolutions = _nj3;
03526 vinfos[4].jointtype = 1;
03527 vinfos[4].foffset = j4;
03528 vinfos[4].indices[0] = _ij4[0];
03529 vinfos[4].indices[1] = _ij4[1];
03530 vinfos[4].maxsolutions = _nj4;
03531 vinfos[5].jointtype = 1;
03532 vinfos[5].foffset = j5;
03533 vinfos[5].indices[0] = _ij5[0];
03534 vinfos[5].indices[1] = _ij5[1];
03535 vinfos[5].maxsolutions = _nj5;
03536 std::vector<int> vfree(0);
03537 solutions.AddSolution(vinfos,vfree);
03538 }
03539 }
03540 }
03541 
03542 }
03543 
03544 }
03545 
03546 } else
03547 {
03548 {
03549 IkReal j1array[1], cj1array[1], sj1array[1];
03550 bool j1valid[1]={false};
03551 _nj1 = 1;
03552 IkReal x980=((IkReal(0.707109999985348))*(sj4));
03553 IkReal x981=((r22)*(sj2));
03554 IkReal x982=((cj5)*(r20));
03555 IkReal x983=((r21)*(sj5));
03556 IkReal x984=((IkReal(0.707109999985348))*(cj4));
03557 IkReal x985=((cj2)*(r22));
03558 IkReal x986=((IkReal(0.707103562373095))*(sj4));
03559 IkReal x987=((IkReal(0.707103562373095))*(cj4));
03560 IkReal x988=((sj2)*(x987));
03561 IkReal x989=((cj2)*(x987));
03562 if( IKabs(((gconst25)*(((((x981)*(x987)))+(((IkReal(-1.00000000000000))*(cj2)*(x980)*(x982)))+(((x982)*(x989)))+(((cj2)*(x980)*(x983)))+(((IkReal(-1.00000000000000))*(sj2)*(x982)*(x984)))+(((IkReal(-1.00000000000000))*(sj2)*(x982)*(x986)))+(((IkReal(-1.00000000000000))*(x980)*(x981)))+(((x984)*(x985)))+(((x985)*(x986)))+(((IkReal(-1.00000000000000))*(x983)*(x989)))+(((sj2)*(x983)*(x986)))+(((sj2)*(x983)*(x984))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((x981)*(x986)))+(((x981)*(x984)))+(((IkReal(-1.00000000000000))*(sj2)*(x980)*(x982)))+(((cj2)*(x982)*(x986)))+(((cj2)*(x982)*(x984)))+(((IkReal(-1.00000000000000))*(cj2)*(x983)*(x986)))+(((IkReal(-1.00000000000000))*(cj2)*(x983)*(x984)))+(((x982)*(x988)))+(((sj2)*(x980)*(x983)))+(((x980)*(x985)))+(((IkReal(-1.00000000000000))*(x985)*(x987)))+(((IkReal(-1.00000000000000))*(x983)*(x988))))))) < IKFAST_ATAN2_MAGTHRESH )
03563     continue;
03564 j1array[0]=IKatan2(((gconst25)*(((((x981)*(x987)))+(((IkReal(-1.00000000000000))*(cj2)*(x980)*(x982)))+(((x982)*(x989)))+(((cj2)*(x980)*(x983)))+(((IkReal(-1.00000000000000))*(sj2)*(x982)*(x984)))+(((IkReal(-1.00000000000000))*(sj2)*(x982)*(x986)))+(((IkReal(-1.00000000000000))*(x980)*(x981)))+(((x984)*(x985)))+(((x985)*(x986)))+(((IkReal(-1.00000000000000))*(x983)*(x989)))+(((sj2)*(x983)*(x986)))+(((sj2)*(x983)*(x984)))))), ((gconst25)*(((((x981)*(x986)))+(((x981)*(x984)))+(((IkReal(-1.00000000000000))*(sj2)*(x980)*(x982)))+(((cj2)*(x982)*(x986)))+(((cj2)*(x982)*(x984)))+(((IkReal(-1.00000000000000))*(cj2)*(x983)*(x986)))+(((IkReal(-1.00000000000000))*(cj2)*(x983)*(x984)))+(((x982)*(x988)))+(((sj2)*(x980)*(x983)))+(((x980)*(x985)))+(((IkReal(-1.00000000000000))*(x985)*(x987)))+(((IkReal(-1.00000000000000))*(x983)*(x988)))))));
03565 sj1array[0]=IKsin(j1array[0]);
03566 cj1array[0]=IKcos(j1array[0]);
03567 if( j1array[0] > IKPI )
03568 {
03569     j1array[0]-=IK2PI;
03570 }
03571 else if( j1array[0] < -IKPI )
03572 {    j1array[0]+=IK2PI;
03573 }
03574 j1valid[0] = true;
03575 for(int ij1 = 0; ij1 < 1; ++ij1)
03576 {
03577 if( !j1valid[ij1] )
03578 {
03579     continue;
03580 }
03581 _ij1[0] = ij1; _ij1[1] = -1;
03582 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03583 {
03584 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03585 {
03586     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03587 }
03588 }
03589 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03590 {
03591 IkReal evalcond[4];
03592 IkReal x990=IKsin(j1);
03593 IkReal x991=IKcos(j1);
03594 IkReal x992=((IkReal(0.707109999985348))*(cj2));
03595 IkReal x993=((IkReal(1.00000000000000))*(sj4));
03596 IkReal x994=((cj5)*(r00));
03597 IkReal x995=((IkReal(0.707109999985348))*(sj2));
03598 IkReal x996=((cj5)*(r20));
03599 IkReal x997=((r12)*(sj0));
03600 IkReal x998=((r21)*(sj5));
03601 IkReal x999=((IkReal(1.00000000000000))*(cj4));
03602 IkReal x1000=((IkReal(0.707103562373095))*(x991));
03603 IkReal x1001=((r11)*(sj0)*(sj5));
03604 IkReal x1002=((cj0)*(x999));
03605 IkReal x1003=((IkReal(0.707103562373095))*(x990));
03606 IkReal x1004=((cj0)*(r01)*(sj5));
03607 IkReal x1005=((cj5)*(r10)*(sj0));
03608 IkReal x1006=((sj2)*(x1000));
03609 IkReal x1007=((cj2)*(x1003));
03610 IkReal x1008=((x991)*(x992));
03611 IkReal x1009=((x990)*(x995));
03612 IkReal x1010=((cj2)*(x1000));
03613 IkReal x1011=((x990)*(x992));
03614 IkReal x1012=((sj2)*(x1003));
03615 IkReal x1013=((x991)*(x995));
03616 IkReal x1014=((x1008)+(x1007)+(x1006));
03617 IkReal x1015=((x1011)+(x1012)+(x1013));
03618 evalcond[0]=((((sj4)*(x998)))+(((cj4)*(r22)))+(x1015)+(((IkReal(-1.00000000000000))*(x1010)))+(((IkReal(-1.00000000000000))*(x993)*(x996))));
03619 evalcond[1]=((x1014)+(((IkReal(-1.00000000000000))*(x1009)))+(((cj4)*(x996)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x998)*(x999))));
03620 evalcond[2]=((((sj4)*(x1005)))+(x1014)+(((IkReal(-1.00000000000000))*(x1009)))+(((IkReal(-1.00000000000000))*(x997)*(x999)))+(((IkReal(-1.00000000000000))*(r02)*(x1002)))+(((IkReal(-1.00000000000000))*(x1001)*(x993)))+(((IkReal(-1.00000000000000))*(x1004)*(x993)))+(((cj0)*(sj4)*(x994))));
03621 evalcond[3]=((x1010)+(((IkReal(-1.00000000000000))*(x1002)*(x994)))+(((IkReal(-1.00000000000000))*(x1015)))+(((cj4)*(x1004)))+(((cj4)*(x1001)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x993)))+(((IkReal(-1.00000000000000))*(x1005)*(x999)))+(((IkReal(-1.00000000000000))*(x993)*(x997))));
03622 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03623 {
03624 continue;
03625 }
03626 }
03627 
03628 {
03629 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03630 vinfos[0].jointtype = 1;
03631 vinfos[0].foffset = j0;
03632 vinfos[0].indices[0] = _ij0[0];
03633 vinfos[0].indices[1] = _ij0[1];
03634 vinfos[0].maxsolutions = _nj0;
03635 vinfos[1].jointtype = 1;
03636 vinfos[1].foffset = j1;
03637 vinfos[1].indices[0] = _ij1[0];
03638 vinfos[1].indices[1] = _ij1[1];
03639 vinfos[1].maxsolutions = _nj1;
03640 vinfos[2].jointtype = 1;
03641 vinfos[2].foffset = j2;
03642 vinfos[2].indices[0] = _ij2[0];
03643 vinfos[2].indices[1] = _ij2[1];
03644 vinfos[2].maxsolutions = _nj2;
03645 vinfos[3].jointtype = 1;
03646 vinfos[3].foffset = j3;
03647 vinfos[3].indices[0] = _ij3[0];
03648 vinfos[3].indices[1] = _ij3[1];
03649 vinfos[3].maxsolutions = _nj3;
03650 vinfos[4].jointtype = 1;
03651 vinfos[4].foffset = j4;
03652 vinfos[4].indices[0] = _ij4[0];
03653 vinfos[4].indices[1] = _ij4[1];
03654 vinfos[4].maxsolutions = _nj4;
03655 vinfos[5].jointtype = 1;
03656 vinfos[5].foffset = j5;
03657 vinfos[5].indices[0] = _ij5[0];
03658 vinfos[5].indices[1] = _ij5[1];
03659 vinfos[5].maxsolutions = _nj5;
03660 std::vector<int> vfree(0);
03661 solutions.AddSolution(vinfos,vfree);
03662 }
03663 }
03664 }
03665 
03666 }
03667 
03668 }
03669 }
03670 }
03671 
03672 }
03673 
03674 }
03675 
03676 } else
03677 {
03678 {
03679 IkReal j0array[1], cj0array[1], sj0array[1];
03680 bool j0valid[1]={false};
03681 _nj0 = 1;
03682 if( IKabs(((gconst20)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst20)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
03683     continue;
03684 j0array[0]=IKatan2(((gconst20)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst20)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
03685 sj0array[0]=IKsin(j0array[0]);
03686 cj0array[0]=IKcos(j0array[0]);
03687 if( j0array[0] > IKPI )
03688 {
03689     j0array[0]-=IK2PI;
03690 }
03691 else if( j0array[0] < -IKPI )
03692 {    j0array[0]+=IK2PI;
03693 }
03694 j0valid[0] = true;
03695 for(int ij0 = 0; ij0 < 1; ++ij0)
03696 {
03697 if( !j0valid[ij0] )
03698 {
03699     continue;
03700 }
03701 _ij0[0] = ij0; _ij0[1] = -1;
03702 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03703 {
03704 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03705 {
03706     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03707 }
03708 }
03709 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03710 {
03711 IkReal evalcond[4];
03712 IkReal x1016=IKsin(j0);
03713 IkReal x1017=IKcos(j0);
03714 IkReal x1018=((IkReal(1.00000000000000))*(cj5));
03715 IkReal x1019=((r01)*(sj5));
03716 IkReal x1020=((IkReal(1.00000000000000))*(r12));
03717 IkReal x1021=((r11)*(sj5));
03718 IkReal x1022=((IkReal(1.00000000000000))*(r10));
03719 IkReal x1023=((cj4)*(x1016));
03720 IkReal x1024=((sj4)*(x1016));
03721 IkReal x1025=((sj4)*(x1017));
03722 IkReal x1026=((sj5)*(x1016));
03723 IkReal x1027=((cj4)*(x1017));
03724 IkReal x1028=((sj5)*(x1017));
03725 evalcond[0]=((IkReal(1.00000000000000))+(((cj5)*(r01)*(x1016)))+(((IkReal(-1.00000000000000))*(x1022)*(x1028)))+(((IkReal(-1.00000000000000))*(r11)*(x1017)*(x1018)))+(((r00)*(x1026))));
03726 evalcond[1]=((((cj5)*(r10)*(x1025)))+(((IkReal(-1.00000000000000))*(x1020)*(x1027)))+(((IkReal(-1.00000000000000))*(x1021)*(x1025)))+(((x1019)*(x1024)))+(((r02)*(x1023)))+(((IkReal(-1.00000000000000))*(r00)*(x1018)*(x1024))));
03727 evalcond[2]=((((cj5)*(r00)*(x1023)))+(((IkReal(-1.00000000000000))*(x1019)*(x1023)))+(((IkReal(-1.00000000000000))*(x1020)*(x1025)))+(((x1021)*(x1027)))+(((r02)*(x1024)))+(((IkReal(-1.00000000000000))*(r10)*(x1018)*(x1027))));
03728 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x1017)*(x1018)))+(((IkReal(-1.00000000000000))*(x1022)*(x1026)))+(((IkReal(-1.00000000000000))*(r00)*(x1028)))+(((IkReal(-1.00000000000000))*(r11)*(x1016)*(x1018))));
03729 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03730 {
03731 continue;
03732 }
03733 }
03734 
03735 {
03736 IkReal dummyeval[1];
03737 IkReal gconst25;
03738 gconst25=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
03739 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
03740 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03741 {
03742 {
03743 IkReal dummyeval[1];
03744 IkReal gconst26;
03745 gconst26=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
03746 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
03747 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03748 {
03749 continue;
03750 
03751 } else
03752 {
03753 {
03754 IkReal j1array[1], cj1array[1], sj1array[1];
03755 bool j1valid[1]={false};
03756 _nj1 = 1;
03757 IkReal x1029=((sj4)*(sj5));
03758 IkReal x1030=((IkReal(0.707103562373095))*(sj0));
03759 IkReal x1031=((r11)*(sj2));
03760 IkReal x1032=((cj2)*(cj4));
03761 IkReal x1033=((IkReal(0.707103562373095))*(r22));
03762 IkReal x1034=((IkReal(0.707109999985348))*(cj0));
03763 IkReal x1035=((cj2)*(r01));
03764 IkReal x1036=((IkReal(0.707109999985348))*(cj2));
03765 IkReal x1037=((IkReal(0.707109999985348))*(sj0));
03766 IkReal x1038=((r21)*(sj2));
03767 IkReal x1039=((IkReal(0.707103562373095))*(cj2));
03768 IkReal x1040=((IkReal(0.707103562373095))*(sj2));
03769 IkReal x1041=((cj5)*(sj4));
03770 IkReal x1042=((r10)*(sj2));
03771 IkReal x1043=((cj0)*(r00));
03772 IkReal x1044=((IkReal(0.707103562373095))*(cj0));
03773 IkReal x1045=((cj4)*(sj2));
03774 IkReal x1046=((IkReal(0.707109999985348))*(r22));
03775 IkReal x1047=((r02)*(x1045));
03776 IkReal x1048=((r20)*(x1041));
03777 if( IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(x1037)*(x1041)*(x1042)))+(((x1034)*(x1047)))+(((r01)*(sj2)*(x1029)*(x1034)))+(((x1029)*(x1031)*(x1037)))+(((r21)*(x1029)*(x1036)))+(((IkReal(-1.00000000000000))*(r12)*(x1030)*(x1032)))+(((IkReal(0.707103562373095))*(x1029)*(x1038)))+(((IkReal(-1.00000000000000))*(x1029)*(x1035)*(x1044)))+(((IkReal(-1.00000000000000))*(r02)*(x1032)*(x1044)))+(((r12)*(x1037)*(x1045)))+(((x1039)*(x1041)*(x1043)))+(((cj2)*(r10)*(x1030)*(x1041)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1029)*(x1030)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1034)*(x1041)))+(((x1032)*(x1046)))+(((IkReal(-1.00000000000000))*(x1040)*(x1048)))+(((IkReal(-1.00000000000000))*(x1036)*(x1048)))+(((x1033)*(x1045))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1029)*(x1040)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1029)*(x1036)))+(((x1030)*(x1041)*(x1042)))+(((IkReal(-1.00000000000000))*(x1032)*(x1033)))+(((IkReal(-1.00000000000000))*(r12)*(x1032)*(x1037)))+(((IkReal(-1.00000000000000))*(x1029)*(x1034)*(x1035)))+(((cj2)*(r00)*(x1034)*(x1041)))+(((IkReal(-1.00000000000000))*(r21)*(x1029)*(x1039)))+(((x1039)*(x1048)))+(((IkReal(-1.00000000000000))*(r12)*(x1030)*(x1045)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1040)))+(((r10)*(sj0)*(x1036)*(x1041)))+(((IkReal(0.707109999985348))*(x1029)*(x1038)))+(((IkReal(-1.00000000000000))*(x1029)*(x1030)*(x1031)))+(((IkReal(-1.00000000000000))*(r02)*(x1032)*(x1034)))+(((x1045)*(x1046)))+(((IkReal(-0.707109999985348))*(sj2)*(x1048)))+(((x1040)*(x1041)*(x1043))))))) < IKFAST_ATAN2_MAGTHRESH )
03778     continue;
03779 j1array[0]=IKatan2(((gconst26)*(((((IkReal(-1.00000000000000))*(x1037)*(x1041)*(x1042)))+(((x1034)*(x1047)))+(((r01)*(sj2)*(x1029)*(x1034)))+(((x1029)*(x1031)*(x1037)))+(((r21)*(x1029)*(x1036)))+(((IkReal(-1.00000000000000))*(r12)*(x1030)*(x1032)))+(((IkReal(0.707103562373095))*(x1029)*(x1038)))+(((IkReal(-1.00000000000000))*(x1029)*(x1035)*(x1044)))+(((IkReal(-1.00000000000000))*(r02)*(x1032)*(x1044)))+(((r12)*(x1037)*(x1045)))+(((x1039)*(x1041)*(x1043)))+(((cj2)*(r10)*(x1030)*(x1041)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1029)*(x1030)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1034)*(x1041)))+(((x1032)*(x1046)))+(((IkReal(-1.00000000000000))*(x1040)*(x1048)))+(((IkReal(-1.00000000000000))*(x1036)*(x1048)))+(((x1033)*(x1045)))))), ((gconst26)*(((((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1029)*(x1040)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1029)*(x1036)))+(((x1030)*(x1041)*(x1042)))+(((IkReal(-1.00000000000000))*(x1032)*(x1033)))+(((IkReal(-1.00000000000000))*(r12)*(x1032)*(x1037)))+(((IkReal(-1.00000000000000))*(x1029)*(x1034)*(x1035)))+(((cj2)*(r00)*(x1034)*(x1041)))+(((IkReal(-1.00000000000000))*(r21)*(x1029)*(x1039)))+(((x1039)*(x1048)))+(((IkReal(-1.00000000000000))*(r12)*(x1030)*(x1045)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1040)))+(((r10)*(sj0)*(x1036)*(x1041)))+(((IkReal(0.707109999985348))*(x1029)*(x1038)))+(((IkReal(-1.00000000000000))*(x1029)*(x1030)*(x1031)))+(((IkReal(-1.00000000000000))*(r02)*(x1032)*(x1034)))+(((x1045)*(x1046)))+(((IkReal(-0.707109999985348))*(sj2)*(x1048)))+(((x1040)*(x1041)*(x1043)))))));
03780 sj1array[0]=IKsin(j1array[0]);
03781 cj1array[0]=IKcos(j1array[0]);
03782 if( j1array[0] > IKPI )
03783 {
03784     j1array[0]-=IK2PI;
03785 }
03786 else if( j1array[0] < -IKPI )
03787 {    j1array[0]+=IK2PI;
03788 }
03789 j1valid[0] = true;
03790 for(int ij1 = 0; ij1 < 1; ++ij1)
03791 {
03792 if( !j1valid[ij1] )
03793 {
03794     continue;
03795 }
03796 _ij1[0] = ij1; _ij1[1] = -1;
03797 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03798 {
03799 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03800 {
03801     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03802 }
03803 }
03804 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03805 {
03806 IkReal evalcond[4];
03807 IkReal x1049=IKsin(j1);
03808 IkReal x1050=IKcos(j1);
03809 IkReal x1051=((IkReal(0.707109999985348))*(cj2));
03810 IkReal x1052=((IkReal(1.00000000000000))*(sj4));
03811 IkReal x1053=((cj5)*(r00));
03812 IkReal x1054=((IkReal(0.707109999985348))*(sj2));
03813 IkReal x1055=((cj5)*(r20));
03814 IkReal x1056=((r12)*(sj0));
03815 IkReal x1057=((r21)*(sj5));
03816 IkReal x1058=((IkReal(1.00000000000000))*(cj4));
03817 IkReal x1059=((IkReal(0.707103562373095))*(x1050));
03818 IkReal x1060=((r11)*(sj0)*(sj5));
03819 IkReal x1061=((cj0)*(x1058));
03820 IkReal x1062=((IkReal(0.707103562373095))*(x1049));
03821 IkReal x1063=((cj0)*(r01)*(sj5));
03822 IkReal x1064=((cj5)*(r10)*(sj0));
03823 IkReal x1065=((sj2)*(x1059));
03824 IkReal x1066=((cj2)*(x1062));
03825 IkReal x1067=((x1050)*(x1051));
03826 IkReal x1068=((x1049)*(x1054));
03827 IkReal x1069=((cj2)*(x1059));
03828 IkReal x1070=((x1049)*(x1051));
03829 IkReal x1071=((sj2)*(x1062));
03830 IkReal x1072=((x1050)*(x1054));
03831 IkReal x1073=((x1065)+(x1067)+(x1066));
03832 IkReal x1074=((x1072)+(x1070)+(x1071));
03833 evalcond[0]=((((IkReal(-1.00000000000000))*(x1052)*(x1055)))+(((cj4)*(r22)))+(x1074)+(((IkReal(-1.00000000000000))*(x1069)))+(((sj4)*(x1057))));
03834 evalcond[1]=((x1073)+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1057)*(x1058)))+(((IkReal(-1.00000000000000))*(x1068)))+(((cj4)*(x1055))));
03835 evalcond[2]=((((cj0)*(sj4)*(x1053)))+(x1073)+(((IkReal(-1.00000000000000))*(r02)*(x1061)))+(((IkReal(-1.00000000000000))*(x1056)*(x1058)))+(((IkReal(-1.00000000000000))*(x1052)*(x1063)))+(((IkReal(-1.00000000000000))*(x1052)*(x1060)))+(((sj4)*(x1064)))+(((IkReal(-1.00000000000000))*(x1068))));
03836 evalcond[3]=((((IkReal(-1.00000000000000))*(x1052)*(x1056)))+(x1069)+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1052)))+(((IkReal(-1.00000000000000))*(x1058)*(x1064)))+(((cj4)*(x1063)))+(((cj4)*(x1060)))+(((IkReal(-1.00000000000000))*(x1074)))+(((IkReal(-1.00000000000000))*(x1053)*(x1061))));
03837 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03838 {
03839 continue;
03840 }
03841 }
03842 
03843 {
03844 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03845 vinfos[0].jointtype = 1;
03846 vinfos[0].foffset = j0;
03847 vinfos[0].indices[0] = _ij0[0];
03848 vinfos[0].indices[1] = _ij0[1];
03849 vinfos[0].maxsolutions = _nj0;
03850 vinfos[1].jointtype = 1;
03851 vinfos[1].foffset = j1;
03852 vinfos[1].indices[0] = _ij1[0];
03853 vinfos[1].indices[1] = _ij1[1];
03854 vinfos[1].maxsolutions = _nj1;
03855 vinfos[2].jointtype = 1;
03856 vinfos[2].foffset = j2;
03857 vinfos[2].indices[0] = _ij2[0];
03858 vinfos[2].indices[1] = _ij2[1];
03859 vinfos[2].maxsolutions = _nj2;
03860 vinfos[3].jointtype = 1;
03861 vinfos[3].foffset = j3;
03862 vinfos[3].indices[0] = _ij3[0];
03863 vinfos[3].indices[1] = _ij3[1];
03864 vinfos[3].maxsolutions = _nj3;
03865 vinfos[4].jointtype = 1;
03866 vinfos[4].foffset = j4;
03867 vinfos[4].indices[0] = _ij4[0];
03868 vinfos[4].indices[1] = _ij4[1];
03869 vinfos[4].maxsolutions = _nj4;
03870 vinfos[5].jointtype = 1;
03871 vinfos[5].foffset = j5;
03872 vinfos[5].indices[0] = _ij5[0];
03873 vinfos[5].indices[1] = _ij5[1];
03874 vinfos[5].maxsolutions = _nj5;
03875 std::vector<int> vfree(0);
03876 solutions.AddSolution(vinfos,vfree);
03877 }
03878 }
03879 }
03880 
03881 }
03882 
03883 }
03884 
03885 } else
03886 {
03887 {
03888 IkReal j1array[1], cj1array[1], sj1array[1];
03889 bool j1valid[1]={false};
03890 _nj1 = 1;
03891 IkReal x1075=((IkReal(0.707109999985348))*(sj4));
03892 IkReal x1076=((r22)*(sj2));
03893 IkReal x1077=((cj5)*(r20));
03894 IkReal x1078=((r21)*(sj5));
03895 IkReal x1079=((IkReal(0.707109999985348))*(cj4));
03896 IkReal x1080=((cj2)*(r22));
03897 IkReal x1081=((IkReal(0.707103562373095))*(sj4));
03898 IkReal x1082=((IkReal(0.707103562373095))*(cj4));
03899 IkReal x1083=((sj2)*(x1082));
03900 IkReal x1084=((cj2)*(x1082));
03901 if( IKabs(((gconst25)*(((((x1079)*(x1080)))+(((IkReal(-1.00000000000000))*(x1075)*(x1076)))+(((sj2)*(x1078)*(x1081)))+(((x1076)*(x1082)))+(((sj2)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(sj2)*(x1077)*(x1081)))+(((IkReal(-1.00000000000000))*(x1078)*(x1084)))+(((cj2)*(x1075)*(x1078)))+(((IkReal(-1.00000000000000))*(cj2)*(x1075)*(x1077)))+(((x1080)*(x1081)))+(((x1077)*(x1084)))+(((IkReal(-1.00000000000000))*(sj2)*(x1077)*(x1079))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((x1076)*(x1081)))+(((IkReal(-1.00000000000000))*(cj2)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(cj2)*(x1078)*(x1081)))+(((cj2)*(x1077)*(x1081)))+(((IkReal(-1.00000000000000))*(x1078)*(x1083)))+(((sj2)*(x1075)*(x1078)))+(((x1075)*(x1080)))+(((IkReal(-1.00000000000000))*(x1080)*(x1082)))+(((cj2)*(x1077)*(x1079)))+(((x1076)*(x1079)))+(((x1077)*(x1083)))+(((IkReal(-1.00000000000000))*(sj2)*(x1075)*(x1077))))))) < IKFAST_ATAN2_MAGTHRESH )
03902     continue;
03903 j1array[0]=IKatan2(((gconst25)*(((((x1079)*(x1080)))+(((IkReal(-1.00000000000000))*(x1075)*(x1076)))+(((sj2)*(x1078)*(x1081)))+(((x1076)*(x1082)))+(((sj2)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(sj2)*(x1077)*(x1081)))+(((IkReal(-1.00000000000000))*(x1078)*(x1084)))+(((cj2)*(x1075)*(x1078)))+(((IkReal(-1.00000000000000))*(cj2)*(x1075)*(x1077)))+(((x1080)*(x1081)))+(((x1077)*(x1084)))+(((IkReal(-1.00000000000000))*(sj2)*(x1077)*(x1079)))))), ((gconst25)*(((((x1076)*(x1081)))+(((IkReal(-1.00000000000000))*(cj2)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(cj2)*(x1078)*(x1081)))+(((cj2)*(x1077)*(x1081)))+(((IkReal(-1.00000000000000))*(x1078)*(x1083)))+(((sj2)*(x1075)*(x1078)))+(((x1075)*(x1080)))+(((IkReal(-1.00000000000000))*(x1080)*(x1082)))+(((cj2)*(x1077)*(x1079)))+(((x1076)*(x1079)))+(((x1077)*(x1083)))+(((IkReal(-1.00000000000000))*(sj2)*(x1075)*(x1077)))))));
03904 sj1array[0]=IKsin(j1array[0]);
03905 cj1array[0]=IKcos(j1array[0]);
03906 if( j1array[0] > IKPI )
03907 {
03908     j1array[0]-=IK2PI;
03909 }
03910 else if( j1array[0] < -IKPI )
03911 {    j1array[0]+=IK2PI;
03912 }
03913 j1valid[0] = true;
03914 for(int ij1 = 0; ij1 < 1; ++ij1)
03915 {
03916 if( !j1valid[ij1] )
03917 {
03918     continue;
03919 }
03920 _ij1[0] = ij1; _ij1[1] = -1;
03921 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03922 {
03923 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03924 {
03925     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03926 }
03927 }
03928 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03929 {
03930 IkReal evalcond[4];
03931 IkReal x1085=IKsin(j1);
03932 IkReal x1086=IKcos(j1);
03933 IkReal x1087=((IkReal(0.707109999985348))*(cj2));
03934 IkReal x1088=((IkReal(1.00000000000000))*(sj4));
03935 IkReal x1089=((cj5)*(r00));
03936 IkReal x1090=((IkReal(0.707109999985348))*(sj2));
03937 IkReal x1091=((cj5)*(r20));
03938 IkReal x1092=((r12)*(sj0));
03939 IkReal x1093=((r21)*(sj5));
03940 IkReal x1094=((IkReal(1.00000000000000))*(cj4));
03941 IkReal x1095=((IkReal(0.707103562373095))*(x1086));
03942 IkReal x1096=((r11)*(sj0)*(sj5));
03943 IkReal x1097=((cj0)*(x1094));
03944 IkReal x1098=((IkReal(0.707103562373095))*(x1085));
03945 IkReal x1099=((cj0)*(r01)*(sj5));
03946 IkReal x1100=((cj5)*(r10)*(sj0));
03947 IkReal x1101=((sj2)*(x1095));
03948 IkReal x1102=((cj2)*(x1098));
03949 IkReal x1103=((x1086)*(x1087));
03950 IkReal x1104=((x1085)*(x1090));
03951 IkReal x1105=((cj2)*(x1095));
03952 IkReal x1106=((x1085)*(x1087));
03953 IkReal x1107=((sj2)*(x1098));
03954 IkReal x1108=((x1086)*(x1090));
03955 IkReal x1109=((x1102)+(x1103)+(x1101));
03956 IkReal x1110=((x1106)+(x1107)+(x1108));
03957 evalcond[0]=((x1110)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1088)*(x1091)))+(((sj4)*(x1093)))+(((IkReal(-1.00000000000000))*(x1105))));
03958 evalcond[1]=((x1109)+(((cj4)*(x1091)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1093)*(x1094)))+(((IkReal(-1.00000000000000))*(x1104))));
03959 evalcond[2]=((((cj0)*(sj4)*(x1089)))+(x1109)+(((IkReal(-1.00000000000000))*(x1088)*(x1096)))+(((IkReal(-1.00000000000000))*(x1088)*(x1099)))+(((IkReal(-1.00000000000000))*(r02)*(x1097)))+(((sj4)*(x1100)))+(((IkReal(-1.00000000000000))*(x1092)*(x1094)))+(((IkReal(-1.00000000000000))*(x1104))));
03960 evalcond[3]=((x1105)+(((IkReal(-1.00000000000000))*(x1088)*(x1092)))+(((cj4)*(x1099)))+(((cj4)*(x1096)))+(((IkReal(-1.00000000000000))*(x1089)*(x1097)))+(((IkReal(-1.00000000000000))*(x1094)*(x1100)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1088)))+(((IkReal(-1.00000000000000))*(x1110))));
03961 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03962 {
03963 continue;
03964 }
03965 }
03966 
03967 {
03968 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03969 vinfos[0].jointtype = 1;
03970 vinfos[0].foffset = j0;
03971 vinfos[0].indices[0] = _ij0[0];
03972 vinfos[0].indices[1] = _ij0[1];
03973 vinfos[0].maxsolutions = _nj0;
03974 vinfos[1].jointtype = 1;
03975 vinfos[1].foffset = j1;
03976 vinfos[1].indices[0] = _ij1[0];
03977 vinfos[1].indices[1] = _ij1[1];
03978 vinfos[1].maxsolutions = _nj1;
03979 vinfos[2].jointtype = 1;
03980 vinfos[2].foffset = j2;
03981 vinfos[2].indices[0] = _ij2[0];
03982 vinfos[2].indices[1] = _ij2[1];
03983 vinfos[2].maxsolutions = _nj2;
03984 vinfos[3].jointtype = 1;
03985 vinfos[3].foffset = j3;
03986 vinfos[3].indices[0] = _ij3[0];
03987 vinfos[3].indices[1] = _ij3[1];
03988 vinfos[3].maxsolutions = _nj3;
03989 vinfos[4].jointtype = 1;
03990 vinfos[4].foffset = j4;
03991 vinfos[4].indices[0] = _ij4[0];
03992 vinfos[4].indices[1] = _ij4[1];
03993 vinfos[4].maxsolutions = _nj4;
03994 vinfos[5].jointtype = 1;
03995 vinfos[5].foffset = j5;
03996 vinfos[5].indices[0] = _ij5[0];
03997 vinfos[5].indices[1] = _ij5[1];
03998 vinfos[5].maxsolutions = _nj5;
03999 std::vector<int> vfree(0);
04000 solutions.AddSolution(vinfos,vfree);
04001 }
04002 }
04003 }
04004 
04005 }
04006 
04007 }
04008 }
04009 }
04010 
04011 }
04012 
04013 }
04014 
04015 } else
04016 {
04017 IkReal x1111=((cj5)*(npx));
04018 IkReal x1112=((npy)*(sj5));
04019 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959))));
04020 evalcond[1]=((IkReal(-0.258003287011922))+(((sj4)*(x1112)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x1111)))+(((IkReal(0.165463933124939))*(sj2))));
04021 evalcond[2]=((((npx)*(sj5)))+(((cj5)*(npy))));
04022 evalcond[3]=((IkReal(-0.0300035672348961))+(((IkReal(-1.00000000000000))*(cj4)*(x1112)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj4)*(x1111)))+(((npz)*(sj4)))+(((IkReal(-0.207888640466058))*(sj2))));
04023 evalcond[4]=((((cj5)*(r21)))+(((r20)*(sj5))));
04024 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  )
04025 {
04026 {
04027 IkReal dummyeval[1];
04028 IkReal gconst27;
04029 IkReal x1113=(cj5)*(cj5);
04030 IkReal x1114=(sj5)*(sj5);
04031 IkReal x1115=((IkReal(1.00000000000000))*(x1114));
04032 IkReal x1116=((IkReal(2.00000000000000))*(cj5)*(sj5));
04033 IkReal x1117=((IkReal(1.00000000000000))*(x1113));
04034 gconst27=IKsign(((((IkReal(-1.00000000000000))*(x1117)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1116)))+(((IkReal(-1.00000000000000))*(x1115)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1115)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1116)))+(((IkReal(-1.00000000000000))*(x1117)*((r01)*(r01))))));
04035 IkReal x1118=(cj5)*(cj5);
04036 IkReal x1119=(sj5)*(sj5);
04037 IkReal x1120=((IkReal(1.00000000000000))*(x1119));
04038 IkReal x1121=((IkReal(2.00000000000000))*(cj5)*(sj5));
04039 IkReal x1122=((IkReal(1.00000000000000))*(x1118));
04040 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1120)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1122)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1121)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1121)))+(((IkReal(-1.00000000000000))*(x1120)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1122)*((r01)*(r01)))));
04041 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04042 {
04043 {
04044 IkReal dummyeval[1];
04045 IkReal gconst28;
04046 IkReal x1123=(sj5)*(sj5);
04047 IkReal x1124=(cj5)*(cj5);
04048 IkReal x1125=((cj4)*(cj5));
04049 IkReal x1126=((IkReal(1.00000000000000))*(r12));
04050 IkReal x1127=((cj4)*(sj5));
04051 IkReal x1128=((r01)*(r10));
04052 IkReal x1129=((sj4)*(x1124));
04053 IkReal x1130=((IkReal(1.00000000000000))*(r00)*(r11));
04054 IkReal x1131=((sj4)*(x1123));
04055 gconst28=IKsign(((((IkReal(-1.00000000000000))*(x1130)*(x1131)))+(((r02)*(r10)*(x1127)))+(((r02)*(r11)*(x1125)))+(((x1128)*(x1129)))+(((x1128)*(x1131)))+(((IkReal(-1.00000000000000))*(r00)*(x1126)*(x1127)))+(((IkReal(-1.00000000000000))*(r01)*(x1125)*(x1126)))+(((IkReal(-1.00000000000000))*(x1129)*(x1130)))));
04056 IkReal x1132=(sj5)*(sj5);
04057 IkReal x1133=(cj5)*(cj5);
04058 IkReal x1134=((cj4)*(cj5));
04059 IkReal x1135=((IkReal(1.00000000000000))*(r12));
04060 IkReal x1136=((cj4)*(sj5));
04061 IkReal x1137=((r01)*(r10));
04062 IkReal x1138=((sj4)*(x1133));
04063 IkReal x1139=((IkReal(1.00000000000000))*(r00)*(r11));
04064 IkReal x1140=((sj4)*(x1132));
04065 dummyeval[0]=((((x1137)*(x1140)))+(((IkReal(-1.00000000000000))*(r00)*(x1135)*(x1136)))+(((IkReal(-1.00000000000000))*(r01)*(x1134)*(x1135)))+(((x1137)*(x1138)))+(((r02)*(r11)*(x1134)))+(((IkReal(-1.00000000000000))*(x1138)*(x1139)))+(((r02)*(r10)*(x1136)))+(((IkReal(-1.00000000000000))*(x1139)*(x1140))));
04066 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04067 {
04068 {
04069 IkReal dummyeval[1];
04070 IkReal gconst29;
04071 gconst29=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
04072 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
04073 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04074 {
04075 continue;
04076 
04077 } else
04078 {
04079 {
04080 IkReal j1array[1], cj1array[1], sj1array[1];
04081 bool j1valid[1]={false};
04082 _nj1 = 1;
04083 IkReal x1141=((IkReal(0.707109999985348))*(sj4));
04084 IkReal x1142=((r22)*(sj2));
04085 IkReal x1143=((cj5)*(r20));
04086 IkReal x1144=((r21)*(sj5));
04087 IkReal x1145=((IkReal(0.707109999985348))*(cj4));
04088 IkReal x1146=((IkReal(0.707103562373095))*(sj4));
04089 IkReal x1147=((cj2)*(r22));
04090 IkReal x1148=((IkReal(0.707103562373095))*(cj4));
04091 IkReal x1149=((sj2)*(x1148));
04092 IkReal x1150=((cj2)*(x1148));
04093 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(x1144)*(x1150)))+(((IkReal(-1.00000000000000))*(x1145)*(x1147)))+(((IkReal(-1.00000000000000))*(cj2)*(x1141)*(x1144)))+(((x1146)*(x1147)))+(((IkReal(-1.00000000000000))*(x1141)*(x1142)))+(((x1143)*(x1150)))+(((IkReal(-1.00000000000000))*(sj2)*(x1144)*(x1146)))+(((sj2)*(x1144)*(x1145)))+(((cj2)*(x1141)*(x1143)))+(((IkReal(-1.00000000000000))*(sj2)*(x1143)*(x1145)))+(((sj2)*(x1143)*(x1146)))+(((IkReal(-1.00000000000000))*(x1142)*(x1148))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((x1143)*(x1149)))+(((x1141)*(x1147)))+(((cj2)*(x1143)*(x1145)))+(((IkReal(-1.00000000000000))*(cj2)*(x1143)*(x1146)))+(((x1142)*(x1146)))+(((IkReal(-1.00000000000000))*(sj2)*(x1141)*(x1144)))+(((cj2)*(x1144)*(x1146)))+(((x1147)*(x1148)))+(((sj2)*(x1141)*(x1143)))+(((IkReal(-1.00000000000000))*(cj2)*(x1144)*(x1145)))+(((IkReal(-1.00000000000000))*(x1144)*(x1149)))+(((IkReal(-1.00000000000000))*(x1142)*(x1145))))))) < IKFAST_ATAN2_MAGTHRESH )
04094     continue;
04095 j1array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(x1144)*(x1150)))+(((IkReal(-1.00000000000000))*(x1145)*(x1147)))+(((IkReal(-1.00000000000000))*(cj2)*(x1141)*(x1144)))+(((x1146)*(x1147)))+(((IkReal(-1.00000000000000))*(x1141)*(x1142)))+(((x1143)*(x1150)))+(((IkReal(-1.00000000000000))*(sj2)*(x1144)*(x1146)))+(((sj2)*(x1144)*(x1145)))+(((cj2)*(x1141)*(x1143)))+(((IkReal(-1.00000000000000))*(sj2)*(x1143)*(x1145)))+(((sj2)*(x1143)*(x1146)))+(((IkReal(-1.00000000000000))*(x1142)*(x1148)))))), ((gconst29)*(((((x1143)*(x1149)))+(((x1141)*(x1147)))+(((cj2)*(x1143)*(x1145)))+(((IkReal(-1.00000000000000))*(cj2)*(x1143)*(x1146)))+(((x1142)*(x1146)))+(((IkReal(-1.00000000000000))*(sj2)*(x1141)*(x1144)))+(((cj2)*(x1144)*(x1146)))+(((x1147)*(x1148)))+(((sj2)*(x1141)*(x1143)))+(((IkReal(-1.00000000000000))*(cj2)*(x1144)*(x1145)))+(((IkReal(-1.00000000000000))*(x1144)*(x1149)))+(((IkReal(-1.00000000000000))*(x1142)*(x1145)))))));
04096 sj1array[0]=IKsin(j1array[0]);
04097 cj1array[0]=IKcos(j1array[0]);
04098 if( j1array[0] > IKPI )
04099 {
04100     j1array[0]-=IK2PI;
04101 }
04102 else if( j1array[0] < -IKPI )
04103 {    j1array[0]+=IK2PI;
04104 }
04105 j1valid[0] = true;
04106 for(int ij1 = 0; ij1 < 1; ++ij1)
04107 {
04108 if( !j1valid[ij1] )
04109 {
04110     continue;
04111 }
04112 _ij1[0] = ij1; _ij1[1] = -1;
04113 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04114 {
04115 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04116 {
04117     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04118 }
04119 }
04120 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04121 {
04122 IkReal evalcond[2];
04123 IkReal x1151=IKsin(j1);
04124 IkReal x1152=IKcos(j1);
04125 IkReal x1153=((cj5)*(r20));
04126 IkReal x1154=((r21)*(sj5));
04127 IkReal x1155=((IkReal(0.707103562373095))*(x1151));
04128 IkReal x1156=((IkReal(0.707109999985348))*(x1151));
04129 IkReal x1157=((IkReal(0.707103562373095))*(x1152));
04130 IkReal x1158=((IkReal(0.707109999985348))*(x1152));
04131 evalcond[0]=((((cj4)*(r22)))+(((cj2)*(x1156)))+(((sj2)*(x1155)))+(((sj2)*(x1158)))+(((IkReal(-1.00000000000000))*(sj4)*(x1153)))+(((IkReal(-1.00000000000000))*(cj2)*(x1157)))+(((sj4)*(x1154))));
04132 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(x1154)))+(((r22)*(sj4)))+(((sj2)*(x1156)))+(((cj4)*(x1153)))+(((IkReal(-1.00000000000000))*(sj2)*(x1157)))+(((IkReal(-1.00000000000000))*(cj2)*(x1158)))+(((IkReal(-1.00000000000000))*(cj2)*(x1155))));
04133 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04134 {
04135 continue;
04136 }
04137 }
04138 
04139 {
04140 IkReal dummyeval[1];
04141 IkReal gconst30;
04142 IkReal x1159=(cj5)*(cj5);
04143 IkReal x1160=(sj5)*(sj5);
04144 IkReal x1161=((IkReal(1.00000000000000))*(x1160));
04145 IkReal x1162=((IkReal(2.00000000000000))*(cj5)*(sj5));
04146 IkReal x1163=((IkReal(1.00000000000000))*(x1159));
04147 gconst30=IKsign(((((IkReal(-1.00000000000000))*(x1161)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1162)))+(((IkReal(-1.00000000000000))*(x1163)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1161)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1163)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1162)))));
04148 IkReal x1164=(cj5)*(cj5);
04149 IkReal x1165=(sj5)*(sj5);
04150 IkReal x1166=((IkReal(1.00000000000000))*(x1165));
04151 IkReal x1167=((IkReal(2.00000000000000))*(cj5)*(sj5));
04152 IkReal x1168=((IkReal(1.00000000000000))*(x1164));
04153 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1166)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1167)))+(((IkReal(-1.00000000000000))*(x1168)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1168)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1166)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1167))));
04154 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04155 {
04156 {
04157 IkReal dummyeval[1];
04158 IkReal gconst31;
04159 IkReal x1169=(sj5)*(sj5);
04160 IkReal x1170=(cj5)*(cj5);
04161 IkReal x1171=((cj4)*(cj5));
04162 IkReal x1172=((IkReal(1.00000000000000))*(r12));
04163 IkReal x1173=((cj4)*(sj5));
04164 IkReal x1174=((r01)*(r10));
04165 IkReal x1175=((sj4)*(x1170));
04166 IkReal x1176=((IkReal(1.00000000000000))*(r00)*(r11));
04167 IkReal x1177=((sj4)*(x1169));
04168 gconst31=IKsign(((((IkReal(-1.00000000000000))*(r00)*(x1172)*(x1173)))+(((x1174)*(x1175)))+(((x1174)*(x1177)))+(((r02)*(r11)*(x1171)))+(((r02)*(r10)*(x1173)))+(((IkReal(-1.00000000000000))*(x1176)*(x1177)))+(((IkReal(-1.00000000000000))*(x1175)*(x1176)))+(((IkReal(-1.00000000000000))*(r01)*(x1171)*(x1172)))));
04169 IkReal x1178=(sj5)*(sj5);
04170 IkReal x1179=(cj5)*(cj5);
04171 IkReal x1180=((cj4)*(cj5));
04172 IkReal x1181=((IkReal(1.00000000000000))*(r12));
04173 IkReal x1182=((cj4)*(sj5));
04174 IkReal x1183=((r01)*(r10));
04175 IkReal x1184=((sj4)*(x1179));
04176 IkReal x1185=((IkReal(1.00000000000000))*(r00)*(r11));
04177 IkReal x1186=((sj4)*(x1178));
04178 dummyeval[0]=((((x1183)*(x1186)))+(((x1183)*(x1184)))+(((r02)*(r10)*(x1182)))+(((r02)*(r11)*(x1180)))+(((IkReal(-1.00000000000000))*(x1184)*(x1185)))+(((IkReal(-1.00000000000000))*(r01)*(x1180)*(x1181)))+(((IkReal(-1.00000000000000))*(x1185)*(x1186)))+(((IkReal(-1.00000000000000))*(r00)*(x1181)*(x1182))));
04179 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04180 {
04181 continue;
04182 
04183 } else
04184 {
04185 {
04186 IkReal j0array[1], cj0array[1], sj0array[1];
04187 bool j0valid[1]={false};
04188 _nj0 = 1;
04189 IkReal x1187=((cj5)*(sj4));
04190 IkReal x1188=((IkReal(1.00000000000000))*(cj4));
04191 IkReal x1189=((IkReal(1.00000000000000))*(sj4)*(sj5));
04192 if( IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r11)*(x1189)))+(((r10)*(x1187)))+(((IkReal(-1.00000000000000))*(r12)*(x1188))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r01)*(x1189)))+(((r00)*(x1187)))+(((IkReal(-1.00000000000000))*(r02)*(x1188))))))) < IKFAST_ATAN2_MAGTHRESH )
04193     continue;
04194 j0array[0]=IKatan2(((gconst31)*(((((IkReal(-1.00000000000000))*(r11)*(x1189)))+(((r10)*(x1187)))+(((IkReal(-1.00000000000000))*(r12)*(x1188)))))), ((gconst31)*(((((IkReal(-1.00000000000000))*(r01)*(x1189)))+(((r00)*(x1187)))+(((IkReal(-1.00000000000000))*(r02)*(x1188)))))));
04195 sj0array[0]=IKsin(j0array[0]);
04196 cj0array[0]=IKcos(j0array[0]);
04197 if( j0array[0] > IKPI )
04198 {
04199     j0array[0]-=IK2PI;
04200 }
04201 else if( j0array[0] < -IKPI )
04202 {    j0array[0]+=IK2PI;
04203 }
04204 j0valid[0] = true;
04205 for(int ij0 = 0; ij0 < 1; ++ij0)
04206 {
04207 if( !j0valid[ij0] )
04208 {
04209     continue;
04210 }
04211 _ij0[0] = ij0; _ij0[1] = -1;
04212 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04213 {
04214 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04215 {
04216     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04217 }
04218 }
04219 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04220 {
04221 IkReal evalcond[6];
04222 IkReal x1190=IKsin(j0);
04223 IkReal x1191=IKcos(j0);
04224 IkReal x1192=((IkReal(0.707103562373095))*(cj2));
04225 IkReal x1193=((cj5)*(sj4));
04226 IkReal x1194=((IkReal(1.00000000000000))*(sj4));
04227 IkReal x1195=((IkReal(1.00000000000000))*(r10));
04228 IkReal x1196=((IkReal(1.00000000000000))*(cj5));
04229 IkReal x1197=((IkReal(1.00000000000000))*(cj4));
04230 IkReal x1198=((sj1)*(sj2));
04231 IkReal x1199=((IkReal(0.707109999985348))*(cj1));
04232 IkReal x1200=((cj4)*(r11));
04233 IkReal x1201=((sj5)*(x1190));
04234 IkReal x1202=((r10)*(x1190));
04235 IkReal x1203=((r01)*(x1191));
04236 IkReal x1204=((r00)*(x1191));
04237 IkReal x1205=((r02)*(x1191));
04238 IkReal x1206=((r12)*(x1191));
04239 IkReal x1207=((cj5)*(x1190));
04240 IkReal x1208=((r12)*(x1190));
04241 IkReal x1209=((sj5)*(x1191));
04242 IkReal x1210=((r02)*(x1190));
04243 evalcond[0]=((IkReal(-1.00000000000000))+(((r01)*(x1207)))+(((r00)*(x1201)))+(((IkReal(-1.00000000000000))*(r11)*(x1191)*(x1196)))+(((IkReal(-1.00000000000000))*(x1195)*(x1209))));
04244 evalcond[1]=((((cj4)*(x1210)))+(((r01)*(sj4)*(x1201)))+(((IkReal(-1.00000000000000))*(r00)*(x1190)*(x1193)))+(((IkReal(-1.00000000000000))*(r11)*(x1194)*(x1209)))+(((IkReal(-1.00000000000000))*(x1197)*(x1206)))+(((r10)*(x1191)*(x1193))));
04245 evalcond[2]=((((sj4)*(x1210)))+(((IkReal(-1.00000000000000))*(r01)*(x1197)*(x1201)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1191)*(x1195)))+(((cj4)*(r00)*(x1207)))+(((x1200)*(x1209)))+(((IkReal(-1.00000000000000))*(x1194)*(x1206))));
04246 evalcond[3]=((((IkReal(-1.00000000000000))*(x1196)*(x1203)))+(((IkReal(-1.00000000000000))*(r11)*(x1190)*(x1196)))+(((IkReal(-1.00000000000000))*(x1195)*(x1201)))+(((IkReal(-1.00000000000000))*(sj5)*(x1204))));
04247 evalcond[4]=((((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((x1193)*(x1202)))+(((x1193)*(x1204)))+(((IkReal(-0.707109999985348))*(x1198)))+(((sj1)*(x1192)))+(((IkReal(-1.00000000000000))*(sj5)*(x1194)*(x1203)))+(((IkReal(-1.00000000000000))*(r11)*(x1194)*(x1201)))+(((IkReal(-1.00000000000000))*(x1197)*(x1205)))+(((IkReal(-1.00000000000000))*(x1197)*(x1208)))+(((cj2)*(x1199))));
04248 evalcond[5]=((((IkReal(0.707103562373095))*(x1198)))+(((IkReal(-1.00000000000000))*(cj4)*(x1196)*(x1204)))+(((x1200)*(x1201)))+(((sj2)*(x1199)))+(((IkReal(-1.00000000000000))*(cj1)*(x1192)))+(((IkReal(0.707109999985348))*(cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x1194)*(x1208)))+(((IkReal(-1.00000000000000))*(x1194)*(x1205)))+(((cj4)*(sj5)*(x1203)))+(((IkReal(-1.00000000000000))*(cj4)*(x1195)*(x1207))));
04249 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  )
04250 {
04251 continue;
04252 }
04253 }
04254 
04255 {
04256 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04257 vinfos[0].jointtype = 1;
04258 vinfos[0].foffset = j0;
04259 vinfos[0].indices[0] = _ij0[0];
04260 vinfos[0].indices[1] = _ij0[1];
04261 vinfos[0].maxsolutions = _nj0;
04262 vinfos[1].jointtype = 1;
04263 vinfos[1].foffset = j1;
04264 vinfos[1].indices[0] = _ij1[0];
04265 vinfos[1].indices[1] = _ij1[1];
04266 vinfos[1].maxsolutions = _nj1;
04267 vinfos[2].jointtype = 1;
04268 vinfos[2].foffset = j2;
04269 vinfos[2].indices[0] = _ij2[0];
04270 vinfos[2].indices[1] = _ij2[1];
04271 vinfos[2].maxsolutions = _nj2;
04272 vinfos[3].jointtype = 1;
04273 vinfos[3].foffset = j3;
04274 vinfos[3].indices[0] = _ij3[0];
04275 vinfos[3].indices[1] = _ij3[1];
04276 vinfos[3].maxsolutions = _nj3;
04277 vinfos[4].jointtype = 1;
04278 vinfos[4].foffset = j4;
04279 vinfos[4].indices[0] = _ij4[0];
04280 vinfos[4].indices[1] = _ij4[1];
04281 vinfos[4].maxsolutions = _nj4;
04282 vinfos[5].jointtype = 1;
04283 vinfos[5].foffset = j5;
04284 vinfos[5].indices[0] = _ij5[0];
04285 vinfos[5].indices[1] = _ij5[1];
04286 vinfos[5].maxsolutions = _nj5;
04287 std::vector<int> vfree(0);
04288 solutions.AddSolution(vinfos,vfree);
04289 }
04290 }
04291 }
04292 
04293 }
04294 
04295 }
04296 
04297 } else
04298 {
04299 {
04300 IkReal j0array[1], cj0array[1], sj0array[1];
04301 bool j0valid[1]={false};
04302 _nj0 = 1;
04303 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
04304     continue;
04305 j0array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst30)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
04306 sj0array[0]=IKsin(j0array[0]);
04307 cj0array[0]=IKcos(j0array[0]);
04308 if( j0array[0] > IKPI )
04309 {
04310     j0array[0]-=IK2PI;
04311 }
04312 else if( j0array[0] < -IKPI )
04313 {    j0array[0]+=IK2PI;
04314 }
04315 j0valid[0] = true;
04316 for(int ij0 = 0; ij0 < 1; ++ij0)
04317 {
04318 if( !j0valid[ij0] )
04319 {
04320     continue;
04321 }
04322 _ij0[0] = ij0; _ij0[1] = -1;
04323 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04324 {
04325 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04326 {
04327     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04328 }
04329 }
04330 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04331 {
04332 IkReal evalcond[6];
04333 IkReal x1211=IKsin(j0);
04334 IkReal x1212=IKcos(j0);
04335 IkReal x1213=((IkReal(0.707103562373095))*(cj2));
04336 IkReal x1214=((cj5)*(sj4));
04337 IkReal x1215=((IkReal(1.00000000000000))*(sj4));
04338 IkReal x1216=((IkReal(1.00000000000000))*(r10));
04339 IkReal x1217=((IkReal(1.00000000000000))*(cj5));
04340 IkReal x1218=((IkReal(1.00000000000000))*(cj4));
04341 IkReal x1219=((sj1)*(sj2));
04342 IkReal x1220=((IkReal(0.707109999985348))*(cj1));
04343 IkReal x1221=((cj4)*(r11));
04344 IkReal x1222=((sj5)*(x1211));
04345 IkReal x1223=((r10)*(x1211));
04346 IkReal x1224=((r01)*(x1212));
04347 IkReal x1225=((r00)*(x1212));
04348 IkReal x1226=((r02)*(x1212));
04349 IkReal x1227=((r12)*(x1212));
04350 IkReal x1228=((cj5)*(x1211));
04351 IkReal x1229=((r12)*(x1211));
04352 IkReal x1230=((sj5)*(x1212));
04353 IkReal x1231=((r02)*(x1211));
04354 evalcond[0]=((IkReal(-1.00000000000000))+(((r01)*(x1228)))+(((r00)*(x1222)))+(((IkReal(-1.00000000000000))*(r11)*(x1212)*(x1217)))+(((IkReal(-1.00000000000000))*(x1216)*(x1230))));
04355 evalcond[1]=((((IkReal(-1.00000000000000))*(x1218)*(x1227)))+(((IkReal(-1.00000000000000))*(r11)*(x1215)*(x1230)))+(((IkReal(-1.00000000000000))*(r00)*(x1211)*(x1214)))+(((cj4)*(x1231)))+(((r10)*(x1212)*(x1214)))+(((r01)*(sj4)*(x1222))));
04356 evalcond[2]=((((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1212)*(x1216)))+(((IkReal(-1.00000000000000))*(x1215)*(x1227)))+(((sj4)*(x1231)))+(((x1221)*(x1230)))+(((IkReal(-1.00000000000000))*(r01)*(x1218)*(x1222)))+(((cj4)*(r00)*(x1228))));
04357 evalcond[3]=((((IkReal(-1.00000000000000))*(sj5)*(x1225)))+(((IkReal(-1.00000000000000))*(r11)*(x1211)*(x1217)))+(((IkReal(-1.00000000000000))*(x1217)*(x1224)))+(((IkReal(-1.00000000000000))*(x1216)*(x1222))));
04358 evalcond[4]=((((x1214)*(x1225)))+(((x1214)*(x1223)))+(((cj2)*(x1220)))+(((IkReal(-1.00000000000000))*(x1218)*(x1229)))+(((IkReal(-1.00000000000000))*(x1218)*(x1226)))+(((IkReal(-1.00000000000000))*(r11)*(x1215)*(x1222)))+(((IkReal(0.707103562373095))*(cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(sj5)*(x1215)*(x1224)))+(((IkReal(-0.707109999985348))*(x1219)))+(((sj1)*(x1213))));
04359 evalcond[5]=((((sj2)*(x1220)))+(((IkReal(-1.00000000000000))*(cj1)*(x1213)))+(((cj4)*(sj5)*(x1224)))+(((IkReal(-1.00000000000000))*(cj4)*(x1216)*(x1228)))+(((IkReal(0.707103562373095))*(x1219)))+(((IkReal(-1.00000000000000))*(x1215)*(x1229)))+(((IkReal(-1.00000000000000))*(x1215)*(x1226)))+(((IkReal(-1.00000000000000))*(cj4)*(x1217)*(x1225)))+(((x1221)*(x1222)))+(((IkReal(0.707109999985348))*(cj2)*(sj1))));
04360 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  )
04361 {
04362 continue;
04363 }
04364 }
04365 
04366 {
04367 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04368 vinfos[0].jointtype = 1;
04369 vinfos[0].foffset = j0;
04370 vinfos[0].indices[0] = _ij0[0];
04371 vinfos[0].indices[1] = _ij0[1];
04372 vinfos[0].maxsolutions = _nj0;
04373 vinfos[1].jointtype = 1;
04374 vinfos[1].foffset = j1;
04375 vinfos[1].indices[0] = _ij1[0];
04376 vinfos[1].indices[1] = _ij1[1];
04377 vinfos[1].maxsolutions = _nj1;
04378 vinfos[2].jointtype = 1;
04379 vinfos[2].foffset = j2;
04380 vinfos[2].indices[0] = _ij2[0];
04381 vinfos[2].indices[1] = _ij2[1];
04382 vinfos[2].maxsolutions = _nj2;
04383 vinfos[3].jointtype = 1;
04384 vinfos[3].foffset = j3;
04385 vinfos[3].indices[0] = _ij3[0];
04386 vinfos[3].indices[1] = _ij3[1];
04387 vinfos[3].maxsolutions = _nj3;
04388 vinfos[4].jointtype = 1;
04389 vinfos[4].foffset = j4;
04390 vinfos[4].indices[0] = _ij4[0];
04391 vinfos[4].indices[1] = _ij4[1];
04392 vinfos[4].maxsolutions = _nj4;
04393 vinfos[5].jointtype = 1;
04394 vinfos[5].foffset = j5;
04395 vinfos[5].indices[0] = _ij5[0];
04396 vinfos[5].indices[1] = _ij5[1];
04397 vinfos[5].maxsolutions = _nj5;
04398 std::vector<int> vfree(0);
04399 solutions.AddSolution(vinfos,vfree);
04400 }
04401 }
04402 }
04403 
04404 }
04405 
04406 }
04407 }
04408 }
04409 
04410 }
04411 
04412 }
04413 
04414 } else
04415 {
04416 {
04417 IkReal j0array[1], cj0array[1], sj0array[1];
04418 bool j0valid[1]={false};
04419 _nj0 = 1;
04420 IkReal x1232=((cj5)*(sj4));
04421 IkReal x1233=((IkReal(1.00000000000000))*(cj4));
04422 IkReal x1234=((IkReal(1.00000000000000))*(sj4)*(sj5));
04423 if( IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(r12)*(x1233)))+(((IkReal(-1.00000000000000))*(r11)*(x1234)))+(((r10)*(x1232))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((r00)*(x1232)))+(((IkReal(-1.00000000000000))*(r01)*(x1234)))+(((IkReal(-1.00000000000000))*(r02)*(x1233))))))) < IKFAST_ATAN2_MAGTHRESH )
04424     continue;
04425 j0array[0]=IKatan2(((gconst28)*(((((IkReal(-1.00000000000000))*(r12)*(x1233)))+(((IkReal(-1.00000000000000))*(r11)*(x1234)))+(((r10)*(x1232)))))), ((gconst28)*(((((r00)*(x1232)))+(((IkReal(-1.00000000000000))*(r01)*(x1234)))+(((IkReal(-1.00000000000000))*(r02)*(x1233)))))));
04426 sj0array[0]=IKsin(j0array[0]);
04427 cj0array[0]=IKcos(j0array[0]);
04428 if( j0array[0] > IKPI )
04429 {
04430     j0array[0]-=IK2PI;
04431 }
04432 else if( j0array[0] < -IKPI )
04433 {    j0array[0]+=IK2PI;
04434 }
04435 j0valid[0] = true;
04436 for(int ij0 = 0; ij0 < 1; ++ij0)
04437 {
04438 if( !j0valid[ij0] )
04439 {
04440     continue;
04441 }
04442 _ij0[0] = ij0; _ij0[1] = -1;
04443 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04444 {
04445 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04446 {
04447     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04448 }
04449 }
04450 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04451 {
04452 IkReal evalcond[4];
04453 IkReal x1235=IKsin(j0);
04454 IkReal x1236=IKcos(j0);
04455 IkReal x1237=((IkReal(1.00000000000000))*(cj5));
04456 IkReal x1238=((r01)*(sj5));
04457 IkReal x1239=((IkReal(1.00000000000000))*(r12));
04458 IkReal x1240=((r11)*(sj5));
04459 IkReal x1241=((IkReal(1.00000000000000))*(r10));
04460 IkReal x1242=((cj4)*(x1235));
04461 IkReal x1243=((sj4)*(x1235));
04462 IkReal x1244=((sj4)*(x1236));
04463 IkReal x1245=((sj5)*(x1235));
04464 IkReal x1246=((cj4)*(x1236));
04465 IkReal x1247=((sj5)*(x1236));
04466 evalcond[0]=((IkReal(-1.00000000000000))+(((r00)*(x1245)))+(((IkReal(-1.00000000000000))*(x1241)*(x1247)))+(((IkReal(-1.00000000000000))*(r11)*(x1236)*(x1237)))+(((cj5)*(r01)*(x1235))));
04467 evalcond[1]=((((IkReal(-1.00000000000000))*(x1239)*(x1246)))+(((IkReal(-1.00000000000000))*(x1240)*(x1244)))+(((r02)*(x1242)))+(((x1238)*(x1243)))+(((cj5)*(r10)*(x1244)))+(((IkReal(-1.00000000000000))*(r00)*(x1237)*(x1243))));
04468 evalcond[2]=((((IkReal(-1.00000000000000))*(x1239)*(x1244)))+(((cj5)*(r00)*(x1242)))+(((x1240)*(x1246)))+(((IkReal(-1.00000000000000))*(r10)*(x1237)*(x1246)))+(((r02)*(x1243)))+(((IkReal(-1.00000000000000))*(x1238)*(x1242))));
04469 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x1235)*(x1237)))+(((IkReal(-1.00000000000000))*(r01)*(x1236)*(x1237)))+(((IkReal(-1.00000000000000))*(r00)*(x1247)))+(((IkReal(-1.00000000000000))*(x1241)*(x1245))));
04470 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04471 {
04472 continue;
04473 }
04474 }
04475 
04476 {
04477 IkReal dummyeval[1];
04478 IkReal gconst32;
04479 gconst32=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
04480 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
04481 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04482 {
04483 {
04484 IkReal dummyeval[1];
04485 IkReal gconst33;
04486 gconst33=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
04487 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
04488 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04489 {
04490 continue;
04491 
04492 } else
04493 {
04494 {
04495 IkReal j1array[1], cj1array[1], sj1array[1];
04496 bool j1valid[1]={false};
04497 _nj1 = 1;
04498 IkReal x1248=((sj4)*(sj5));
04499 IkReal x1249=((IkReal(0.707103562373095))*(sj0));
04500 IkReal x1250=((r11)*(sj2));
04501 IkReal x1251=((cj2)*(cj4));
04502 IkReal x1252=((IkReal(0.707103562373095))*(r22));
04503 IkReal x1253=((IkReal(0.707109999985348))*(cj0));
04504 IkReal x1254=((cj2)*(r01));
04505 IkReal x1255=((IkReal(0.707109999985348))*(cj2));
04506 IkReal x1256=((IkReal(0.707109999985348))*(sj0));
04507 IkReal x1257=((r21)*(sj2));
04508 IkReal x1258=((IkReal(0.707103562373095))*(cj2));
04509 IkReal x1259=((IkReal(0.707103562373095))*(sj2));
04510 IkReal x1260=((cj5)*(sj4));
04511 IkReal x1261=((r10)*(sj2));
04512 IkReal x1262=((cj0)*(r00));
04513 IkReal x1263=((IkReal(0.707103562373095))*(cj0));
04514 IkReal x1264=((cj4)*(sj2));
04515 IkReal x1265=((IkReal(0.707109999985348))*(r22));
04516 IkReal x1266=((r02)*(x1264));
04517 IkReal x1267=((r20)*(x1260));
04518 if( IKabs(((gconst33)*(((((r21)*(x1248)*(x1255)))+(((x1248)*(x1250)*(x1256)))+(((r12)*(x1256)*(x1264)))+(((IkReal(0.707103562373095))*(x1248)*(x1257)))+(((IkReal(-1.00000000000000))*(x1255)*(x1267)))+(((x1253)*(x1266)))+(((x1258)*(x1260)*(x1262)))+(((r01)*(sj2)*(x1248)*(x1253)))+(((x1252)*(x1264)))+(((IkReal(-1.00000000000000))*(r02)*(x1251)*(x1263)))+(((IkReal(-1.00000000000000))*(x1248)*(x1254)*(x1263)))+(((IkReal(-1.00000000000000))*(x1256)*(x1260)*(x1261)))+(((IkReal(-1.00000000000000))*(r12)*(x1249)*(x1251)))+(((x1251)*(x1265)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1253)*(x1260)))+(((IkReal(-1.00000000000000))*(x1259)*(x1267)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1248)*(x1249)))+(((cj2)*(r10)*(x1249)*(x1260))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((x1259)*(x1260)*(x1262)))+(((IkReal(0.707109999985348))*(x1248)*(x1257)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1248)*(x1255)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1248)*(x1259)))+(((cj2)*(r00)*(x1253)*(x1260)))+(((x1258)*(x1267)))+(((x1264)*(x1265)))+(((IkReal(-1.00000000000000))*(r21)*(x1248)*(x1258)))+(((r10)*(sj0)*(x1255)*(x1260)))+(((x1249)*(x1260)*(x1261)))+(((IkReal(-1.00000000000000))*(r12)*(x1251)*(x1256)))+(((IkReal(-1.00000000000000))*(x1248)*(x1249)*(x1250)))+(((IkReal(-1.00000000000000))*(x1248)*(x1253)*(x1254)))+(((IkReal(-1.00000000000000))*(x1251)*(x1252)))+(((IkReal(-1.00000000000000))*(r02)*(x1251)*(x1253)))+(((IkReal(-1.00000000000000))*(r12)*(x1249)*(x1264)))+(((IkReal(-0.707109999985348))*(sj2)*(x1267)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1259))))))) < IKFAST_ATAN2_MAGTHRESH )
04519     continue;
04520 j1array[0]=IKatan2(((gconst33)*(((((r21)*(x1248)*(x1255)))+(((x1248)*(x1250)*(x1256)))+(((r12)*(x1256)*(x1264)))+(((IkReal(0.707103562373095))*(x1248)*(x1257)))+(((IkReal(-1.00000000000000))*(x1255)*(x1267)))+(((x1253)*(x1266)))+(((x1258)*(x1260)*(x1262)))+(((r01)*(sj2)*(x1248)*(x1253)))+(((x1252)*(x1264)))+(((IkReal(-1.00000000000000))*(r02)*(x1251)*(x1263)))+(((IkReal(-1.00000000000000))*(x1248)*(x1254)*(x1263)))+(((IkReal(-1.00000000000000))*(x1256)*(x1260)*(x1261)))+(((IkReal(-1.00000000000000))*(r12)*(x1249)*(x1251)))+(((x1251)*(x1265)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1253)*(x1260)))+(((IkReal(-1.00000000000000))*(x1259)*(x1267)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1248)*(x1249)))+(((cj2)*(r10)*(x1249)*(x1260)))))), ((gconst33)*(((((x1259)*(x1260)*(x1262)))+(((IkReal(0.707109999985348))*(x1248)*(x1257)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1248)*(x1255)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1248)*(x1259)))+(((cj2)*(r00)*(x1253)*(x1260)))+(((x1258)*(x1267)))+(((x1264)*(x1265)))+(((IkReal(-1.00000000000000))*(r21)*(x1248)*(x1258)))+(((r10)*(sj0)*(x1255)*(x1260)))+(((x1249)*(x1260)*(x1261)))+(((IkReal(-1.00000000000000))*(r12)*(x1251)*(x1256)))+(((IkReal(-1.00000000000000))*(x1248)*(x1249)*(x1250)))+(((IkReal(-1.00000000000000))*(x1248)*(x1253)*(x1254)))+(((IkReal(-1.00000000000000))*(x1251)*(x1252)))+(((IkReal(-1.00000000000000))*(r02)*(x1251)*(x1253)))+(((IkReal(-1.00000000000000))*(r12)*(x1249)*(x1264)))+(((IkReal(-0.707109999985348))*(sj2)*(x1267)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1259)))))));
04521 sj1array[0]=IKsin(j1array[0]);
04522 cj1array[0]=IKcos(j1array[0]);
04523 if( j1array[0] > IKPI )
04524 {
04525     j1array[0]-=IK2PI;
04526 }
04527 else if( j1array[0] < -IKPI )
04528 {    j1array[0]+=IK2PI;
04529 }
04530 j1valid[0] = true;
04531 for(int ij1 = 0; ij1 < 1; ++ij1)
04532 {
04533 if( !j1valid[ij1] )
04534 {
04535     continue;
04536 }
04537 _ij1[0] = ij1; _ij1[1] = -1;
04538 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04539 {
04540 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04541 {
04542     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04543 }
04544 }
04545 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04546 {
04547 IkReal evalcond[4];
04548 IkReal x1268=IKsin(j1);
04549 IkReal x1269=IKcos(j1);
04550 IkReal x1270=((IkReal(0.707109999985348))*(cj2));
04551 IkReal x1271=((IkReal(1.00000000000000))*(sj4));
04552 IkReal x1272=((cj5)*(r00));
04553 IkReal x1273=((IkReal(0.707109999985348))*(sj2));
04554 IkReal x1274=((cj5)*(r20));
04555 IkReal x1275=((r12)*(sj0));
04556 IkReal x1276=((r21)*(sj5));
04557 IkReal x1277=((IkReal(1.00000000000000))*(cj4));
04558 IkReal x1278=((IkReal(0.707103562373095))*(x1269));
04559 IkReal x1279=((r11)*(sj0)*(sj5));
04560 IkReal x1280=((cj0)*(x1277));
04561 IkReal x1281=((IkReal(0.707103562373095))*(x1268));
04562 IkReal x1282=((cj0)*(r01)*(sj5));
04563 IkReal x1283=((cj5)*(r10)*(sj0));
04564 IkReal x1284=((sj2)*(x1278));
04565 IkReal x1285=((cj2)*(x1281));
04566 IkReal x1286=((x1269)*(x1270));
04567 IkReal x1287=((x1268)*(x1273));
04568 IkReal x1288=((x1268)*(x1270));
04569 IkReal x1289=((sj2)*(x1281));
04570 IkReal x1290=((x1269)*(x1273));
04571 IkReal x1291=((cj2)*(x1278));
04572 IkReal x1292=((x1285)+(x1284)+(x1286));
04573 IkReal x1293=((x1289)+(x1288)+(x1290));
04574 evalcond[0]=((x1293)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1291)))+(((IkReal(-1.00000000000000))*(x1271)*(x1274)))+(((sj4)*(x1276))));
04575 evalcond[1]=((x1287)+(((IkReal(-1.00000000000000))*(x1292)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1276)*(x1277)))+(((cj4)*(x1274))));
04576 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x1280)))+(x1292)+(((sj4)*(x1283)))+(((IkReal(-1.00000000000000))*(x1271)*(x1279)))+(((IkReal(-1.00000000000000))*(x1275)*(x1277)))+(((cj0)*(sj4)*(x1272)))+(((IkReal(-1.00000000000000))*(x1271)*(x1282)))+(((IkReal(-1.00000000000000))*(x1287))));
04577 evalcond[3]=((x1293)+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1271)))+(((IkReal(-1.00000000000000))*(x1291)))+(((cj4)*(x1282)))+(((IkReal(-1.00000000000000))*(x1271)*(x1275)))+(((IkReal(-1.00000000000000))*(x1277)*(x1283)))+(((IkReal(-1.00000000000000))*(x1272)*(x1280)))+(((cj4)*(x1279))));
04578 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04579 {
04580 continue;
04581 }
04582 }
04583 
04584 {
04585 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04586 vinfos[0].jointtype = 1;
04587 vinfos[0].foffset = j0;
04588 vinfos[0].indices[0] = _ij0[0];
04589 vinfos[0].indices[1] = _ij0[1];
04590 vinfos[0].maxsolutions = _nj0;
04591 vinfos[1].jointtype = 1;
04592 vinfos[1].foffset = j1;
04593 vinfos[1].indices[0] = _ij1[0];
04594 vinfos[1].indices[1] = _ij1[1];
04595 vinfos[1].maxsolutions = _nj1;
04596 vinfos[2].jointtype = 1;
04597 vinfos[2].foffset = j2;
04598 vinfos[2].indices[0] = _ij2[0];
04599 vinfos[2].indices[1] = _ij2[1];
04600 vinfos[2].maxsolutions = _nj2;
04601 vinfos[3].jointtype = 1;
04602 vinfos[3].foffset = j3;
04603 vinfos[3].indices[0] = _ij3[0];
04604 vinfos[3].indices[1] = _ij3[1];
04605 vinfos[3].maxsolutions = _nj3;
04606 vinfos[4].jointtype = 1;
04607 vinfos[4].foffset = j4;
04608 vinfos[4].indices[0] = _ij4[0];
04609 vinfos[4].indices[1] = _ij4[1];
04610 vinfos[4].maxsolutions = _nj4;
04611 vinfos[5].jointtype = 1;
04612 vinfos[5].foffset = j5;
04613 vinfos[5].indices[0] = _ij5[0];
04614 vinfos[5].indices[1] = _ij5[1];
04615 vinfos[5].maxsolutions = _nj5;
04616 std::vector<int> vfree(0);
04617 solutions.AddSolution(vinfos,vfree);
04618 }
04619 }
04620 }
04621 
04622 }
04623 
04624 }
04625 
04626 } else
04627 {
04628 {
04629 IkReal j1array[1], cj1array[1], sj1array[1];
04630 bool j1valid[1]={false};
04631 _nj1 = 1;
04632 IkReal x1294=((IkReal(0.707109999985348))*(sj4));
04633 IkReal x1295=((r22)*(sj2));
04634 IkReal x1296=((cj5)*(r20));
04635 IkReal x1297=((r21)*(sj5));
04636 IkReal x1298=((IkReal(0.707109999985348))*(cj4));
04637 IkReal x1299=((IkReal(0.707103562373095))*(sj4));
04638 IkReal x1300=((cj2)*(r22));
04639 IkReal x1301=((IkReal(0.707103562373095))*(cj4));
04640 IkReal x1302=((sj2)*(x1301));
04641 IkReal x1303=((cj2)*(x1301));
04642 if( IKabs(((gconst32)*(((((x1299)*(x1300)))+(((sj2)*(x1297)*(x1298)))+(((IkReal(-1.00000000000000))*(x1297)*(x1303)))+(((IkReal(-1.00000000000000))*(cj2)*(x1294)*(x1297)))+(((IkReal(-1.00000000000000))*(sj2)*(x1296)*(x1298)))+(((sj2)*(x1296)*(x1299)))+(((cj2)*(x1294)*(x1296)))+(((IkReal(-1.00000000000000))*(sj2)*(x1297)*(x1299)))+(((IkReal(-1.00000000000000))*(x1298)*(x1300)))+(((IkReal(-1.00000000000000))*(x1295)*(x1301)))+(((x1296)*(x1303)))+(((IkReal(-1.00000000000000))*(x1294)*(x1295))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst32)*(((((IkReal(-1.00000000000000))*(cj2)*(x1297)*(x1298)))+(((cj2)*(x1297)*(x1299)))+(((sj2)*(x1294)*(x1296)))+(((IkReal(-1.00000000000000))*(sj2)*(x1294)*(x1297)))+(((x1295)*(x1299)))+(((IkReal(-1.00000000000000))*(cj2)*(x1296)*(x1299)))+(((x1300)*(x1301)))+(((IkReal(-1.00000000000000))*(x1297)*(x1302)))+(((x1294)*(x1300)))+(((cj2)*(x1296)*(x1298)))+(((IkReal(-1.00000000000000))*(x1295)*(x1298)))+(((x1296)*(x1302))))))) < IKFAST_ATAN2_MAGTHRESH )
04643     continue;
04644 j1array[0]=IKatan2(((gconst32)*(((((x1299)*(x1300)))+(((sj2)*(x1297)*(x1298)))+(((IkReal(-1.00000000000000))*(x1297)*(x1303)))+(((IkReal(-1.00000000000000))*(cj2)*(x1294)*(x1297)))+(((IkReal(-1.00000000000000))*(sj2)*(x1296)*(x1298)))+(((sj2)*(x1296)*(x1299)))+(((cj2)*(x1294)*(x1296)))+(((IkReal(-1.00000000000000))*(sj2)*(x1297)*(x1299)))+(((IkReal(-1.00000000000000))*(x1298)*(x1300)))+(((IkReal(-1.00000000000000))*(x1295)*(x1301)))+(((x1296)*(x1303)))+(((IkReal(-1.00000000000000))*(x1294)*(x1295)))))), ((gconst32)*(((((IkReal(-1.00000000000000))*(cj2)*(x1297)*(x1298)))+(((cj2)*(x1297)*(x1299)))+(((sj2)*(x1294)*(x1296)))+(((IkReal(-1.00000000000000))*(sj2)*(x1294)*(x1297)))+(((x1295)*(x1299)))+(((IkReal(-1.00000000000000))*(cj2)*(x1296)*(x1299)))+(((x1300)*(x1301)))+(((IkReal(-1.00000000000000))*(x1297)*(x1302)))+(((x1294)*(x1300)))+(((cj2)*(x1296)*(x1298)))+(((IkReal(-1.00000000000000))*(x1295)*(x1298)))+(((x1296)*(x1302)))))));
04645 sj1array[0]=IKsin(j1array[0]);
04646 cj1array[0]=IKcos(j1array[0]);
04647 if( j1array[0] > IKPI )
04648 {
04649     j1array[0]-=IK2PI;
04650 }
04651 else if( j1array[0] < -IKPI )
04652 {    j1array[0]+=IK2PI;
04653 }
04654 j1valid[0] = true;
04655 for(int ij1 = 0; ij1 < 1; ++ij1)
04656 {
04657 if( !j1valid[ij1] )
04658 {
04659     continue;
04660 }
04661 _ij1[0] = ij1; _ij1[1] = -1;
04662 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04663 {
04664 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04665 {
04666     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04667 }
04668 }
04669 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04670 {
04671 IkReal evalcond[4];
04672 IkReal x1304=IKsin(j1);
04673 IkReal x1305=IKcos(j1);
04674 IkReal x1306=((IkReal(0.707109999985348))*(cj2));
04675 IkReal x1307=((IkReal(1.00000000000000))*(sj4));
04676 IkReal x1308=((cj5)*(r00));
04677 IkReal x1309=((IkReal(0.707109999985348))*(sj2));
04678 IkReal x1310=((cj5)*(r20));
04679 IkReal x1311=((r12)*(sj0));
04680 IkReal x1312=((r21)*(sj5));
04681 IkReal x1313=((IkReal(1.00000000000000))*(cj4));
04682 IkReal x1314=((IkReal(0.707103562373095))*(x1305));
04683 IkReal x1315=((r11)*(sj0)*(sj5));
04684 IkReal x1316=((cj0)*(x1313));
04685 IkReal x1317=((IkReal(0.707103562373095))*(x1304));
04686 IkReal x1318=((cj0)*(r01)*(sj5));
04687 IkReal x1319=((cj5)*(r10)*(sj0));
04688 IkReal x1320=((sj2)*(x1314));
04689 IkReal x1321=((cj2)*(x1317));
04690 IkReal x1322=((x1305)*(x1306));
04691 IkReal x1323=((x1304)*(x1309));
04692 IkReal x1324=((x1304)*(x1306));
04693 IkReal x1325=((sj2)*(x1317));
04694 IkReal x1326=((x1305)*(x1309));
04695 IkReal x1327=((cj2)*(x1314));
04696 IkReal x1328=((x1322)+(x1320)+(x1321));
04697 IkReal x1329=((x1326)+(x1324)+(x1325));
04698 evalcond[0]=((x1329)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1327)))+(((IkReal(-1.00000000000000))*(x1307)*(x1310)))+(((sj4)*(x1312))));
04699 evalcond[1]=((x1323)+(((cj4)*(x1310)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1328)))+(((IkReal(-1.00000000000000))*(x1312)*(x1313))));
04700 evalcond[2]=((x1328)+(((IkReal(-1.00000000000000))*(x1311)*(x1313)))+(((IkReal(-1.00000000000000))*(x1323)))+(((IkReal(-1.00000000000000))*(x1307)*(x1318)))+(((IkReal(-1.00000000000000))*(x1307)*(x1315)))+(((cj0)*(sj4)*(x1308)))+(((sj4)*(x1319)))+(((IkReal(-1.00000000000000))*(r02)*(x1316))));
04701 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1307)))+(x1329)+(((IkReal(-1.00000000000000))*(x1313)*(x1319)))+(((IkReal(-1.00000000000000))*(x1308)*(x1316)))+(((cj4)*(x1318)))+(((cj4)*(x1315)))+(((IkReal(-1.00000000000000))*(x1327)))+(((IkReal(-1.00000000000000))*(x1307)*(x1311))));
04702 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04703 {
04704 continue;
04705 }
04706 }
04707 
04708 {
04709 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04710 vinfos[0].jointtype = 1;
04711 vinfos[0].foffset = j0;
04712 vinfos[0].indices[0] = _ij0[0];
04713 vinfos[0].indices[1] = _ij0[1];
04714 vinfos[0].maxsolutions = _nj0;
04715 vinfos[1].jointtype = 1;
04716 vinfos[1].foffset = j1;
04717 vinfos[1].indices[0] = _ij1[0];
04718 vinfos[1].indices[1] = _ij1[1];
04719 vinfos[1].maxsolutions = _nj1;
04720 vinfos[2].jointtype = 1;
04721 vinfos[2].foffset = j2;
04722 vinfos[2].indices[0] = _ij2[0];
04723 vinfos[2].indices[1] = _ij2[1];
04724 vinfos[2].maxsolutions = _nj2;
04725 vinfos[3].jointtype = 1;
04726 vinfos[3].foffset = j3;
04727 vinfos[3].indices[0] = _ij3[0];
04728 vinfos[3].indices[1] = _ij3[1];
04729 vinfos[3].maxsolutions = _nj3;
04730 vinfos[4].jointtype = 1;
04731 vinfos[4].foffset = j4;
04732 vinfos[4].indices[0] = _ij4[0];
04733 vinfos[4].indices[1] = _ij4[1];
04734 vinfos[4].maxsolutions = _nj4;
04735 vinfos[5].jointtype = 1;
04736 vinfos[5].foffset = j5;
04737 vinfos[5].indices[0] = _ij5[0];
04738 vinfos[5].indices[1] = _ij5[1];
04739 vinfos[5].maxsolutions = _nj5;
04740 std::vector<int> vfree(0);
04741 solutions.AddSolution(vinfos,vfree);
04742 }
04743 }
04744 }
04745 
04746 }
04747 
04748 }
04749 }
04750 }
04751 
04752 }
04753 
04754 }
04755 
04756 } else
04757 {
04758 {
04759 IkReal j0array[1], cj0array[1], sj0array[1];
04760 bool j0valid[1]={false};
04761 _nj0 = 1;
04762 if( IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst27)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
04763     continue;
04764 j0array[0]=IKatan2(((gconst27)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst27)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
04765 sj0array[0]=IKsin(j0array[0]);
04766 cj0array[0]=IKcos(j0array[0]);
04767 if( j0array[0] > IKPI )
04768 {
04769     j0array[0]-=IK2PI;
04770 }
04771 else if( j0array[0] < -IKPI )
04772 {    j0array[0]+=IK2PI;
04773 }
04774 j0valid[0] = true;
04775 for(int ij0 = 0; ij0 < 1; ++ij0)
04776 {
04777 if( !j0valid[ij0] )
04778 {
04779     continue;
04780 }
04781 _ij0[0] = ij0; _ij0[1] = -1;
04782 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04783 {
04784 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04785 {
04786     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04787 }
04788 }
04789 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04790 {
04791 IkReal evalcond[4];
04792 IkReal x1330=IKsin(j0);
04793 IkReal x1331=IKcos(j0);
04794 IkReal x1332=((IkReal(1.00000000000000))*(cj5));
04795 IkReal x1333=((r01)*(sj5));
04796 IkReal x1334=((IkReal(1.00000000000000))*(r12));
04797 IkReal x1335=((r11)*(sj5));
04798 IkReal x1336=((IkReal(1.00000000000000))*(r10));
04799 IkReal x1337=((cj4)*(x1330));
04800 IkReal x1338=((sj4)*(x1330));
04801 IkReal x1339=((sj4)*(x1331));
04802 IkReal x1340=((sj5)*(x1330));
04803 IkReal x1341=((cj4)*(x1331));
04804 IkReal x1342=((sj5)*(x1331));
04805 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1336)*(x1342)))+(((cj5)*(r01)*(x1330)))+(((r00)*(x1340)))+(((IkReal(-1.00000000000000))*(r11)*(x1331)*(x1332))));
04806 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x1332)*(x1338)))+(((IkReal(-1.00000000000000))*(x1335)*(x1339)))+(((cj5)*(r10)*(x1339)))+(((IkReal(-1.00000000000000))*(x1334)*(x1341)))+(((r02)*(x1337)))+(((x1333)*(x1338))));
04807 evalcond[2]=((((IkReal(-1.00000000000000))*(x1333)*(x1337)))+(((cj5)*(r00)*(x1337)))+(((IkReal(-1.00000000000000))*(r10)*(x1332)*(x1341)))+(((IkReal(-1.00000000000000))*(x1334)*(x1339)))+(((x1335)*(x1341)))+(((r02)*(x1338))));
04808 evalcond[3]=((((IkReal(-1.00000000000000))*(x1336)*(x1340)))+(((IkReal(-1.00000000000000))*(r01)*(x1331)*(x1332)))+(((IkReal(-1.00000000000000))*(r11)*(x1330)*(x1332)))+(((IkReal(-1.00000000000000))*(r00)*(x1342))));
04809 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04810 {
04811 continue;
04812 }
04813 }
04814 
04815 {
04816 IkReal dummyeval[1];
04817 IkReal gconst32;
04818 gconst32=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
04819 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
04820 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04821 {
04822 {
04823 IkReal dummyeval[1];
04824 IkReal gconst33;
04825 gconst33=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
04826 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
04827 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04828 {
04829 continue;
04830 
04831 } else
04832 {
04833 {
04834 IkReal j1array[1], cj1array[1], sj1array[1];
04835 bool j1valid[1]={false};
04836 _nj1 = 1;
04837 IkReal x1343=((sj4)*(sj5));
04838 IkReal x1344=((IkReal(0.707103562373095))*(sj0));
04839 IkReal x1345=((r11)*(sj2));
04840 IkReal x1346=((cj2)*(cj4));
04841 IkReal x1347=((IkReal(0.707103562373095))*(r22));
04842 IkReal x1348=((IkReal(0.707109999985348))*(cj0));
04843 IkReal x1349=((cj2)*(r01));
04844 IkReal x1350=((IkReal(0.707109999985348))*(cj2));
04845 IkReal x1351=((IkReal(0.707109999985348))*(sj0));
04846 IkReal x1352=((r21)*(sj2));
04847 IkReal x1353=((IkReal(0.707103562373095))*(cj2));
04848 IkReal x1354=((IkReal(0.707103562373095))*(sj2));
04849 IkReal x1355=((cj5)*(sj4));
04850 IkReal x1356=((r10)*(sj2));
04851 IkReal x1357=((cj0)*(r00));
04852 IkReal x1358=((IkReal(0.707103562373095))*(cj0));
04853 IkReal x1359=((cj4)*(sj2));
04854 IkReal x1360=((IkReal(0.707109999985348))*(r22));
04855 IkReal x1361=((r02)*(x1359));
04856 IkReal x1362=((r20)*(x1355));
04857 if( IKabs(((gconst33)*(((((IkReal(-1.00000000000000))*(x1351)*(x1355)*(x1356)))+(((r12)*(x1351)*(x1359)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1343)*(x1344)))+(((IkReal(0.707103562373095))*(x1343)*(x1352)))+(((IkReal(-1.00000000000000))*(x1350)*(x1362)))+(((IkReal(-1.00000000000000))*(x1343)*(x1349)*(x1358)))+(((IkReal(-1.00000000000000))*(x1354)*(x1362)))+(((IkReal(-1.00000000000000))*(r12)*(x1344)*(x1346)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1348)*(x1355)))+(((cj2)*(r10)*(x1344)*(x1355)))+(((r21)*(x1343)*(x1350)))+(((r01)*(sj2)*(x1343)*(x1348)))+(((x1348)*(x1361)))+(((x1346)*(x1360)))+(((x1347)*(x1359)))+(((x1353)*(x1355)*(x1357)))+(((IkReal(-1.00000000000000))*(r02)*(x1346)*(x1358)))+(((x1343)*(x1345)*(x1351))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((cj2)*(r00)*(x1348)*(x1355)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1343)*(x1350)))+(((IkReal(-1.00000000000000))*(x1346)*(x1347)))+(((x1344)*(x1355)*(x1356)))+(((IkReal(0.707109999985348))*(x1343)*(x1352)))+(((IkReal(-1.00000000000000))*(r21)*(x1343)*(x1353)))+(((x1359)*(x1360)))+(((IkReal(-1.00000000000000))*(x1343)*(x1344)*(x1345)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1343)*(x1354)))+(((x1354)*(x1355)*(x1357)))+(((IkReal(-1.00000000000000))*(x1343)*(x1348)*(x1349)))+(((IkReal(-1.00000000000000))*(r12)*(x1344)*(x1359)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1354)))+(((r10)*(sj0)*(x1350)*(x1355)))+(((IkReal(-0.707109999985348))*(sj2)*(x1362)))+(((x1353)*(x1362)))+(((IkReal(-1.00000000000000))*(r02)*(x1346)*(x1348)))+(((IkReal(-1.00000000000000))*(r12)*(x1346)*(x1351))))))) < IKFAST_ATAN2_MAGTHRESH )
04858     continue;
04859 j1array[0]=IKatan2(((gconst33)*(((((IkReal(-1.00000000000000))*(x1351)*(x1355)*(x1356)))+(((r12)*(x1351)*(x1359)))+(((IkReal(-1.00000000000000))*(cj2)*(r11)*(x1343)*(x1344)))+(((IkReal(0.707103562373095))*(x1343)*(x1352)))+(((IkReal(-1.00000000000000))*(x1350)*(x1362)))+(((IkReal(-1.00000000000000))*(x1343)*(x1349)*(x1358)))+(((IkReal(-1.00000000000000))*(x1354)*(x1362)))+(((IkReal(-1.00000000000000))*(r12)*(x1344)*(x1346)))+(((IkReal(-1.00000000000000))*(r00)*(sj2)*(x1348)*(x1355)))+(((cj2)*(r10)*(x1344)*(x1355)))+(((r21)*(x1343)*(x1350)))+(((r01)*(sj2)*(x1343)*(x1348)))+(((x1348)*(x1361)))+(((x1346)*(x1360)))+(((x1347)*(x1359)))+(((x1353)*(x1355)*(x1357)))+(((IkReal(-1.00000000000000))*(r02)*(x1346)*(x1358)))+(((x1343)*(x1345)*(x1351)))))), ((gconst33)*(((((cj2)*(r00)*(x1348)*(x1355)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(x1343)*(x1350)))+(((IkReal(-1.00000000000000))*(x1346)*(x1347)))+(((x1344)*(x1355)*(x1356)))+(((IkReal(0.707109999985348))*(x1343)*(x1352)))+(((IkReal(-1.00000000000000))*(r21)*(x1343)*(x1353)))+(((x1359)*(x1360)))+(((IkReal(-1.00000000000000))*(x1343)*(x1344)*(x1345)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1343)*(x1354)))+(((x1354)*(x1355)*(x1357)))+(((IkReal(-1.00000000000000))*(x1343)*(x1348)*(x1349)))+(((IkReal(-1.00000000000000))*(r12)*(x1344)*(x1359)))+(((IkReal(-1.00000000000000))*(cj0)*(cj4)*(r02)*(x1354)))+(((r10)*(sj0)*(x1350)*(x1355)))+(((IkReal(-0.707109999985348))*(sj2)*(x1362)))+(((x1353)*(x1362)))+(((IkReal(-1.00000000000000))*(r02)*(x1346)*(x1348)))+(((IkReal(-1.00000000000000))*(r12)*(x1346)*(x1351)))))));
04860 sj1array[0]=IKsin(j1array[0]);
04861 cj1array[0]=IKcos(j1array[0]);
04862 if( j1array[0] > IKPI )
04863 {
04864     j1array[0]-=IK2PI;
04865 }
04866 else if( j1array[0] < -IKPI )
04867 {    j1array[0]+=IK2PI;
04868 }
04869 j1valid[0] = true;
04870 for(int ij1 = 0; ij1 < 1; ++ij1)
04871 {
04872 if( !j1valid[ij1] )
04873 {
04874     continue;
04875 }
04876 _ij1[0] = ij1; _ij1[1] = -1;
04877 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04878 {
04879 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04880 {
04881     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04882 }
04883 }
04884 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04885 {
04886 IkReal evalcond[4];
04887 IkReal x1363=IKsin(j1);
04888 IkReal x1364=IKcos(j1);
04889 IkReal x1365=((IkReal(0.707109999985348))*(cj2));
04890 IkReal x1366=((IkReal(1.00000000000000))*(sj4));
04891 IkReal x1367=((cj5)*(r00));
04892 IkReal x1368=((IkReal(0.707109999985348))*(sj2));
04893 IkReal x1369=((cj5)*(r20));
04894 IkReal x1370=((r12)*(sj0));
04895 IkReal x1371=((r21)*(sj5));
04896 IkReal x1372=((IkReal(1.00000000000000))*(cj4));
04897 IkReal x1373=((IkReal(0.707103562373095))*(x1364));
04898 IkReal x1374=((r11)*(sj0)*(sj5));
04899 IkReal x1375=((cj0)*(x1372));
04900 IkReal x1376=((IkReal(0.707103562373095))*(x1363));
04901 IkReal x1377=((cj0)*(r01)*(sj5));
04902 IkReal x1378=((cj5)*(r10)*(sj0));
04903 IkReal x1379=((sj2)*(x1373));
04904 IkReal x1380=((cj2)*(x1376));
04905 IkReal x1381=((x1364)*(x1365));
04906 IkReal x1382=((x1363)*(x1368));
04907 IkReal x1383=((x1363)*(x1365));
04908 IkReal x1384=((sj2)*(x1376));
04909 IkReal x1385=((x1364)*(x1368));
04910 IkReal x1386=((cj2)*(x1373));
04911 IkReal x1387=((x1379)+(x1380)+(x1381));
04912 IkReal x1388=((x1384)+(x1385)+(x1383));
04913 evalcond[0]=((((IkReal(-1.00000000000000))*(x1366)*(x1369)))+(((IkReal(-1.00000000000000))*(x1386)))+(x1388)+(((cj4)*(r22)))+(((sj4)*(x1371))));
04914 evalcond[1]=((((IkReal(-1.00000000000000))*(x1387)))+(x1382)+(((IkReal(-1.00000000000000))*(x1371)*(x1372)))+(((r22)*(sj4)))+(((cj4)*(x1369))));
04915 evalcond[2]=((((IkReal(-1.00000000000000))*(x1382)))+(x1387)+(((IkReal(-1.00000000000000))*(x1370)*(x1372)))+(((IkReal(-1.00000000000000))*(r02)*(x1375)))+(((cj0)*(sj4)*(x1367)))+(((sj4)*(x1378)))+(((IkReal(-1.00000000000000))*(x1366)*(x1374)))+(((IkReal(-1.00000000000000))*(x1366)*(x1377))));
04916 evalcond[3]=((((IkReal(-1.00000000000000))*(x1386)))+(x1388)+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1366)))+(((cj4)*(x1377)))+(((cj4)*(x1374)))+(((IkReal(-1.00000000000000))*(x1372)*(x1378)))+(((IkReal(-1.00000000000000))*(x1366)*(x1370)))+(((IkReal(-1.00000000000000))*(x1367)*(x1375))));
04917 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04918 {
04919 continue;
04920 }
04921 }
04922 
04923 {
04924 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04925 vinfos[0].jointtype = 1;
04926 vinfos[0].foffset = j0;
04927 vinfos[0].indices[0] = _ij0[0];
04928 vinfos[0].indices[1] = _ij0[1];
04929 vinfos[0].maxsolutions = _nj0;
04930 vinfos[1].jointtype = 1;
04931 vinfos[1].foffset = j1;
04932 vinfos[1].indices[0] = _ij1[0];
04933 vinfos[1].indices[1] = _ij1[1];
04934 vinfos[1].maxsolutions = _nj1;
04935 vinfos[2].jointtype = 1;
04936 vinfos[2].foffset = j2;
04937 vinfos[2].indices[0] = _ij2[0];
04938 vinfos[2].indices[1] = _ij2[1];
04939 vinfos[2].maxsolutions = _nj2;
04940 vinfos[3].jointtype = 1;
04941 vinfos[3].foffset = j3;
04942 vinfos[3].indices[0] = _ij3[0];
04943 vinfos[3].indices[1] = _ij3[1];
04944 vinfos[3].maxsolutions = _nj3;
04945 vinfos[4].jointtype = 1;
04946 vinfos[4].foffset = j4;
04947 vinfos[4].indices[0] = _ij4[0];
04948 vinfos[4].indices[1] = _ij4[1];
04949 vinfos[4].maxsolutions = _nj4;
04950 vinfos[5].jointtype = 1;
04951 vinfos[5].foffset = j5;
04952 vinfos[5].indices[0] = _ij5[0];
04953 vinfos[5].indices[1] = _ij5[1];
04954 vinfos[5].maxsolutions = _nj5;
04955 std::vector<int> vfree(0);
04956 solutions.AddSolution(vinfos,vfree);
04957 }
04958 }
04959 }
04960 
04961 }
04962 
04963 }
04964 
04965 } else
04966 {
04967 {
04968 IkReal j1array[1], cj1array[1], sj1array[1];
04969 bool j1valid[1]={false};
04970 _nj1 = 1;
04971 IkReal x1389=((IkReal(0.707109999985348))*(sj4));
04972 IkReal x1390=((r22)*(sj2));
04973 IkReal x1391=((cj5)*(r20));
04974 IkReal x1392=((r21)*(sj5));
04975 IkReal x1393=((IkReal(0.707109999985348))*(cj4));
04976 IkReal x1394=((IkReal(0.707103562373095))*(sj4));
04977 IkReal x1395=((cj2)*(r22));
04978 IkReal x1396=((IkReal(0.707103562373095))*(cj4));
04979 IkReal x1397=((sj2)*(x1396));
04980 IkReal x1398=((cj2)*(x1396));
04981 if( IKabs(((gconst32)*(((((IkReal(-1.00000000000000))*(x1392)*(x1398)))+(((sj2)*(x1392)*(x1393)))+(((cj2)*(x1389)*(x1391)))+(((IkReal(-1.00000000000000))*(x1389)*(x1390)))+(((sj2)*(x1391)*(x1394)))+(((IkReal(-1.00000000000000))*(x1393)*(x1395)))+(((IkReal(-1.00000000000000))*(cj2)*(x1389)*(x1392)))+(((x1394)*(x1395)))+(((IkReal(-1.00000000000000))*(x1390)*(x1396)))+(((IkReal(-1.00000000000000))*(sj2)*(x1391)*(x1393)))+(((IkReal(-1.00000000000000))*(sj2)*(x1392)*(x1394)))+(((x1391)*(x1398))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst32)*(((((IkReal(-1.00000000000000))*(sj2)*(x1389)*(x1392)))+(((IkReal(-1.00000000000000))*(x1392)*(x1397)))+(((x1390)*(x1394)))+(((sj2)*(x1389)*(x1391)))+(((x1395)*(x1396)))+(((IkReal(-1.00000000000000))*(x1390)*(x1393)))+(((cj2)*(x1392)*(x1394)))+(((IkReal(-1.00000000000000))*(cj2)*(x1391)*(x1394)))+(((x1389)*(x1395)))+(((x1391)*(x1397)))+(((IkReal(-1.00000000000000))*(cj2)*(x1392)*(x1393)))+(((cj2)*(x1391)*(x1393))))))) < IKFAST_ATAN2_MAGTHRESH )
04982     continue;
04983 j1array[0]=IKatan2(((gconst32)*(((((IkReal(-1.00000000000000))*(x1392)*(x1398)))+(((sj2)*(x1392)*(x1393)))+(((cj2)*(x1389)*(x1391)))+(((IkReal(-1.00000000000000))*(x1389)*(x1390)))+(((sj2)*(x1391)*(x1394)))+(((IkReal(-1.00000000000000))*(x1393)*(x1395)))+(((IkReal(-1.00000000000000))*(cj2)*(x1389)*(x1392)))+(((x1394)*(x1395)))+(((IkReal(-1.00000000000000))*(x1390)*(x1396)))+(((IkReal(-1.00000000000000))*(sj2)*(x1391)*(x1393)))+(((IkReal(-1.00000000000000))*(sj2)*(x1392)*(x1394)))+(((x1391)*(x1398)))))), ((gconst32)*(((((IkReal(-1.00000000000000))*(sj2)*(x1389)*(x1392)))+(((IkReal(-1.00000000000000))*(x1392)*(x1397)))+(((x1390)*(x1394)))+(((sj2)*(x1389)*(x1391)))+(((x1395)*(x1396)))+(((IkReal(-1.00000000000000))*(x1390)*(x1393)))+(((cj2)*(x1392)*(x1394)))+(((IkReal(-1.00000000000000))*(cj2)*(x1391)*(x1394)))+(((x1389)*(x1395)))+(((x1391)*(x1397)))+(((IkReal(-1.00000000000000))*(cj2)*(x1392)*(x1393)))+(((cj2)*(x1391)*(x1393)))))));
04984 sj1array[0]=IKsin(j1array[0]);
04985 cj1array[0]=IKcos(j1array[0]);
04986 if( j1array[0] > IKPI )
04987 {
04988     j1array[0]-=IK2PI;
04989 }
04990 else if( j1array[0] < -IKPI )
04991 {    j1array[0]+=IK2PI;
04992 }
04993 j1valid[0] = true;
04994 for(int ij1 = 0; ij1 < 1; ++ij1)
04995 {
04996 if( !j1valid[ij1] )
04997 {
04998     continue;
04999 }
05000 _ij1[0] = ij1; _ij1[1] = -1;
05001 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05002 {
05003 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05004 {
05005     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05006 }
05007 }
05008 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05009 {
05010 IkReal evalcond[4];
05011 IkReal x1399=IKsin(j1);
05012 IkReal x1400=IKcos(j1);
05013 IkReal x1401=((IkReal(0.707109999985348))*(cj2));
05014 IkReal x1402=((IkReal(1.00000000000000))*(sj4));
05015 IkReal x1403=((cj5)*(r00));
05016 IkReal x1404=((IkReal(0.707109999985348))*(sj2));
05017 IkReal x1405=((cj5)*(r20));
05018 IkReal x1406=((r12)*(sj0));
05019 IkReal x1407=((r21)*(sj5));
05020 IkReal x1408=((IkReal(1.00000000000000))*(cj4));
05021 IkReal x1409=((IkReal(0.707103562373095))*(x1400));
05022 IkReal x1410=((r11)*(sj0)*(sj5));
05023 IkReal x1411=((cj0)*(x1408));
05024 IkReal x1412=((IkReal(0.707103562373095))*(x1399));
05025 IkReal x1413=((cj0)*(r01)*(sj5));
05026 IkReal x1414=((cj5)*(r10)*(sj0));
05027 IkReal x1415=((sj2)*(x1409));
05028 IkReal x1416=((cj2)*(x1412));
05029 IkReal x1417=((x1400)*(x1401));
05030 IkReal x1418=((x1399)*(x1404));
05031 IkReal x1419=((x1399)*(x1401));
05032 IkReal x1420=((sj2)*(x1412));
05033 IkReal x1421=((x1400)*(x1404));
05034 IkReal x1422=((cj2)*(x1409));
05035 IkReal x1423=((x1415)+(x1416)+(x1417));
05036 IkReal x1424=((x1421)+(x1420)+(x1419));
05037 evalcond[0]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1402)*(x1405)))+(x1424)+(((sj4)*(x1407)))+(((IkReal(-1.00000000000000))*(x1422))));
05038 evalcond[1]=((((r22)*(sj4)))+(((cj4)*(x1405)))+(x1418)+(((IkReal(-1.00000000000000))*(x1407)*(x1408)))+(((IkReal(-1.00000000000000))*(x1423))));
05039 evalcond[2]=((((IkReal(-1.00000000000000))*(x1418)))+(((IkReal(-1.00000000000000))*(r02)*(x1411)))+(((IkReal(-1.00000000000000))*(x1406)*(x1408)))+(((cj0)*(sj4)*(x1403)))+(((sj4)*(x1414)))+(x1423)+(((IkReal(-1.00000000000000))*(x1402)*(x1413)))+(((IkReal(-1.00000000000000))*(x1402)*(x1410))));
05040 evalcond[3]=((((cj4)*(x1413)))+(((cj4)*(x1410)))+(((IkReal(-1.00000000000000))*(x1408)*(x1414)))+(((IkReal(-1.00000000000000))*(x1402)*(x1406)))+(((IkReal(-1.00000000000000))*(x1403)*(x1411)))+(x1424)+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1402)))+(((IkReal(-1.00000000000000))*(x1422))));
05041 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05042 {
05043 continue;
05044 }
05045 }
05046 
05047 {
05048 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05049 vinfos[0].jointtype = 1;
05050 vinfos[0].foffset = j0;
05051 vinfos[0].indices[0] = _ij0[0];
05052 vinfos[0].indices[1] = _ij0[1];
05053 vinfos[0].maxsolutions = _nj0;
05054 vinfos[1].jointtype = 1;
05055 vinfos[1].foffset = j1;
05056 vinfos[1].indices[0] = _ij1[0];
05057 vinfos[1].indices[1] = _ij1[1];
05058 vinfos[1].maxsolutions = _nj1;
05059 vinfos[2].jointtype = 1;
05060 vinfos[2].foffset = j2;
05061 vinfos[2].indices[0] = _ij2[0];
05062 vinfos[2].indices[1] = _ij2[1];
05063 vinfos[2].maxsolutions = _nj2;
05064 vinfos[3].jointtype = 1;
05065 vinfos[3].foffset = j3;
05066 vinfos[3].indices[0] = _ij3[0];
05067 vinfos[3].indices[1] = _ij3[1];
05068 vinfos[3].maxsolutions = _nj3;
05069 vinfos[4].jointtype = 1;
05070 vinfos[4].foffset = j4;
05071 vinfos[4].indices[0] = _ij4[0];
05072 vinfos[4].indices[1] = _ij4[1];
05073 vinfos[4].maxsolutions = _nj4;
05074 vinfos[5].jointtype = 1;
05075 vinfos[5].foffset = j5;
05076 vinfos[5].indices[0] = _ij5[0];
05077 vinfos[5].indices[1] = _ij5[1];
05078 vinfos[5].maxsolutions = _nj5;
05079 std::vector<int> vfree(0);
05080 solutions.AddSolution(vinfos,vfree);
05081 }
05082 }
05083 }
05084 
05085 }
05086 
05087 }
05088 }
05089 }
05090 
05091 }
05092 
05093 }
05094 
05095 } else
05096 {
05097 if( 1 )
05098 {
05099 continue;
05100 
05101 } else
05102 {
05103 }
05104 }
05105 }
05106 }
05107 
05108 } else
05109 {
05110 {
05111 IkReal j1array[1], cj1array[1], sj1array[1];
05112 bool j1valid[1]={false};
05113 _nj1 = 1;
05114 IkReal x1425=((sj2)*(sj3));
05115 IkReal x1426=((cj4)*(r22));
05116 IkReal x1427=((r20)*(sj5));
05117 IkReal x1428=((IkReal(0.707103562373095))*(cj2));
05118 IkReal x1429=((IkReal(0.707109999985348))*(sj2));
05119 IkReal x1430=((IkReal(0.707109999985348))*(cj2));
05120 IkReal x1431=((cj5)*(r21));
05121 IkReal x1432=((IkReal(0.707103562373095))*(sj2));
05122 IkReal x1433=((r21)*(sj4)*(sj5));
05123 IkReal x1434=((cj5)*(r20)*(sj4));
05124 if( IKabs(((gconst6)*(((((x1429)*(x1431)))+(((IkReal(0.707103562373095))*(x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(x1427)*(x1428)))+(((IkReal(-1.00000000000000))*(sj3)*(x1430)*(x1434)))+(((sj3)*(x1430)*(x1433)))+(((sj3)*(x1426)*(x1430)))+(((IkReal(-1.00000000000000))*(x1428)*(x1431)))+(((IkReal(-0.707103562373095))*(x1425)*(x1434)))+(((IkReal(0.707103562373095))*(x1425)*(x1433)))+(((x1427)*(x1429))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((IkReal(-0.707109999985348))*(x1425)*(x1434)))+(((IkReal(0.707109999985348))*(x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(sj3)*(x1428)*(x1433)))+(((IkReal(-1.00000000000000))*(x1431)*(x1432)))+(((IkReal(-1.00000000000000))*(x1427)*(x1430)))+(((IkReal(-1.00000000000000))*(x1427)*(x1432)))+(((sj3)*(x1428)*(x1434)))+(((IkReal(-1.00000000000000))*(x1430)*(x1431)))+(((IkReal(0.707109999985348))*(x1425)*(x1433)))+(((IkReal(-1.00000000000000))*(sj3)*(x1426)*(x1428))))))) < IKFAST_ATAN2_MAGTHRESH )
05125     continue;
05126 j1array[0]=IKatan2(((gconst6)*(((((x1429)*(x1431)))+(((IkReal(0.707103562373095))*(x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(x1427)*(x1428)))+(((IkReal(-1.00000000000000))*(sj3)*(x1430)*(x1434)))+(((sj3)*(x1430)*(x1433)))+(((sj3)*(x1426)*(x1430)))+(((IkReal(-1.00000000000000))*(x1428)*(x1431)))+(((IkReal(-0.707103562373095))*(x1425)*(x1434)))+(((IkReal(0.707103562373095))*(x1425)*(x1433)))+(((x1427)*(x1429)))))), ((gconst6)*(((((IkReal(-0.707109999985348))*(x1425)*(x1434)))+(((IkReal(0.707109999985348))*(x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(sj3)*(x1428)*(x1433)))+(((IkReal(-1.00000000000000))*(x1431)*(x1432)))+(((IkReal(-1.00000000000000))*(x1427)*(x1430)))+(((IkReal(-1.00000000000000))*(x1427)*(x1432)))+(((sj3)*(x1428)*(x1434)))+(((IkReal(-1.00000000000000))*(x1430)*(x1431)))+(((IkReal(0.707109999985348))*(x1425)*(x1433)))+(((IkReal(-1.00000000000000))*(sj3)*(x1426)*(x1428)))))));
05127 sj1array[0]=IKsin(j1array[0]);
05128 cj1array[0]=IKcos(j1array[0]);
05129 if( j1array[0] > IKPI )
05130 {
05131     j1array[0]-=IK2PI;
05132 }
05133 else if( j1array[0] < -IKPI )
05134 {    j1array[0]+=IK2PI;
05135 }
05136 j1valid[0] = true;
05137 for(int ij1 = 0; ij1 < 1; ++ij1)
05138 {
05139 if( !j1valid[ij1] )
05140 {
05141     continue;
05142 }
05143 _ij1[0] = ij1; _ij1[1] = -1;
05144 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05145 {
05146 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05147 {
05148     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05149 }
05150 }
05151 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05152 {
05153 IkReal evalcond[3];
05154 IkReal x1435=IKcos(j1);
05155 IkReal x1436=IKsin(j1);
05156 IkReal x1437=((IkReal(0.707109999985348))*(cj3));
05157 IkReal x1438=((IkReal(0.707109999985348))*(sj3));
05158 IkReal x1439=((IkReal(0.707103562373095))*(cj3));
05159 IkReal x1440=((IkReal(0.707103562373095))*(sj3));
05160 IkReal x1441=((r21)*(sj5));
05161 IkReal x1442=((cj5)*(r20));
05162 IkReal x1443=((sj2)*(x1436));
05163 IkReal x1444=((cj2)*(x1435));
05164 IkReal x1445=((cj2)*(x1436));
05165 IkReal x1446=((sj2)*(x1435));
05166 evalcond[0]=((((x1438)*(x1443)))+(((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x1438)*(x1444)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x1440)*(x1446)))+(((IkReal(-1.00000000000000))*(x1440)*(x1445))));
05167 evalcond[1]=((((sj4)*(x1441)))+(((cj4)*(r22)))+(((IkReal(0.707109999985348))*(x1446)))+(((IkReal(0.707109999985348))*(x1445)))+(((IkReal(-1.00000000000000))*(sj4)*(x1442)))+(((IkReal(0.707103562373095))*(x1443)))+(((IkReal(-0.707103562373095))*(x1444))));
05168 evalcond[2]=((((x1437)*(x1444)))+(((cj4)*(x1442)))+(((x1439)*(x1446)))+(((x1439)*(x1445)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1437)*(x1443)))+(((IkReal(-1.00000000000000))*(cj4)*(x1441))));
05169 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
05170 {
05171 continue;
05172 }
05173 }
05174 
05175 {
05176 IkReal dummyeval[1];
05177 IkReal gconst8;
05178 IkReal x1447=(cj5)*(cj5);
05179 IkReal x1448=(sj5)*(sj5);
05180 IkReal x1449=((IkReal(1.00000000000000))*(r10));
05181 IkReal x1450=((cj4)*(sj5));
05182 IkReal x1451=((r00)*(r11));
05183 IkReal x1452=((cj4)*(cj5));
05184 IkReal x1453=((sj4)*(x1447));
05185 IkReal x1454=((sj4)*(x1448));
05186 gconst8=IKsign(((((r00)*(r12)*(x1450)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1452)))+(((IkReal(-1.00000000000000))*(r01)*(x1449)*(x1454)))+(((IkReal(-1.00000000000000))*(r01)*(x1449)*(x1453)))+(((r01)*(r12)*(x1452)))+(((IkReal(-1.00000000000000))*(r02)*(x1449)*(x1450)))+(((x1451)*(x1453)))+(((x1451)*(x1454)))));
05187 IkReal x1455=(cj5)*(cj5);
05188 IkReal x1456=(sj5)*(sj5);
05189 IkReal x1457=((IkReal(1.00000000000000))*(r10));
05190 IkReal x1458=((cj4)*(sj5));
05191 IkReal x1459=((r00)*(r11));
05192 IkReal x1460=((cj4)*(cj5));
05193 IkReal x1461=((sj4)*(x1455));
05194 IkReal x1462=((sj4)*(x1456));
05195 dummyeval[0]=((((r00)*(r12)*(x1458)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1460)))+(((x1459)*(x1461)))+(((x1459)*(x1462)))+(((IkReal(-1.00000000000000))*(r02)*(x1457)*(x1458)))+(((IkReal(-1.00000000000000))*(r01)*(x1457)*(x1462)))+(((IkReal(-1.00000000000000))*(r01)*(x1457)*(x1461)))+(((r01)*(r12)*(x1460))));
05196 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05197 {
05198 {
05199 IkReal dummyeval[1];
05200 IkReal gconst9;
05201 IkReal x1463=(cj5)*(cj5);
05202 IkReal x1464=(sj5)*(sj5);
05203 IkReal x1465=((IkReal(1.00000000000000))*(r11));
05204 IkReal x1466=((cj4)*(r00));
05205 IkReal x1467=((r02)*(sj4));
05206 IkReal x1468=((r12)*(sj4));
05207 IkReal x1469=((cj4)*(r01)*(r10));
05208 gconst9=IKsign(((((x1463)*(x1469)))+(((cj5)*(r01)*(x1468)))+(((r00)*(sj5)*(x1468)))+(((x1464)*(x1469)))+(((IkReal(-1.00000000000000))*(cj5)*(x1465)*(x1467)))+(((IkReal(-1.00000000000000))*(x1463)*(x1465)*(x1466)))+(((IkReal(-1.00000000000000))*(x1464)*(x1465)*(x1466)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1467)))));
05209 IkReal x1470=(cj5)*(cj5);
05210 IkReal x1471=(sj5)*(sj5);
05211 IkReal x1472=((IkReal(1.00000000000000))*(r11));
05212 IkReal x1473=((cj4)*(r00));
05213 IkReal x1474=((r02)*(sj4));
05214 IkReal x1475=((r12)*(sj4));
05215 IkReal x1476=((cj4)*(r01)*(r10));
05216 dummyeval[0]=((((x1471)*(x1476)))+(((IkReal(-1.00000000000000))*(x1471)*(x1472)*(x1473)))+(((x1470)*(x1476)))+(((IkReal(-1.00000000000000))*(cj5)*(x1472)*(x1474)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1474)))+(((IkReal(-1.00000000000000))*(x1470)*(x1472)*(x1473)))+(((cj5)*(r01)*(x1475)))+(((r00)*(sj5)*(x1475))));
05217 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05218 {
05219 continue;
05220 
05221 } else
05222 {
05223 {
05224 IkReal j0array[1], cj0array[1], sj0array[1];
05225 bool j0valid[1]={false};
05226 _nj0 = 1;
05227 IkReal x1477=((cj5)*(sj3));
05228 IkReal x1478=((IkReal(1.00000000000000))*(cj3));
05229 IkReal x1479=((cj4)*(cj5));
05230 IkReal x1480=((sj3)*(sj5));
05231 IkReal x1481=((cj3)*(cj4)*(sj5));
05232 if( IKabs(((gconst9)*(((((r10)*(x1480)))+(((r11)*(x1477)))+(((IkReal(-1.00000000000000))*(r10)*(x1478)*(x1479)))+(((r11)*(x1481)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1478))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((IkReal(-1.00000000000000))*(r00)*(x1478)*(x1479)))+(((r01)*(x1481)))+(((r00)*(x1480)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1478)))+(((r01)*(x1477))))))) < IKFAST_ATAN2_MAGTHRESH )
05233     continue;
05234 j0array[0]=IKatan2(((gconst9)*(((((r10)*(x1480)))+(((r11)*(x1477)))+(((IkReal(-1.00000000000000))*(r10)*(x1478)*(x1479)))+(((r11)*(x1481)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1478)))))), ((gconst9)*(((((IkReal(-1.00000000000000))*(r00)*(x1478)*(x1479)))+(((r01)*(x1481)))+(((r00)*(x1480)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1478)))+(((r01)*(x1477)))))));
05235 sj0array[0]=IKsin(j0array[0]);
05236 cj0array[0]=IKcos(j0array[0]);
05237 if( j0array[0] > IKPI )
05238 {
05239     j0array[0]-=IK2PI;
05240 }
05241 else if( j0array[0] < -IKPI )
05242 {    j0array[0]+=IK2PI;
05243 }
05244 j0valid[0] = true;
05245 for(int ij0 = 0; ij0 < 1; ++ij0)
05246 {
05247 if( !j0valid[ij0] )
05248 {
05249     continue;
05250 }
05251 _ij0[0] = ij0; _ij0[1] = -1;
05252 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05253 {
05254 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05255 {
05256     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05257 }
05258 }
05259 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05260 {
05261 IkReal evalcond[6];
05262 IkReal x1482=IKsin(j0);
05263 IkReal x1483=IKcos(j0);
05264 IkReal x1484=((IkReal(0.707103562373095))*(cj2));
05265 IkReal x1485=((cj1)*(cj3));
05266 IkReal x1486=((cj4)*(r12));
05267 IkReal x1487=((IkReal(1.00000000000000))*(sj4));
05268 IkReal x1488=((cj1)*(sj3));
05269 IkReal x1489=((IkReal(1.00000000000000))*(r10));
05270 IkReal x1490=((r01)*(sj5));
05271 IkReal x1491=((cj3)*(sj1));
05272 IkReal x1492=((IkReal(0.707109999985348))*(cj2));
05273 IkReal x1493=((r02)*(sj4));
05274 IkReal x1494=((cj5)*(r01));
05275 IkReal x1495=((IkReal(0.707103562373095))*(sj2));
05276 IkReal x1496=((cj5)*(r00));
05277 IkReal x1497=((sj1)*(sj3));
05278 IkReal x1498=((IkReal(0.707109999985348))*(sj2));
05279 IkReal x1499=((r11)*(sj5));
05280 IkReal x1500=((sj5)*(x1482));
05281 IkReal x1501=((IkReal(1.00000000000000))*(x1483));
05282 IkReal x1502=((cj4)*(x1482));
05283 IkReal x1503=((cj5)*(x1482));
05284 IkReal x1504=((cj4)*(x1483));
05285 IkReal x1505=((cj5)*(sj4)*(x1483));
05286 evalcond[0]=((((x1482)*(x1494)))+(cj3)+(((IkReal(-1.00000000000000))*(sj5)*(x1483)*(x1489)))+(((r00)*(x1500)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1501))));
05287 evalcond[1]=((((IkReal(-1.00000000000000))*(x1486)*(x1501)))+(((r10)*(x1505)))+(((IkReal(-1.00000000000000))*(x1483)*(x1487)*(x1499)))+(((IkReal(-1.00000000000000))*(x1482)*(x1487)*(x1496)))+(((r02)*(x1502)))+(((sj4)*(x1482)*(x1490))));
05288 evalcond[2]=((((x1499)*(x1504)))+(((IkReal(-1.00000000000000))*(r12)*(x1483)*(x1487)))+(((x1482)*(x1493)))+(sj3)+(((IkReal(-1.00000000000000))*(x1490)*(x1502)))+(((IkReal(-1.00000000000000))*(cj5)*(x1489)*(x1504)))+(((x1496)*(x1502))));
05289 evalcond[3]=((((IkReal(-1.00000000000000))*(x1484)*(x1488)))+(((IkReal(-1.00000000000000))*(x1494)*(x1501)))+(((x1495)*(x1497)))+(((x1492)*(x1497)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1501)))+(((IkReal(-1.00000000000000))*(x1489)*(x1500)))+(((IkReal(-1.00000000000000))*(r11)*(x1503)))+(((x1488)*(x1498))));
05290 evalcond[4]=((((cj1)*(x1492)))+(((cj1)*(x1495)))+(((sj1)*(x1484)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1501)))+(((sj4)*(x1483)*(x1496)))+(((r10)*(sj4)*(x1503)))+(((IkReal(-1.00000000000000))*(x1482)*(x1486)))+(((IkReal(-1.00000000000000))*(x1483)*(x1487)*(x1490)))+(((IkReal(-1.00000000000000))*(sj1)*(x1498)))+(((IkReal(-1.00000000000000))*(x1482)*(x1487)*(x1499))));
05291 evalcond[5]=((((x1499)*(x1502)))+(((x1490)*(x1504)))+(((IkReal(-1.00000000000000))*(r02)*(x1483)*(x1487)))+(((IkReal(-1.00000000000000))*(x1485)*(x1498)))+(((IkReal(-1.00000000000000))*(cj5)*(x1489)*(x1502)))+(((IkReal(-1.00000000000000))*(cj4)*(x1496)*(x1501)))+(((x1484)*(x1485)))+(((IkReal(-1.00000000000000))*(x1491)*(x1495)))+(((IkReal(-1.00000000000000))*(x1491)*(x1492)))+(((IkReal(-1.00000000000000))*(r12)*(x1482)*(x1487))));
05292 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  )
05293 {
05294 continue;
05295 }
05296 }
05297 
05298 {
05299 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05300 vinfos[0].jointtype = 1;
05301 vinfos[0].foffset = j0;
05302 vinfos[0].indices[0] = _ij0[0];
05303 vinfos[0].indices[1] = _ij0[1];
05304 vinfos[0].maxsolutions = _nj0;
05305 vinfos[1].jointtype = 1;
05306 vinfos[1].foffset = j1;
05307 vinfos[1].indices[0] = _ij1[0];
05308 vinfos[1].indices[1] = _ij1[1];
05309 vinfos[1].maxsolutions = _nj1;
05310 vinfos[2].jointtype = 1;
05311 vinfos[2].foffset = j2;
05312 vinfos[2].indices[0] = _ij2[0];
05313 vinfos[2].indices[1] = _ij2[1];
05314 vinfos[2].maxsolutions = _nj2;
05315 vinfos[3].jointtype = 1;
05316 vinfos[3].foffset = j3;
05317 vinfos[3].indices[0] = _ij3[0];
05318 vinfos[3].indices[1] = _ij3[1];
05319 vinfos[3].maxsolutions = _nj3;
05320 vinfos[4].jointtype = 1;
05321 vinfos[4].foffset = j4;
05322 vinfos[4].indices[0] = _ij4[0];
05323 vinfos[4].indices[1] = _ij4[1];
05324 vinfos[4].maxsolutions = _nj4;
05325 vinfos[5].jointtype = 1;
05326 vinfos[5].foffset = j5;
05327 vinfos[5].indices[0] = _ij5[0];
05328 vinfos[5].indices[1] = _ij5[1];
05329 vinfos[5].maxsolutions = _nj5;
05330 std::vector<int> vfree(0);
05331 solutions.AddSolution(vinfos,vfree);
05332 }
05333 }
05334 }
05335 
05336 }
05337 
05338 }
05339 
05340 } else
05341 {
05342 {
05343 IkReal j0array[1], cj0array[1], sj0array[1];
05344 bool j0valid[1]={false};
05345 _nj0 = 1;
05346 IkReal x1506=((cj3)*(sj4));
05347 IkReal x1507=((IkReal(1.00000000000000))*(sj5));
05348 IkReal x1508=((IkReal(1.00000000000000))*(cj3)*(cj4));
05349 if( IKabs(((gconst8)*(((((cj5)*(r10)*(x1506)))+(((IkReal(-1.00000000000000))*(r11)*(x1506)*(x1507)))+(((IkReal(-1.00000000000000))*(r12)*(x1508))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((cj5)*(r00)*(x1506)))+(((IkReal(-1.00000000000000))*(r02)*(x1508)))+(((IkReal(-1.00000000000000))*(r01)*(x1506)*(x1507))))))) < IKFAST_ATAN2_MAGTHRESH )
05350     continue;
05351 j0array[0]=IKatan2(((gconst8)*(((((cj5)*(r10)*(x1506)))+(((IkReal(-1.00000000000000))*(r11)*(x1506)*(x1507)))+(((IkReal(-1.00000000000000))*(r12)*(x1508)))))), ((gconst8)*(((((cj5)*(r00)*(x1506)))+(((IkReal(-1.00000000000000))*(r02)*(x1508)))+(((IkReal(-1.00000000000000))*(r01)*(x1506)*(x1507)))))));
05352 sj0array[0]=IKsin(j0array[0]);
05353 cj0array[0]=IKcos(j0array[0]);
05354 if( j0array[0] > IKPI )
05355 {
05356     j0array[0]-=IK2PI;
05357 }
05358 else if( j0array[0] < -IKPI )
05359 {    j0array[0]+=IK2PI;
05360 }
05361 j0valid[0] = true;
05362 for(int ij0 = 0; ij0 < 1; ++ij0)
05363 {
05364 if( !j0valid[ij0] )
05365 {
05366     continue;
05367 }
05368 _ij0[0] = ij0; _ij0[1] = -1;
05369 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05370 {
05371 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05372 {
05373     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05374 }
05375 }
05376 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05377 {
05378 IkReal evalcond[6];
05379 IkReal x1509=IKsin(j0);
05380 IkReal x1510=IKcos(j0);
05381 IkReal x1511=((IkReal(0.707103562373095))*(cj2));
05382 IkReal x1512=((cj1)*(cj3));
05383 IkReal x1513=((cj4)*(r12));
05384 IkReal x1514=((IkReal(1.00000000000000))*(sj4));
05385 IkReal x1515=((cj1)*(sj3));
05386 IkReal x1516=((IkReal(1.00000000000000))*(r10));
05387 IkReal x1517=((r01)*(sj5));
05388 IkReal x1518=((cj3)*(sj1));
05389 IkReal x1519=((IkReal(0.707109999985348))*(cj2));
05390 IkReal x1520=((r02)*(sj4));
05391 IkReal x1521=((cj5)*(r01));
05392 IkReal x1522=((IkReal(0.707103562373095))*(sj2));
05393 IkReal x1523=((cj5)*(r00));
05394 IkReal x1524=((sj1)*(sj3));
05395 IkReal x1525=((IkReal(0.707109999985348))*(sj2));
05396 IkReal x1526=((r11)*(sj5));
05397 IkReal x1527=((sj5)*(x1509));
05398 IkReal x1528=((IkReal(1.00000000000000))*(x1510));
05399 IkReal x1529=((cj4)*(x1509));
05400 IkReal x1530=((cj5)*(x1509));
05401 IkReal x1531=((cj4)*(x1510));
05402 IkReal x1532=((cj5)*(sj4)*(x1510));
05403 evalcond[0]=((((x1509)*(x1521)))+(cj3)+(((IkReal(-1.00000000000000))*(sj5)*(x1510)*(x1516)))+(((r00)*(x1527)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1528))));
05404 evalcond[1]=((((sj4)*(x1509)*(x1517)))+(((r10)*(x1532)))+(((IkReal(-1.00000000000000))*(x1513)*(x1528)))+(((IkReal(-1.00000000000000))*(x1509)*(x1514)*(x1523)))+(((IkReal(-1.00000000000000))*(x1510)*(x1514)*(x1526)))+(((r02)*(x1529))));
05405 evalcond[2]=((((IkReal(-1.00000000000000))*(x1517)*(x1529)))+(sj3)+(((x1509)*(x1520)))+(((x1523)*(x1529)))+(((IkReal(-1.00000000000000))*(r12)*(x1510)*(x1514)))+(((IkReal(-1.00000000000000))*(cj5)*(x1516)*(x1531)))+(((x1526)*(x1531))));
05406 evalcond[3]=((((x1519)*(x1524)))+(((x1522)*(x1524)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1528)))+(((x1515)*(x1525)))+(((IkReal(-1.00000000000000))*(x1516)*(x1527)))+(((IkReal(-1.00000000000000))*(x1511)*(x1515)))+(((IkReal(-1.00000000000000))*(x1521)*(x1528)))+(((IkReal(-1.00000000000000))*(r11)*(x1530))));
05407 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1528)))+(((IkReal(-1.00000000000000))*(sj1)*(x1525)))+(((cj1)*(x1522)))+(((sj4)*(x1510)*(x1523)))+(((cj1)*(x1519)))+(((IkReal(-1.00000000000000))*(x1509)*(x1513)))+(((sj1)*(x1511)))+(((IkReal(-1.00000000000000))*(x1509)*(x1514)*(x1526)))+(((r10)*(sj4)*(x1530)))+(((IkReal(-1.00000000000000))*(x1510)*(x1514)*(x1517))));
05408 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x1509)*(x1514)))+(((IkReal(-1.00000000000000))*(r02)*(x1510)*(x1514)))+(((IkReal(-1.00000000000000))*(x1518)*(x1522)))+(((IkReal(-1.00000000000000))*(x1518)*(x1519)))+(((IkReal(-1.00000000000000))*(cj4)*(x1523)*(x1528)))+(((x1517)*(x1531)))+(((x1526)*(x1529)))+(((IkReal(-1.00000000000000))*(cj5)*(x1516)*(x1529)))+(((IkReal(-1.00000000000000))*(x1512)*(x1525)))+(((x1511)*(x1512))));
05409 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  )
05410 {
05411 continue;
05412 }
05413 }
05414 
05415 {
05416 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05417 vinfos[0].jointtype = 1;
05418 vinfos[0].foffset = j0;
05419 vinfos[0].indices[0] = _ij0[0];
05420 vinfos[0].indices[1] = _ij0[1];
05421 vinfos[0].maxsolutions = _nj0;
05422 vinfos[1].jointtype = 1;
05423 vinfos[1].foffset = j1;
05424 vinfos[1].indices[0] = _ij1[0];
05425 vinfos[1].indices[1] = _ij1[1];
05426 vinfos[1].maxsolutions = _nj1;
05427 vinfos[2].jointtype = 1;
05428 vinfos[2].foffset = j2;
05429 vinfos[2].indices[0] = _ij2[0];
05430 vinfos[2].indices[1] = _ij2[1];
05431 vinfos[2].maxsolutions = _nj2;
05432 vinfos[3].jointtype = 1;
05433 vinfos[3].foffset = j3;
05434 vinfos[3].indices[0] = _ij3[0];
05435 vinfos[3].indices[1] = _ij3[1];
05436 vinfos[3].maxsolutions = _nj3;
05437 vinfos[4].jointtype = 1;
05438 vinfos[4].foffset = j4;
05439 vinfos[4].indices[0] = _ij4[0];
05440 vinfos[4].indices[1] = _ij4[1];
05441 vinfos[4].maxsolutions = _nj4;
05442 vinfos[5].jointtype = 1;
05443 vinfos[5].foffset = j5;
05444 vinfos[5].indices[0] = _ij5[0];
05445 vinfos[5].indices[1] = _ij5[1];
05446 vinfos[5].maxsolutions = _nj5;
05447 std::vector<int> vfree(0);
05448 solutions.AddSolution(vinfos,vfree);
05449 }
05450 }
05451 }
05452 
05453 }
05454 
05455 }
05456 }
05457 }
05458 
05459 }
05460 
05461 }
05462 
05463 } else
05464 {
05465 {
05466 IkReal j0array[1], cj0array[1], sj0array[1];
05467 bool j0valid[1]={false};
05468 _nj0 = 1;
05469 IkReal x1533=((cj5)*(sj3));
05470 IkReal x1534=((IkReal(1.00000000000000))*(cj3));
05471 IkReal x1535=((cj4)*(cj5));
05472 IkReal x1536=((sj3)*(sj5));
05473 IkReal x1537=((cj3)*(cj4)*(sj5));
05474 if( IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(r10)*(x1534)*(x1535)))+(((r10)*(x1536)))+(((r11)*(x1533)))+(((r11)*(x1537)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1534))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(r00)*(x1534)*(x1535)))+(((r01)*(x1537)))+(((r01)*(x1533)))+(((r00)*(x1536)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1534))))))) < IKFAST_ATAN2_MAGTHRESH )
05475     continue;
05476 j0array[0]=IKatan2(((gconst5)*(((((IkReal(-1.00000000000000))*(r10)*(x1534)*(x1535)))+(((r10)*(x1536)))+(((r11)*(x1533)))+(((r11)*(x1537)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1534)))))), ((gconst5)*(((((IkReal(-1.00000000000000))*(r00)*(x1534)*(x1535)))+(((r01)*(x1537)))+(((r01)*(x1533)))+(((r00)*(x1536)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1534)))))));
05477 sj0array[0]=IKsin(j0array[0]);
05478 cj0array[0]=IKcos(j0array[0]);
05479 if( j0array[0] > IKPI )
05480 {
05481     j0array[0]-=IK2PI;
05482 }
05483 else if( j0array[0] < -IKPI )
05484 {    j0array[0]+=IK2PI;
05485 }
05486 j0valid[0] = true;
05487 for(int ij0 = 0; ij0 < 1; ++ij0)
05488 {
05489 if( !j0valid[ij0] )
05490 {
05491     continue;
05492 }
05493 _ij0[0] = ij0; _ij0[1] = -1;
05494 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05495 {
05496 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05497 {
05498     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05499 }
05500 }
05501 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05502 {
05503 IkReal evalcond[3];
05504 IkReal x1538=IKsin(j0);
05505 IkReal x1539=IKcos(j0);
05506 IkReal x1540=((cj5)*(r00));
05507 IkReal x1541=((r01)*(sj5));
05508 IkReal x1542=((cj5)*(r10));
05509 IkReal x1543=((IkReal(1.00000000000000))*(r12));
05510 IkReal x1544=((r11)*(sj5));
05511 IkReal x1545=((cj4)*(x1538));
05512 IkReal x1546=((sj4)*(x1538));
05513 IkReal x1547=((sj4)*(x1539));
05514 IkReal x1548=((cj4)*(x1539));
05515 IkReal x1549=((IkReal(1.00000000000000))*(x1539));
05516 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1549)))+(cj3)+(((cj5)*(r01)*(x1538)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1549)))+(((r00)*(sj5)*(x1538))));
05517 evalcond[1]=((((IkReal(-1.00000000000000))*(x1544)*(x1547)))+(((IkReal(-1.00000000000000))*(x1543)*(x1548)))+(((x1541)*(x1546)))+(((r02)*(x1545)))+(((IkReal(-1.00000000000000))*(x1540)*(x1546)))+(((x1542)*(x1547))));
05518 evalcond[2]=((((IkReal(-1.00000000000000))*(x1541)*(x1545)))+(((IkReal(-1.00000000000000))*(x1543)*(x1547)))+(sj3)+(((IkReal(-1.00000000000000))*(x1542)*(x1548)))+(((x1544)*(x1548)))+(((x1540)*(x1545)))+(((r02)*(x1546))));
05519 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
05520 {
05521 continue;
05522 }
05523 }
05524 
05525 {
05526 IkReal dummyeval[1];
05527 IkReal gconst10;
05528 IkReal x1550=((IkReal(1.00000000000000))*(sj3));
05529 gconst10=IKsign(((((IkReal(-1.00000000000000))*(x1550)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x1550)*((cj2)*(cj2))))));
05530 IkReal x1551=((IkReal(1.00000000000000))*(sj3));
05531 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1551)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x1551)*((sj2)*(sj2)))));
05532 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05533 {
05534 {
05535 IkReal dummyeval[1];
05536 IkReal gconst11;
05537 IkReal x1552=((IkReal(1.00000000000000))*(cj3));
05538 gconst11=IKsign(((((IkReal(-1.00000000000000))*(x1552)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x1552)*((sj2)*(sj2))))));
05539 IkReal x1553=((IkReal(1.00000000000000))*(cj3));
05540 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1553)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x1553)*((sj2)*(sj2)))));
05541 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05542 {
05543 {
05544 IkReal evalcond[9];
05545 IkReal x1554=((sj0)*(sj4));
05546 IkReal x1555=((IkReal(1.00000000000000))*(r12));
05547 IkReal x1556=((cj0)*(cj4));
05548 IkReal x1557=((r01)*(sj5));
05549 IkReal x1558=((IkReal(1.00000000000000))*(cj5));
05550 IkReal x1559=((cj4)*(cj5));
05551 IkReal x1560=((IkReal(1.00000000000000))*(cj0));
05552 IkReal x1561=((cj4)*(sj0));
05553 IkReal x1562=((r00)*(sj0));
05554 IkReal x1563=((npy)*(sj5));
05555 IkReal x1564=((IkReal(1.00000000000000))*(cj4));
05556 IkReal x1565=((cj0)*(sj4));
05557 IkReal x1566=((r11)*(sj5));
05558 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
05559 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x1558)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1560)))+(((sj5)*(x1562))));
05560 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x1563)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1558))));
05561 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
05562 evalcond[4]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x1563)*(x1564)))+(((npx)*(x1559))));
05563 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x1560)*(x1566)))+(((cj5)*(r10)*(x1565)))+(((IkReal(-1.00000000000000))*(x1555)*(x1556)))+(((IkReal(-1.00000000000000))*(r00)*(x1554)*(x1558)))+(((x1554)*(x1557)))+(((r02)*(x1561))));
05564 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x1556)*(x1558)))+(((x1556)*(x1566)))+(((IkReal(-1.00000000000000))*(x1557)*(x1561)))+(((IkReal(-1.00000000000000))*(x1555)*(x1565)))+(((r02)*(x1554)))+(((x1559)*(x1562))));
05565 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x1564)))+(((r22)*(sj4)))+(((r20)*(x1559))));
05566 evalcond[8]=((((x1556)*(x1557)))+(((x1561)*(x1566)))+(((IkReal(-1.00000000000000))*(r00)*(x1556)*(x1558)))+(((IkReal(-1.00000000000000))*(r10)*(x1558)*(x1561)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1560)))+(((IkReal(-1.00000000000000))*(x1554)*(x1555))));
05567 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  )
05568 {
05569 {
05570 IkReal dummyeval[1];
05571 IkReal gconst12;
05572 gconst12=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
05573 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
05574 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05575 {
05576 {
05577 IkReal dummyeval[1];
05578 IkReal gconst13;
05579 gconst13=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
05580 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
05581 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05582 {
05583 continue;
05584 
05585 } else
05586 {
05587 {
05588 IkReal j1array[1], cj1array[1], sj1array[1];
05589 bool j1valid[1]={false};
05590 _nj1 = 1;
05591 IkReal x1567=((cj5)*(r11));
05592 IkReal x1568=((r10)*(sj0));
05593 IkReal x1569=((IkReal(0.707103562373095))*(cj2));
05594 IkReal x1570=((r20)*(sj5));
05595 IkReal x1571=((IkReal(0.707103562373095))*(sj2));
05596 IkReal x1572=((IkReal(0.707109999985348))*(cj2));
05597 IkReal x1573=((cj0)*(r00));
05598 IkReal x1574=((IkReal(0.707109999985348))*(sj2));
05599 IkReal x1575=((cj5)*(r21));
05600 IkReal x1576=((sj0)*(x1571));
05601 IkReal x1577=((sj5)*(x1572));
05602 IkReal x1578=((cj0)*(cj5)*(r01));
05603 if( IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(x1571)*(x1578)))+(((IkReal(-1.00000000000000))*(x1572)*(x1578)))+(((x1570)*(x1574)))+(((IkReal(-1.00000000000000))*(x1573)*(x1577)))+(((IkReal(-1.00000000000000))*(x1567)*(x1576)))+(((IkReal(-1.00000000000000))*(sj5)*(x1571)*(x1573)))+(((IkReal(-1.00000000000000))*(sj5)*(x1568)*(x1571)))+(((IkReal(-1.00000000000000))*(x1568)*(x1577)))+(((IkReal(-1.00000000000000))*(x1569)*(x1575)))+(((IkReal(-1.00000000000000))*(x1569)*(x1570)))+(((IkReal(-1.00000000000000))*(sj0)*(x1567)*(x1572)))+(((x1574)*(x1575))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((sj5)*(x1569)*(x1573)))+(((IkReal(-1.00000000000000))*(x1571)*(x1575)))+(((x1569)*(x1578)))+(((IkReal(-1.00000000000000))*(sj5)*(x1573)*(x1574)))+(((IkReal(-1.00000000000000))*(x1572)*(x1575)))+(((IkReal(-1.00000000000000))*(x1570)*(x1572)))+(((IkReal(-1.00000000000000))*(x1570)*(x1571)))+(((IkReal(-1.00000000000000))*(sj5)*(x1568)*(x1574)))+(((IkReal(-1.00000000000000))*(x1574)*(x1578)))+(((IkReal(-1.00000000000000))*(sj0)*(x1567)*(x1574)))+(((sj5)*(x1568)*(x1569)))+(((sj0)*(x1567)*(x1569))))))) < IKFAST_ATAN2_MAGTHRESH )
05604     continue;
05605 j1array[0]=IKatan2(((gconst13)*(((((IkReal(-1.00000000000000))*(x1571)*(x1578)))+(((IkReal(-1.00000000000000))*(x1572)*(x1578)))+(((x1570)*(x1574)))+(((IkReal(-1.00000000000000))*(x1573)*(x1577)))+(((IkReal(-1.00000000000000))*(x1567)*(x1576)))+(((IkReal(-1.00000000000000))*(sj5)*(x1571)*(x1573)))+(((IkReal(-1.00000000000000))*(sj5)*(x1568)*(x1571)))+(((IkReal(-1.00000000000000))*(x1568)*(x1577)))+(((IkReal(-1.00000000000000))*(x1569)*(x1575)))+(((IkReal(-1.00000000000000))*(x1569)*(x1570)))+(((IkReal(-1.00000000000000))*(sj0)*(x1567)*(x1572)))+(((x1574)*(x1575)))))), ((gconst13)*(((((sj5)*(x1569)*(x1573)))+(((IkReal(-1.00000000000000))*(x1571)*(x1575)))+(((x1569)*(x1578)))+(((IkReal(-1.00000000000000))*(sj5)*(x1573)*(x1574)))+(((IkReal(-1.00000000000000))*(x1572)*(x1575)))+(((IkReal(-1.00000000000000))*(x1570)*(x1572)))+(((IkReal(-1.00000000000000))*(x1570)*(x1571)))+(((IkReal(-1.00000000000000))*(sj5)*(x1568)*(x1574)))+(((IkReal(-1.00000000000000))*(x1574)*(x1578)))+(((IkReal(-1.00000000000000))*(sj0)*(x1567)*(x1574)))+(((sj5)*(x1568)*(x1569)))+(((sj0)*(x1567)*(x1569)))))));
05606 sj1array[0]=IKsin(j1array[0]);
05607 cj1array[0]=IKcos(j1array[0]);
05608 if( j1array[0] > IKPI )
05609 {
05610     j1array[0]-=IK2PI;
05611 }
05612 else if( j1array[0] < -IKPI )
05613 {    j1array[0]+=IK2PI;
05614 }
05615 j1valid[0] = true;
05616 for(int ij1 = 0; ij1 < 1; ++ij1)
05617 {
05618 if( !j1valid[ij1] )
05619 {
05620     continue;
05621 }
05622 _ij1[0] = ij1; _ij1[1] = -1;
05623 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05624 {
05625 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05626 {
05627     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05628 }
05629 }
05630 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05631 {
05632 IkReal evalcond[4];
05633 IkReal x1579=IKsin(j1);
05634 IkReal x1580=IKcos(j1);
05635 IkReal x1581=((IkReal(0.707109999985348))*(cj2));
05636 IkReal x1582=((IkReal(1.00000000000000))*(cj0));
05637 IkReal x1583=((IkReal(0.707109999985348))*(sj2));
05638 IkReal x1584=((cj5)*(sj4));
05639 IkReal x1585=((sj4)*(sj5));
05640 IkReal x1586=((IkReal(1.00000000000000))*(sj0));
05641 IkReal x1587=((sj5)*(x1586));
05642 IkReal x1588=((IkReal(0.707103562373095))*(x1580));
05643 IkReal x1589=((IkReal(0.707103562373095))*(x1579));
05644 IkReal x1590=((x1579)*(x1581));
05645 IkReal x1591=((sj2)*(x1589));
05646 IkReal x1592=((x1580)*(x1583));
05647 IkReal x1593=((cj2)*(x1588));
05648 IkReal x1594=((sj2)*(x1588));
05649 IkReal x1595=((cj2)*(x1589));
05650 IkReal x1596=((x1580)*(x1581));
05651 IkReal x1597=((x1579)*(x1583));
05652 IkReal x1598=((x1595)+(x1594)+(x1596));
05653 IkReal x1599=((x1591)+(x1590)+(x1592));
05654 evalcond[0]=((((IkReal(-1.00000000000000))*(x1598)))+(((cj5)*(r21)))+(x1597)+(((r20)*(sj5))));
05655 evalcond[1]=((((IkReal(-1.00000000000000))*(x1593)))+(((cj4)*(r22)))+(x1599)+(((r21)*(x1585)))+(((IkReal(-1.00000000000000))*(r20)*(x1584))));
05656 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1582)))+(((IkReal(-1.00000000000000))*(x1593)))+(x1599)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1582)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1586)))+(((IkReal(-1.00000000000000))*(r10)*(x1587))));
05657 evalcond[3]=((((IkReal(-1.00000000000000))*(x1597)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1582)))+(((cj0)*(r00)*(x1584)))+(((IkReal(-1.00000000000000))*(r01)*(x1582)*(x1585)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1586)))+(x1598)+(((r10)*(sj0)*(x1584)))+(((IkReal(-1.00000000000000))*(r11)*(x1585)*(x1586))));
05658 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05659 {
05660 continue;
05661 }
05662 }
05663 
05664 {
05665 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05666 vinfos[0].jointtype = 1;
05667 vinfos[0].foffset = j0;
05668 vinfos[0].indices[0] = _ij0[0];
05669 vinfos[0].indices[1] = _ij0[1];
05670 vinfos[0].maxsolutions = _nj0;
05671 vinfos[1].jointtype = 1;
05672 vinfos[1].foffset = j1;
05673 vinfos[1].indices[0] = _ij1[0];
05674 vinfos[1].indices[1] = _ij1[1];
05675 vinfos[1].maxsolutions = _nj1;
05676 vinfos[2].jointtype = 1;
05677 vinfos[2].foffset = j2;
05678 vinfos[2].indices[0] = _ij2[0];
05679 vinfos[2].indices[1] = _ij2[1];
05680 vinfos[2].maxsolutions = _nj2;
05681 vinfos[3].jointtype = 1;
05682 vinfos[3].foffset = j3;
05683 vinfos[3].indices[0] = _ij3[0];
05684 vinfos[3].indices[1] = _ij3[1];
05685 vinfos[3].maxsolutions = _nj3;
05686 vinfos[4].jointtype = 1;
05687 vinfos[4].foffset = j4;
05688 vinfos[4].indices[0] = _ij4[0];
05689 vinfos[4].indices[1] = _ij4[1];
05690 vinfos[4].maxsolutions = _nj4;
05691 vinfos[5].jointtype = 1;
05692 vinfos[5].foffset = j5;
05693 vinfos[5].indices[0] = _ij5[0];
05694 vinfos[5].indices[1] = _ij5[1];
05695 vinfos[5].maxsolutions = _nj5;
05696 std::vector<int> vfree(0);
05697 solutions.AddSolution(vinfos,vfree);
05698 }
05699 }
05700 }
05701 
05702 }
05703 
05704 }
05705 
05706 } else
05707 {
05708 {
05709 IkReal j1array[1], cj1array[1], sj1array[1];
05710 bool j1valid[1]={false};
05711 _nj1 = 1;
05712 IkReal x1600=((cj5)*(sj4));
05713 IkReal x1601=((r21)*(sj4));
05714 IkReal x1602=((cj5)*(r21));
05715 IkReal x1603=((IkReal(0.707109999985348))*(cj2));
05716 IkReal x1604=((IkReal(0.707103562373095))*(sj2));
05717 IkReal x1605=((IkReal(0.707109999985348))*(sj2));
05718 IkReal x1606=((cj4)*(r22));
05719 IkReal x1607=((IkReal(0.707103562373095))*(cj2));
05720 IkReal x1608=((r20)*(x1603));
05721 IkReal x1609=((sj5)*(x1607));
05722 IkReal x1610=((sj5)*(x1605));
05723 if( IKabs(((gconst12)*(((((r20)*(x1610)))+(((IkReal(-1.00000000000000))*(r20)*(x1609)))+(((sj5)*(x1601)*(x1604)))+(((sj5)*(x1601)*(x1603)))+(((IkReal(-1.00000000000000))*(x1600)*(x1608)))+(((IkReal(-1.00000000000000))*(r20)*(x1600)*(x1604)))+(((x1603)*(x1606)))+(((x1602)*(x1605)))+(((IkReal(-1.00000000000000))*(x1602)*(x1607)))+(((x1604)*(x1606))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((IkReal(-1.00000000000000))*(x1601)*(x1609)))+(((x1601)*(x1610)))+(((r20)*(x1600)*(x1607)))+(((IkReal(-1.00000000000000))*(r20)*(x1600)*(x1605)))+(((IkReal(-1.00000000000000))*(x1602)*(x1603)))+(((IkReal(-1.00000000000000))*(x1602)*(x1604)))+(((IkReal(-1.00000000000000))*(x1606)*(x1607)))+(((x1605)*(x1606)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1604)))+(((IkReal(-1.00000000000000))*(sj5)*(x1608))))))) < IKFAST_ATAN2_MAGTHRESH )
05724     continue;
05725 j1array[0]=IKatan2(((gconst12)*(((((r20)*(x1610)))+(((IkReal(-1.00000000000000))*(r20)*(x1609)))+(((sj5)*(x1601)*(x1604)))+(((sj5)*(x1601)*(x1603)))+(((IkReal(-1.00000000000000))*(x1600)*(x1608)))+(((IkReal(-1.00000000000000))*(r20)*(x1600)*(x1604)))+(((x1603)*(x1606)))+(((x1602)*(x1605)))+(((IkReal(-1.00000000000000))*(x1602)*(x1607)))+(((x1604)*(x1606)))))), ((gconst12)*(((((IkReal(-1.00000000000000))*(x1601)*(x1609)))+(((x1601)*(x1610)))+(((r20)*(x1600)*(x1607)))+(((IkReal(-1.00000000000000))*(r20)*(x1600)*(x1605)))+(((IkReal(-1.00000000000000))*(x1602)*(x1603)))+(((IkReal(-1.00000000000000))*(x1602)*(x1604)))+(((IkReal(-1.00000000000000))*(x1606)*(x1607)))+(((x1605)*(x1606)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1604)))+(((IkReal(-1.00000000000000))*(sj5)*(x1608)))))));
05726 sj1array[0]=IKsin(j1array[0]);
05727 cj1array[0]=IKcos(j1array[0]);
05728 if( j1array[0] > IKPI )
05729 {
05730     j1array[0]-=IK2PI;
05731 }
05732 else if( j1array[0] < -IKPI )
05733 {    j1array[0]+=IK2PI;
05734 }
05735 j1valid[0] = true;
05736 for(int ij1 = 0; ij1 < 1; ++ij1)
05737 {
05738 if( !j1valid[ij1] )
05739 {
05740     continue;
05741 }
05742 _ij1[0] = ij1; _ij1[1] = -1;
05743 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05744 {
05745 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05746 {
05747     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05748 }
05749 }
05750 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05751 {
05752 IkReal evalcond[4];
05753 IkReal x1611=IKsin(j1);
05754 IkReal x1612=IKcos(j1);
05755 IkReal x1613=((IkReal(0.707109999985348))*(cj2));
05756 IkReal x1614=((IkReal(1.00000000000000))*(cj0));
05757 IkReal x1615=((IkReal(0.707109999985348))*(sj2));
05758 IkReal x1616=((cj5)*(sj4));
05759 IkReal x1617=((sj4)*(sj5));
05760 IkReal x1618=((IkReal(1.00000000000000))*(sj0));
05761 IkReal x1619=((sj5)*(x1618));
05762 IkReal x1620=((IkReal(0.707103562373095))*(x1612));
05763 IkReal x1621=((IkReal(0.707103562373095))*(x1611));
05764 IkReal x1622=((x1611)*(x1613));
05765 IkReal x1623=((sj2)*(x1621));
05766 IkReal x1624=((x1612)*(x1615));
05767 IkReal x1625=((cj2)*(x1620));
05768 IkReal x1626=((sj2)*(x1620));
05769 IkReal x1627=((cj2)*(x1621));
05770 IkReal x1628=((x1612)*(x1613));
05771 IkReal x1629=((x1611)*(x1615));
05772 IkReal x1630=((x1627)+(x1626)+(x1628));
05773 IkReal x1631=((x1623)+(x1622)+(x1624));
05774 evalcond[0]=((((cj5)*(r21)))+(x1629)+(((IkReal(-1.00000000000000))*(x1630)))+(((r20)*(sj5))));
05775 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x1616)))+(((cj4)*(r22)))+(((r21)*(x1617)))+(x1631)+(((IkReal(-1.00000000000000))*(x1625))));
05776 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1614)))+(x1631)+(((IkReal(-1.00000000000000))*(x1625)))+(((IkReal(-1.00000000000000))*(r10)*(x1619)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1618)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1614))));
05777 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x1617)*(x1618)))+(((r10)*(sj0)*(x1616)))+(x1630)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1618)))+(((cj0)*(r00)*(x1616)))+(((IkReal(-1.00000000000000))*(x1629)))+(((IkReal(-1.00000000000000))*(r01)*(x1614)*(x1617)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1614))));
05778 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05779 {
05780 continue;
05781 }
05782 }
05783 
05784 {
05785 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05786 vinfos[0].jointtype = 1;
05787 vinfos[0].foffset = j0;
05788 vinfos[0].indices[0] = _ij0[0];
05789 vinfos[0].indices[1] = _ij0[1];
05790 vinfos[0].maxsolutions = _nj0;
05791 vinfos[1].jointtype = 1;
05792 vinfos[1].foffset = j1;
05793 vinfos[1].indices[0] = _ij1[0];
05794 vinfos[1].indices[1] = _ij1[1];
05795 vinfos[1].maxsolutions = _nj1;
05796 vinfos[2].jointtype = 1;
05797 vinfos[2].foffset = j2;
05798 vinfos[2].indices[0] = _ij2[0];
05799 vinfos[2].indices[1] = _ij2[1];
05800 vinfos[2].maxsolutions = _nj2;
05801 vinfos[3].jointtype = 1;
05802 vinfos[3].foffset = j3;
05803 vinfos[3].indices[0] = _ij3[0];
05804 vinfos[3].indices[1] = _ij3[1];
05805 vinfos[3].maxsolutions = _nj3;
05806 vinfos[4].jointtype = 1;
05807 vinfos[4].foffset = j4;
05808 vinfos[4].indices[0] = _ij4[0];
05809 vinfos[4].indices[1] = _ij4[1];
05810 vinfos[4].maxsolutions = _nj4;
05811 vinfos[5].jointtype = 1;
05812 vinfos[5].foffset = j5;
05813 vinfos[5].indices[0] = _ij5[0];
05814 vinfos[5].indices[1] = _ij5[1];
05815 vinfos[5].maxsolutions = _nj5;
05816 std::vector<int> vfree(0);
05817 solutions.AddSolution(vinfos,vfree);
05818 }
05819 }
05820 }
05821 
05822 }
05823 
05824 }
05825 
05826 } else
05827 {
05828 IkReal x1632=((sj0)*(sj4));
05829 IkReal x1633=((IkReal(1.00000000000000))*(r12));
05830 IkReal x1634=((cj0)*(cj4));
05831 IkReal x1635=((r01)*(sj5));
05832 IkReal x1636=((IkReal(1.00000000000000))*(cj5));
05833 IkReal x1637=((cj4)*(cj5));
05834 IkReal x1638=((IkReal(1.00000000000000))*(cj0));
05835 IkReal x1639=((cj4)*(sj0));
05836 IkReal x1640=((r00)*(sj0));
05837 IkReal x1641=((npy)*(sj5));
05838 IkReal x1642=((IkReal(1.00000000000000))*(cj4));
05839 IkReal x1643=((cj0)*(sj4));
05840 IkReal x1644=((r11)*(sj5));
05841 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
05842 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x1640)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x1636)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1638))));
05843 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x1641)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1636)))+(((IkReal(0.165463933124939))*(sj2))));
05844 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
05845 evalcond[4]=((IkReal(-0.00600000000000000))+(((npx)*(x1637)))+(((IkReal(-1.00000000000000))*(x1641)*(x1642)))+(((npz)*(sj4))));
05846 evalcond[5]=((((r02)*(x1639)))+(((IkReal(-1.00000000000000))*(sj4)*(x1638)*(x1644)))+(((cj5)*(r10)*(x1643)))+(((IkReal(-1.00000000000000))*(r00)*(x1632)*(x1636)))+(((IkReal(-1.00000000000000))*(x1633)*(x1634)))+(((x1632)*(x1635))));
05847 evalcond[6]=((IkReal(1.00000000000000))+(((r02)*(x1632)))+(((x1637)*(x1640)))+(((IkReal(-1.00000000000000))*(r10)*(x1634)*(x1636)))+(((IkReal(-1.00000000000000))*(x1635)*(x1639)))+(((IkReal(-1.00000000000000))*(x1633)*(x1643)))+(((x1634)*(x1644))));
05848 evalcond[7]=((((r20)*(x1637)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x1642))));
05849 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1638)))+(((IkReal(-1.00000000000000))*(r10)*(x1636)*(x1639)))+(((IkReal(-1.00000000000000))*(x1632)*(x1633)))+(((x1639)*(x1644)))+(((IkReal(-1.00000000000000))*(r00)*(x1634)*(x1636)))+(((x1634)*(x1635))));
05850 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  )
05851 {
05852 {
05853 IkReal dummyeval[1];
05854 IkReal gconst14;
05855 gconst14=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
05856 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
05857 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05858 {
05859 {
05860 IkReal dummyeval[1];
05861 IkReal gconst15;
05862 gconst15=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
05863 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
05864 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05865 {
05866 continue;
05867 
05868 } else
05869 {
05870 {
05871 IkReal j1array[1], cj1array[1], sj1array[1];
05872 bool j1valid[1]={false};
05873 _nj1 = 1;
05874 IkReal x1645=((cj5)*(r11));
05875 IkReal x1646=((r10)*(sj0));
05876 IkReal x1647=((IkReal(0.707103562373095))*(cj2));
05877 IkReal x1648=((r20)*(sj5));
05878 IkReal x1649=((IkReal(0.707103562373095))*(sj2));
05879 IkReal x1650=((IkReal(0.707109999985348))*(cj2));
05880 IkReal x1651=((cj0)*(r00));
05881 IkReal x1652=((IkReal(0.707109999985348))*(sj2));
05882 IkReal x1653=((cj5)*(r21));
05883 IkReal x1654=((sj0)*(x1649));
05884 IkReal x1655=((sj5)*(x1650));
05885 IkReal x1656=((cj0)*(cj5)*(r01));
05886 if( IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x1647)*(x1648)))+(((IkReal(-1.00000000000000))*(sj5)*(x1646)*(x1649)))+(((IkReal(-1.00000000000000))*(sj0)*(x1645)*(x1650)))+(((x1648)*(x1652)))+(((IkReal(-1.00000000000000))*(x1647)*(x1653)))+(((IkReal(-1.00000000000000))*(x1646)*(x1655)))+(((IkReal(-1.00000000000000))*(x1650)*(x1656)))+(((IkReal(-1.00000000000000))*(x1645)*(x1654)))+(((IkReal(-1.00000000000000))*(x1649)*(x1656)))+(((IkReal(-1.00000000000000))*(sj5)*(x1649)*(x1651)))+(((IkReal(-1.00000000000000))*(x1651)*(x1655)))+(((x1652)*(x1653))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((sj5)*(x1646)*(x1647)))+(((IkReal(-1.00000000000000))*(x1652)*(x1656)))+(((IkReal(-1.00000000000000))*(sj0)*(x1645)*(x1652)))+(((IkReal(-1.00000000000000))*(sj5)*(x1651)*(x1652)))+(((sj0)*(x1645)*(x1647)))+(((IkReal(-1.00000000000000))*(sj5)*(x1646)*(x1652)))+(((IkReal(-1.00000000000000))*(x1650)*(x1653)))+(((x1647)*(x1656)))+(((IkReal(-1.00000000000000))*(x1648)*(x1649)))+(((IkReal(-1.00000000000000))*(x1649)*(x1653)))+(((IkReal(-1.00000000000000))*(x1648)*(x1650)))+(((sj5)*(x1647)*(x1651))))))) < IKFAST_ATAN2_MAGTHRESH )
05887     continue;
05888 j1array[0]=IKatan2(((gconst15)*(((((IkReal(-1.00000000000000))*(x1647)*(x1648)))+(((IkReal(-1.00000000000000))*(sj5)*(x1646)*(x1649)))+(((IkReal(-1.00000000000000))*(sj0)*(x1645)*(x1650)))+(((x1648)*(x1652)))+(((IkReal(-1.00000000000000))*(x1647)*(x1653)))+(((IkReal(-1.00000000000000))*(x1646)*(x1655)))+(((IkReal(-1.00000000000000))*(x1650)*(x1656)))+(((IkReal(-1.00000000000000))*(x1645)*(x1654)))+(((IkReal(-1.00000000000000))*(x1649)*(x1656)))+(((IkReal(-1.00000000000000))*(sj5)*(x1649)*(x1651)))+(((IkReal(-1.00000000000000))*(x1651)*(x1655)))+(((x1652)*(x1653)))))), ((gconst15)*(((((sj5)*(x1646)*(x1647)))+(((IkReal(-1.00000000000000))*(x1652)*(x1656)))+(((IkReal(-1.00000000000000))*(sj0)*(x1645)*(x1652)))+(((IkReal(-1.00000000000000))*(sj5)*(x1651)*(x1652)))+(((sj0)*(x1645)*(x1647)))+(((IkReal(-1.00000000000000))*(sj5)*(x1646)*(x1652)))+(((IkReal(-1.00000000000000))*(x1650)*(x1653)))+(((x1647)*(x1656)))+(((IkReal(-1.00000000000000))*(x1648)*(x1649)))+(((IkReal(-1.00000000000000))*(x1649)*(x1653)))+(((IkReal(-1.00000000000000))*(x1648)*(x1650)))+(((sj5)*(x1647)*(x1651)))))));
05889 sj1array[0]=IKsin(j1array[0]);
05890 cj1array[0]=IKcos(j1array[0]);
05891 if( j1array[0] > IKPI )
05892 {
05893     j1array[0]-=IK2PI;
05894 }
05895 else if( j1array[0] < -IKPI )
05896 {    j1array[0]+=IK2PI;
05897 }
05898 j1valid[0] = true;
05899 for(int ij1 = 0; ij1 < 1; ++ij1)
05900 {
05901 if( !j1valid[ij1] )
05902 {
05903     continue;
05904 }
05905 _ij1[0] = ij1; _ij1[1] = -1;
05906 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05907 {
05908 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05909 {
05910     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05911 }
05912 }
05913 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05914 {
05915 IkReal evalcond[4];
05916 IkReal x1657=IKsin(j1);
05917 IkReal x1658=IKcos(j1);
05918 IkReal x1659=((IkReal(0.707109999985348))*(cj2));
05919 IkReal x1660=((IkReal(1.00000000000000))*(cj0));
05920 IkReal x1661=((IkReal(0.707109999985348))*(sj2));
05921 IkReal x1662=((cj5)*(sj4));
05922 IkReal x1663=((sj4)*(sj5));
05923 IkReal x1664=((IkReal(1.00000000000000))*(sj0));
05924 IkReal x1665=((sj5)*(x1664));
05925 IkReal x1666=((IkReal(0.707103562373095))*(x1658));
05926 IkReal x1667=((IkReal(0.707103562373095))*(x1657));
05927 IkReal x1668=((x1657)*(x1659));
05928 IkReal x1669=((sj2)*(x1667));
05929 IkReal x1670=((x1658)*(x1661));
05930 IkReal x1671=((cj2)*(x1666));
05931 IkReal x1672=((sj2)*(x1666));
05932 IkReal x1673=((cj2)*(x1667));
05933 IkReal x1674=((x1658)*(x1659));
05934 IkReal x1675=((x1657)*(x1661));
05935 IkReal x1676=((x1674)+(x1672)+(x1673));
05936 IkReal x1677=((x1669)+(x1668)+(x1670));
05937 evalcond[0]=((((cj5)*(r21)))+(x1675)+(((IkReal(-1.00000000000000))*(x1676)))+(((r20)*(sj5))));
05938 evalcond[1]=((((cj4)*(r22)))+(x1677)+(((IkReal(-1.00000000000000))*(r20)*(x1662)))+(((IkReal(-1.00000000000000))*(x1671)))+(((r21)*(x1663))));
05939 evalcond[2]=((x1677)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1664)))+(((IkReal(-1.00000000000000))*(r10)*(x1665)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1660)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1660)))+(((IkReal(-1.00000000000000))*(x1671))));
05940 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1664)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1660)))+(((IkReal(-1.00000000000000))*(r11)*(x1663)*(x1664)))+(x1676)+(((IkReal(-1.00000000000000))*(r01)*(x1660)*(x1663)))+(((r10)*(sj0)*(x1662)))+(((cj0)*(r00)*(x1662)))+(((IkReal(-1.00000000000000))*(x1675))));
05941 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05942 {
05943 continue;
05944 }
05945 }
05946 
05947 {
05948 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05949 vinfos[0].jointtype = 1;
05950 vinfos[0].foffset = j0;
05951 vinfos[0].indices[0] = _ij0[0];
05952 vinfos[0].indices[1] = _ij0[1];
05953 vinfos[0].maxsolutions = _nj0;
05954 vinfos[1].jointtype = 1;
05955 vinfos[1].foffset = j1;
05956 vinfos[1].indices[0] = _ij1[0];
05957 vinfos[1].indices[1] = _ij1[1];
05958 vinfos[1].maxsolutions = _nj1;
05959 vinfos[2].jointtype = 1;
05960 vinfos[2].foffset = j2;
05961 vinfos[2].indices[0] = _ij2[0];
05962 vinfos[2].indices[1] = _ij2[1];
05963 vinfos[2].maxsolutions = _nj2;
05964 vinfos[3].jointtype = 1;
05965 vinfos[3].foffset = j3;
05966 vinfos[3].indices[0] = _ij3[0];
05967 vinfos[3].indices[1] = _ij3[1];
05968 vinfos[3].maxsolutions = _nj3;
05969 vinfos[4].jointtype = 1;
05970 vinfos[4].foffset = j4;
05971 vinfos[4].indices[0] = _ij4[0];
05972 vinfos[4].indices[1] = _ij4[1];
05973 vinfos[4].maxsolutions = _nj4;
05974 vinfos[5].jointtype = 1;
05975 vinfos[5].foffset = j5;
05976 vinfos[5].indices[0] = _ij5[0];
05977 vinfos[5].indices[1] = _ij5[1];
05978 vinfos[5].maxsolutions = _nj5;
05979 std::vector<int> vfree(0);
05980 solutions.AddSolution(vinfos,vfree);
05981 }
05982 }
05983 }
05984 
05985 }
05986 
05987 }
05988 
05989 } else
05990 {
05991 {
05992 IkReal j1array[1], cj1array[1], sj1array[1];
05993 bool j1valid[1]={false};
05994 _nj1 = 1;
05995 IkReal x1678=((cj5)*(sj4));
05996 IkReal x1679=((r21)*(sj4));
05997 IkReal x1680=((cj5)*(r21));
05998 IkReal x1681=((IkReal(0.707109999985348))*(cj2));
05999 IkReal x1682=((IkReal(0.707103562373095))*(sj2));
06000 IkReal x1683=((IkReal(0.707109999985348))*(sj2));
06001 IkReal x1684=((cj4)*(r22));
06002 IkReal x1685=((IkReal(0.707103562373095))*(cj2));
06003 IkReal x1686=((r20)*(x1681));
06004 IkReal x1687=((sj5)*(x1685));
06005 IkReal x1688=((sj5)*(x1683));
06006 if( IKabs(((gconst14)*(((((x1681)*(x1684)))+(((x1680)*(x1683)))+(((IkReal(-1.00000000000000))*(r20)*(x1687)))+(((IkReal(-1.00000000000000))*(x1678)*(x1686)))+(((IkReal(-1.00000000000000))*(x1680)*(x1685)))+(((x1682)*(x1684)))+(((sj5)*(x1679)*(x1682)))+(((sj5)*(x1679)*(x1681)))+(((IkReal(-1.00000000000000))*(r20)*(x1678)*(x1682)))+(((r20)*(x1688))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(sj5)*(x1686)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1682)))+(((IkReal(-1.00000000000000))*(x1679)*(x1687)))+(((IkReal(-1.00000000000000))*(x1680)*(x1682)))+(((IkReal(-1.00000000000000))*(x1680)*(x1681)))+(((x1679)*(x1688)))+(((r20)*(x1678)*(x1685)))+(((IkReal(-1.00000000000000))*(r20)*(x1678)*(x1683)))+(((x1683)*(x1684)))+(((IkReal(-1.00000000000000))*(x1684)*(x1685))))))) < IKFAST_ATAN2_MAGTHRESH )
06007     continue;
06008 j1array[0]=IKatan2(((gconst14)*(((((x1681)*(x1684)))+(((x1680)*(x1683)))+(((IkReal(-1.00000000000000))*(r20)*(x1687)))+(((IkReal(-1.00000000000000))*(x1678)*(x1686)))+(((IkReal(-1.00000000000000))*(x1680)*(x1685)))+(((x1682)*(x1684)))+(((sj5)*(x1679)*(x1682)))+(((sj5)*(x1679)*(x1681)))+(((IkReal(-1.00000000000000))*(r20)*(x1678)*(x1682)))+(((r20)*(x1688)))))), ((gconst14)*(((((IkReal(-1.00000000000000))*(sj5)*(x1686)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1682)))+(((IkReal(-1.00000000000000))*(x1679)*(x1687)))+(((IkReal(-1.00000000000000))*(x1680)*(x1682)))+(((IkReal(-1.00000000000000))*(x1680)*(x1681)))+(((x1679)*(x1688)))+(((r20)*(x1678)*(x1685)))+(((IkReal(-1.00000000000000))*(r20)*(x1678)*(x1683)))+(((x1683)*(x1684)))+(((IkReal(-1.00000000000000))*(x1684)*(x1685)))))));
06009 sj1array[0]=IKsin(j1array[0]);
06010 cj1array[0]=IKcos(j1array[0]);
06011 if( j1array[0] > IKPI )
06012 {
06013     j1array[0]-=IK2PI;
06014 }
06015 else if( j1array[0] < -IKPI )
06016 {    j1array[0]+=IK2PI;
06017 }
06018 j1valid[0] = true;
06019 for(int ij1 = 0; ij1 < 1; ++ij1)
06020 {
06021 if( !j1valid[ij1] )
06022 {
06023     continue;
06024 }
06025 _ij1[0] = ij1; _ij1[1] = -1;
06026 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06027 {
06028 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06029 {
06030     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06031 }
06032 }
06033 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06034 {
06035 IkReal evalcond[4];
06036 IkReal x1689=IKsin(j1);
06037 IkReal x1690=IKcos(j1);
06038 IkReal x1691=((IkReal(0.707109999985348))*(cj2));
06039 IkReal x1692=((IkReal(1.00000000000000))*(cj0));
06040 IkReal x1693=((IkReal(0.707109999985348))*(sj2));
06041 IkReal x1694=((cj5)*(sj4));
06042 IkReal x1695=((sj4)*(sj5));
06043 IkReal x1696=((IkReal(1.00000000000000))*(sj0));
06044 IkReal x1697=((sj5)*(x1696));
06045 IkReal x1698=((IkReal(0.707103562373095))*(x1690));
06046 IkReal x1699=((IkReal(0.707103562373095))*(x1689));
06047 IkReal x1700=((x1689)*(x1691));
06048 IkReal x1701=((sj2)*(x1699));
06049 IkReal x1702=((x1690)*(x1693));
06050 IkReal x1703=((cj2)*(x1698));
06051 IkReal x1704=((sj2)*(x1698));
06052 IkReal x1705=((cj2)*(x1699));
06053 IkReal x1706=((x1690)*(x1691));
06054 IkReal x1707=((x1689)*(x1693));
06055 IkReal x1708=((x1704)+(x1705)+(x1706));
06056 IkReal x1709=((x1700)+(x1701)+(x1702));
06057 evalcond[0]=((((cj5)*(r21)))+(x1707)+(((IkReal(-1.00000000000000))*(x1708)))+(((r20)*(sj5))));
06058 evalcond[1]=((((r21)*(x1695)))+(((cj4)*(r22)))+(x1709)+(((IkReal(-1.00000000000000))*(x1703)))+(((IkReal(-1.00000000000000))*(r20)*(x1694))));
06059 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1696)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1692)))+(x1709)+(((IkReal(-1.00000000000000))*(x1703)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1692)))+(((IkReal(-1.00000000000000))*(r10)*(x1697))));
06060 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1696)))+(((IkReal(-1.00000000000000))*(r11)*(x1695)*(x1696)))+(x1708)+(((cj0)*(r00)*(x1694)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1692)))+(((IkReal(-1.00000000000000))*(x1707)))+(((r10)*(sj0)*(x1694)))+(((IkReal(-1.00000000000000))*(r01)*(x1692)*(x1695))));
06061 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06062 {
06063 continue;
06064 }
06065 }
06066 
06067 {
06068 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06069 vinfos[0].jointtype = 1;
06070 vinfos[0].foffset = j0;
06071 vinfos[0].indices[0] = _ij0[0];
06072 vinfos[0].indices[1] = _ij0[1];
06073 vinfos[0].maxsolutions = _nj0;
06074 vinfos[1].jointtype = 1;
06075 vinfos[1].foffset = j1;
06076 vinfos[1].indices[0] = _ij1[0];
06077 vinfos[1].indices[1] = _ij1[1];
06078 vinfos[1].maxsolutions = _nj1;
06079 vinfos[2].jointtype = 1;
06080 vinfos[2].foffset = j2;
06081 vinfos[2].indices[0] = _ij2[0];
06082 vinfos[2].indices[1] = _ij2[1];
06083 vinfos[2].maxsolutions = _nj2;
06084 vinfos[3].jointtype = 1;
06085 vinfos[3].foffset = j3;
06086 vinfos[3].indices[0] = _ij3[0];
06087 vinfos[3].indices[1] = _ij3[1];
06088 vinfos[3].maxsolutions = _nj3;
06089 vinfos[4].jointtype = 1;
06090 vinfos[4].foffset = j4;
06091 vinfos[4].indices[0] = _ij4[0];
06092 vinfos[4].indices[1] = _ij4[1];
06093 vinfos[4].maxsolutions = _nj4;
06094 vinfos[5].jointtype = 1;
06095 vinfos[5].foffset = j5;
06096 vinfos[5].indices[0] = _ij5[0];
06097 vinfos[5].indices[1] = _ij5[1];
06098 vinfos[5].maxsolutions = _nj5;
06099 std::vector<int> vfree(0);
06100 solutions.AddSolution(vinfos,vfree);
06101 }
06102 }
06103 }
06104 
06105 }
06106 
06107 }
06108 
06109 } else
06110 {
06111 IkReal x1710=((sj0)*(sj4));
06112 IkReal x1711=((IkReal(1.00000000000000))*(r12));
06113 IkReal x1712=((cj0)*(cj4));
06114 IkReal x1713=((r01)*(sj5));
06115 IkReal x1714=((IkReal(1.00000000000000))*(cj5));
06116 IkReal x1715=((cj4)*(cj5));
06117 IkReal x1716=((IkReal(1.00000000000000))*(cj0));
06118 IkReal x1717=((cj4)*(sj0));
06119 IkReal x1718=((r00)*(sj0));
06120 IkReal x1719=((npy)*(sj5));
06121 IkReal x1720=((IkReal(1.00000000000000))*(cj4));
06122 IkReal x1721=((cj0)*(sj4));
06123 IkReal x1722=((r11)*(sj5));
06124 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
06125 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1716)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x1714)))+(((sj5)*(x1718))));
06126 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x1719)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1714)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2))));
06127 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
06128 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x1719)*(x1720)))+(((npx)*(x1715))));
06129 evalcond[5]=((((x1710)*(x1713)))+(((r02)*(x1717)))+(((IkReal(-1.00000000000000))*(x1711)*(x1712)))+(((IkReal(-1.00000000000000))*(r00)*(x1710)*(x1714)))+(((IkReal(-1.00000000000000))*(sj4)*(x1716)*(x1722)))+(((cj5)*(r10)*(x1721))));
06130 evalcond[6]=((IkReal(-1.00000000000000))+(((r02)*(x1710)))+(((IkReal(-1.00000000000000))*(r10)*(x1712)*(x1714)))+(((IkReal(-1.00000000000000))*(x1713)*(x1717)))+(((x1715)*(x1718)))+(((x1712)*(x1722)))+(((IkReal(-1.00000000000000))*(x1711)*(x1721))));
06131 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x1720)))+(((r22)*(sj4)))+(((r20)*(x1715))));
06132 evalcond[8]=((((IkReal(-1.00000000000000))*(x1710)*(x1711)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1716)))+(((IkReal(-1.00000000000000))*(r10)*(x1714)*(x1717)))+(((x1712)*(x1713)))+(((x1717)*(x1722)))+(((IkReal(-1.00000000000000))*(r00)*(x1712)*(x1714))));
06133 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  )
06134 {
06135 {
06136 IkReal dummyeval[1];
06137 IkReal gconst16;
06138 gconst16=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
06139 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
06140 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06141 {
06142 {
06143 IkReal dummyeval[1];
06144 IkReal gconst17;
06145 gconst17=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
06146 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
06147 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06148 {
06149 continue;
06150 
06151 } else
06152 {
06153 {
06154 IkReal j1array[1], cj1array[1], sj1array[1];
06155 bool j1valid[1]={false};
06156 _nj1 = 1;
06157 IkReal x1723=((cj5)*(r11));
06158 IkReal x1724=((r10)*(sj0));
06159 IkReal x1725=((IkReal(0.707103562373095))*(cj2));
06160 IkReal x1726=((r20)*(sj5));
06161 IkReal x1727=((IkReal(0.707103562373095))*(sj2));
06162 IkReal x1728=((IkReal(0.707109999985348))*(cj2));
06163 IkReal x1729=((cj0)*(r00));
06164 IkReal x1730=((IkReal(0.707109999985348))*(sj2));
06165 IkReal x1731=((cj5)*(r21));
06166 IkReal x1732=((sj0)*(x1727));
06167 IkReal x1733=((sj5)*(x1728));
06168 IkReal x1734=((cj0)*(cj5)*(r01));
06169 if( IKabs(((gconst17)*(((((x1723)*(x1732)))+(((x1728)*(x1734)))+(((x1725)*(x1726)))+(((x1724)*(x1733)))+(((x1725)*(x1731)))+(((IkReal(-1.00000000000000))*(x1726)*(x1730)))+(((sj0)*(x1723)*(x1728)))+(((x1729)*(x1733)))+(((sj5)*(x1724)*(x1727)))+(((IkReal(-1.00000000000000))*(x1730)*(x1731)))+(((sj5)*(x1727)*(x1729)))+(((x1727)*(x1734))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((x1728)*(x1731)))+(((x1730)*(x1734)))+(((IkReal(-1.00000000000000))*(sj5)*(x1724)*(x1725)))+(((x1726)*(x1728)))+(((x1726)*(x1727)))+(((sj0)*(x1723)*(x1730)))+(((sj5)*(x1724)*(x1730)))+(((sj5)*(x1729)*(x1730)))+(((x1727)*(x1731)))+(((IkReal(-1.00000000000000))*(x1725)*(x1734)))+(((IkReal(-1.00000000000000))*(sj0)*(x1723)*(x1725)))+(((IkReal(-1.00000000000000))*(sj5)*(x1725)*(x1729))))))) < IKFAST_ATAN2_MAGTHRESH )
06170     continue;
06171 j1array[0]=IKatan2(((gconst17)*(((((x1723)*(x1732)))+(((x1728)*(x1734)))+(((x1725)*(x1726)))+(((x1724)*(x1733)))+(((x1725)*(x1731)))+(((IkReal(-1.00000000000000))*(x1726)*(x1730)))+(((sj0)*(x1723)*(x1728)))+(((x1729)*(x1733)))+(((sj5)*(x1724)*(x1727)))+(((IkReal(-1.00000000000000))*(x1730)*(x1731)))+(((sj5)*(x1727)*(x1729)))+(((x1727)*(x1734)))))), ((gconst17)*(((((x1728)*(x1731)))+(((x1730)*(x1734)))+(((IkReal(-1.00000000000000))*(sj5)*(x1724)*(x1725)))+(((x1726)*(x1728)))+(((x1726)*(x1727)))+(((sj0)*(x1723)*(x1730)))+(((sj5)*(x1724)*(x1730)))+(((sj5)*(x1729)*(x1730)))+(((x1727)*(x1731)))+(((IkReal(-1.00000000000000))*(x1725)*(x1734)))+(((IkReal(-1.00000000000000))*(sj0)*(x1723)*(x1725)))+(((IkReal(-1.00000000000000))*(sj5)*(x1725)*(x1729)))))));
06172 sj1array[0]=IKsin(j1array[0]);
06173 cj1array[0]=IKcos(j1array[0]);
06174 if( j1array[0] > IKPI )
06175 {
06176     j1array[0]-=IK2PI;
06177 }
06178 else if( j1array[0] < -IKPI )
06179 {    j1array[0]+=IK2PI;
06180 }
06181 j1valid[0] = true;
06182 for(int ij1 = 0; ij1 < 1; ++ij1)
06183 {
06184 if( !j1valid[ij1] )
06185 {
06186     continue;
06187 }
06188 _ij1[0] = ij1; _ij1[1] = -1;
06189 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06190 {
06191 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06192 {
06193     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06194 }
06195 }
06196 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06197 {
06198 IkReal evalcond[4];
06199 IkReal x1735=IKcos(j1);
06200 IkReal x1736=IKsin(j1);
06201 IkReal x1737=((IkReal(0.707109999985348))*(cj2));
06202 IkReal x1738=((IkReal(1.00000000000000))*(cj0));
06203 IkReal x1739=((IkReal(0.707109999985348))*(sj2));
06204 IkReal x1740=((cj5)*(sj4));
06205 IkReal x1741=((sj4)*(sj5));
06206 IkReal x1742=((IkReal(1.00000000000000))*(sj0));
06207 IkReal x1743=((sj5)*(x1742));
06208 IkReal x1744=((IkReal(0.707103562373095))*(x1735));
06209 IkReal x1745=((IkReal(0.707103562373095))*(x1736));
06210 IkReal x1746=((cj2)*(x1744));
06211 IkReal x1747=((x1736)*(x1737));
06212 IkReal x1748=((sj2)*(x1745));
06213 IkReal x1749=((x1735)*(x1739));
06214 IkReal x1750=((sj2)*(x1744));
06215 IkReal x1751=((cj2)*(x1745));
06216 IkReal x1752=((x1735)*(x1737));
06217 IkReal x1753=((x1736)*(x1739));
06218 IkReal x1754=((x1752)+(x1751)+(x1750));
06219 IkReal x1755=((x1748)+(x1749)+(x1747));
06220 evalcond[0]=((((cj5)*(r21)))+(x1754)+(((IkReal(-1.00000000000000))*(x1753)))+(((r20)*(sj5))));
06221 evalcond[1]=((((cj4)*(r22)))+(x1755)+(((IkReal(-1.00000000000000))*(r20)*(x1740)))+(((r21)*(x1741)))+(((IkReal(-1.00000000000000))*(x1746))));
06222 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1738)))+(x1746)+(((IkReal(-1.00000000000000))*(r10)*(x1743)))+(((IkReal(-1.00000000000000))*(x1755)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1742)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1738))));
06223 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1742)))+(((IkReal(-1.00000000000000))*(r11)*(x1741)*(x1742)))+(x1754)+(((r10)*(sj0)*(x1740)))+(((IkReal(-1.00000000000000))*(x1753)))+(((IkReal(-1.00000000000000))*(r01)*(x1738)*(x1741)))+(((cj0)*(r00)*(x1740)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1738))));
06224 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06225 {
06226 continue;
06227 }
06228 }
06229 
06230 {
06231 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06232 vinfos[0].jointtype = 1;
06233 vinfos[0].foffset = j0;
06234 vinfos[0].indices[0] = _ij0[0];
06235 vinfos[0].indices[1] = _ij0[1];
06236 vinfos[0].maxsolutions = _nj0;
06237 vinfos[1].jointtype = 1;
06238 vinfos[1].foffset = j1;
06239 vinfos[1].indices[0] = _ij1[0];
06240 vinfos[1].indices[1] = _ij1[1];
06241 vinfos[1].maxsolutions = _nj1;
06242 vinfos[2].jointtype = 1;
06243 vinfos[2].foffset = j2;
06244 vinfos[2].indices[0] = _ij2[0];
06245 vinfos[2].indices[1] = _ij2[1];
06246 vinfos[2].maxsolutions = _nj2;
06247 vinfos[3].jointtype = 1;
06248 vinfos[3].foffset = j3;
06249 vinfos[3].indices[0] = _ij3[0];
06250 vinfos[3].indices[1] = _ij3[1];
06251 vinfos[3].maxsolutions = _nj3;
06252 vinfos[4].jointtype = 1;
06253 vinfos[4].foffset = j4;
06254 vinfos[4].indices[0] = _ij4[0];
06255 vinfos[4].indices[1] = _ij4[1];
06256 vinfos[4].maxsolutions = _nj4;
06257 vinfos[5].jointtype = 1;
06258 vinfos[5].foffset = j5;
06259 vinfos[5].indices[0] = _ij5[0];
06260 vinfos[5].indices[1] = _ij5[1];
06261 vinfos[5].maxsolutions = _nj5;
06262 std::vector<int> vfree(0);
06263 solutions.AddSolution(vinfos,vfree);
06264 }
06265 }
06266 }
06267 
06268 }
06269 
06270 }
06271 
06272 } else
06273 {
06274 {
06275 IkReal j1array[1], cj1array[1], sj1array[1];
06276 bool j1valid[1]={false};
06277 _nj1 = 1;
06278 IkReal x1756=((cj5)*(sj4));
06279 IkReal x1757=((r21)*(sj4));
06280 IkReal x1758=((cj5)*(r21));
06281 IkReal x1759=((IkReal(0.707109999985348))*(cj2));
06282 IkReal x1760=((IkReal(0.707103562373095))*(sj2));
06283 IkReal x1761=((IkReal(0.707109999985348))*(sj2));
06284 IkReal x1762=((cj4)*(r22));
06285 IkReal x1763=((IkReal(0.707103562373095))*(cj2));
06286 IkReal x1764=((r20)*(x1759));
06287 IkReal x1765=((sj5)*(x1763));
06288 IkReal x1766=((sj5)*(x1761));
06289 if( IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(sj5)*(x1757)*(x1760)))+(((r20)*(x1766)))+(((IkReal(-1.00000000000000))*(r20)*(x1765)))+(((IkReal(-1.00000000000000))*(x1759)*(x1762)))+(((x1756)*(x1764)))+(((IkReal(-1.00000000000000))*(x1760)*(x1762)))+(((x1758)*(x1761)))+(((IkReal(-1.00000000000000))*(x1758)*(x1763)))+(((IkReal(-1.00000000000000))*(sj5)*(x1757)*(x1759)))+(((r20)*(x1756)*(x1760))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1760)))+(((IkReal(-1.00000000000000))*(sj5)*(x1764)))+(((IkReal(-1.00000000000000))*(x1758)*(x1759)))+(((IkReal(-1.00000000000000))*(x1761)*(x1762)))+(((x1757)*(x1765)))+(((IkReal(-1.00000000000000))*(x1757)*(x1766)))+(((x1762)*(x1763)))+(((IkReal(-1.00000000000000))*(x1758)*(x1760)))+(((r20)*(x1756)*(x1761)))+(((IkReal(-1.00000000000000))*(r20)*(x1756)*(x1763))))))) < IKFAST_ATAN2_MAGTHRESH )
06290     continue;
06291 j1array[0]=IKatan2(((gconst16)*(((((IkReal(-1.00000000000000))*(sj5)*(x1757)*(x1760)))+(((r20)*(x1766)))+(((IkReal(-1.00000000000000))*(r20)*(x1765)))+(((IkReal(-1.00000000000000))*(x1759)*(x1762)))+(((x1756)*(x1764)))+(((IkReal(-1.00000000000000))*(x1760)*(x1762)))+(((x1758)*(x1761)))+(((IkReal(-1.00000000000000))*(x1758)*(x1763)))+(((IkReal(-1.00000000000000))*(sj5)*(x1757)*(x1759)))+(((r20)*(x1756)*(x1760)))))), ((gconst16)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1760)))+(((IkReal(-1.00000000000000))*(sj5)*(x1764)))+(((IkReal(-1.00000000000000))*(x1758)*(x1759)))+(((IkReal(-1.00000000000000))*(x1761)*(x1762)))+(((x1757)*(x1765)))+(((IkReal(-1.00000000000000))*(x1757)*(x1766)))+(((x1762)*(x1763)))+(((IkReal(-1.00000000000000))*(x1758)*(x1760)))+(((r20)*(x1756)*(x1761)))+(((IkReal(-1.00000000000000))*(r20)*(x1756)*(x1763)))))));
06292 sj1array[0]=IKsin(j1array[0]);
06293 cj1array[0]=IKcos(j1array[0]);
06294 if( j1array[0] > IKPI )
06295 {
06296     j1array[0]-=IK2PI;
06297 }
06298 else if( j1array[0] < -IKPI )
06299 {    j1array[0]+=IK2PI;
06300 }
06301 j1valid[0] = true;
06302 for(int ij1 = 0; ij1 < 1; ++ij1)
06303 {
06304 if( !j1valid[ij1] )
06305 {
06306     continue;
06307 }
06308 _ij1[0] = ij1; _ij1[1] = -1;
06309 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06310 {
06311 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06312 {
06313     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06314 }
06315 }
06316 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06317 {
06318 IkReal evalcond[4];
06319 IkReal x1767=IKcos(j1);
06320 IkReal x1768=IKsin(j1);
06321 IkReal x1769=((IkReal(0.707109999985348))*(cj2));
06322 IkReal x1770=((IkReal(1.00000000000000))*(cj0));
06323 IkReal x1771=((IkReal(0.707109999985348))*(sj2));
06324 IkReal x1772=((cj5)*(sj4));
06325 IkReal x1773=((sj4)*(sj5));
06326 IkReal x1774=((IkReal(1.00000000000000))*(sj0));
06327 IkReal x1775=((sj5)*(x1774));
06328 IkReal x1776=((IkReal(0.707103562373095))*(x1767));
06329 IkReal x1777=((IkReal(0.707103562373095))*(x1768));
06330 IkReal x1778=((cj2)*(x1776));
06331 IkReal x1779=((x1768)*(x1769));
06332 IkReal x1780=((sj2)*(x1777));
06333 IkReal x1781=((x1767)*(x1771));
06334 IkReal x1782=((sj2)*(x1776));
06335 IkReal x1783=((cj2)*(x1777));
06336 IkReal x1784=((x1767)*(x1769));
06337 IkReal x1785=((x1768)*(x1771));
06338 IkReal x1786=((x1782)+(x1783)+(x1784));
06339 IkReal x1787=((x1780)+(x1781)+(x1779));
06340 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x1785)))+(x1786)+(((r20)*(sj5))));
06341 evalcond[1]=((((cj4)*(r22)))+(x1787)+(((IkReal(-1.00000000000000))*(x1778)))+(((r21)*(x1773)))+(((IkReal(-1.00000000000000))*(r20)*(x1772))));
06342 evalcond[2]=((((IkReal(-1.00000000000000))*(x1787)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1774)))+(x1778)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1770)))+(((IkReal(-1.00000000000000))*(r10)*(x1775)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1770))));
06343 evalcond[3]=((((IkReal(-1.00000000000000))*(x1785)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1770)))+(((IkReal(-1.00000000000000))*(r11)*(x1773)*(x1774)))+(x1786)+(((r10)*(sj0)*(x1772)))+(((IkReal(-1.00000000000000))*(r01)*(x1770)*(x1773)))+(((cj0)*(r00)*(x1772)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1774))));
06344 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06345 {
06346 continue;
06347 }
06348 }
06349 
06350 {
06351 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06352 vinfos[0].jointtype = 1;
06353 vinfos[0].foffset = j0;
06354 vinfos[0].indices[0] = _ij0[0];
06355 vinfos[0].indices[1] = _ij0[1];
06356 vinfos[0].maxsolutions = _nj0;
06357 vinfos[1].jointtype = 1;
06358 vinfos[1].foffset = j1;
06359 vinfos[1].indices[0] = _ij1[0];
06360 vinfos[1].indices[1] = _ij1[1];
06361 vinfos[1].maxsolutions = _nj1;
06362 vinfos[2].jointtype = 1;
06363 vinfos[2].foffset = j2;
06364 vinfos[2].indices[0] = _ij2[0];
06365 vinfos[2].indices[1] = _ij2[1];
06366 vinfos[2].maxsolutions = _nj2;
06367 vinfos[3].jointtype = 1;
06368 vinfos[3].foffset = j3;
06369 vinfos[3].indices[0] = _ij3[0];
06370 vinfos[3].indices[1] = _ij3[1];
06371 vinfos[3].maxsolutions = _nj3;
06372 vinfos[4].jointtype = 1;
06373 vinfos[4].foffset = j4;
06374 vinfos[4].indices[0] = _ij4[0];
06375 vinfos[4].indices[1] = _ij4[1];
06376 vinfos[4].maxsolutions = _nj4;
06377 vinfos[5].jointtype = 1;
06378 vinfos[5].foffset = j5;
06379 vinfos[5].indices[0] = _ij5[0];
06380 vinfos[5].indices[1] = _ij5[1];
06381 vinfos[5].maxsolutions = _nj5;
06382 std::vector<int> vfree(0);
06383 solutions.AddSolution(vinfos,vfree);
06384 }
06385 }
06386 }
06387 
06388 }
06389 
06390 }
06391 
06392 } else
06393 {
06394 IkReal x1788=((sj0)*(sj4));
06395 IkReal x1789=((IkReal(1.00000000000000))*(r12));
06396 IkReal x1790=((cj0)*(cj4));
06397 IkReal x1791=((r01)*(sj5));
06398 IkReal x1792=((IkReal(1.00000000000000))*(cj5));
06399 IkReal x1793=((cj4)*(cj5));
06400 IkReal x1794=((IkReal(1.00000000000000))*(cj0));
06401 IkReal x1795=((cj4)*(sj0));
06402 IkReal x1796=((r00)*(sj0));
06403 IkReal x1797=((npy)*(sj5));
06404 IkReal x1798=((IkReal(1.00000000000000))*(cj4));
06405 IkReal x1799=((cj0)*(sj4));
06406 IkReal x1800=((r11)*(sj5));
06407 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
06408 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x1792)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1794)))+(((sj5)*(x1796))));
06409 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x1797)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1792)))+(((IkReal(0.165463933124939))*(sj2))));
06410 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
06411 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((npx)*(x1793)))+(((IkReal(-1.00000000000000))*(x1797)*(x1798))));
06412 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x1788)*(x1792)))+(((IkReal(-1.00000000000000))*(x1789)*(x1790)))+(((r02)*(x1795)))+(((IkReal(-1.00000000000000))*(sj4)*(x1794)*(x1800)))+(((x1788)*(x1791)))+(((cj5)*(r10)*(x1799))));
06413 evalcond[6]=((IkReal(-1.00000000000000))+(((x1793)*(x1796)))+(((IkReal(-1.00000000000000))*(r10)*(x1790)*(x1792)))+(((IkReal(-1.00000000000000))*(x1789)*(x1799)))+(((IkReal(-1.00000000000000))*(x1791)*(x1795)))+(((r02)*(x1788)))+(((x1790)*(x1800))));
06414 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x1798)))+(((r22)*(sj4)))+(((r20)*(x1793))));
06415 evalcond[8]=((((IkReal(-1.00000000000000))*(r10)*(x1792)*(x1795)))+(((x1795)*(x1800)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1794)))+(((IkReal(-1.00000000000000))*(x1788)*(x1789)))+(((IkReal(-1.00000000000000))*(r00)*(x1790)*(x1792)))+(((x1790)*(x1791))));
06416 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  )
06417 {
06418 {
06419 IkReal dummyeval[1];
06420 IkReal gconst18;
06421 gconst18=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
06422 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
06423 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06424 {
06425 {
06426 IkReal dummyeval[1];
06427 IkReal gconst19;
06428 gconst19=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
06429 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
06430 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06431 {
06432 continue;
06433 
06434 } else
06435 {
06436 {
06437 IkReal j1array[1], cj1array[1], sj1array[1];
06438 bool j1valid[1]={false};
06439 _nj1 = 1;
06440 IkReal x1801=((cj5)*(r11));
06441 IkReal x1802=((r10)*(sj0));
06442 IkReal x1803=((IkReal(0.707103562373095))*(cj2));
06443 IkReal x1804=((r20)*(sj5));
06444 IkReal x1805=((IkReal(0.707103562373095))*(sj2));
06445 IkReal x1806=((IkReal(0.707109999985348))*(cj2));
06446 IkReal x1807=((cj0)*(r00));
06447 IkReal x1808=((IkReal(0.707109999985348))*(sj2));
06448 IkReal x1809=((cj5)*(r21));
06449 IkReal x1810=((sj0)*(x1805));
06450 IkReal x1811=((sj5)*(x1806));
06451 IkReal x1812=((cj0)*(cj5)*(r01));
06452 if( IKabs(((gconst19)*(((((x1802)*(x1811)))+(((x1805)*(x1812)))+(((IkReal(-1.00000000000000))*(x1804)*(x1808)))+(((sj5)*(x1805)*(x1807)))+(((x1803)*(x1804)))+(((x1803)*(x1809)))+(((x1807)*(x1811)))+(((IkReal(-1.00000000000000))*(x1808)*(x1809)))+(((sj5)*(x1802)*(x1805)))+(((x1806)*(x1812)))+(((x1801)*(x1810)))+(((sj0)*(x1801)*(x1806))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst19)*(((((IkReal(-1.00000000000000))*(sj5)*(x1802)*(x1803)))+(((IkReal(-1.00000000000000))*(sj0)*(x1801)*(x1803)))+(((x1806)*(x1809)))+(((IkReal(-1.00000000000000))*(x1803)*(x1812)))+(((x1808)*(x1812)))+(((sj5)*(x1807)*(x1808)))+(((sj5)*(x1802)*(x1808)))+(((x1805)*(x1809)))+(((IkReal(-1.00000000000000))*(sj5)*(x1803)*(x1807)))+(((x1804)*(x1806)))+(((x1804)*(x1805)))+(((sj0)*(x1801)*(x1808))))))) < IKFAST_ATAN2_MAGTHRESH )
06453     continue;
06454 j1array[0]=IKatan2(((gconst19)*(((((x1802)*(x1811)))+(((x1805)*(x1812)))+(((IkReal(-1.00000000000000))*(x1804)*(x1808)))+(((sj5)*(x1805)*(x1807)))+(((x1803)*(x1804)))+(((x1803)*(x1809)))+(((x1807)*(x1811)))+(((IkReal(-1.00000000000000))*(x1808)*(x1809)))+(((sj5)*(x1802)*(x1805)))+(((x1806)*(x1812)))+(((x1801)*(x1810)))+(((sj0)*(x1801)*(x1806)))))), ((gconst19)*(((((IkReal(-1.00000000000000))*(sj5)*(x1802)*(x1803)))+(((IkReal(-1.00000000000000))*(sj0)*(x1801)*(x1803)))+(((x1806)*(x1809)))+(((IkReal(-1.00000000000000))*(x1803)*(x1812)))+(((x1808)*(x1812)))+(((sj5)*(x1807)*(x1808)))+(((sj5)*(x1802)*(x1808)))+(((x1805)*(x1809)))+(((IkReal(-1.00000000000000))*(sj5)*(x1803)*(x1807)))+(((x1804)*(x1806)))+(((x1804)*(x1805)))+(((sj0)*(x1801)*(x1808)))))));
06455 sj1array[0]=IKsin(j1array[0]);
06456 cj1array[0]=IKcos(j1array[0]);
06457 if( j1array[0] > IKPI )
06458 {
06459     j1array[0]-=IK2PI;
06460 }
06461 else if( j1array[0] < -IKPI )
06462 {    j1array[0]+=IK2PI;
06463 }
06464 j1valid[0] = true;
06465 for(int ij1 = 0; ij1 < 1; ++ij1)
06466 {
06467 if( !j1valid[ij1] )
06468 {
06469     continue;
06470 }
06471 _ij1[0] = ij1; _ij1[1] = -1;
06472 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06473 {
06474 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06475 {
06476     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06477 }
06478 }
06479 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06480 {
06481 IkReal evalcond[4];
06482 IkReal x1813=IKcos(j1);
06483 IkReal x1814=IKsin(j1);
06484 IkReal x1815=((IkReal(0.707109999985348))*(cj2));
06485 IkReal x1816=((IkReal(1.00000000000000))*(cj0));
06486 IkReal x1817=((IkReal(0.707109999985348))*(sj2));
06487 IkReal x1818=((cj5)*(sj4));
06488 IkReal x1819=((sj4)*(sj5));
06489 IkReal x1820=((IkReal(1.00000000000000))*(sj0));
06490 IkReal x1821=((sj5)*(x1820));
06491 IkReal x1822=((IkReal(0.707103562373095))*(x1813));
06492 IkReal x1823=((IkReal(0.707103562373095))*(x1814));
06493 IkReal x1824=((cj2)*(x1822));
06494 IkReal x1825=((x1814)*(x1815));
06495 IkReal x1826=((sj2)*(x1823));
06496 IkReal x1827=((x1813)*(x1817));
06497 IkReal x1828=((sj2)*(x1822));
06498 IkReal x1829=((cj2)*(x1823));
06499 IkReal x1830=((x1813)*(x1815));
06500 IkReal x1831=((x1814)*(x1817));
06501 IkReal x1832=((x1829)+(x1828)+(x1830));
06502 IkReal x1833=((x1825)+(x1827)+(x1826));
06503 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x1831)))+(x1832)+(((r20)*(sj5))));
06504 evalcond[1]=((((IkReal(-1.00000000000000))*(x1824)))+(((cj4)*(r22)))+(x1833)+(((r21)*(x1819)))+(((IkReal(-1.00000000000000))*(r20)*(x1818))));
06505 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1816)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1816)))+(((IkReal(-1.00000000000000))*(x1833)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1820)))+(x1824)+(((IkReal(-1.00000000000000))*(r10)*(x1821))));
06506 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1820)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1816)))+(((IkReal(-1.00000000000000))*(r01)*(x1816)*(x1819)))+(((IkReal(-1.00000000000000))*(r11)*(x1819)*(x1820)))+(((IkReal(-1.00000000000000))*(x1831)))+(((cj0)*(r00)*(x1818)))+(((r10)*(sj0)*(x1818)))+(x1832));
06507 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06508 {
06509 continue;
06510 }
06511 }
06512 
06513 {
06514 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06515 vinfos[0].jointtype = 1;
06516 vinfos[0].foffset = j0;
06517 vinfos[0].indices[0] = _ij0[0];
06518 vinfos[0].indices[1] = _ij0[1];
06519 vinfos[0].maxsolutions = _nj0;
06520 vinfos[1].jointtype = 1;
06521 vinfos[1].foffset = j1;
06522 vinfos[1].indices[0] = _ij1[0];
06523 vinfos[1].indices[1] = _ij1[1];
06524 vinfos[1].maxsolutions = _nj1;
06525 vinfos[2].jointtype = 1;
06526 vinfos[2].foffset = j2;
06527 vinfos[2].indices[0] = _ij2[0];
06528 vinfos[2].indices[1] = _ij2[1];
06529 vinfos[2].maxsolutions = _nj2;
06530 vinfos[3].jointtype = 1;
06531 vinfos[3].foffset = j3;
06532 vinfos[3].indices[0] = _ij3[0];
06533 vinfos[3].indices[1] = _ij3[1];
06534 vinfos[3].maxsolutions = _nj3;
06535 vinfos[4].jointtype = 1;
06536 vinfos[4].foffset = j4;
06537 vinfos[4].indices[0] = _ij4[0];
06538 vinfos[4].indices[1] = _ij4[1];
06539 vinfos[4].maxsolutions = _nj4;
06540 vinfos[5].jointtype = 1;
06541 vinfos[5].foffset = j5;
06542 vinfos[5].indices[0] = _ij5[0];
06543 vinfos[5].indices[1] = _ij5[1];
06544 vinfos[5].maxsolutions = _nj5;
06545 std::vector<int> vfree(0);
06546 solutions.AddSolution(vinfos,vfree);
06547 }
06548 }
06549 }
06550 
06551 }
06552 
06553 }
06554 
06555 } else
06556 {
06557 {
06558 IkReal j1array[1], cj1array[1], sj1array[1];
06559 bool j1valid[1]={false};
06560 _nj1 = 1;
06561 IkReal x1834=((cj5)*(sj4));
06562 IkReal x1835=((r21)*(sj4));
06563 IkReal x1836=((cj5)*(r21));
06564 IkReal x1837=((IkReal(0.707109999985348))*(cj2));
06565 IkReal x1838=((IkReal(0.707103562373095))*(sj2));
06566 IkReal x1839=((IkReal(0.707109999985348))*(sj2));
06567 IkReal x1840=((cj4)*(r22));
06568 IkReal x1841=((IkReal(0.707103562373095))*(cj2));
06569 IkReal x1842=((r20)*(x1837));
06570 IkReal x1843=((sj5)*(x1841));
06571 IkReal x1844=((sj5)*(x1839));
06572 if( IKabs(((gconst18)*(((((r20)*(x1834)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1835)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1835)*(x1837)))+(((x1834)*(x1842)))+(((r20)*(x1844)))+(((IkReal(-1.00000000000000))*(x1836)*(x1841)))+(((IkReal(-1.00000000000000))*(r20)*(x1843)))+(((IkReal(-1.00000000000000))*(x1837)*(x1840)))+(((IkReal(-1.00000000000000))*(x1838)*(x1840)))+(((x1836)*(x1839))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst18)*(((((r20)*(x1834)*(x1839)))+(((IkReal(-1.00000000000000))*(x1836)*(x1837)))+(((IkReal(-1.00000000000000))*(x1836)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1842)))+(((IkReal(-1.00000000000000))*(x1839)*(x1840)))+(((x1840)*(x1841)))+(((IkReal(-1.00000000000000))*(x1835)*(x1844)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1838)))+(((x1835)*(x1843)))+(((IkReal(-1.00000000000000))*(r20)*(x1834)*(x1841))))))) < IKFAST_ATAN2_MAGTHRESH )
06573     continue;
06574 j1array[0]=IKatan2(((gconst18)*(((((r20)*(x1834)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1835)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1835)*(x1837)))+(((x1834)*(x1842)))+(((r20)*(x1844)))+(((IkReal(-1.00000000000000))*(x1836)*(x1841)))+(((IkReal(-1.00000000000000))*(r20)*(x1843)))+(((IkReal(-1.00000000000000))*(x1837)*(x1840)))+(((IkReal(-1.00000000000000))*(x1838)*(x1840)))+(((x1836)*(x1839)))))), ((gconst18)*(((((r20)*(x1834)*(x1839)))+(((IkReal(-1.00000000000000))*(x1836)*(x1837)))+(((IkReal(-1.00000000000000))*(x1836)*(x1838)))+(((IkReal(-1.00000000000000))*(sj5)*(x1842)))+(((IkReal(-1.00000000000000))*(x1839)*(x1840)))+(((x1840)*(x1841)))+(((IkReal(-1.00000000000000))*(x1835)*(x1844)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x1838)))+(((x1835)*(x1843)))+(((IkReal(-1.00000000000000))*(r20)*(x1834)*(x1841)))))));
06575 sj1array[0]=IKsin(j1array[0]);
06576 cj1array[0]=IKcos(j1array[0]);
06577 if( j1array[0] > IKPI )
06578 {
06579     j1array[0]-=IK2PI;
06580 }
06581 else if( j1array[0] < -IKPI )
06582 {    j1array[0]+=IK2PI;
06583 }
06584 j1valid[0] = true;
06585 for(int ij1 = 0; ij1 < 1; ++ij1)
06586 {
06587 if( !j1valid[ij1] )
06588 {
06589     continue;
06590 }
06591 _ij1[0] = ij1; _ij1[1] = -1;
06592 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06593 {
06594 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06595 {
06596     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06597 }
06598 }
06599 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06600 {
06601 IkReal evalcond[4];
06602 IkReal x1845=IKcos(j1);
06603 IkReal x1846=IKsin(j1);
06604 IkReal x1847=((IkReal(0.707109999985348))*(cj2));
06605 IkReal x1848=((IkReal(1.00000000000000))*(cj0));
06606 IkReal x1849=((IkReal(0.707109999985348))*(sj2));
06607 IkReal x1850=((cj5)*(sj4));
06608 IkReal x1851=((sj4)*(sj5));
06609 IkReal x1852=((IkReal(1.00000000000000))*(sj0));
06610 IkReal x1853=((sj5)*(x1852));
06611 IkReal x1854=((IkReal(0.707103562373095))*(x1845));
06612 IkReal x1855=((IkReal(0.707103562373095))*(x1846));
06613 IkReal x1856=((cj2)*(x1854));
06614 IkReal x1857=((x1846)*(x1847));
06615 IkReal x1858=((sj2)*(x1855));
06616 IkReal x1859=((x1845)*(x1849));
06617 IkReal x1860=((sj2)*(x1854));
06618 IkReal x1861=((cj2)*(x1855));
06619 IkReal x1862=((x1845)*(x1847));
06620 IkReal x1863=((x1846)*(x1849));
06621 IkReal x1864=((x1861)+(x1860)+(x1862));
06622 IkReal x1865=((x1858)+(x1859)+(x1857));
06623 evalcond[0]=((((cj5)*(r21)))+(x1864)+(((IkReal(-1.00000000000000))*(x1863)))+(((r20)*(sj5))));
06624 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x1850)))+(x1865)+(((r21)*(x1851)))+(((IkReal(-1.00000000000000))*(x1856))));
06625 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1848)))+(x1856)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1852)))+(((IkReal(-1.00000000000000))*(x1865)))+(((IkReal(-1.00000000000000))*(r10)*(x1853)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1848))));
06626 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x1851)*(x1852)))+(((IkReal(-1.00000000000000))*(r01)*(x1848)*(x1851)))+(((r10)*(sj0)*(x1850)))+(x1864)+(((cj0)*(r00)*(x1850)))+(((IkReal(-1.00000000000000))*(x1863)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1848)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1852))));
06627 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06628 {
06629 continue;
06630 }
06631 }
06632 
06633 {
06634 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06635 vinfos[0].jointtype = 1;
06636 vinfos[0].foffset = j0;
06637 vinfos[0].indices[0] = _ij0[0];
06638 vinfos[0].indices[1] = _ij0[1];
06639 vinfos[0].maxsolutions = _nj0;
06640 vinfos[1].jointtype = 1;
06641 vinfos[1].foffset = j1;
06642 vinfos[1].indices[0] = _ij1[0];
06643 vinfos[1].indices[1] = _ij1[1];
06644 vinfos[1].maxsolutions = _nj1;
06645 vinfos[2].jointtype = 1;
06646 vinfos[2].foffset = j2;
06647 vinfos[2].indices[0] = _ij2[0];
06648 vinfos[2].indices[1] = _ij2[1];
06649 vinfos[2].maxsolutions = _nj2;
06650 vinfos[3].jointtype = 1;
06651 vinfos[3].foffset = j3;
06652 vinfos[3].indices[0] = _ij3[0];
06653 vinfos[3].indices[1] = _ij3[1];
06654 vinfos[3].maxsolutions = _nj3;
06655 vinfos[4].jointtype = 1;
06656 vinfos[4].foffset = j4;
06657 vinfos[4].indices[0] = _ij4[0];
06658 vinfos[4].indices[1] = _ij4[1];
06659 vinfos[4].maxsolutions = _nj4;
06660 vinfos[5].jointtype = 1;
06661 vinfos[5].foffset = j5;
06662 vinfos[5].indices[0] = _ij5[0];
06663 vinfos[5].indices[1] = _ij5[1];
06664 vinfos[5].maxsolutions = _nj5;
06665 std::vector<int> vfree(0);
06666 solutions.AddSolution(vinfos,vfree);
06667 }
06668 }
06669 }
06670 
06671 }
06672 
06673 }
06674 
06675 } else
06676 {
06677 if( 1 )
06678 {
06679 continue;
06680 
06681 } else
06682 {
06683 }
06684 }
06685 }
06686 }
06687 }
06688 }
06689 
06690 } else
06691 {
06692 {
06693 IkReal j1array[1], cj1array[1], sj1array[1];
06694 bool j1valid[1]={false};
06695 _nj1 = 1;
06696 IkReal x1866=((IkReal(0.707109999985348))*(sj2));
06697 IkReal x1867=((r22)*(sj4));
06698 IkReal x1868=((cj5)*(r20));
06699 IkReal x1869=((r21)*(sj5));
06700 IkReal x1870=((IkReal(0.707109999985348))*(cj2));
06701 IkReal x1871=((cj3)*(r22));
06702 IkReal x1872=((cj3)*(sj4));
06703 IkReal x1873=((IkReal(0.707103562373095))*(cj4)*(sj2));
06704 IkReal x1874=((IkReal(0.707103562373095))*(x1872));
06705 IkReal x1875=((IkReal(0.707103562373095))*(cj2)*(cj4));
06706 if( IKabs(((gconst11)*(((((sj2)*(x1869)*(x1874)))+(((IkReal(-1.00000000000000))*(x1869)*(x1875)))+(((IkReal(0.707103562373095))*(cj2)*(x1867)))+(((IkReal(-1.00000000000000))*(x1866)*(x1867)))+(((x1871)*(x1873)))+(((IkReal(-1.00000000000000))*(sj2)*(x1868)*(x1874)))+(((cj4)*(x1866)*(x1869)))+(((x1869)*(x1870)*(x1872)))+(((IkReal(-1.00000000000000))*(x1868)*(x1870)*(x1872)))+(((x1868)*(x1875)))+(((cj4)*(x1870)*(x1871)))+(((IkReal(-1.00000000000000))*(cj4)*(x1866)*(x1868))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(cj4)*(x1869)*(x1870)))+(((x1866)*(x1869)*(x1872)))+(((IkReal(-1.00000000000000))*(x1869)*(x1873)))+(((IkReal(0.707103562373095))*(sj2)*(x1867)))+(((IkReal(-1.00000000000000))*(x1866)*(x1868)*(x1872)))+(((cj4)*(x1866)*(x1871)))+(((cj2)*(x1868)*(x1874)))+(((IkReal(-1.00000000000000))*(x1871)*(x1875)))+(((x1868)*(x1873)))+(((cj4)*(x1868)*(x1870)))+(((IkReal(-1.00000000000000))*(cj2)*(x1869)*(x1874)))+(((x1867)*(x1870))))))) < IKFAST_ATAN2_MAGTHRESH )
06707     continue;
06708 j1array[0]=IKatan2(((gconst11)*(((((sj2)*(x1869)*(x1874)))+(((IkReal(-1.00000000000000))*(x1869)*(x1875)))+(((IkReal(0.707103562373095))*(cj2)*(x1867)))+(((IkReal(-1.00000000000000))*(x1866)*(x1867)))+(((x1871)*(x1873)))+(((IkReal(-1.00000000000000))*(sj2)*(x1868)*(x1874)))+(((cj4)*(x1866)*(x1869)))+(((x1869)*(x1870)*(x1872)))+(((IkReal(-1.00000000000000))*(x1868)*(x1870)*(x1872)))+(((x1868)*(x1875)))+(((cj4)*(x1870)*(x1871)))+(((IkReal(-1.00000000000000))*(cj4)*(x1866)*(x1868)))))), ((gconst11)*(((((IkReal(-1.00000000000000))*(cj4)*(x1869)*(x1870)))+(((x1866)*(x1869)*(x1872)))+(((IkReal(-1.00000000000000))*(x1869)*(x1873)))+(((IkReal(0.707103562373095))*(sj2)*(x1867)))+(((IkReal(-1.00000000000000))*(x1866)*(x1868)*(x1872)))+(((cj4)*(x1866)*(x1871)))+(((cj2)*(x1868)*(x1874)))+(((IkReal(-1.00000000000000))*(x1871)*(x1875)))+(((x1868)*(x1873)))+(((cj4)*(x1868)*(x1870)))+(((IkReal(-1.00000000000000))*(cj2)*(x1869)*(x1874)))+(((x1867)*(x1870)))))));
06709 sj1array[0]=IKsin(j1array[0]);
06710 cj1array[0]=IKcos(j1array[0]);
06711 if( j1array[0] > IKPI )
06712 {
06713     j1array[0]-=IK2PI;
06714 }
06715 else if( j1array[0] < -IKPI )
06716 {    j1array[0]+=IK2PI;
06717 }
06718 j1valid[0] = true;
06719 for(int ij1 = 0; ij1 < 1; ++ij1)
06720 {
06721 if( !j1valid[ij1] )
06722 {
06723     continue;
06724 }
06725 _ij1[0] = ij1; _ij1[1] = -1;
06726 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06727 {
06728 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06729 {
06730     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06731 }
06732 }
06733 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06734 {
06735 IkReal evalcond[6];
06736 IkReal x1876=IKcos(j1);
06737 IkReal x1877=IKsin(j1);
06738 IkReal x1878=((cj0)*(cj4));
06739 IkReal x1879=((r01)*(sj5));
06740 IkReal x1880=((IkReal(1.00000000000000))*(cj4));
06741 IkReal x1881=((IkReal(1.00000000000000))*(r02));
06742 IkReal x1882=((IkReal(0.707109999985348))*(sj3));
06743 IkReal x1883=((IkReal(0.707103562373095))*(sj3));
06744 IkReal x1884=((IkReal(1.00000000000000))*(sj4));
06745 IkReal x1885=((cj5)*(r20));
06746 IkReal x1886=((cj5)*(sj0));
06747 IkReal x1887=((IkReal(1.00000000000000))*(cj0));
06748 IkReal x1888=((r12)*(sj0));
06749 IkReal x1889=((cj2)*(cj3));
06750 IkReal x1890=((IkReal(0.707103562373095))*(cj3));
06751 IkReal x1891=((r21)*(sj5));
06752 IkReal x1892=((IkReal(0.707109999985348))*(cj3));
06753 IkReal x1893=((IkReal(1.00000000000000))*(sj0)*(sj5));
06754 IkReal x1894=((sj2)*(x1876));
06755 IkReal x1895=((cj2)*(x1876));
06756 IkReal x1896=((cj0)*(cj5)*(r00));
06757 IkReal x1897=((IkReal(0.707103562373095))*(x1877));
06758 IkReal x1898=((cj2)*(x1877));
06759 IkReal x1899=((IkReal(0.707109999985348))*(sj2)*(x1877));
06760 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x1883)*(x1894)))+(((IkReal(-1.00000000000000))*(x1883)*(x1898)))+(((IkReal(-1.00000000000000))*(x1882)*(x1895)))+(((sj2)*(x1877)*(x1882)))+(((r20)*(sj5))));
06761 evalcond[1]=((((sj2)*(x1897)))+(((cj4)*(r22)))+(((IkReal(-0.707103562373095))*(x1895)))+(((IkReal(-1.00000000000000))*(x1884)*(x1885)))+(((sj4)*(x1891)))+(((IkReal(0.707109999985348))*(x1894)))+(((IkReal(0.707109999985348))*(x1898))));
06762 evalcond[2]=((((IkReal(-1.00000000000000))*(x1880)*(x1891)))+(((cj4)*(x1885)))+(((IkReal(-1.00000000000000))*(sj2)*(x1877)*(x1892)))+(((r22)*(sj4)))+(((IkReal(0.707109999985348))*(x1876)*(x1889)))+(((x1889)*(x1897)))+(((x1890)*(x1894))));
06763 evalcond[3]=((((x1882)*(x1894)))+(((x1882)*(x1898)))+(((IkReal(-1.00000000000000))*(x1883)*(x1895)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1887)))+(((sj2)*(x1877)*(x1883)))+(((IkReal(-1.00000000000000))*(r10)*(x1893)))+(((IkReal(-1.00000000000000))*(r11)*(x1886)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1887))));
06764 evalcond[4]=((((IkReal(-1.00000000000000))*(x1880)*(x1888)))+(((IkReal(-1.00000000000000))*(cj0)*(x1879)*(x1884)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1884)))+(((IkReal(-1.00000000000000))*(x1878)*(x1881)))+(((r10)*(sj4)*(x1886)))+(((cj2)*(x1897)))+(((sj4)*(x1896)))+(((IkReal(0.707109999985348))*(x1895)))+(((IkReal(-1.00000000000000))*(x1899)))+(((IkReal(0.707103562373095))*(x1894))));
06765 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x1878)))+(((IkReal(-1.00000000000000))*(x1892)*(x1894)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x1881)))+(((IkReal(-1.00000000000000))*(sj2)*(x1877)*(x1890)))+(((IkReal(0.707103562373095))*(x1876)*(x1889)))+(((IkReal(-1.00000000000000))*(r10)*(x1880)*(x1886)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x1884)*(x1888)))+(((x1878)*(x1879)))+(((IkReal(-0.707109999985348))*(x1877)*(x1889))));
06766 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  )
06767 {
06768 continue;
06769 }
06770 }
06771 
06772 {
06773 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06774 vinfos[0].jointtype = 1;
06775 vinfos[0].foffset = j0;
06776 vinfos[0].indices[0] = _ij0[0];
06777 vinfos[0].indices[1] = _ij0[1];
06778 vinfos[0].maxsolutions = _nj0;
06779 vinfos[1].jointtype = 1;
06780 vinfos[1].foffset = j1;
06781 vinfos[1].indices[0] = _ij1[0];
06782 vinfos[1].indices[1] = _ij1[1];
06783 vinfos[1].maxsolutions = _nj1;
06784 vinfos[2].jointtype = 1;
06785 vinfos[2].foffset = j2;
06786 vinfos[2].indices[0] = _ij2[0];
06787 vinfos[2].indices[1] = _ij2[1];
06788 vinfos[2].maxsolutions = _nj2;
06789 vinfos[3].jointtype = 1;
06790 vinfos[3].foffset = j3;
06791 vinfos[3].indices[0] = _ij3[0];
06792 vinfos[3].indices[1] = _ij3[1];
06793 vinfos[3].maxsolutions = _nj3;
06794 vinfos[4].jointtype = 1;
06795 vinfos[4].foffset = j4;
06796 vinfos[4].indices[0] = _ij4[0];
06797 vinfos[4].indices[1] = _ij4[1];
06798 vinfos[4].maxsolutions = _nj4;
06799 vinfos[5].jointtype = 1;
06800 vinfos[5].foffset = j5;
06801 vinfos[5].indices[0] = _ij5[0];
06802 vinfos[5].indices[1] = _ij5[1];
06803 vinfos[5].maxsolutions = _nj5;
06804 std::vector<int> vfree(0);
06805 solutions.AddSolution(vinfos,vfree);
06806 }
06807 }
06808 }
06809 
06810 }
06811 
06812 }
06813 
06814 } else
06815 {
06816 {
06817 IkReal j1array[1], cj1array[1], sj1array[1];
06818 bool j1valid[1]={false};
06819 _nj1 = 1;
06820 IkReal x1900=((sj2)*(sj3));
06821 IkReal x1901=((cj4)*(r22));
06822 IkReal x1902=((r20)*(sj5));
06823 IkReal x1903=((IkReal(0.707103562373095))*(cj2));
06824 IkReal x1904=((IkReal(0.707109999985348))*(sj2));
06825 IkReal x1905=((IkReal(0.707109999985348))*(cj2));
06826 IkReal x1906=((cj5)*(r21));
06827 IkReal x1907=((IkReal(0.707103562373095))*(sj2));
06828 IkReal x1908=((r21)*(sj4)*(sj5));
06829 IkReal x1909=((cj5)*(r20)*(sj4));
06830 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(x1902)*(x1903)))+(((IkReal(0.707103562373095))*(x1900)*(x1901)))+(((IkReal(0.707103562373095))*(x1900)*(x1908)))+(((sj3)*(x1905)*(x1908)))+(((IkReal(-1.00000000000000))*(x1903)*(x1906)))+(((x1904)*(x1906)))+(((IkReal(-0.707103562373095))*(x1900)*(x1909)))+(((x1902)*(x1904)))+(((sj3)*(x1901)*(x1905)))+(((IkReal(-1.00000000000000))*(sj3)*(x1905)*(x1909))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(x1902)*(x1907)))+(((IkReal(-1.00000000000000))*(x1902)*(x1905)))+(((IkReal(-0.707109999985348))*(x1900)*(x1909)))+(((IkReal(-1.00000000000000))*(x1905)*(x1906)))+(((IkReal(0.707109999985348))*(x1900)*(x1901)))+(((IkReal(0.707109999985348))*(x1900)*(x1908)))+(((IkReal(-1.00000000000000))*(sj3)*(x1901)*(x1903)))+(((IkReal(-1.00000000000000))*(sj3)*(x1903)*(x1908)))+(((IkReal(-1.00000000000000))*(x1906)*(x1907)))+(((sj3)*(x1903)*(x1909))))))) < IKFAST_ATAN2_MAGTHRESH )
06831     continue;
06832 j1array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(x1902)*(x1903)))+(((IkReal(0.707103562373095))*(x1900)*(x1901)))+(((IkReal(0.707103562373095))*(x1900)*(x1908)))+(((sj3)*(x1905)*(x1908)))+(((IkReal(-1.00000000000000))*(x1903)*(x1906)))+(((x1904)*(x1906)))+(((IkReal(-0.707103562373095))*(x1900)*(x1909)))+(((x1902)*(x1904)))+(((sj3)*(x1901)*(x1905)))+(((IkReal(-1.00000000000000))*(sj3)*(x1905)*(x1909)))))), ((gconst10)*(((((IkReal(-1.00000000000000))*(x1902)*(x1907)))+(((IkReal(-1.00000000000000))*(x1902)*(x1905)))+(((IkReal(-0.707109999985348))*(x1900)*(x1909)))+(((IkReal(-1.00000000000000))*(x1905)*(x1906)))+(((IkReal(0.707109999985348))*(x1900)*(x1901)))+(((IkReal(0.707109999985348))*(x1900)*(x1908)))+(((IkReal(-1.00000000000000))*(sj3)*(x1901)*(x1903)))+(((IkReal(-1.00000000000000))*(sj3)*(x1903)*(x1908)))+(((IkReal(-1.00000000000000))*(x1906)*(x1907)))+(((sj3)*(x1903)*(x1909)))))));
06833 sj1array[0]=IKsin(j1array[0]);
06834 cj1array[0]=IKcos(j1array[0]);
06835 if( j1array[0] > IKPI )
06836 {
06837     j1array[0]-=IK2PI;
06838 }
06839 else if( j1array[0] < -IKPI )
06840 {    j1array[0]+=IK2PI;
06841 }
06842 j1valid[0] = true;
06843 for(int ij1 = 0; ij1 < 1; ++ij1)
06844 {
06845 if( !j1valid[ij1] )
06846 {
06847     continue;
06848 }
06849 _ij1[0] = ij1; _ij1[1] = -1;
06850 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06851 {
06852 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06853 {
06854     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06855 }
06856 }
06857 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06858 {
06859 IkReal evalcond[6];
06860 IkReal x1910=IKcos(j1);
06861 IkReal x1911=IKsin(j1);
06862 IkReal x1912=((cj0)*(cj4));
06863 IkReal x1913=((r01)*(sj5));
06864 IkReal x1914=((IkReal(1.00000000000000))*(cj4));
06865 IkReal x1915=((IkReal(1.00000000000000))*(r02));
06866 IkReal x1916=((IkReal(0.707109999985348))*(sj3));
06867 IkReal x1917=((IkReal(0.707103562373095))*(sj3));
06868 IkReal x1918=((IkReal(1.00000000000000))*(sj4));
06869 IkReal x1919=((cj5)*(r20));
06870 IkReal x1920=((cj5)*(sj0));
06871 IkReal x1921=((IkReal(1.00000000000000))*(cj0));
06872 IkReal x1922=((r12)*(sj0));
06873 IkReal x1923=((cj2)*(cj3));
06874 IkReal x1924=((IkReal(0.707103562373095))*(cj3));
06875 IkReal x1925=((r21)*(sj5));
06876 IkReal x1926=((IkReal(0.707109999985348))*(cj3));
06877 IkReal x1927=((IkReal(1.00000000000000))*(sj0)*(sj5));
06878 IkReal x1928=((sj2)*(x1910));
06879 IkReal x1929=((cj2)*(x1910));
06880 IkReal x1930=((cj0)*(cj5)*(r00));
06881 IkReal x1931=((IkReal(0.707103562373095))*(x1911));
06882 IkReal x1932=((cj2)*(x1911));
06883 IkReal x1933=((IkReal(0.707109999985348))*(sj2)*(x1911));
06884 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x1916)*(x1929)))+(((IkReal(-1.00000000000000))*(x1917)*(x1928)))+(((sj2)*(x1911)*(x1916)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x1917)*(x1932))));
06885 evalcond[1]=((((sj2)*(x1931)))+(((sj4)*(x1925)))+(((IkReal(0.707109999985348))*(x1928)))+(((cj4)*(r22)))+(((IkReal(0.707109999985348))*(x1932)))+(((IkReal(-1.00000000000000))*(x1918)*(x1919)))+(((IkReal(-0.707103562373095))*(x1929))));
06886 evalcond[2]=((((IkReal(0.707109999985348))*(x1910)*(x1923)))+(((IkReal(-1.00000000000000))*(sj2)*(x1911)*(x1926)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1914)*(x1925)))+(((x1923)*(x1931)))+(((x1924)*(x1928)))+(((cj4)*(x1919))));
06887 evalcond[3]=((((IkReal(-1.00000000000000))*(x1917)*(x1929)))+(((x1916)*(x1932)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1921)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1921)))+(((x1916)*(x1928)))+(((IkReal(-1.00000000000000))*(r11)*(x1920)))+(((sj2)*(x1911)*(x1917)))+(((IkReal(-1.00000000000000))*(r10)*(x1927))));
06888 evalcond[4]=((((IkReal(0.707109999985348))*(x1929)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1918)))+(((IkReal(-1.00000000000000))*(x1914)*(x1922)))+(((r10)*(sj4)*(x1920)))+(((sj4)*(x1930)))+(((cj2)*(x1931)))+(((IkReal(0.707103562373095))*(x1928)))+(((IkReal(-1.00000000000000))*(x1912)*(x1915)))+(((IkReal(-1.00000000000000))*(cj0)*(x1913)*(x1918)))+(((IkReal(-1.00000000000000))*(x1933))));
06889 evalcond[5]=((((x1912)*(x1913)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x1912)))+(((IkReal(-1.00000000000000))*(x1918)*(x1922)))+(((IkReal(-1.00000000000000))*(sj2)*(x1911)*(x1924)))+(((IkReal(-0.707109999985348))*(x1911)*(x1923)))+(((IkReal(-1.00000000000000))*(r10)*(x1914)*(x1920)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x1926)*(x1928)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x1915)))+(((IkReal(0.707103562373095))*(x1910)*(x1923))));
06890 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  )
06891 {
06892 continue;
06893 }
06894 }
06895 
06896 {
06897 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06898 vinfos[0].jointtype = 1;
06899 vinfos[0].foffset = j0;
06900 vinfos[0].indices[0] = _ij0[0];
06901 vinfos[0].indices[1] = _ij0[1];
06902 vinfos[0].maxsolutions = _nj0;
06903 vinfos[1].jointtype = 1;
06904 vinfos[1].foffset = j1;
06905 vinfos[1].indices[0] = _ij1[0];
06906 vinfos[1].indices[1] = _ij1[1];
06907 vinfos[1].maxsolutions = _nj1;
06908 vinfos[2].jointtype = 1;
06909 vinfos[2].foffset = j2;
06910 vinfos[2].indices[0] = _ij2[0];
06911 vinfos[2].indices[1] = _ij2[1];
06912 vinfos[2].maxsolutions = _nj2;
06913 vinfos[3].jointtype = 1;
06914 vinfos[3].foffset = j3;
06915 vinfos[3].indices[0] = _ij3[0];
06916 vinfos[3].indices[1] = _ij3[1];
06917 vinfos[3].maxsolutions = _nj3;
06918 vinfos[4].jointtype = 1;
06919 vinfos[4].foffset = j4;
06920 vinfos[4].indices[0] = _ij4[0];
06921 vinfos[4].indices[1] = _ij4[1];
06922 vinfos[4].maxsolutions = _nj4;
06923 vinfos[5].jointtype = 1;
06924 vinfos[5].foffset = j5;
06925 vinfos[5].indices[0] = _ij5[0];
06926 vinfos[5].indices[1] = _ij5[1];
06927 vinfos[5].maxsolutions = _nj5;
06928 std::vector<int> vfree(0);
06929 solutions.AddSolution(vinfos,vfree);
06930 }
06931 }
06932 }
06933 
06934 }
06935 
06936 }
06937 }
06938 }
06939 
06940 }
06941 
06942 }
06943 
06944 } else
06945 {
06946 {
06947 IkReal j0array[1], cj0array[1], sj0array[1];
06948 bool j0valid[1]={false};
06949 _nj0 = 1;
06950 IkReal x1934=((cj3)*(sj4));
06951 IkReal x1935=((IkReal(1.00000000000000))*(sj5));
06952 IkReal x1936=((IkReal(1.00000000000000))*(cj3)*(cj4));
06953 if( IKabs(((gconst4)*(((((cj5)*(r10)*(x1934)))+(((IkReal(-1.00000000000000))*(r12)*(x1936)))+(((IkReal(-1.00000000000000))*(r11)*(x1934)*(x1935))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(r01)*(x1934)*(x1935)))+(((cj5)*(r00)*(x1934)))+(((IkReal(-1.00000000000000))*(r02)*(x1936))))))) < IKFAST_ATAN2_MAGTHRESH )
06954     continue;
06955 j0array[0]=IKatan2(((gconst4)*(((((cj5)*(r10)*(x1934)))+(((IkReal(-1.00000000000000))*(r12)*(x1936)))+(((IkReal(-1.00000000000000))*(r11)*(x1934)*(x1935)))))), ((gconst4)*(((((IkReal(-1.00000000000000))*(r01)*(x1934)*(x1935)))+(((cj5)*(r00)*(x1934)))+(((IkReal(-1.00000000000000))*(r02)*(x1936)))))));
06956 sj0array[0]=IKsin(j0array[0]);
06957 cj0array[0]=IKcos(j0array[0]);
06958 if( j0array[0] > IKPI )
06959 {
06960     j0array[0]-=IK2PI;
06961 }
06962 else if( j0array[0] < -IKPI )
06963 {    j0array[0]+=IK2PI;
06964 }
06965 j0valid[0] = true;
06966 for(int ij0 = 0; ij0 < 1; ++ij0)
06967 {
06968 if( !j0valid[ij0] )
06969 {
06970     continue;
06971 }
06972 _ij0[0] = ij0; _ij0[1] = -1;
06973 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
06974 {
06975 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
06976 {
06977     j0valid[iij0]=false; _ij0[1] = iij0; break; 
06978 }
06979 }
06980 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
06981 {
06982 IkReal evalcond[3];
06983 IkReal x1937=IKsin(j0);
06984 IkReal x1938=IKcos(j0);
06985 IkReal x1939=((cj5)*(r00));
06986 IkReal x1940=((r01)*(sj5));
06987 IkReal x1941=((cj5)*(r10));
06988 IkReal x1942=((IkReal(1.00000000000000))*(r12));
06989 IkReal x1943=((r11)*(sj5));
06990 IkReal x1944=((cj4)*(x1937));
06991 IkReal x1945=((sj4)*(x1937));
06992 IkReal x1946=((sj4)*(x1938));
06993 IkReal x1947=((cj4)*(x1938));
06994 IkReal x1948=((IkReal(1.00000000000000))*(x1938));
06995 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1948)))+(cj3)+(((cj5)*(r01)*(x1937)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1948)))+(((r00)*(sj5)*(x1937))));
06996 evalcond[1]=((((IkReal(-1.00000000000000))*(x1942)*(x1947)))+(((IkReal(-1.00000000000000))*(x1943)*(x1946)))+(((x1940)*(x1945)))+(((x1941)*(x1946)))+(((IkReal(-1.00000000000000))*(x1939)*(x1945)))+(((r02)*(x1944))));
06997 evalcond[2]=((((x1943)*(x1947)))+(sj3)+(((IkReal(-1.00000000000000))*(x1942)*(x1946)))+(((x1939)*(x1944)))+(((IkReal(-1.00000000000000))*(x1940)*(x1944)))+(((IkReal(-1.00000000000000))*(x1941)*(x1947)))+(((r02)*(x1945))));
06998 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
06999 {
07000 continue;
07001 }
07002 }
07003 
07004 {
07005 IkReal dummyeval[1];
07006 IkReal gconst10;
07007 IkReal x1949=((IkReal(1.00000000000000))*(sj3));
07008 gconst10=IKsign(((((IkReal(-1.00000000000000))*(x1949)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x1949)*((cj2)*(cj2))))));
07009 IkReal x1950=((IkReal(1.00000000000000))*(sj3));
07010 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1950)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x1950)*((sj2)*(sj2)))));
07011 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07012 {
07013 {
07014 IkReal dummyeval[1];
07015 IkReal gconst11;
07016 IkReal x1951=((IkReal(1.00000000000000))*(cj3));
07017 gconst11=IKsign(((((IkReal(-1.00000000000000))*(x1951)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x1951)*((cj2)*(cj2))))));
07018 IkReal x1952=((IkReal(1.00000000000000))*(cj3));
07019 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1952)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x1952)*((sj2)*(sj2)))));
07020 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07021 {
07022 {
07023 IkReal evalcond[9];
07024 IkReal x1953=((sj0)*(sj4));
07025 IkReal x1954=((IkReal(1.00000000000000))*(r12));
07026 IkReal x1955=((cj0)*(cj4));
07027 IkReal x1956=((r01)*(sj5));
07028 IkReal x1957=((IkReal(1.00000000000000))*(cj5));
07029 IkReal x1958=((cj4)*(cj5));
07030 IkReal x1959=((IkReal(1.00000000000000))*(cj0));
07031 IkReal x1960=((cj4)*(sj0));
07032 IkReal x1961=((r00)*(sj0));
07033 IkReal x1962=((npy)*(sj5));
07034 IkReal x1963=((IkReal(1.00000000000000))*(cj4));
07035 IkReal x1964=((cj0)*(sj4));
07036 IkReal x1965=((r11)*(sj5));
07037 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
07038 evalcond[1]=((((sj5)*(x1961)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1959)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x1957))));
07039 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1957)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x1962)))+(((IkReal(0.165463933124939))*(sj2))));
07040 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
07041 evalcond[4]=((IkReal(-0.00600000000000000))+(((npx)*(x1958)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x1962)*(x1963))));
07042 evalcond[5]=((((r02)*(x1960)))+(((IkReal(-1.00000000000000))*(x1954)*(x1955)))+(((x1953)*(x1956)))+(((IkReal(-1.00000000000000))*(sj4)*(x1959)*(x1965)))+(((cj5)*(r10)*(x1964)))+(((IkReal(-1.00000000000000))*(r00)*(x1953)*(x1957))));
07043 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x1955)*(x1957)))+(((x1958)*(x1961)))+(((IkReal(-1.00000000000000))*(x1956)*(x1960)))+(((x1955)*(x1965)))+(((r02)*(x1953)))+(((IkReal(-1.00000000000000))*(x1954)*(x1964))));
07044 evalcond[7]=((((r20)*(x1958)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x1963))));
07045 evalcond[8]=((((x1955)*(x1956)))+(((x1960)*(x1965)))+(((IkReal(-1.00000000000000))*(x1953)*(x1954)))+(((IkReal(-1.00000000000000))*(r00)*(x1955)*(x1957)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1959)))+(((IkReal(-1.00000000000000))*(r10)*(x1957)*(x1960))));
07046 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  )
07047 {
07048 {
07049 IkReal dummyeval[1];
07050 IkReal gconst12;
07051 gconst12=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07052 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07053 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07054 {
07055 {
07056 IkReal dummyeval[1];
07057 IkReal gconst13;
07058 gconst13=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07059 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07060 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07061 {
07062 continue;
07063 
07064 } else
07065 {
07066 {
07067 IkReal j1array[1], cj1array[1], sj1array[1];
07068 bool j1valid[1]={false};
07069 _nj1 = 1;
07070 IkReal x1966=((cj5)*(r11));
07071 IkReal x1967=((r10)*(sj0));
07072 IkReal x1968=((IkReal(0.707103562373095))*(cj2));
07073 IkReal x1969=((r20)*(sj5));
07074 IkReal x1970=((IkReal(0.707103562373095))*(sj2));
07075 IkReal x1971=((IkReal(0.707109999985348))*(cj2));
07076 IkReal x1972=((cj0)*(r00));
07077 IkReal x1973=((IkReal(0.707109999985348))*(sj2));
07078 IkReal x1974=((cj5)*(r21));
07079 IkReal x1975=((sj0)*(x1970));
07080 IkReal x1976=((sj5)*(x1971));
07081 IkReal x1977=((cj0)*(cj5)*(r01));
07082 if( IKabs(((gconst13)*(((((x1969)*(x1973)))+(((IkReal(-1.00000000000000))*(x1968)*(x1969)))+(((IkReal(-1.00000000000000))*(x1966)*(x1975)))+(((IkReal(-1.00000000000000))*(x1968)*(x1974)))+(((IkReal(-1.00000000000000))*(x1971)*(x1977)))+(((IkReal(-1.00000000000000))*(x1972)*(x1976)))+(((IkReal(-1.00000000000000))*(sj5)*(x1967)*(x1970)))+(((IkReal(-1.00000000000000))*(x1970)*(x1977)))+(((IkReal(-1.00000000000000))*(sj5)*(x1970)*(x1972)))+(((x1973)*(x1974)))+(((IkReal(-1.00000000000000))*(sj0)*(x1966)*(x1971)))+(((IkReal(-1.00000000000000))*(x1967)*(x1976))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(x1973)*(x1977)))+(((sj0)*(x1966)*(x1968)))+(((IkReal(-1.00000000000000))*(x1971)*(x1974)))+(((IkReal(-1.00000000000000))*(sj5)*(x1967)*(x1973)))+(((IkReal(-1.00000000000000))*(x1970)*(x1974)))+(((sj5)*(x1968)*(x1972)))+(((IkReal(-1.00000000000000))*(sj5)*(x1972)*(x1973)))+(((IkReal(-1.00000000000000))*(x1969)*(x1971)))+(((IkReal(-1.00000000000000))*(x1969)*(x1970)))+(((IkReal(-1.00000000000000))*(sj0)*(x1966)*(x1973)))+(((x1968)*(x1977)))+(((sj5)*(x1967)*(x1968))))))) < IKFAST_ATAN2_MAGTHRESH )
07083     continue;
07084 j1array[0]=IKatan2(((gconst13)*(((((x1969)*(x1973)))+(((IkReal(-1.00000000000000))*(x1968)*(x1969)))+(((IkReal(-1.00000000000000))*(x1966)*(x1975)))+(((IkReal(-1.00000000000000))*(x1968)*(x1974)))+(((IkReal(-1.00000000000000))*(x1971)*(x1977)))+(((IkReal(-1.00000000000000))*(x1972)*(x1976)))+(((IkReal(-1.00000000000000))*(sj5)*(x1967)*(x1970)))+(((IkReal(-1.00000000000000))*(x1970)*(x1977)))+(((IkReal(-1.00000000000000))*(sj5)*(x1970)*(x1972)))+(((x1973)*(x1974)))+(((IkReal(-1.00000000000000))*(sj0)*(x1966)*(x1971)))+(((IkReal(-1.00000000000000))*(x1967)*(x1976)))))), ((gconst13)*(((((IkReal(-1.00000000000000))*(x1973)*(x1977)))+(((sj0)*(x1966)*(x1968)))+(((IkReal(-1.00000000000000))*(x1971)*(x1974)))+(((IkReal(-1.00000000000000))*(sj5)*(x1967)*(x1973)))+(((IkReal(-1.00000000000000))*(x1970)*(x1974)))+(((sj5)*(x1968)*(x1972)))+(((IkReal(-1.00000000000000))*(sj5)*(x1972)*(x1973)))+(((IkReal(-1.00000000000000))*(x1969)*(x1971)))+(((IkReal(-1.00000000000000))*(x1969)*(x1970)))+(((IkReal(-1.00000000000000))*(sj0)*(x1966)*(x1973)))+(((x1968)*(x1977)))+(((sj5)*(x1967)*(x1968)))))));
07085 sj1array[0]=IKsin(j1array[0]);
07086 cj1array[0]=IKcos(j1array[0]);
07087 if( j1array[0] > IKPI )
07088 {
07089     j1array[0]-=IK2PI;
07090 }
07091 else if( j1array[0] < -IKPI )
07092 {    j1array[0]+=IK2PI;
07093 }
07094 j1valid[0] = true;
07095 for(int ij1 = 0; ij1 < 1; ++ij1)
07096 {
07097 if( !j1valid[ij1] )
07098 {
07099     continue;
07100 }
07101 _ij1[0] = ij1; _ij1[1] = -1;
07102 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07103 {
07104 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07105 {
07106     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07107 }
07108 }
07109 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07110 {
07111 IkReal evalcond[4];
07112 IkReal x1978=IKsin(j1);
07113 IkReal x1979=IKcos(j1);
07114 IkReal x1980=((IkReal(0.707109999985348))*(cj2));
07115 IkReal x1981=((IkReal(1.00000000000000))*(cj0));
07116 IkReal x1982=((IkReal(0.707109999985348))*(sj2));
07117 IkReal x1983=((cj5)*(sj4));
07118 IkReal x1984=((sj4)*(sj5));
07119 IkReal x1985=((IkReal(1.00000000000000))*(sj0));
07120 IkReal x1986=((sj5)*(x1985));
07121 IkReal x1987=((IkReal(0.707103562373095))*(x1979));
07122 IkReal x1988=((IkReal(0.707103562373095))*(x1978));
07123 IkReal x1989=((x1978)*(x1980));
07124 IkReal x1990=((sj2)*(x1988));
07125 IkReal x1991=((x1979)*(x1982));
07126 IkReal x1992=((cj2)*(x1987));
07127 IkReal x1993=((sj2)*(x1987));
07128 IkReal x1994=((cj2)*(x1988));
07129 IkReal x1995=((x1979)*(x1980));
07130 IkReal x1996=((x1978)*(x1982));
07131 IkReal x1997=((x1993)+(x1995)+(x1994));
07132 IkReal x1998=((x1989)+(x1991)+(x1990));
07133 evalcond[0]=((((cj5)*(r21)))+(x1996)+(((IkReal(-1.00000000000000))*(x1997)))+(((r20)*(sj5))));
07134 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x1983)))+(((r21)*(x1984)))+(x1998)+(((IkReal(-1.00000000000000))*(x1992))));
07135 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1981)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1981)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1985)))+(((IkReal(-1.00000000000000))*(r10)*(x1986)))+(x1998)+(((IkReal(-1.00000000000000))*(x1992))));
07136 evalcond[3]=((((r10)*(sj0)*(x1983)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1981)))+(((cj0)*(r00)*(x1983)))+(x1997)+(((IkReal(-1.00000000000000))*(x1996)))+(((IkReal(-1.00000000000000))*(r11)*(x1984)*(x1985)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1985)))+(((IkReal(-1.00000000000000))*(r01)*(x1981)*(x1984))));
07137 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07138 {
07139 continue;
07140 }
07141 }
07142 
07143 {
07144 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07145 vinfos[0].jointtype = 1;
07146 vinfos[0].foffset = j0;
07147 vinfos[0].indices[0] = _ij0[0];
07148 vinfos[0].indices[1] = _ij0[1];
07149 vinfos[0].maxsolutions = _nj0;
07150 vinfos[1].jointtype = 1;
07151 vinfos[1].foffset = j1;
07152 vinfos[1].indices[0] = _ij1[0];
07153 vinfos[1].indices[1] = _ij1[1];
07154 vinfos[1].maxsolutions = _nj1;
07155 vinfos[2].jointtype = 1;
07156 vinfos[2].foffset = j2;
07157 vinfos[2].indices[0] = _ij2[0];
07158 vinfos[2].indices[1] = _ij2[1];
07159 vinfos[2].maxsolutions = _nj2;
07160 vinfos[3].jointtype = 1;
07161 vinfos[3].foffset = j3;
07162 vinfos[3].indices[0] = _ij3[0];
07163 vinfos[3].indices[1] = _ij3[1];
07164 vinfos[3].maxsolutions = _nj3;
07165 vinfos[4].jointtype = 1;
07166 vinfos[4].foffset = j4;
07167 vinfos[4].indices[0] = _ij4[0];
07168 vinfos[4].indices[1] = _ij4[1];
07169 vinfos[4].maxsolutions = _nj4;
07170 vinfos[5].jointtype = 1;
07171 vinfos[5].foffset = j5;
07172 vinfos[5].indices[0] = _ij5[0];
07173 vinfos[5].indices[1] = _ij5[1];
07174 vinfos[5].maxsolutions = _nj5;
07175 std::vector<int> vfree(0);
07176 solutions.AddSolution(vinfos,vfree);
07177 }
07178 }
07179 }
07180 
07181 }
07182 
07183 }
07184 
07185 } else
07186 {
07187 {
07188 IkReal j1array[1], cj1array[1], sj1array[1];
07189 bool j1valid[1]={false};
07190 _nj1 = 1;
07191 IkReal x1999=((cj5)*(sj4));
07192 IkReal x2000=((r21)*(sj4));
07193 IkReal x2001=((cj5)*(r21));
07194 IkReal x2002=((IkReal(0.707109999985348))*(cj2));
07195 IkReal x2003=((IkReal(0.707103562373095))*(sj2));
07196 IkReal x2004=((IkReal(0.707109999985348))*(sj2));
07197 IkReal x2005=((cj4)*(r22));
07198 IkReal x2006=((IkReal(0.707103562373095))*(cj2));
07199 IkReal x2007=((r20)*(x2002));
07200 IkReal x2008=((sj5)*(x2006));
07201 IkReal x2009=((sj5)*(x2004));
07202 if( IKabs(((gconst12)*(((((x2002)*(x2005)))+(((IkReal(-1.00000000000000))*(x2001)*(x2006)))+(((r20)*(x2009)))+(((sj5)*(x2000)*(x2003)))+(((sj5)*(x2000)*(x2002)))+(((x2001)*(x2004)))+(((IkReal(-1.00000000000000))*(r20)*(x1999)*(x2003)))+(((x2003)*(x2005)))+(((IkReal(-1.00000000000000))*(r20)*(x2008)))+(((IkReal(-1.00000000000000))*(x1999)*(x2007))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((IkReal(-1.00000000000000))*(x2005)*(x2006)))+(((x2000)*(x2009)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2003)))+(((IkReal(-1.00000000000000))*(x2001)*(x2002)))+(((IkReal(-1.00000000000000))*(x2001)*(x2003)))+(((IkReal(-1.00000000000000))*(sj5)*(x2007)))+(((IkReal(-1.00000000000000))*(x2000)*(x2008)))+(((IkReal(-1.00000000000000))*(r20)*(x1999)*(x2004)))+(((x2004)*(x2005)))+(((r20)*(x1999)*(x2006))))))) < IKFAST_ATAN2_MAGTHRESH )
07203     continue;
07204 j1array[0]=IKatan2(((gconst12)*(((((x2002)*(x2005)))+(((IkReal(-1.00000000000000))*(x2001)*(x2006)))+(((r20)*(x2009)))+(((sj5)*(x2000)*(x2003)))+(((sj5)*(x2000)*(x2002)))+(((x2001)*(x2004)))+(((IkReal(-1.00000000000000))*(r20)*(x1999)*(x2003)))+(((x2003)*(x2005)))+(((IkReal(-1.00000000000000))*(r20)*(x2008)))+(((IkReal(-1.00000000000000))*(x1999)*(x2007)))))), ((gconst12)*(((((IkReal(-1.00000000000000))*(x2005)*(x2006)))+(((x2000)*(x2009)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2003)))+(((IkReal(-1.00000000000000))*(x2001)*(x2002)))+(((IkReal(-1.00000000000000))*(x2001)*(x2003)))+(((IkReal(-1.00000000000000))*(sj5)*(x2007)))+(((IkReal(-1.00000000000000))*(x2000)*(x2008)))+(((IkReal(-1.00000000000000))*(r20)*(x1999)*(x2004)))+(((x2004)*(x2005)))+(((r20)*(x1999)*(x2006)))))));
07205 sj1array[0]=IKsin(j1array[0]);
07206 cj1array[0]=IKcos(j1array[0]);
07207 if( j1array[0] > IKPI )
07208 {
07209     j1array[0]-=IK2PI;
07210 }
07211 else if( j1array[0] < -IKPI )
07212 {    j1array[0]+=IK2PI;
07213 }
07214 j1valid[0] = true;
07215 for(int ij1 = 0; ij1 < 1; ++ij1)
07216 {
07217 if( !j1valid[ij1] )
07218 {
07219     continue;
07220 }
07221 _ij1[0] = ij1; _ij1[1] = -1;
07222 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07223 {
07224 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07225 {
07226     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07227 }
07228 }
07229 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07230 {
07231 IkReal evalcond[4];
07232 IkReal x2010=IKsin(j1);
07233 IkReal x2011=IKcos(j1);
07234 IkReal x2012=((IkReal(0.707109999985348))*(cj2));
07235 IkReal x2013=((IkReal(1.00000000000000))*(cj0));
07236 IkReal x2014=((IkReal(0.707109999985348))*(sj2));
07237 IkReal x2015=((cj5)*(sj4));
07238 IkReal x2016=((sj4)*(sj5));
07239 IkReal x2017=((IkReal(1.00000000000000))*(sj0));
07240 IkReal x2018=((sj5)*(x2017));
07241 IkReal x2019=((IkReal(0.707103562373095))*(x2011));
07242 IkReal x2020=((IkReal(0.707103562373095))*(x2010));
07243 IkReal x2021=((x2010)*(x2012));
07244 IkReal x2022=((sj2)*(x2020));
07245 IkReal x2023=((x2011)*(x2014));
07246 IkReal x2024=((cj2)*(x2019));
07247 IkReal x2025=((sj2)*(x2019));
07248 IkReal x2026=((cj2)*(x2020));
07249 IkReal x2027=((x2011)*(x2012));
07250 IkReal x2028=((x2010)*(x2014));
07251 IkReal x2029=((x2025)+(x2026)+(x2027));
07252 IkReal x2030=((x2021)+(x2022)+(x2023));
07253 evalcond[0]=((((cj5)*(r21)))+(x2028)+(((IkReal(-1.00000000000000))*(x2029)))+(((r20)*(sj5))));
07254 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x2015)))+(((cj4)*(r22)))+(x2030)+(((r21)*(x2016)))+(((IkReal(-1.00000000000000))*(x2024))));
07255 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2013)))+(x2030)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2013)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2017)))+(((IkReal(-1.00000000000000))*(x2024)))+(((IkReal(-1.00000000000000))*(r10)*(x2018))));
07256 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2017)))+(((IkReal(-1.00000000000000))*(r11)*(x2016)*(x2017)))+(((cj0)*(r00)*(x2015)))+(x2029)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2013)))+(((r10)*(sj0)*(x2015)))+(((IkReal(-1.00000000000000))*(r01)*(x2013)*(x2016)))+(((IkReal(-1.00000000000000))*(x2028))));
07257 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07258 {
07259 continue;
07260 }
07261 }
07262 
07263 {
07264 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07265 vinfos[0].jointtype = 1;
07266 vinfos[0].foffset = j0;
07267 vinfos[0].indices[0] = _ij0[0];
07268 vinfos[0].indices[1] = _ij0[1];
07269 vinfos[0].maxsolutions = _nj0;
07270 vinfos[1].jointtype = 1;
07271 vinfos[1].foffset = j1;
07272 vinfos[1].indices[0] = _ij1[0];
07273 vinfos[1].indices[1] = _ij1[1];
07274 vinfos[1].maxsolutions = _nj1;
07275 vinfos[2].jointtype = 1;
07276 vinfos[2].foffset = j2;
07277 vinfos[2].indices[0] = _ij2[0];
07278 vinfos[2].indices[1] = _ij2[1];
07279 vinfos[2].maxsolutions = _nj2;
07280 vinfos[3].jointtype = 1;
07281 vinfos[3].foffset = j3;
07282 vinfos[3].indices[0] = _ij3[0];
07283 vinfos[3].indices[1] = _ij3[1];
07284 vinfos[3].maxsolutions = _nj3;
07285 vinfos[4].jointtype = 1;
07286 vinfos[4].foffset = j4;
07287 vinfos[4].indices[0] = _ij4[0];
07288 vinfos[4].indices[1] = _ij4[1];
07289 vinfos[4].maxsolutions = _nj4;
07290 vinfos[5].jointtype = 1;
07291 vinfos[5].foffset = j5;
07292 vinfos[5].indices[0] = _ij5[0];
07293 vinfos[5].indices[1] = _ij5[1];
07294 vinfos[5].maxsolutions = _nj5;
07295 std::vector<int> vfree(0);
07296 solutions.AddSolution(vinfos,vfree);
07297 }
07298 }
07299 }
07300 
07301 }
07302 
07303 }
07304 
07305 } else
07306 {
07307 IkReal x2031=((sj0)*(sj4));
07308 IkReal x2032=((IkReal(1.00000000000000))*(r12));
07309 IkReal x2033=((cj0)*(cj4));
07310 IkReal x2034=((r01)*(sj5));
07311 IkReal x2035=((IkReal(1.00000000000000))*(cj5));
07312 IkReal x2036=((cj4)*(cj5));
07313 IkReal x2037=((IkReal(1.00000000000000))*(cj0));
07314 IkReal x2038=((cj4)*(sj0));
07315 IkReal x2039=((r00)*(sj0));
07316 IkReal x2040=((npy)*(sj5));
07317 IkReal x2041=((IkReal(1.00000000000000))*(cj4));
07318 IkReal x2042=((cj0)*(sj4));
07319 IkReal x2043=((r11)*(sj5));
07320 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
07321 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x2039)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2037)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2035))));
07322 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x2040)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2035)))+(((IkReal(0.165463933124939))*(sj2))));
07323 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
07324 evalcond[4]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x2040)*(x2041)))+(((npx)*(x2036))));
07325 evalcond[5]=((((cj5)*(r10)*(x2042)))+(((x2031)*(x2034)))+(((IkReal(-1.00000000000000))*(r00)*(x2031)*(x2035)))+(((IkReal(-1.00000000000000))*(sj4)*(x2037)*(x2043)))+(((r02)*(x2038)))+(((IkReal(-1.00000000000000))*(x2032)*(x2033))));
07326 evalcond[6]=((IkReal(1.00000000000000))+(((x2033)*(x2043)))+(((IkReal(-1.00000000000000))*(x2034)*(x2038)))+(((r02)*(x2031)))+(((IkReal(-1.00000000000000))*(r10)*(x2033)*(x2035)))+(((IkReal(-1.00000000000000))*(x2032)*(x2042)))+(((x2036)*(x2039))));
07327 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2041)))+(((r20)*(x2036))));
07328 evalcond[8]=((((IkReal(-1.00000000000000))*(r10)*(x2035)*(x2038)))+(((x2033)*(x2034)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2037)))+(((IkReal(-1.00000000000000))*(x2031)*(x2032)))+(((IkReal(-1.00000000000000))*(r00)*(x2033)*(x2035)))+(((x2038)*(x2043))));
07329 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  )
07330 {
07331 {
07332 IkReal dummyeval[1];
07333 IkReal gconst14;
07334 gconst14=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07335 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07336 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07337 {
07338 {
07339 IkReal dummyeval[1];
07340 IkReal gconst15;
07341 gconst15=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07342 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07343 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07344 {
07345 continue;
07346 
07347 } else
07348 {
07349 {
07350 IkReal j1array[1], cj1array[1], sj1array[1];
07351 bool j1valid[1]={false};
07352 _nj1 = 1;
07353 IkReal x2044=((cj5)*(r11));
07354 IkReal x2045=((r10)*(sj0));
07355 IkReal x2046=((IkReal(0.707103562373095))*(cj2));
07356 IkReal x2047=((r20)*(sj5));
07357 IkReal x2048=((IkReal(0.707103562373095))*(sj2));
07358 IkReal x2049=((IkReal(0.707109999985348))*(cj2));
07359 IkReal x2050=((cj0)*(r00));
07360 IkReal x2051=((IkReal(0.707109999985348))*(sj2));
07361 IkReal x2052=((cj5)*(r21));
07362 IkReal x2053=((sj0)*(x2048));
07363 IkReal x2054=((sj5)*(x2049));
07364 IkReal x2055=((cj0)*(cj5)*(r01));
07365 if( IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x2044)*(x2053)))+(((IkReal(-1.00000000000000))*(sj5)*(x2045)*(x2048)))+(((IkReal(-1.00000000000000))*(x2045)*(x2054)))+(((x2047)*(x2051)))+(((IkReal(-1.00000000000000))*(sj5)*(x2048)*(x2050)))+(((IkReal(-1.00000000000000))*(x2046)*(x2052)))+(((IkReal(-1.00000000000000))*(x2048)*(x2055)))+(((IkReal(-1.00000000000000))*(x2049)*(x2055)))+(((IkReal(-1.00000000000000))*(sj0)*(x2044)*(x2049)))+(((IkReal(-1.00000000000000))*(x2050)*(x2054)))+(((x2051)*(x2052)))+(((IkReal(-1.00000000000000))*(x2046)*(x2047))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(sj5)*(x2050)*(x2051)))+(((IkReal(-1.00000000000000))*(sj0)*(x2044)*(x2051)))+(((sj0)*(x2044)*(x2046)))+(((sj5)*(x2046)*(x2050)))+(((IkReal(-1.00000000000000))*(sj5)*(x2045)*(x2051)))+(((IkReal(-1.00000000000000))*(x2048)*(x2052)))+(((IkReal(-1.00000000000000))*(x2049)*(x2052)))+(((sj5)*(x2045)*(x2046)))+(((IkReal(-1.00000000000000))*(x2047)*(x2048)))+(((IkReal(-1.00000000000000))*(x2047)*(x2049)))+(((IkReal(-1.00000000000000))*(x2051)*(x2055)))+(((x2046)*(x2055))))))) < IKFAST_ATAN2_MAGTHRESH )
07366     continue;
07367 j1array[0]=IKatan2(((gconst15)*(((((IkReal(-1.00000000000000))*(x2044)*(x2053)))+(((IkReal(-1.00000000000000))*(sj5)*(x2045)*(x2048)))+(((IkReal(-1.00000000000000))*(x2045)*(x2054)))+(((x2047)*(x2051)))+(((IkReal(-1.00000000000000))*(sj5)*(x2048)*(x2050)))+(((IkReal(-1.00000000000000))*(x2046)*(x2052)))+(((IkReal(-1.00000000000000))*(x2048)*(x2055)))+(((IkReal(-1.00000000000000))*(x2049)*(x2055)))+(((IkReal(-1.00000000000000))*(sj0)*(x2044)*(x2049)))+(((IkReal(-1.00000000000000))*(x2050)*(x2054)))+(((x2051)*(x2052)))+(((IkReal(-1.00000000000000))*(x2046)*(x2047)))))), ((gconst15)*(((((IkReal(-1.00000000000000))*(sj5)*(x2050)*(x2051)))+(((IkReal(-1.00000000000000))*(sj0)*(x2044)*(x2051)))+(((sj0)*(x2044)*(x2046)))+(((sj5)*(x2046)*(x2050)))+(((IkReal(-1.00000000000000))*(sj5)*(x2045)*(x2051)))+(((IkReal(-1.00000000000000))*(x2048)*(x2052)))+(((IkReal(-1.00000000000000))*(x2049)*(x2052)))+(((sj5)*(x2045)*(x2046)))+(((IkReal(-1.00000000000000))*(x2047)*(x2048)))+(((IkReal(-1.00000000000000))*(x2047)*(x2049)))+(((IkReal(-1.00000000000000))*(x2051)*(x2055)))+(((x2046)*(x2055)))))));
07368 sj1array[0]=IKsin(j1array[0]);
07369 cj1array[0]=IKcos(j1array[0]);
07370 if( j1array[0] > IKPI )
07371 {
07372     j1array[0]-=IK2PI;
07373 }
07374 else if( j1array[0] < -IKPI )
07375 {    j1array[0]+=IK2PI;
07376 }
07377 j1valid[0] = true;
07378 for(int ij1 = 0; ij1 < 1; ++ij1)
07379 {
07380 if( !j1valid[ij1] )
07381 {
07382     continue;
07383 }
07384 _ij1[0] = ij1; _ij1[1] = -1;
07385 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07386 {
07387 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07388 {
07389     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07390 }
07391 }
07392 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07393 {
07394 IkReal evalcond[4];
07395 IkReal x2056=IKsin(j1);
07396 IkReal x2057=IKcos(j1);
07397 IkReal x2058=((IkReal(0.707109999985348))*(cj2));
07398 IkReal x2059=((IkReal(1.00000000000000))*(cj0));
07399 IkReal x2060=((IkReal(0.707109999985348))*(sj2));
07400 IkReal x2061=((cj5)*(sj4));
07401 IkReal x2062=((sj4)*(sj5));
07402 IkReal x2063=((IkReal(1.00000000000000))*(sj0));
07403 IkReal x2064=((sj5)*(x2063));
07404 IkReal x2065=((IkReal(0.707103562373095))*(x2057));
07405 IkReal x2066=((IkReal(0.707103562373095))*(x2056));
07406 IkReal x2067=((x2056)*(x2058));
07407 IkReal x2068=((sj2)*(x2066));
07408 IkReal x2069=((x2057)*(x2060));
07409 IkReal x2070=((cj2)*(x2065));
07410 IkReal x2071=((sj2)*(x2065));
07411 IkReal x2072=((cj2)*(x2066));
07412 IkReal x2073=((x2057)*(x2058));
07413 IkReal x2074=((x2056)*(x2060));
07414 IkReal x2075=((x2073)+(x2072)+(x2071));
07415 IkReal x2076=((x2068)+(x2069)+(x2067));
07416 evalcond[0]=((((cj5)*(r21)))+(x2074)+(((IkReal(-1.00000000000000))*(x2075)))+(((r20)*(sj5))));
07417 evalcond[1]=((((r21)*(x2062)))+(((cj4)*(r22)))+(x2076)+(((IkReal(-1.00000000000000))*(x2070)))+(((IkReal(-1.00000000000000))*(r20)*(x2061))));
07418 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x2064)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2063)))+(x2076)+(((IkReal(-1.00000000000000))*(x2070)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2059)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2059))));
07419 evalcond[3]=((((r10)*(sj0)*(x2061)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2063)))+(x2075)+(((IkReal(-1.00000000000000))*(x2074)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2059)))+(((IkReal(-1.00000000000000))*(r01)*(x2059)*(x2062)))+(((IkReal(-1.00000000000000))*(r11)*(x2062)*(x2063)))+(((cj0)*(r00)*(x2061))));
07420 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07421 {
07422 continue;
07423 }
07424 }
07425 
07426 {
07427 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07428 vinfos[0].jointtype = 1;
07429 vinfos[0].foffset = j0;
07430 vinfos[0].indices[0] = _ij0[0];
07431 vinfos[0].indices[1] = _ij0[1];
07432 vinfos[0].maxsolutions = _nj0;
07433 vinfos[1].jointtype = 1;
07434 vinfos[1].foffset = j1;
07435 vinfos[1].indices[0] = _ij1[0];
07436 vinfos[1].indices[1] = _ij1[1];
07437 vinfos[1].maxsolutions = _nj1;
07438 vinfos[2].jointtype = 1;
07439 vinfos[2].foffset = j2;
07440 vinfos[2].indices[0] = _ij2[0];
07441 vinfos[2].indices[1] = _ij2[1];
07442 vinfos[2].maxsolutions = _nj2;
07443 vinfos[3].jointtype = 1;
07444 vinfos[3].foffset = j3;
07445 vinfos[3].indices[0] = _ij3[0];
07446 vinfos[3].indices[1] = _ij3[1];
07447 vinfos[3].maxsolutions = _nj3;
07448 vinfos[4].jointtype = 1;
07449 vinfos[4].foffset = j4;
07450 vinfos[4].indices[0] = _ij4[0];
07451 vinfos[4].indices[1] = _ij4[1];
07452 vinfos[4].maxsolutions = _nj4;
07453 vinfos[5].jointtype = 1;
07454 vinfos[5].foffset = j5;
07455 vinfos[5].indices[0] = _ij5[0];
07456 vinfos[5].indices[1] = _ij5[1];
07457 vinfos[5].maxsolutions = _nj5;
07458 std::vector<int> vfree(0);
07459 solutions.AddSolution(vinfos,vfree);
07460 }
07461 }
07462 }
07463 
07464 }
07465 
07466 }
07467 
07468 } else
07469 {
07470 {
07471 IkReal j1array[1], cj1array[1], sj1array[1];
07472 bool j1valid[1]={false};
07473 _nj1 = 1;
07474 IkReal x2077=((cj5)*(sj4));
07475 IkReal x2078=((r21)*(sj4));
07476 IkReal x2079=((cj5)*(r21));
07477 IkReal x2080=((IkReal(0.707109999985348))*(cj2));
07478 IkReal x2081=((IkReal(0.707103562373095))*(sj2));
07479 IkReal x2082=((IkReal(0.707109999985348))*(sj2));
07480 IkReal x2083=((cj4)*(r22));
07481 IkReal x2084=((IkReal(0.707103562373095))*(cj2));
07482 IkReal x2085=((r20)*(x2080));
07483 IkReal x2086=((sj5)*(x2084));
07484 IkReal x2087=((sj5)*(x2082));
07485 if( IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(r20)*(x2086)))+(((r20)*(x2087)))+(((x2081)*(x2083)))+(((IkReal(-1.00000000000000))*(x2077)*(x2085)))+(((IkReal(-1.00000000000000))*(r20)*(x2077)*(x2081)))+(((sj5)*(x2078)*(x2081)))+(((sj5)*(x2078)*(x2080)))+(((IkReal(-1.00000000000000))*(x2079)*(x2084)))+(((x2079)*(x2082)))+(((x2080)*(x2083))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2081)))+(((IkReal(-1.00000000000000))*(x2078)*(x2086)))+(((x2078)*(x2087)))+(((IkReal(-1.00000000000000))*(sj5)*(x2085)))+(((r20)*(x2077)*(x2084)))+(((IkReal(-1.00000000000000))*(r20)*(x2077)*(x2082)))+(((IkReal(-1.00000000000000))*(x2083)*(x2084)))+(((x2082)*(x2083)))+(((IkReal(-1.00000000000000))*(x2079)*(x2081)))+(((IkReal(-1.00000000000000))*(x2079)*(x2080))))))) < IKFAST_ATAN2_MAGTHRESH )
07486     continue;
07487 j1array[0]=IKatan2(((gconst14)*(((((IkReal(-1.00000000000000))*(r20)*(x2086)))+(((r20)*(x2087)))+(((x2081)*(x2083)))+(((IkReal(-1.00000000000000))*(x2077)*(x2085)))+(((IkReal(-1.00000000000000))*(r20)*(x2077)*(x2081)))+(((sj5)*(x2078)*(x2081)))+(((sj5)*(x2078)*(x2080)))+(((IkReal(-1.00000000000000))*(x2079)*(x2084)))+(((x2079)*(x2082)))+(((x2080)*(x2083)))))), ((gconst14)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2081)))+(((IkReal(-1.00000000000000))*(x2078)*(x2086)))+(((x2078)*(x2087)))+(((IkReal(-1.00000000000000))*(sj5)*(x2085)))+(((r20)*(x2077)*(x2084)))+(((IkReal(-1.00000000000000))*(r20)*(x2077)*(x2082)))+(((IkReal(-1.00000000000000))*(x2083)*(x2084)))+(((x2082)*(x2083)))+(((IkReal(-1.00000000000000))*(x2079)*(x2081)))+(((IkReal(-1.00000000000000))*(x2079)*(x2080)))))));
07488 sj1array[0]=IKsin(j1array[0]);
07489 cj1array[0]=IKcos(j1array[0]);
07490 if( j1array[0] > IKPI )
07491 {
07492     j1array[0]-=IK2PI;
07493 }
07494 else if( j1array[0] < -IKPI )
07495 {    j1array[0]+=IK2PI;
07496 }
07497 j1valid[0] = true;
07498 for(int ij1 = 0; ij1 < 1; ++ij1)
07499 {
07500 if( !j1valid[ij1] )
07501 {
07502     continue;
07503 }
07504 _ij1[0] = ij1; _ij1[1] = -1;
07505 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07506 {
07507 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07508 {
07509     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07510 }
07511 }
07512 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07513 {
07514 IkReal evalcond[4];
07515 IkReal x2088=IKsin(j1);
07516 IkReal x2089=IKcos(j1);
07517 IkReal x2090=((IkReal(0.707109999985348))*(cj2));
07518 IkReal x2091=((IkReal(1.00000000000000))*(cj0));
07519 IkReal x2092=((IkReal(0.707109999985348))*(sj2));
07520 IkReal x2093=((cj5)*(sj4));
07521 IkReal x2094=((sj4)*(sj5));
07522 IkReal x2095=((IkReal(1.00000000000000))*(sj0));
07523 IkReal x2096=((sj5)*(x2095));
07524 IkReal x2097=((IkReal(0.707103562373095))*(x2089));
07525 IkReal x2098=((IkReal(0.707103562373095))*(x2088));
07526 IkReal x2099=((x2088)*(x2090));
07527 IkReal x2100=((sj2)*(x2098));
07528 IkReal x2101=((x2089)*(x2092));
07529 IkReal x2102=((cj2)*(x2097));
07530 IkReal x2103=((sj2)*(x2097));
07531 IkReal x2104=((cj2)*(x2098));
07532 IkReal x2105=((x2089)*(x2090));
07533 IkReal x2106=((x2088)*(x2092));
07534 IkReal x2107=((x2103)+(x2105)+(x2104));
07535 IkReal x2108=((x2099)+(x2101)+(x2100));
07536 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2107)))+(x2106)+(((r20)*(sj5))));
07537 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2093)))+(((IkReal(-1.00000000000000))*(x2102)))+(x2108)+(((r21)*(x2094))));
07538 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2091)))+(((IkReal(-1.00000000000000))*(x2102)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2091)))+(x2108)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2095)))+(((IkReal(-1.00000000000000))*(r10)*(x2096))));
07539 evalcond[3]=((((cj0)*(r00)*(x2093)))+(((IkReal(-1.00000000000000))*(x2106)))+(((IkReal(-1.00000000000000))*(r01)*(x2091)*(x2094)))+(x2107)+(((r10)*(sj0)*(x2093)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2091)))+(((IkReal(-1.00000000000000))*(r11)*(x2094)*(x2095)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2095))));
07540 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07541 {
07542 continue;
07543 }
07544 }
07545 
07546 {
07547 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07548 vinfos[0].jointtype = 1;
07549 vinfos[0].foffset = j0;
07550 vinfos[0].indices[0] = _ij0[0];
07551 vinfos[0].indices[1] = _ij0[1];
07552 vinfos[0].maxsolutions = _nj0;
07553 vinfos[1].jointtype = 1;
07554 vinfos[1].foffset = j1;
07555 vinfos[1].indices[0] = _ij1[0];
07556 vinfos[1].indices[1] = _ij1[1];
07557 vinfos[1].maxsolutions = _nj1;
07558 vinfos[2].jointtype = 1;
07559 vinfos[2].foffset = j2;
07560 vinfos[2].indices[0] = _ij2[0];
07561 vinfos[2].indices[1] = _ij2[1];
07562 vinfos[2].maxsolutions = _nj2;
07563 vinfos[3].jointtype = 1;
07564 vinfos[3].foffset = j3;
07565 vinfos[3].indices[0] = _ij3[0];
07566 vinfos[3].indices[1] = _ij3[1];
07567 vinfos[3].maxsolutions = _nj3;
07568 vinfos[4].jointtype = 1;
07569 vinfos[4].foffset = j4;
07570 vinfos[4].indices[0] = _ij4[0];
07571 vinfos[4].indices[1] = _ij4[1];
07572 vinfos[4].maxsolutions = _nj4;
07573 vinfos[5].jointtype = 1;
07574 vinfos[5].foffset = j5;
07575 vinfos[5].indices[0] = _ij5[0];
07576 vinfos[5].indices[1] = _ij5[1];
07577 vinfos[5].maxsolutions = _nj5;
07578 std::vector<int> vfree(0);
07579 solutions.AddSolution(vinfos,vfree);
07580 }
07581 }
07582 }
07583 
07584 }
07585 
07586 }
07587 
07588 } else
07589 {
07590 IkReal x2109=((sj0)*(sj4));
07591 IkReal x2110=((IkReal(1.00000000000000))*(r12));
07592 IkReal x2111=((cj0)*(cj4));
07593 IkReal x2112=((r01)*(sj5));
07594 IkReal x2113=((IkReal(1.00000000000000))*(cj5));
07595 IkReal x2114=((cj4)*(cj5));
07596 IkReal x2115=((IkReal(1.00000000000000))*(cj0));
07597 IkReal x2116=((cj4)*(sj0));
07598 IkReal x2117=((r00)*(sj0));
07599 IkReal x2118=((npy)*(sj5));
07600 IkReal x2119=((IkReal(1.00000000000000))*(cj4));
07601 IkReal x2120=((cj0)*(sj4));
07602 IkReal x2121=((r11)*(sj5));
07603 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
07604 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2113)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x2117)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2115))));
07605 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x2118)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2113))));
07606 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
07607 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x2118)*(x2119)))+(((npx)*(x2114))));
07608 evalcond[5]=((((x2109)*(x2112)))+(((IkReal(-1.00000000000000))*(r00)*(x2109)*(x2113)))+(((r02)*(x2116)))+(((cj5)*(r10)*(x2120)))+(((IkReal(-1.00000000000000))*(x2110)*(x2111)))+(((IkReal(-1.00000000000000))*(sj4)*(x2115)*(x2121))));
07609 evalcond[6]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2111)*(x2113)))+(((r02)*(x2109)))+(((x2111)*(x2121)))+(((IkReal(-1.00000000000000))*(x2112)*(x2116)))+(((IkReal(-1.00000000000000))*(x2110)*(x2120)))+(((x2114)*(x2117))));
07610 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2119)))+(((r22)*(sj4)))+(((r20)*(x2114))));
07611 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2115)))+(((IkReal(-1.00000000000000))*(r10)*(x2113)*(x2116)))+(((x2111)*(x2112)))+(((IkReal(-1.00000000000000))*(x2109)*(x2110)))+(((IkReal(-1.00000000000000))*(r00)*(x2111)*(x2113)))+(((x2116)*(x2121))));
07612 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  )
07613 {
07614 {
07615 IkReal dummyeval[1];
07616 IkReal gconst16;
07617 gconst16=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
07618 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
07619 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07620 {
07621 {
07622 IkReal dummyeval[1];
07623 IkReal gconst17;
07624 gconst17=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07625 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07626 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07627 {
07628 continue;
07629 
07630 } else
07631 {
07632 {
07633 IkReal j1array[1], cj1array[1], sj1array[1];
07634 bool j1valid[1]={false};
07635 _nj1 = 1;
07636 IkReal x2122=((cj5)*(r11));
07637 IkReal x2123=((r10)*(sj0));
07638 IkReal x2124=((IkReal(0.707103562373095))*(cj2));
07639 IkReal x2125=((r20)*(sj5));
07640 IkReal x2126=((IkReal(0.707103562373095))*(sj2));
07641 IkReal x2127=((IkReal(0.707109999985348))*(cj2));
07642 IkReal x2128=((cj0)*(r00));
07643 IkReal x2129=((IkReal(0.707109999985348))*(sj2));
07644 IkReal x2130=((cj5)*(r21));
07645 IkReal x2131=((sj0)*(x2126));
07646 IkReal x2132=((sj5)*(x2127));
07647 IkReal x2133=((cj0)*(cj5)*(r01));
07648 if( IKabs(((gconst17)*(((((sj5)*(x2126)*(x2128)))+(((sj0)*(x2122)*(x2127)))+(((IkReal(-1.00000000000000))*(x2125)*(x2129)))+(((x2124)*(x2130)))+(((x2126)*(x2133)))+(((x2127)*(x2133)))+(((x2128)*(x2132)))+(((IkReal(-1.00000000000000))*(x2129)*(x2130)))+(((x2124)*(x2125)))+(((x2123)*(x2132)))+(((sj5)*(x2123)*(x2126)))+(((x2122)*(x2131))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((x2125)*(x2127)))+(((x2125)*(x2126)))+(((sj0)*(x2122)*(x2129)))+(((IkReal(-1.00000000000000))*(x2124)*(x2133)))+(((IkReal(-1.00000000000000))*(sj5)*(x2123)*(x2124)))+(((x2126)*(x2130)))+(((sj5)*(x2128)*(x2129)))+(((x2127)*(x2130)))+(((IkReal(-1.00000000000000))*(sj0)*(x2122)*(x2124)))+(((x2129)*(x2133)))+(((IkReal(-1.00000000000000))*(sj5)*(x2124)*(x2128)))+(((sj5)*(x2123)*(x2129))))))) < IKFAST_ATAN2_MAGTHRESH )
07649     continue;
07650 j1array[0]=IKatan2(((gconst17)*(((((sj5)*(x2126)*(x2128)))+(((sj0)*(x2122)*(x2127)))+(((IkReal(-1.00000000000000))*(x2125)*(x2129)))+(((x2124)*(x2130)))+(((x2126)*(x2133)))+(((x2127)*(x2133)))+(((x2128)*(x2132)))+(((IkReal(-1.00000000000000))*(x2129)*(x2130)))+(((x2124)*(x2125)))+(((x2123)*(x2132)))+(((sj5)*(x2123)*(x2126)))+(((x2122)*(x2131)))))), ((gconst17)*(((((x2125)*(x2127)))+(((x2125)*(x2126)))+(((sj0)*(x2122)*(x2129)))+(((IkReal(-1.00000000000000))*(x2124)*(x2133)))+(((IkReal(-1.00000000000000))*(sj5)*(x2123)*(x2124)))+(((x2126)*(x2130)))+(((sj5)*(x2128)*(x2129)))+(((x2127)*(x2130)))+(((IkReal(-1.00000000000000))*(sj0)*(x2122)*(x2124)))+(((x2129)*(x2133)))+(((IkReal(-1.00000000000000))*(sj5)*(x2124)*(x2128)))+(((sj5)*(x2123)*(x2129)))))));
07651 sj1array[0]=IKsin(j1array[0]);
07652 cj1array[0]=IKcos(j1array[0]);
07653 if( j1array[0] > IKPI )
07654 {
07655     j1array[0]-=IK2PI;
07656 }
07657 else if( j1array[0] < -IKPI )
07658 {    j1array[0]+=IK2PI;
07659 }
07660 j1valid[0] = true;
07661 for(int ij1 = 0; ij1 < 1; ++ij1)
07662 {
07663 if( !j1valid[ij1] )
07664 {
07665     continue;
07666 }
07667 _ij1[0] = ij1; _ij1[1] = -1;
07668 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07669 {
07670 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07671 {
07672     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07673 }
07674 }
07675 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07676 {
07677 IkReal evalcond[4];
07678 IkReal x2134=IKcos(j1);
07679 IkReal x2135=IKsin(j1);
07680 IkReal x2136=((IkReal(0.707109999985348))*(cj2));
07681 IkReal x2137=((IkReal(1.00000000000000))*(cj0));
07682 IkReal x2138=((IkReal(0.707109999985348))*(sj2));
07683 IkReal x2139=((cj5)*(sj4));
07684 IkReal x2140=((sj4)*(sj5));
07685 IkReal x2141=((IkReal(1.00000000000000))*(sj0));
07686 IkReal x2142=((sj5)*(x2141));
07687 IkReal x2143=((IkReal(0.707103562373095))*(x2134));
07688 IkReal x2144=((IkReal(0.707103562373095))*(x2135));
07689 IkReal x2145=((cj2)*(x2143));
07690 IkReal x2146=((x2135)*(x2136));
07691 IkReal x2147=((sj2)*(x2144));
07692 IkReal x2148=((x2134)*(x2138));
07693 IkReal x2149=((sj2)*(x2143));
07694 IkReal x2150=((cj2)*(x2144));
07695 IkReal x2151=((x2134)*(x2136));
07696 IkReal x2152=((x2135)*(x2138));
07697 IkReal x2153=((x2150)+(x2151)+(x2149));
07698 IkReal x2154=((x2147)+(x2146)+(x2148));
07699 evalcond[0]=((((cj5)*(r21)))+(x2153)+(((IkReal(-1.00000000000000))*(x2152)))+(((r20)*(sj5))));
07700 evalcond[1]=((((cj4)*(r22)))+(x2154)+(((IkReal(-1.00000000000000))*(x2145)))+(((IkReal(-1.00000000000000))*(r20)*(x2139)))+(((r21)*(x2140))));
07701 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2141)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2137)))+(x2145)+(((IkReal(-1.00000000000000))*(x2154)))+(((IkReal(-1.00000000000000))*(r10)*(x2142)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2137))));
07702 evalcond[3]=((x2153)+(((IkReal(-1.00000000000000))*(r11)*(x2140)*(x2141)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2141)))+(((IkReal(-1.00000000000000))*(x2152)))+(((r10)*(sj0)*(x2139)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2137)))+(((cj0)*(r00)*(x2139)))+(((IkReal(-1.00000000000000))*(r01)*(x2137)*(x2140))));
07703 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07704 {
07705 continue;
07706 }
07707 }
07708 
07709 {
07710 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07711 vinfos[0].jointtype = 1;
07712 vinfos[0].foffset = j0;
07713 vinfos[0].indices[0] = _ij0[0];
07714 vinfos[0].indices[1] = _ij0[1];
07715 vinfos[0].maxsolutions = _nj0;
07716 vinfos[1].jointtype = 1;
07717 vinfos[1].foffset = j1;
07718 vinfos[1].indices[0] = _ij1[0];
07719 vinfos[1].indices[1] = _ij1[1];
07720 vinfos[1].maxsolutions = _nj1;
07721 vinfos[2].jointtype = 1;
07722 vinfos[2].foffset = j2;
07723 vinfos[2].indices[0] = _ij2[0];
07724 vinfos[2].indices[1] = _ij2[1];
07725 vinfos[2].maxsolutions = _nj2;
07726 vinfos[3].jointtype = 1;
07727 vinfos[3].foffset = j3;
07728 vinfos[3].indices[0] = _ij3[0];
07729 vinfos[3].indices[1] = _ij3[1];
07730 vinfos[3].maxsolutions = _nj3;
07731 vinfos[4].jointtype = 1;
07732 vinfos[4].foffset = j4;
07733 vinfos[4].indices[0] = _ij4[0];
07734 vinfos[4].indices[1] = _ij4[1];
07735 vinfos[4].maxsolutions = _nj4;
07736 vinfos[5].jointtype = 1;
07737 vinfos[5].foffset = j5;
07738 vinfos[5].indices[0] = _ij5[0];
07739 vinfos[5].indices[1] = _ij5[1];
07740 vinfos[5].maxsolutions = _nj5;
07741 std::vector<int> vfree(0);
07742 solutions.AddSolution(vinfos,vfree);
07743 }
07744 }
07745 }
07746 
07747 }
07748 
07749 }
07750 
07751 } else
07752 {
07753 {
07754 IkReal j1array[1], cj1array[1], sj1array[1];
07755 bool j1valid[1]={false};
07756 _nj1 = 1;
07757 IkReal x2155=((cj5)*(sj4));
07758 IkReal x2156=((r21)*(sj4));
07759 IkReal x2157=((cj5)*(r21));
07760 IkReal x2158=((IkReal(0.707109999985348))*(cj2));
07761 IkReal x2159=((IkReal(0.707103562373095))*(sj2));
07762 IkReal x2160=((IkReal(0.707109999985348))*(sj2));
07763 IkReal x2161=((cj4)*(r22));
07764 IkReal x2162=((IkReal(0.707103562373095))*(cj2));
07765 IkReal x2163=((r20)*(x2158));
07766 IkReal x2164=((sj5)*(x2162));
07767 IkReal x2165=((sj5)*(x2160));
07768 if( IKabs(((gconst16)*(((((x2157)*(x2160)))+(((r20)*(x2155)*(x2159)))+(((IkReal(-1.00000000000000))*(r20)*(x2164)))+(((IkReal(-1.00000000000000))*(x2157)*(x2162)))+(((r20)*(x2165)))+(((IkReal(-1.00000000000000))*(x2158)*(x2161)))+(((IkReal(-1.00000000000000))*(x2159)*(x2161)))+(((x2155)*(x2163)))+(((IkReal(-1.00000000000000))*(sj5)*(x2156)*(x2159)))+(((IkReal(-1.00000000000000))*(sj5)*(x2156)*(x2158))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((r20)*(x2155)*(x2160)))+(((IkReal(-1.00000000000000))*(r20)*(x2155)*(x2162)))+(((IkReal(-1.00000000000000))*(x2160)*(x2161)))+(((IkReal(-1.00000000000000))*(sj5)*(x2163)))+(((IkReal(-1.00000000000000))*(x2157)*(x2158)))+(((IkReal(-1.00000000000000))*(x2157)*(x2159)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2159)))+(((x2161)*(x2162)))+(((x2156)*(x2164)))+(((IkReal(-1.00000000000000))*(x2156)*(x2165))))))) < IKFAST_ATAN2_MAGTHRESH )
07769     continue;
07770 j1array[0]=IKatan2(((gconst16)*(((((x2157)*(x2160)))+(((r20)*(x2155)*(x2159)))+(((IkReal(-1.00000000000000))*(r20)*(x2164)))+(((IkReal(-1.00000000000000))*(x2157)*(x2162)))+(((r20)*(x2165)))+(((IkReal(-1.00000000000000))*(x2158)*(x2161)))+(((IkReal(-1.00000000000000))*(x2159)*(x2161)))+(((x2155)*(x2163)))+(((IkReal(-1.00000000000000))*(sj5)*(x2156)*(x2159)))+(((IkReal(-1.00000000000000))*(sj5)*(x2156)*(x2158)))))), ((gconst16)*(((((r20)*(x2155)*(x2160)))+(((IkReal(-1.00000000000000))*(r20)*(x2155)*(x2162)))+(((IkReal(-1.00000000000000))*(x2160)*(x2161)))+(((IkReal(-1.00000000000000))*(sj5)*(x2163)))+(((IkReal(-1.00000000000000))*(x2157)*(x2158)))+(((IkReal(-1.00000000000000))*(x2157)*(x2159)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2159)))+(((x2161)*(x2162)))+(((x2156)*(x2164)))+(((IkReal(-1.00000000000000))*(x2156)*(x2165)))))));
07771 sj1array[0]=IKsin(j1array[0]);
07772 cj1array[0]=IKcos(j1array[0]);
07773 if( j1array[0] > IKPI )
07774 {
07775     j1array[0]-=IK2PI;
07776 }
07777 else if( j1array[0] < -IKPI )
07778 {    j1array[0]+=IK2PI;
07779 }
07780 j1valid[0] = true;
07781 for(int ij1 = 0; ij1 < 1; ++ij1)
07782 {
07783 if( !j1valid[ij1] )
07784 {
07785     continue;
07786 }
07787 _ij1[0] = ij1; _ij1[1] = -1;
07788 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07789 {
07790 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07791 {
07792     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07793 }
07794 }
07795 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07796 {
07797 IkReal evalcond[4];
07798 IkReal x2166=IKcos(j1);
07799 IkReal x2167=IKsin(j1);
07800 IkReal x2168=((IkReal(0.707109999985348))*(cj2));
07801 IkReal x2169=((IkReal(1.00000000000000))*(cj0));
07802 IkReal x2170=((IkReal(0.707109999985348))*(sj2));
07803 IkReal x2171=((cj5)*(sj4));
07804 IkReal x2172=((sj4)*(sj5));
07805 IkReal x2173=((IkReal(1.00000000000000))*(sj0));
07806 IkReal x2174=((sj5)*(x2173));
07807 IkReal x2175=((IkReal(0.707103562373095))*(x2166));
07808 IkReal x2176=((IkReal(0.707103562373095))*(x2167));
07809 IkReal x2177=((cj2)*(x2175));
07810 IkReal x2178=((x2167)*(x2168));
07811 IkReal x2179=((sj2)*(x2176));
07812 IkReal x2180=((x2166)*(x2170));
07813 IkReal x2181=((sj2)*(x2175));
07814 IkReal x2182=((cj2)*(x2176));
07815 IkReal x2183=((x2166)*(x2168));
07816 IkReal x2184=((x2167)*(x2170));
07817 IkReal x2185=((x2183)+(x2182)+(x2181));
07818 IkReal x2186=((x2178)+(x2179)+(x2180));
07819 evalcond[0]=((((cj5)*(r21)))+(x2185)+(((IkReal(-1.00000000000000))*(x2184)))+(((r20)*(sj5))));
07820 evalcond[1]=((((r21)*(x2172)))+(((IkReal(-1.00000000000000))*(r20)*(x2171)))+(((cj4)*(r22)))+(x2186)+(((IkReal(-1.00000000000000))*(x2177))));
07821 evalcond[2]=((x2177)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2169)))+(((IkReal(-1.00000000000000))*(x2186)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2169)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2173)))+(((IkReal(-1.00000000000000))*(r10)*(x2174))));
07822 evalcond[3]=((((cj0)*(r00)*(x2171)))+(((IkReal(-1.00000000000000))*(r11)*(x2172)*(x2173)))+(x2185)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2169)))+(((IkReal(-1.00000000000000))*(x2184)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2173)))+(((r10)*(sj0)*(x2171)))+(((IkReal(-1.00000000000000))*(r01)*(x2169)*(x2172))));
07823 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07824 {
07825 continue;
07826 }
07827 }
07828 
07829 {
07830 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07831 vinfos[0].jointtype = 1;
07832 vinfos[0].foffset = j0;
07833 vinfos[0].indices[0] = _ij0[0];
07834 vinfos[0].indices[1] = _ij0[1];
07835 vinfos[0].maxsolutions = _nj0;
07836 vinfos[1].jointtype = 1;
07837 vinfos[1].foffset = j1;
07838 vinfos[1].indices[0] = _ij1[0];
07839 vinfos[1].indices[1] = _ij1[1];
07840 vinfos[1].maxsolutions = _nj1;
07841 vinfos[2].jointtype = 1;
07842 vinfos[2].foffset = j2;
07843 vinfos[2].indices[0] = _ij2[0];
07844 vinfos[2].indices[1] = _ij2[1];
07845 vinfos[2].maxsolutions = _nj2;
07846 vinfos[3].jointtype = 1;
07847 vinfos[3].foffset = j3;
07848 vinfos[3].indices[0] = _ij3[0];
07849 vinfos[3].indices[1] = _ij3[1];
07850 vinfos[3].maxsolutions = _nj3;
07851 vinfos[4].jointtype = 1;
07852 vinfos[4].foffset = j4;
07853 vinfos[4].indices[0] = _ij4[0];
07854 vinfos[4].indices[1] = _ij4[1];
07855 vinfos[4].maxsolutions = _nj4;
07856 vinfos[5].jointtype = 1;
07857 vinfos[5].foffset = j5;
07858 vinfos[5].indices[0] = _ij5[0];
07859 vinfos[5].indices[1] = _ij5[1];
07860 vinfos[5].maxsolutions = _nj5;
07861 std::vector<int> vfree(0);
07862 solutions.AddSolution(vinfos,vfree);
07863 }
07864 }
07865 }
07866 
07867 }
07868 
07869 }
07870 
07871 } else
07872 {
07873 IkReal x2187=((sj0)*(sj4));
07874 IkReal x2188=((IkReal(1.00000000000000))*(r12));
07875 IkReal x2189=((cj0)*(cj4));
07876 IkReal x2190=((r01)*(sj5));
07877 IkReal x2191=((IkReal(1.00000000000000))*(cj5));
07878 IkReal x2192=((cj4)*(cj5));
07879 IkReal x2193=((IkReal(1.00000000000000))*(cj0));
07880 IkReal x2194=((cj4)*(sj0));
07881 IkReal x2195=((r00)*(sj0));
07882 IkReal x2196=((npy)*(sj5));
07883 IkReal x2197=((IkReal(1.00000000000000))*(cj4));
07884 IkReal x2198=((cj0)*(sj4));
07885 IkReal x2199=((r11)*(sj5));
07886 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
07887 evalcond[1]=((((sj5)*(x2195)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2191)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2193))));
07888 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x2196)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2191)))+(((IkReal(0.165463933124939))*(sj2))));
07889 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
07890 evalcond[4]=((IkReal(0.00600000000000000))+(((IkReal(-1.00000000000000))*(x2196)*(x2197)))+(((npz)*(sj4)))+(((npx)*(x2192))));
07891 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x2187)*(x2191)))+(((IkReal(-1.00000000000000))*(x2188)*(x2189)))+(((cj5)*(r10)*(x2198)))+(((x2187)*(x2190)))+(((IkReal(-1.00000000000000))*(sj4)*(x2193)*(x2199)))+(((r02)*(x2194))));
07892 evalcond[6]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2190)*(x2194)))+(((x2192)*(x2195)))+(((IkReal(-1.00000000000000))*(r10)*(x2189)*(x2191)))+(((IkReal(-1.00000000000000))*(x2188)*(x2198)))+(((x2189)*(x2199)))+(((r02)*(x2187))));
07893 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2197)))+(((r22)*(sj4)))+(((r20)*(x2192))));
07894 evalcond[8]=((((x2194)*(x2199)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2193)))+(((IkReal(-1.00000000000000))*(r10)*(x2191)*(x2194)))+(((x2189)*(x2190)))+(((IkReal(-1.00000000000000))*(r00)*(x2189)*(x2191))));
07895 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  )
07896 {
07897 {
07898 IkReal dummyeval[1];
07899 IkReal gconst18;
07900 gconst18=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
07901 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
07902 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07903 {
07904 {
07905 IkReal dummyeval[1];
07906 IkReal gconst19;
07907 gconst19=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
07908 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
07909 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07910 {
07911 continue;
07912 
07913 } else
07914 {
07915 {
07916 IkReal j1array[1], cj1array[1], sj1array[1];
07917 bool j1valid[1]={false};
07918 _nj1 = 1;
07919 IkReal x2200=((cj5)*(r11));
07920 IkReal x2201=((r10)*(sj0));
07921 IkReal x2202=((IkReal(0.707103562373095))*(cj2));
07922 IkReal x2203=((r20)*(sj5));
07923 IkReal x2204=((IkReal(0.707103562373095))*(sj2));
07924 IkReal x2205=((IkReal(0.707109999985348))*(cj2));
07925 IkReal x2206=((cj0)*(r00));
07926 IkReal x2207=((IkReal(0.707109999985348))*(sj2));
07927 IkReal x2208=((cj5)*(r21));
07928 IkReal x2209=((sj0)*(x2204));
07929 IkReal x2210=((sj5)*(x2205));
07930 IkReal x2211=((cj0)*(cj5)*(r01));
07931 if( IKabs(((gconst19)*(((((x2202)*(x2203)))+(((x2202)*(x2208)))+(((IkReal(-1.00000000000000))*(x2203)*(x2207)))+(((IkReal(-1.00000000000000))*(x2207)*(x2208)))+(((x2206)*(x2210)))+(((x2200)*(x2209)))+(((x2205)*(x2211)))+(((sj5)*(x2201)*(x2204)))+(((x2201)*(x2210)))+(((x2204)*(x2211)))+(((sj0)*(x2200)*(x2205)))+(((sj5)*(x2204)*(x2206))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst19)*(((((sj5)*(x2206)*(x2207)))+(((IkReal(-1.00000000000000))*(sj0)*(x2200)*(x2202)))+(((IkReal(-1.00000000000000))*(sj5)*(x2201)*(x2202)))+(((IkReal(-1.00000000000000))*(x2202)*(x2211)))+(((x2203)*(x2204)))+(((x2203)*(x2205)))+(((IkReal(-1.00000000000000))*(sj5)*(x2202)*(x2206)))+(((sj5)*(x2201)*(x2207)))+(((x2204)*(x2208)))+(((x2205)*(x2208)))+(((x2207)*(x2211)))+(((sj0)*(x2200)*(x2207))))))) < IKFAST_ATAN2_MAGTHRESH )
07932     continue;
07933 j1array[0]=IKatan2(((gconst19)*(((((x2202)*(x2203)))+(((x2202)*(x2208)))+(((IkReal(-1.00000000000000))*(x2203)*(x2207)))+(((IkReal(-1.00000000000000))*(x2207)*(x2208)))+(((x2206)*(x2210)))+(((x2200)*(x2209)))+(((x2205)*(x2211)))+(((sj5)*(x2201)*(x2204)))+(((x2201)*(x2210)))+(((x2204)*(x2211)))+(((sj0)*(x2200)*(x2205)))+(((sj5)*(x2204)*(x2206)))))), ((gconst19)*(((((sj5)*(x2206)*(x2207)))+(((IkReal(-1.00000000000000))*(sj0)*(x2200)*(x2202)))+(((IkReal(-1.00000000000000))*(sj5)*(x2201)*(x2202)))+(((IkReal(-1.00000000000000))*(x2202)*(x2211)))+(((x2203)*(x2204)))+(((x2203)*(x2205)))+(((IkReal(-1.00000000000000))*(sj5)*(x2202)*(x2206)))+(((sj5)*(x2201)*(x2207)))+(((x2204)*(x2208)))+(((x2205)*(x2208)))+(((x2207)*(x2211)))+(((sj0)*(x2200)*(x2207)))))));
07934 sj1array[0]=IKsin(j1array[0]);
07935 cj1array[0]=IKcos(j1array[0]);
07936 if( j1array[0] > IKPI )
07937 {
07938     j1array[0]-=IK2PI;
07939 }
07940 else if( j1array[0] < -IKPI )
07941 {    j1array[0]+=IK2PI;
07942 }
07943 j1valid[0] = true;
07944 for(int ij1 = 0; ij1 < 1; ++ij1)
07945 {
07946 if( !j1valid[ij1] )
07947 {
07948     continue;
07949 }
07950 _ij1[0] = ij1; _ij1[1] = -1;
07951 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07952 {
07953 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07954 {
07955     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07956 }
07957 }
07958 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07959 {
07960 IkReal evalcond[4];
07961 IkReal x2212=IKcos(j1);
07962 IkReal x2213=IKsin(j1);
07963 IkReal x2214=((IkReal(0.707109999985348))*(cj2));
07964 IkReal x2215=((IkReal(1.00000000000000))*(cj0));
07965 IkReal x2216=((IkReal(0.707109999985348))*(sj2));
07966 IkReal x2217=((cj5)*(sj4));
07967 IkReal x2218=((sj4)*(sj5));
07968 IkReal x2219=((IkReal(1.00000000000000))*(sj0));
07969 IkReal x2220=((sj5)*(x2219));
07970 IkReal x2221=((IkReal(0.707103562373095))*(x2212));
07971 IkReal x2222=((IkReal(0.707103562373095))*(x2213));
07972 IkReal x2223=((cj2)*(x2221));
07973 IkReal x2224=((x2213)*(x2214));
07974 IkReal x2225=((sj2)*(x2222));
07975 IkReal x2226=((x2212)*(x2216));
07976 IkReal x2227=((sj2)*(x2221));
07977 IkReal x2228=((cj2)*(x2222));
07978 IkReal x2229=((x2212)*(x2214));
07979 IkReal x2230=((x2213)*(x2216));
07980 IkReal x2231=((x2228)+(x2229)+(x2227));
07981 IkReal x2232=((x2226)+(x2224)+(x2225));
07982 evalcond[0]=((((cj5)*(r21)))+(x2231)+(((IkReal(-1.00000000000000))*(x2230)))+(((r20)*(sj5))));
07983 evalcond[1]=((x2232)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2223)))+(((r21)*(x2218)))+(((IkReal(-1.00000000000000))*(r20)*(x2217))));
07984 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2219)))+(((IkReal(-1.00000000000000))*(r10)*(x2220)))+(x2223)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2215)))+(((IkReal(-1.00000000000000))*(x2232)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2215))));
07985 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2215)*(x2218)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2219)))+(x2231)+(((r10)*(sj0)*(x2217)))+(((IkReal(-1.00000000000000))*(x2230)))+(((IkReal(-1.00000000000000))*(r11)*(x2218)*(x2219)))+(((cj0)*(r00)*(x2217)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2215))));
07986 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07987 {
07988 continue;
07989 }
07990 }
07991 
07992 {
07993 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07994 vinfos[0].jointtype = 1;
07995 vinfos[0].foffset = j0;
07996 vinfos[0].indices[0] = _ij0[0];
07997 vinfos[0].indices[1] = _ij0[1];
07998 vinfos[0].maxsolutions = _nj0;
07999 vinfos[1].jointtype = 1;
08000 vinfos[1].foffset = j1;
08001 vinfos[1].indices[0] = _ij1[0];
08002 vinfos[1].indices[1] = _ij1[1];
08003 vinfos[1].maxsolutions = _nj1;
08004 vinfos[2].jointtype = 1;
08005 vinfos[2].foffset = j2;
08006 vinfos[2].indices[0] = _ij2[0];
08007 vinfos[2].indices[1] = _ij2[1];
08008 vinfos[2].maxsolutions = _nj2;
08009 vinfos[3].jointtype = 1;
08010 vinfos[3].foffset = j3;
08011 vinfos[3].indices[0] = _ij3[0];
08012 vinfos[3].indices[1] = _ij3[1];
08013 vinfos[3].maxsolutions = _nj3;
08014 vinfos[4].jointtype = 1;
08015 vinfos[4].foffset = j4;
08016 vinfos[4].indices[0] = _ij4[0];
08017 vinfos[4].indices[1] = _ij4[1];
08018 vinfos[4].maxsolutions = _nj4;
08019 vinfos[5].jointtype = 1;
08020 vinfos[5].foffset = j5;
08021 vinfos[5].indices[0] = _ij5[0];
08022 vinfos[5].indices[1] = _ij5[1];
08023 vinfos[5].maxsolutions = _nj5;
08024 std::vector<int> vfree(0);
08025 solutions.AddSolution(vinfos,vfree);
08026 }
08027 }
08028 }
08029 
08030 }
08031 
08032 }
08033 
08034 } else
08035 {
08036 {
08037 IkReal j1array[1], cj1array[1], sj1array[1];
08038 bool j1valid[1]={false};
08039 _nj1 = 1;
08040 IkReal x2233=((cj5)*(sj4));
08041 IkReal x2234=((r21)*(sj4));
08042 IkReal x2235=((cj5)*(r21));
08043 IkReal x2236=((IkReal(0.707109999985348))*(cj2));
08044 IkReal x2237=((IkReal(0.707103562373095))*(sj2));
08045 IkReal x2238=((IkReal(0.707109999985348))*(sj2));
08046 IkReal x2239=((cj4)*(r22));
08047 IkReal x2240=((IkReal(0.707103562373095))*(cj2));
08048 IkReal x2241=((r20)*(x2236));
08049 IkReal x2242=((sj5)*(x2240));
08050 IkReal x2243=((sj5)*(x2238));
08051 if( IKabs(((gconst18)*(((((x2235)*(x2238)))+(((IkReal(-1.00000000000000))*(x2237)*(x2239)))+(((x2233)*(x2241)))+(((IkReal(-1.00000000000000))*(x2236)*(x2239)))+(((r20)*(x2233)*(x2237)))+(((r20)*(x2243)))+(((IkReal(-1.00000000000000))*(r20)*(x2242)))+(((IkReal(-1.00000000000000))*(x2235)*(x2240)))+(((IkReal(-1.00000000000000))*(sj5)*(x2234)*(x2236)))+(((IkReal(-1.00000000000000))*(sj5)*(x2234)*(x2237))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst18)*(((((IkReal(-1.00000000000000))*(sj5)*(x2241)))+(((IkReal(-1.00000000000000))*(x2234)*(x2243)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2237)))+(((IkReal(-1.00000000000000))*(x2235)*(x2236)))+(((IkReal(-1.00000000000000))*(x2235)*(x2237)))+(((x2234)*(x2242)))+(((IkReal(-1.00000000000000))*(x2238)*(x2239)))+(((r20)*(x2233)*(x2238)))+(((IkReal(-1.00000000000000))*(r20)*(x2233)*(x2240)))+(((x2239)*(x2240))))))) < IKFAST_ATAN2_MAGTHRESH )
08052     continue;
08053 j1array[0]=IKatan2(((gconst18)*(((((x2235)*(x2238)))+(((IkReal(-1.00000000000000))*(x2237)*(x2239)))+(((x2233)*(x2241)))+(((IkReal(-1.00000000000000))*(x2236)*(x2239)))+(((r20)*(x2233)*(x2237)))+(((r20)*(x2243)))+(((IkReal(-1.00000000000000))*(r20)*(x2242)))+(((IkReal(-1.00000000000000))*(x2235)*(x2240)))+(((IkReal(-1.00000000000000))*(sj5)*(x2234)*(x2236)))+(((IkReal(-1.00000000000000))*(sj5)*(x2234)*(x2237)))))), ((gconst18)*(((((IkReal(-1.00000000000000))*(sj5)*(x2241)))+(((IkReal(-1.00000000000000))*(x2234)*(x2243)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2237)))+(((IkReal(-1.00000000000000))*(x2235)*(x2236)))+(((IkReal(-1.00000000000000))*(x2235)*(x2237)))+(((x2234)*(x2242)))+(((IkReal(-1.00000000000000))*(x2238)*(x2239)))+(((r20)*(x2233)*(x2238)))+(((IkReal(-1.00000000000000))*(r20)*(x2233)*(x2240)))+(((x2239)*(x2240)))))));
08054 sj1array[0]=IKsin(j1array[0]);
08055 cj1array[0]=IKcos(j1array[0]);
08056 if( j1array[0] > IKPI )
08057 {
08058     j1array[0]-=IK2PI;
08059 }
08060 else if( j1array[0] < -IKPI )
08061 {    j1array[0]+=IK2PI;
08062 }
08063 j1valid[0] = true;
08064 for(int ij1 = 0; ij1 < 1; ++ij1)
08065 {
08066 if( !j1valid[ij1] )
08067 {
08068     continue;
08069 }
08070 _ij1[0] = ij1; _ij1[1] = -1;
08071 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08072 {
08073 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08074 {
08075     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08076 }
08077 }
08078 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08079 {
08080 IkReal evalcond[4];
08081 IkReal x2244=IKcos(j1);
08082 IkReal x2245=IKsin(j1);
08083 IkReal x2246=((IkReal(0.707109999985348))*(cj2));
08084 IkReal x2247=((IkReal(1.00000000000000))*(cj0));
08085 IkReal x2248=((IkReal(0.707109999985348))*(sj2));
08086 IkReal x2249=((cj5)*(sj4));
08087 IkReal x2250=((sj4)*(sj5));
08088 IkReal x2251=((IkReal(1.00000000000000))*(sj0));
08089 IkReal x2252=((sj5)*(x2251));
08090 IkReal x2253=((IkReal(0.707103562373095))*(x2244));
08091 IkReal x2254=((IkReal(0.707103562373095))*(x2245));
08092 IkReal x2255=((cj2)*(x2253));
08093 IkReal x2256=((x2245)*(x2246));
08094 IkReal x2257=((sj2)*(x2254));
08095 IkReal x2258=((x2244)*(x2248));
08096 IkReal x2259=((sj2)*(x2253));
08097 IkReal x2260=((cj2)*(x2254));
08098 IkReal x2261=((x2244)*(x2246));
08099 IkReal x2262=((x2245)*(x2248));
08100 IkReal x2263=((x2260)+(x2261)+(x2259));
08101 IkReal x2264=((x2258)+(x2257)+(x2256));
08102 evalcond[0]=((((cj5)*(r21)))+(x2263)+(((IkReal(-1.00000000000000))*(x2262)))+(((r20)*(sj5))));
08103 evalcond[1]=((x2264)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2249)))+(((IkReal(-1.00000000000000))*(x2255)))+(((r21)*(x2250))));
08104 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2247)))+(x2255)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2247)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2251)))+(((IkReal(-1.00000000000000))*(r10)*(x2252)))+(((IkReal(-1.00000000000000))*(x2264))));
08105 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2247)))+(x2263)+(((IkReal(-1.00000000000000))*(r11)*(x2250)*(x2251)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2251)))+(((r10)*(sj0)*(x2249)))+(((cj0)*(r00)*(x2249)))+(((IkReal(-1.00000000000000))*(x2262)))+(((IkReal(-1.00000000000000))*(r01)*(x2247)*(x2250))));
08106 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
08107 {
08108 continue;
08109 }
08110 }
08111 
08112 {
08113 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08114 vinfos[0].jointtype = 1;
08115 vinfos[0].foffset = j0;
08116 vinfos[0].indices[0] = _ij0[0];
08117 vinfos[0].indices[1] = _ij0[1];
08118 vinfos[0].maxsolutions = _nj0;
08119 vinfos[1].jointtype = 1;
08120 vinfos[1].foffset = j1;
08121 vinfos[1].indices[0] = _ij1[0];
08122 vinfos[1].indices[1] = _ij1[1];
08123 vinfos[1].maxsolutions = _nj1;
08124 vinfos[2].jointtype = 1;
08125 vinfos[2].foffset = j2;
08126 vinfos[2].indices[0] = _ij2[0];
08127 vinfos[2].indices[1] = _ij2[1];
08128 vinfos[2].maxsolutions = _nj2;
08129 vinfos[3].jointtype = 1;
08130 vinfos[3].foffset = j3;
08131 vinfos[3].indices[0] = _ij3[0];
08132 vinfos[3].indices[1] = _ij3[1];
08133 vinfos[3].maxsolutions = _nj3;
08134 vinfos[4].jointtype = 1;
08135 vinfos[4].foffset = j4;
08136 vinfos[4].indices[0] = _ij4[0];
08137 vinfos[4].indices[1] = _ij4[1];
08138 vinfos[4].maxsolutions = _nj4;
08139 vinfos[5].jointtype = 1;
08140 vinfos[5].foffset = j5;
08141 vinfos[5].indices[0] = _ij5[0];
08142 vinfos[5].indices[1] = _ij5[1];
08143 vinfos[5].maxsolutions = _nj5;
08144 std::vector<int> vfree(0);
08145 solutions.AddSolution(vinfos,vfree);
08146 }
08147 }
08148 }
08149 
08150 }
08151 
08152 }
08153 
08154 } else
08155 {
08156 if( 1 )
08157 {
08158 continue;
08159 
08160 } else
08161 {
08162 }
08163 }
08164 }
08165 }
08166 }
08167 }
08168 
08169 } else
08170 {
08171 {
08172 IkReal j1array[1], cj1array[1], sj1array[1];
08173 bool j1valid[1]={false};
08174 _nj1 = 1;
08175 IkReal x2265=((IkReal(0.707109999985348))*(sj2));
08176 IkReal x2266=((r22)*(sj4));
08177 IkReal x2267=((cj5)*(r20));
08178 IkReal x2268=((r21)*(sj5));
08179 IkReal x2269=((IkReal(0.707109999985348))*(cj2));
08180 IkReal x2270=((cj3)*(r22));
08181 IkReal x2271=((cj3)*(sj4));
08182 IkReal x2272=((IkReal(0.707103562373095))*(cj4)*(sj2));
08183 IkReal x2273=((IkReal(0.707103562373095))*(x2271));
08184 IkReal x2274=((IkReal(0.707103562373095))*(cj2)*(cj4));
08185 if( IKabs(((gconst11)*(((((x2270)*(x2272)))+(((IkReal(-1.00000000000000))*(cj4)*(x2265)*(x2267)))+(((cj4)*(x2269)*(x2270)))+(((cj4)*(x2265)*(x2268)))+(((IkReal(-1.00000000000000))*(sj2)*(x2267)*(x2273)))+(((IkReal(0.707103562373095))*(cj2)*(x2266)))+(((IkReal(-1.00000000000000))*(x2267)*(x2269)*(x2271)))+(((IkReal(-1.00000000000000))*(x2268)*(x2274)))+(((sj2)*(x2268)*(x2273)))+(((x2267)*(x2274)))+(((x2268)*(x2269)*(x2271)))+(((IkReal(-1.00000000000000))*(x2265)*(x2266))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(cj4)*(x2268)*(x2269)))+(((IkReal(0.707103562373095))*(sj2)*(x2266)))+(((x2265)*(x2268)*(x2271)))+(((cj2)*(x2267)*(x2273)))+(((cj4)*(x2267)*(x2269)))+(((IkReal(-1.00000000000000))*(x2270)*(x2274)))+(((cj4)*(x2265)*(x2270)))+(((IkReal(-1.00000000000000))*(x2265)*(x2267)*(x2271)))+(((IkReal(-1.00000000000000))*(cj2)*(x2268)*(x2273)))+(((IkReal(-1.00000000000000))*(x2268)*(x2272)))+(((x2267)*(x2272)))+(((x2266)*(x2269))))))) < IKFAST_ATAN2_MAGTHRESH )
08186     continue;
08187 j1array[0]=IKatan2(((gconst11)*(((((x2270)*(x2272)))+(((IkReal(-1.00000000000000))*(cj4)*(x2265)*(x2267)))+(((cj4)*(x2269)*(x2270)))+(((cj4)*(x2265)*(x2268)))+(((IkReal(-1.00000000000000))*(sj2)*(x2267)*(x2273)))+(((IkReal(0.707103562373095))*(cj2)*(x2266)))+(((IkReal(-1.00000000000000))*(x2267)*(x2269)*(x2271)))+(((IkReal(-1.00000000000000))*(x2268)*(x2274)))+(((sj2)*(x2268)*(x2273)))+(((x2267)*(x2274)))+(((x2268)*(x2269)*(x2271)))+(((IkReal(-1.00000000000000))*(x2265)*(x2266)))))), ((gconst11)*(((((IkReal(-1.00000000000000))*(cj4)*(x2268)*(x2269)))+(((IkReal(0.707103562373095))*(sj2)*(x2266)))+(((x2265)*(x2268)*(x2271)))+(((cj2)*(x2267)*(x2273)))+(((cj4)*(x2267)*(x2269)))+(((IkReal(-1.00000000000000))*(x2270)*(x2274)))+(((cj4)*(x2265)*(x2270)))+(((IkReal(-1.00000000000000))*(x2265)*(x2267)*(x2271)))+(((IkReal(-1.00000000000000))*(cj2)*(x2268)*(x2273)))+(((IkReal(-1.00000000000000))*(x2268)*(x2272)))+(((x2267)*(x2272)))+(((x2266)*(x2269)))))));
08188 sj1array[0]=IKsin(j1array[0]);
08189 cj1array[0]=IKcos(j1array[0]);
08190 if( j1array[0] > IKPI )
08191 {
08192     j1array[0]-=IK2PI;
08193 }
08194 else if( j1array[0] < -IKPI )
08195 {    j1array[0]+=IK2PI;
08196 }
08197 j1valid[0] = true;
08198 for(int ij1 = 0; ij1 < 1; ++ij1)
08199 {
08200 if( !j1valid[ij1] )
08201 {
08202     continue;
08203 }
08204 _ij1[0] = ij1; _ij1[1] = -1;
08205 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08206 {
08207 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08208 {
08209     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08210 }
08211 }
08212 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08213 {
08214 IkReal evalcond[6];
08215 IkReal x2275=IKcos(j1);
08216 IkReal x2276=IKsin(j1);
08217 IkReal x2277=((cj0)*(cj4));
08218 IkReal x2278=((r01)*(sj5));
08219 IkReal x2279=((IkReal(1.00000000000000))*(cj4));
08220 IkReal x2280=((IkReal(1.00000000000000))*(r02));
08221 IkReal x2281=((IkReal(0.707109999985348))*(sj3));
08222 IkReal x2282=((IkReal(0.707103562373095))*(sj3));
08223 IkReal x2283=((IkReal(1.00000000000000))*(sj4));
08224 IkReal x2284=((cj5)*(r20));
08225 IkReal x2285=((cj5)*(sj0));
08226 IkReal x2286=((IkReal(1.00000000000000))*(cj0));
08227 IkReal x2287=((r12)*(sj0));
08228 IkReal x2288=((cj2)*(cj3));
08229 IkReal x2289=((IkReal(0.707103562373095))*(cj3));
08230 IkReal x2290=((r21)*(sj5));
08231 IkReal x2291=((IkReal(0.707109999985348))*(cj3));
08232 IkReal x2292=((IkReal(1.00000000000000))*(sj0)*(sj5));
08233 IkReal x2293=((sj2)*(x2275));
08234 IkReal x2294=((cj2)*(x2275));
08235 IkReal x2295=((cj0)*(cj5)*(r00));
08236 IkReal x2296=((IkReal(0.707103562373095))*(x2276));
08237 IkReal x2297=((cj2)*(x2276));
08238 IkReal x2298=((IkReal(0.707109999985348))*(sj2)*(x2276));
08239 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2282)*(x2293)))+(((IkReal(-1.00000000000000))*(x2282)*(x2297)))+(((sj2)*(x2276)*(x2281)))+(((IkReal(-1.00000000000000))*(x2281)*(x2294)))+(((r20)*(sj5))));
08240 evalcond[1]=((((IkReal(-0.707103562373095))*(x2294)))+(((sj4)*(x2290)))+(((cj4)*(r22)))+(((IkReal(0.707109999985348))*(x2297)))+(((IkReal(0.707109999985348))*(x2293)))+(((sj2)*(x2296)))+(((IkReal(-1.00000000000000))*(x2283)*(x2284))));
08241 evalcond[2]=((((IkReal(-1.00000000000000))*(x2279)*(x2290)))+(((r22)*(sj4)))+(((IkReal(0.707109999985348))*(x2275)*(x2288)))+(((IkReal(-1.00000000000000))*(sj2)*(x2276)*(x2291)))+(((x2289)*(x2293)))+(((cj4)*(x2284)))+(((x2288)*(x2296))));
08242 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2286)))+(((IkReal(-1.00000000000000))*(x2282)*(x2294)))+(((sj2)*(x2276)*(x2282)))+(((x2281)*(x2293)))+(((x2281)*(x2297)))+(((IkReal(-1.00000000000000))*(r11)*(x2285)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2286)))+(((IkReal(-1.00000000000000))*(r10)*(x2292))));
08243 evalcond[4]=((((sj4)*(x2295)))+(((cj2)*(x2296)))+(((IkReal(-1.00000000000000))*(x2277)*(x2280)))+(((r10)*(sj4)*(x2285)))+(((IkReal(0.707109999985348))*(x2294)))+(((IkReal(0.707103562373095))*(x2293)))+(((IkReal(-1.00000000000000))*(x2279)*(x2287)))+(((IkReal(-1.00000000000000))*(cj0)*(x2278)*(x2283)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x2283)))+(((IkReal(-1.00000000000000))*(x2298))));
08244 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2277)))+(((IkReal(0.707103562373095))*(x2275)*(x2288)))+(((IkReal(-0.707109999985348))*(x2276)*(x2288)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x2280)))+(((IkReal(-1.00000000000000))*(x2291)*(x2293)))+(((x2277)*(x2278)))+(((IkReal(-1.00000000000000))*(x2283)*(x2287)))+(((IkReal(-1.00000000000000))*(sj2)*(x2276)*(x2289)))+(((IkReal(-1.00000000000000))*(r10)*(x2279)*(x2285))));
08245 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  )
08246 {
08247 continue;
08248 }
08249 }
08250 
08251 {
08252 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08253 vinfos[0].jointtype = 1;
08254 vinfos[0].foffset = j0;
08255 vinfos[0].indices[0] = _ij0[0];
08256 vinfos[0].indices[1] = _ij0[1];
08257 vinfos[0].maxsolutions = _nj0;
08258 vinfos[1].jointtype = 1;
08259 vinfos[1].foffset = j1;
08260 vinfos[1].indices[0] = _ij1[0];
08261 vinfos[1].indices[1] = _ij1[1];
08262 vinfos[1].maxsolutions = _nj1;
08263 vinfos[2].jointtype = 1;
08264 vinfos[2].foffset = j2;
08265 vinfos[2].indices[0] = _ij2[0];
08266 vinfos[2].indices[1] = _ij2[1];
08267 vinfos[2].maxsolutions = _nj2;
08268 vinfos[3].jointtype = 1;
08269 vinfos[3].foffset = j3;
08270 vinfos[3].indices[0] = _ij3[0];
08271 vinfos[3].indices[1] = _ij3[1];
08272 vinfos[3].maxsolutions = _nj3;
08273 vinfos[4].jointtype = 1;
08274 vinfos[4].foffset = j4;
08275 vinfos[4].indices[0] = _ij4[0];
08276 vinfos[4].indices[1] = _ij4[1];
08277 vinfos[4].maxsolutions = _nj4;
08278 vinfos[5].jointtype = 1;
08279 vinfos[5].foffset = j5;
08280 vinfos[5].indices[0] = _ij5[0];
08281 vinfos[5].indices[1] = _ij5[1];
08282 vinfos[5].maxsolutions = _nj5;
08283 std::vector<int> vfree(0);
08284 solutions.AddSolution(vinfos,vfree);
08285 }
08286 }
08287 }
08288 
08289 }
08290 
08291 }
08292 
08293 } else
08294 {
08295 {
08296 IkReal j1array[1], cj1array[1], sj1array[1];
08297 bool j1valid[1]={false};
08298 _nj1 = 1;
08299 IkReal x2299=((sj2)*(sj3));
08300 IkReal x2300=((cj4)*(r22));
08301 IkReal x2301=((r20)*(sj5));
08302 IkReal x2302=((IkReal(0.707103562373095))*(cj2));
08303 IkReal x2303=((IkReal(0.707109999985348))*(sj2));
08304 IkReal x2304=((IkReal(0.707109999985348))*(cj2));
08305 IkReal x2305=((cj5)*(r21));
08306 IkReal x2306=((IkReal(0.707103562373095))*(sj2));
08307 IkReal x2307=((r21)*(sj4)*(sj5));
08308 IkReal x2308=((cj5)*(r20)*(sj4));
08309 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(x2301)*(x2302)))+(((x2303)*(x2305)))+(((IkReal(0.707103562373095))*(x2299)*(x2300)))+(((IkReal(0.707103562373095))*(x2299)*(x2307)))+(((IkReal(-1.00000000000000))*(sj3)*(x2304)*(x2308)))+(((IkReal(-0.707103562373095))*(x2299)*(x2308)))+(((x2301)*(x2303)))+(((sj3)*(x2304)*(x2307)))+(((IkReal(-1.00000000000000))*(x2302)*(x2305)))+(((sj3)*(x2300)*(x2304))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(x2301)*(x2306)))+(((IkReal(-1.00000000000000))*(x2301)*(x2304)))+(((IkReal(-0.707109999985348))*(x2299)*(x2308)))+(((IkReal(-1.00000000000000))*(sj3)*(x2300)*(x2302)))+(((IkReal(-1.00000000000000))*(x2304)*(x2305)))+(((IkReal(0.707109999985348))*(x2299)*(x2307)))+(((IkReal(0.707109999985348))*(x2299)*(x2300)))+(((sj3)*(x2302)*(x2308)))+(((IkReal(-1.00000000000000))*(sj3)*(x2302)*(x2307)))+(((IkReal(-1.00000000000000))*(x2305)*(x2306))))))) < IKFAST_ATAN2_MAGTHRESH )
08310     continue;
08311 j1array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(x2301)*(x2302)))+(((x2303)*(x2305)))+(((IkReal(0.707103562373095))*(x2299)*(x2300)))+(((IkReal(0.707103562373095))*(x2299)*(x2307)))+(((IkReal(-1.00000000000000))*(sj3)*(x2304)*(x2308)))+(((IkReal(-0.707103562373095))*(x2299)*(x2308)))+(((x2301)*(x2303)))+(((sj3)*(x2304)*(x2307)))+(((IkReal(-1.00000000000000))*(x2302)*(x2305)))+(((sj3)*(x2300)*(x2304)))))), ((gconst10)*(((((IkReal(-1.00000000000000))*(x2301)*(x2306)))+(((IkReal(-1.00000000000000))*(x2301)*(x2304)))+(((IkReal(-0.707109999985348))*(x2299)*(x2308)))+(((IkReal(-1.00000000000000))*(sj3)*(x2300)*(x2302)))+(((IkReal(-1.00000000000000))*(x2304)*(x2305)))+(((IkReal(0.707109999985348))*(x2299)*(x2307)))+(((IkReal(0.707109999985348))*(x2299)*(x2300)))+(((sj3)*(x2302)*(x2308)))+(((IkReal(-1.00000000000000))*(sj3)*(x2302)*(x2307)))+(((IkReal(-1.00000000000000))*(x2305)*(x2306)))))));
08312 sj1array[0]=IKsin(j1array[0]);
08313 cj1array[0]=IKcos(j1array[0]);
08314 if( j1array[0] > IKPI )
08315 {
08316     j1array[0]-=IK2PI;
08317 }
08318 else if( j1array[0] < -IKPI )
08319 {    j1array[0]+=IK2PI;
08320 }
08321 j1valid[0] = true;
08322 for(int ij1 = 0; ij1 < 1; ++ij1)
08323 {
08324 if( !j1valid[ij1] )
08325 {
08326     continue;
08327 }
08328 _ij1[0] = ij1; _ij1[1] = -1;
08329 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08330 {
08331 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08332 {
08333     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08334 }
08335 }
08336 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08337 {
08338 IkReal evalcond[6];
08339 IkReal x2309=IKcos(j1);
08340 IkReal x2310=IKsin(j1);
08341 IkReal x2311=((cj0)*(cj4));
08342 IkReal x2312=((r01)*(sj5));
08343 IkReal x2313=((IkReal(1.00000000000000))*(cj4));
08344 IkReal x2314=((IkReal(1.00000000000000))*(r02));
08345 IkReal x2315=((IkReal(0.707109999985348))*(sj3));
08346 IkReal x2316=((IkReal(0.707103562373095))*(sj3));
08347 IkReal x2317=((IkReal(1.00000000000000))*(sj4));
08348 IkReal x2318=((cj5)*(r20));
08349 IkReal x2319=((cj5)*(sj0));
08350 IkReal x2320=((IkReal(1.00000000000000))*(cj0));
08351 IkReal x2321=((r12)*(sj0));
08352 IkReal x2322=((cj2)*(cj3));
08353 IkReal x2323=((IkReal(0.707103562373095))*(cj3));
08354 IkReal x2324=((r21)*(sj5));
08355 IkReal x2325=((IkReal(0.707109999985348))*(cj3));
08356 IkReal x2326=((IkReal(1.00000000000000))*(sj0)*(sj5));
08357 IkReal x2327=((sj2)*(x2309));
08358 IkReal x2328=((cj2)*(x2309));
08359 IkReal x2329=((cj0)*(cj5)*(r00));
08360 IkReal x2330=((IkReal(0.707103562373095))*(x2310));
08361 IkReal x2331=((cj2)*(x2310));
08362 IkReal x2332=((IkReal(0.707109999985348))*(sj2)*(x2310));
08363 evalcond[0]=((((cj5)*(r21)))+(((sj2)*(x2310)*(x2315)))+(((IkReal(-1.00000000000000))*(x2315)*(x2328)))+(((IkReal(-1.00000000000000))*(x2316)*(x2331)))+(((IkReal(-1.00000000000000))*(x2316)*(x2327)))+(((r20)*(sj5))));
08364 evalcond[1]=((((cj4)*(r22)))+(((sj2)*(x2330)))+(((IkReal(-0.707103562373095))*(x2328)))+(((IkReal(0.707109999985348))*(x2331)))+(((sj4)*(x2324)))+(((IkReal(0.707109999985348))*(x2327)))+(((IkReal(-1.00000000000000))*(x2317)*(x2318))));
08365 evalcond[2]=((((r22)*(sj4)))+(((x2322)*(x2330)))+(((cj4)*(x2318)))+(((IkReal(-1.00000000000000))*(x2313)*(x2324)))+(((x2323)*(x2327)))+(((IkReal(0.707109999985348))*(x2309)*(x2322)))+(((IkReal(-1.00000000000000))*(sj2)*(x2310)*(x2325))));
08366 evalcond[3]=((((x2315)*(x2331)))+(((x2315)*(x2327)))+(((sj2)*(x2310)*(x2316)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2320)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2320)))+(((IkReal(-1.00000000000000))*(r11)*(x2319)))+(((IkReal(-1.00000000000000))*(r10)*(x2326)))+(((IkReal(-1.00000000000000))*(x2316)*(x2328))));
08367 evalcond[4]=((((r10)*(sj4)*(x2319)))+(((IkReal(-1.00000000000000))*(x2332)))+(((IkReal(0.707103562373095))*(x2327)))+(((cj2)*(x2330)))+(((IkReal(-1.00000000000000))*(x2311)*(x2314)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x2317)))+(((sj4)*(x2329)))+(((IkReal(-1.00000000000000))*(x2313)*(x2321)))+(((IkReal(0.707109999985348))*(x2328)))+(((IkReal(-1.00000000000000))*(cj0)*(x2312)*(x2317))));
08368 evalcond[5]=((((x2311)*(x2312)))+(((IkReal(-0.707109999985348))*(x2310)*(x2322)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2311)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(0.707103562373095))*(x2309)*(x2322)))+(((IkReal(-1.00000000000000))*(x2317)*(x2321)))+(((IkReal(-1.00000000000000))*(r10)*(x2313)*(x2319)))+(((IkReal(-1.00000000000000))*(x2325)*(x2327)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x2314)))+(((IkReal(-1.00000000000000))*(sj2)*(x2310)*(x2323))));
08369 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  )
08370 {
08371 continue;
08372 }
08373 }
08374 
08375 {
08376 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08377 vinfos[0].jointtype = 1;
08378 vinfos[0].foffset = j0;
08379 vinfos[0].indices[0] = _ij0[0];
08380 vinfos[0].indices[1] = _ij0[1];
08381 vinfos[0].maxsolutions = _nj0;
08382 vinfos[1].jointtype = 1;
08383 vinfos[1].foffset = j1;
08384 vinfos[1].indices[0] = _ij1[0];
08385 vinfos[1].indices[1] = _ij1[1];
08386 vinfos[1].maxsolutions = _nj1;
08387 vinfos[2].jointtype = 1;
08388 vinfos[2].foffset = j2;
08389 vinfos[2].indices[0] = _ij2[0];
08390 vinfos[2].indices[1] = _ij2[1];
08391 vinfos[2].maxsolutions = _nj2;
08392 vinfos[3].jointtype = 1;
08393 vinfos[3].foffset = j3;
08394 vinfos[3].indices[0] = _ij3[0];
08395 vinfos[3].indices[1] = _ij3[1];
08396 vinfos[3].maxsolutions = _nj3;
08397 vinfos[4].jointtype = 1;
08398 vinfos[4].foffset = j4;
08399 vinfos[4].indices[0] = _ij4[0];
08400 vinfos[4].indices[1] = _ij4[1];
08401 vinfos[4].maxsolutions = _nj4;
08402 vinfos[5].jointtype = 1;
08403 vinfos[5].foffset = j5;
08404 vinfos[5].indices[0] = _ij5[0];
08405 vinfos[5].indices[1] = _ij5[1];
08406 vinfos[5].maxsolutions = _nj5;
08407 std::vector<int> vfree(0);
08408 solutions.AddSolution(vinfos,vfree);
08409 }
08410 }
08411 }
08412 
08413 }
08414 
08415 }
08416 }
08417 }
08418 
08419 }
08420 
08421 }
08422 }
08423 }
08424 
08425 }
08426 
08427 }
08428 
08429 } else
08430 {
08431 {
08432 IkReal j0array[1], cj0array[1], sj0array[1];
08433 bool j0valid[1]={false};
08434 _nj0 = 1;
08435 IkReal x2333=((cj5)*(sj3));
08436 IkReal x2334=((IkReal(1.00000000000000))*(cj3));
08437 IkReal x2335=((cj4)*(cj5));
08438 IkReal x2336=((sj3)*(sj5));
08439 IkReal x2337=((cj3)*(cj4)*(sj5));
08440 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(r12)*(sj4)*(x2334)))+(((r11)*(x2337)))+(((r11)*(x2333)))+(((IkReal(-1.00000000000000))*(r10)*(x2334)*(x2335)))+(((r10)*(x2336))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2334)))+(((r01)*(x2337)))+(((r01)*(x2333)))+(((r00)*(x2336)))+(((IkReal(-1.00000000000000))*(r00)*(x2334)*(x2335))))))) < IKFAST_ATAN2_MAGTHRESH )
08441     continue;
08442 j0array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(r12)*(sj4)*(x2334)))+(((r11)*(x2337)))+(((r11)*(x2333)))+(((IkReal(-1.00000000000000))*(r10)*(x2334)*(x2335)))+(((r10)*(x2336)))))), ((gconst1)*(((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2334)))+(((r01)*(x2337)))+(((r01)*(x2333)))+(((r00)*(x2336)))+(((IkReal(-1.00000000000000))*(r00)*(x2334)*(x2335)))))));
08443 sj0array[0]=IKsin(j0array[0]);
08444 cj0array[0]=IKcos(j0array[0]);
08445 if( j0array[0] > IKPI )
08446 {
08447     j0array[0]-=IK2PI;
08448 }
08449 else if( j0array[0] < -IKPI )
08450 {    j0array[0]+=IK2PI;
08451 }
08452 j0valid[0] = true;
08453 for(int ij0 = 0; ij0 < 1; ++ij0)
08454 {
08455 if( !j0valid[ij0] )
08456 {
08457     continue;
08458 }
08459 _ij0[0] = ij0; _ij0[1] = -1;
08460 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
08461 {
08462 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
08463 {
08464     j0valid[iij0]=false; _ij0[1] = iij0; break; 
08465 }
08466 }
08467 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
08468 {
08469 IkReal evalcond[3];
08470 IkReal x2338=IKsin(j0);
08471 IkReal x2339=IKcos(j0);
08472 IkReal x2340=((cj5)*(r00));
08473 IkReal x2341=((r01)*(sj5));
08474 IkReal x2342=((cj5)*(r10));
08475 IkReal x2343=((IkReal(1.00000000000000))*(r12));
08476 IkReal x2344=((r11)*(sj5));
08477 IkReal x2345=((cj4)*(x2338));
08478 IkReal x2346=((sj4)*(x2338));
08479 IkReal x2347=((sj4)*(x2339));
08480 IkReal x2348=((cj4)*(x2339));
08481 IkReal x2349=((IkReal(1.00000000000000))*(x2339));
08482 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2349)))+(cj3)+(((cj5)*(r01)*(x2338)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2349)))+(((r00)*(sj5)*(x2338))));
08483 evalcond[1]=((((IkReal(-1.00000000000000))*(x2344)*(x2347)))+(((x2341)*(x2346)))+(((IkReal(-1.00000000000000))*(x2340)*(x2346)))+(((IkReal(-1.00000000000000))*(x2343)*(x2348)))+(((x2342)*(x2347)))+(((r02)*(x2345))));
08484 evalcond[2]=((sj3)+(((x2340)*(x2345)))+(((IkReal(-1.00000000000000))*(x2341)*(x2345)))+(((x2344)*(x2348)))+(((IkReal(-1.00000000000000))*(x2343)*(x2347)))+(((r02)*(x2346)))+(((IkReal(-1.00000000000000))*(x2342)*(x2348))));
08485 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
08486 {
08487 continue;
08488 }
08489 }
08490 
08491 {
08492 IkReal dummyeval[1];
08493 IkReal gconst34;
08494 gconst34=IKsign(sj3);
08495 dummyeval[0]=sj3;
08496 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08497 {
08498 {
08499 IkReal dummyeval[1];
08500 IkReal gconst35;
08501 gconst35=IKsign(cj3);
08502 dummyeval[0]=cj3;
08503 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08504 {
08505 {
08506 IkReal evalcond[7];
08507 IkReal x2350=((sj0)*(sj4));
08508 IkReal x2351=((IkReal(1.00000000000000))*(r12));
08509 IkReal x2352=((IkReal(1.00000000000000))*(cj0));
08510 IkReal x2353=((cj4)*(cj5));
08511 IkReal x2354=((r11)*(sj5));
08512 IkReal x2355=((cj4)*(sj0));
08513 IkReal x2356=((IkReal(1.00000000000000))*(sj5));
08514 IkReal x2357=((cj0)*(cj4));
08515 IkReal x2358=((r00)*(sj0));
08516 IkReal x2359=((cj0)*(sj4));
08517 IkReal x2360=((r01)*(sj5));
08518 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
08519 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2352)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2352)))+(((sj5)*(x2358))));
08520 evalcond[2]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((npx)*(x2353)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x2356))));
08521 evalcond[3]=((((cj5)*(r10)*(x2359)))+(((IkReal(-1.00000000000000))*(sj4)*(x2352)*(x2354)))+(((x2350)*(x2360)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2350)))+(((IkReal(-1.00000000000000))*(x2351)*(x2357)))+(((r02)*(x2355))));
08522 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2352)*(x2353)))+(((x2354)*(x2357)))+(((x2353)*(x2358)))+(((IkReal(-1.00000000000000))*(r01)*(x2355)*(x2356)))+(((IkReal(-1.00000000000000))*(x2351)*(x2359)))+(((r02)*(x2350))));
08523 evalcond[5]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x2356)))+(((r20)*(x2353))));
08524 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2353)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2352)))+(((x2354)*(x2355)))+(((IkReal(-1.00000000000000))*(x2350)*(x2351)))+(((x2357)*(x2360)))+(((IkReal(-1.00000000000000))*(r00)*(x2352)*(x2353))));
08525 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  )
08526 {
08527 {
08528 IkReal j2array[1], cj2array[1], sj2array[1];
08529 bool j2valid[1]={false};
08530 _nj2 = 1;
08531 IkReal x2361=((cj4)*(npz));
08532 IkReal x2362=((IkReal(2.94476514910275))*(cj5));
08533 IkReal x2363=((npx)*(sj4));
08534 IkReal x2364=((IkReal(2.34381456633434))*(sj5));
08535 IkReal x2365=((npy)*(sj4));
08536 IkReal x2366=((IkReal(2.94476514910275))*(sj5));
08537 IkReal x2367=((IkReal(2.34381456633434))*(cj5));
08538 if( IKabs(((IkReal(0.498689812223981))+(((npx)*(x2366)))+(((IkReal(-2.34381456633434))*(x2361)))+(((IkReal(-1.00000000000000))*(x2364)*(x2365)))+(((x2363)*(x2367)))+(((npy)*(x2362))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.844144773271807))+(((npx)*(x2364)))+(((x2365)*(x2366)))+(((IkReal(-1.00000000000000))*(x2362)*(x2363)))+(((npy)*(x2367)))+(((IkReal(2.94476514910275))*(x2361))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.498689812223981))+(((npx)*(x2366)))+(((IkReal(-2.34381456633434))*(x2361)))+(((IkReal(-1.00000000000000))*(x2364)*(x2365)))+(((x2363)*(x2367)))+(((npy)*(x2362)))))+IKsqr(((IkReal(-0.844144773271807))+(((npx)*(x2364)))+(((x2365)*(x2366)))+(((IkReal(-1.00000000000000))*(x2362)*(x2363)))+(((npy)*(x2367)))+(((IkReal(2.94476514910275))*(x2361)))))-1) <= IKFAST_SINCOS_THRESH )
08539     continue;
08540 j2array[0]=IKatan2(((IkReal(0.498689812223981))+(((npx)*(x2366)))+(((IkReal(-2.34381456633434))*(x2361)))+(((IkReal(-1.00000000000000))*(x2364)*(x2365)))+(((x2363)*(x2367)))+(((npy)*(x2362)))), ((IkReal(-0.844144773271807))+(((npx)*(x2364)))+(((x2365)*(x2366)))+(((IkReal(-1.00000000000000))*(x2362)*(x2363)))+(((npy)*(x2367)))+(((IkReal(2.94476514910275))*(x2361)))));
08541 sj2array[0]=IKsin(j2array[0]);
08542 cj2array[0]=IKcos(j2array[0]);
08543 if( j2array[0] > IKPI )
08544 {
08545     j2array[0]-=IK2PI;
08546 }
08547 else if( j2array[0] < -IKPI )
08548 {    j2array[0]+=IK2PI;
08549 }
08550 j2valid[0] = true;
08551 for(int ij2 = 0; ij2 < 1; ++ij2)
08552 {
08553 if( !j2valid[ij2] )
08554 {
08555     continue;
08556 }
08557 _ij2[0] = ij2; _ij2[1] = -1;
08558 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
08559 {
08560 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
08561 {
08562     j2valid[iij2]=false; _ij2[1] = iij2; break; 
08563 }
08564 }
08565 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
08566 {
08567 IkReal evalcond[2];
08568 IkReal x2368=IKcos(j2);
08569 IkReal x2369=IKsin(j2);
08570 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x2368)))+(((IkReal(0.165463933124939))*(x2369))));
08571 evalcond[1]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(x2368)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(x2369))));
08572 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
08573 {
08574 continue;
08575 }
08576 }
08577 
08578 {
08579 IkReal dummyeval[1];
08580 IkReal gconst46;
08581 gconst46=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
08582 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
08583 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08584 {
08585 {
08586 IkReal dummyeval[1];
08587 IkReal gconst47;
08588 gconst47=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
08589 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
08590 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08591 {
08592 continue;
08593 
08594 } else
08595 {
08596 {
08597 IkReal j1array[1], cj1array[1], sj1array[1];
08598 bool j1valid[1]={false};
08599 _nj1 = 1;
08600 IkReal x2370=((cj5)*(r11));
08601 IkReal x2371=((r10)*(sj0));
08602 IkReal x2372=((IkReal(0.707103562373095))*(cj2));
08603 IkReal x2373=((r20)*(sj5));
08604 IkReal x2374=((IkReal(0.707103562373095))*(sj2));
08605 IkReal x2375=((IkReal(0.707109999985348))*(cj2));
08606 IkReal x2376=((IkReal(0.707109999985348))*(sj2));
08607 IkReal x2377=((cj5)*(r21));
08608 IkReal x2378=((sj0)*(x2374));
08609 IkReal x2379=((sj5)*(x2375));
08610 IkReal x2380=((cj0)*(cj5)*(r01));
08611 IkReal x2381=((cj0)*(r00)*(sj5));
08612 if( IKabs(((gconst47)*(((((x2373)*(x2376)))+(((IkReal(-1.00000000000000))*(x2374)*(x2381)))+(((IkReal(-1.00000000000000))*(x2374)*(x2380)))+(((IkReal(-1.00000000000000))*(x2375)*(x2380)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x2379)))+(((IkReal(-1.00000000000000))*(x2372)*(x2377)))+(((IkReal(-1.00000000000000))*(x2372)*(x2373)))+(((IkReal(-1.00000000000000))*(x2370)*(x2378)))+(((IkReal(-1.00000000000000))*(x2371)*(x2379)))+(((x2376)*(x2377)))+(((IkReal(-1.00000000000000))*(sj0)*(x2370)*(x2375)))+(((IkReal(-1.00000000000000))*(sj5)*(x2371)*(x2374))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((sj0)*(x2370)*(x2372)))+(((IkReal(-1.00000000000000))*(x2376)*(x2381)))+(((IkReal(-1.00000000000000))*(x2376)*(x2380)))+(((sj5)*(x2371)*(x2372)))+(((IkReal(-1.00000000000000))*(x2375)*(x2377)))+(((IkReal(-1.00000000000000))*(x2374)*(x2377)))+(((IkReal(-1.00000000000000))*(x2373)*(x2374)))+(((IkReal(-1.00000000000000))*(x2373)*(x2375)))+(((x2372)*(x2380)))+(((x2372)*(x2381)))+(((IkReal(-1.00000000000000))*(sj0)*(x2370)*(x2376)))+(((IkReal(-1.00000000000000))*(sj5)*(x2371)*(x2376))))))) < IKFAST_ATAN2_MAGTHRESH )
08613     continue;
08614 j1array[0]=IKatan2(((gconst47)*(((((x2373)*(x2376)))+(((IkReal(-1.00000000000000))*(x2374)*(x2381)))+(((IkReal(-1.00000000000000))*(x2374)*(x2380)))+(((IkReal(-1.00000000000000))*(x2375)*(x2380)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x2379)))+(((IkReal(-1.00000000000000))*(x2372)*(x2377)))+(((IkReal(-1.00000000000000))*(x2372)*(x2373)))+(((IkReal(-1.00000000000000))*(x2370)*(x2378)))+(((IkReal(-1.00000000000000))*(x2371)*(x2379)))+(((x2376)*(x2377)))+(((IkReal(-1.00000000000000))*(sj0)*(x2370)*(x2375)))+(((IkReal(-1.00000000000000))*(sj5)*(x2371)*(x2374)))))), ((gconst47)*(((((sj0)*(x2370)*(x2372)))+(((IkReal(-1.00000000000000))*(x2376)*(x2381)))+(((IkReal(-1.00000000000000))*(x2376)*(x2380)))+(((sj5)*(x2371)*(x2372)))+(((IkReal(-1.00000000000000))*(x2375)*(x2377)))+(((IkReal(-1.00000000000000))*(x2374)*(x2377)))+(((IkReal(-1.00000000000000))*(x2373)*(x2374)))+(((IkReal(-1.00000000000000))*(x2373)*(x2375)))+(((x2372)*(x2380)))+(((x2372)*(x2381)))+(((IkReal(-1.00000000000000))*(sj0)*(x2370)*(x2376)))+(((IkReal(-1.00000000000000))*(sj5)*(x2371)*(x2376)))))));
08615 sj1array[0]=IKsin(j1array[0]);
08616 cj1array[0]=IKcos(j1array[0]);
08617 if( j1array[0] > IKPI )
08618 {
08619     j1array[0]-=IK2PI;
08620 }
08621 else if( j1array[0] < -IKPI )
08622 {    j1array[0]+=IK2PI;
08623 }
08624 j1valid[0] = true;
08625 for(int ij1 = 0; ij1 < 1; ++ij1)
08626 {
08627 if( !j1valid[ij1] )
08628 {
08629     continue;
08630 }
08631 _ij1[0] = ij1; _ij1[1] = -1;
08632 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08633 {
08634 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08635 {
08636     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08637 }
08638 }
08639 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08640 {
08641 IkReal evalcond[4];
08642 IkReal x2382=IKsin(j1);
08643 IkReal x2383=IKcos(j1);
08644 IkReal x2384=((IkReal(0.707109999985348))*(cj2));
08645 IkReal x2385=((IkReal(1.00000000000000))*(cj0));
08646 IkReal x2386=((IkReal(0.707109999985348))*(sj2));
08647 IkReal x2387=((cj5)*(sj4));
08648 IkReal x2388=((sj4)*(sj5));
08649 IkReal x2389=((IkReal(1.00000000000000))*(sj0));
08650 IkReal x2390=((sj5)*(x2389));
08651 IkReal x2391=((IkReal(0.707103562373095))*(x2383));
08652 IkReal x2392=((IkReal(0.707103562373095))*(x2382));
08653 IkReal x2393=((x2382)*(x2384));
08654 IkReal x2394=((sj2)*(x2392));
08655 IkReal x2395=((x2383)*(x2386));
08656 IkReal x2396=((cj2)*(x2391));
08657 IkReal x2397=((sj2)*(x2391));
08658 IkReal x2398=((cj2)*(x2392));
08659 IkReal x2399=((x2383)*(x2384));
08660 IkReal x2400=((x2382)*(x2386));
08661 IkReal x2401=((x2397)+(x2398)+(x2399));
08662 IkReal x2402=((x2394)+(x2395)+(x2393));
08663 evalcond[0]=((((cj5)*(r21)))+(x2400)+(((IkReal(-1.00000000000000))*(x2401)))+(((r20)*(sj5))));
08664 evalcond[1]=((x2402)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2396)))+(((IkReal(-1.00000000000000))*(r20)*(x2387)))+(((r21)*(x2388))));
08665 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x2390)))+(x2402)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2385)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2389)))+(((IkReal(-1.00000000000000))*(x2396)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2385))));
08666 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2385)*(x2388)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2389)))+(x2401)+(((IkReal(-1.00000000000000))*(x2400)))+(((IkReal(-1.00000000000000))*(r11)*(x2388)*(x2389)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2385)))+(((r10)*(sj0)*(x2387)))+(((cj0)*(r00)*(x2387))));
08667 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
08668 {
08669 continue;
08670 }
08671 }
08672 
08673 {
08674 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08675 vinfos[0].jointtype = 1;
08676 vinfos[0].foffset = j0;
08677 vinfos[0].indices[0] = _ij0[0];
08678 vinfos[0].indices[1] = _ij0[1];
08679 vinfos[0].maxsolutions = _nj0;
08680 vinfos[1].jointtype = 1;
08681 vinfos[1].foffset = j1;
08682 vinfos[1].indices[0] = _ij1[0];
08683 vinfos[1].indices[1] = _ij1[1];
08684 vinfos[1].maxsolutions = _nj1;
08685 vinfos[2].jointtype = 1;
08686 vinfos[2].foffset = j2;
08687 vinfos[2].indices[0] = _ij2[0];
08688 vinfos[2].indices[1] = _ij2[1];
08689 vinfos[2].maxsolutions = _nj2;
08690 vinfos[3].jointtype = 1;
08691 vinfos[3].foffset = j3;
08692 vinfos[3].indices[0] = _ij3[0];
08693 vinfos[3].indices[1] = _ij3[1];
08694 vinfos[3].maxsolutions = _nj3;
08695 vinfos[4].jointtype = 1;
08696 vinfos[4].foffset = j4;
08697 vinfos[4].indices[0] = _ij4[0];
08698 vinfos[4].indices[1] = _ij4[1];
08699 vinfos[4].maxsolutions = _nj4;
08700 vinfos[5].jointtype = 1;
08701 vinfos[5].foffset = j5;
08702 vinfos[5].indices[0] = _ij5[0];
08703 vinfos[5].indices[1] = _ij5[1];
08704 vinfos[5].maxsolutions = _nj5;
08705 std::vector<int> vfree(0);
08706 solutions.AddSolution(vinfos,vfree);
08707 }
08708 }
08709 }
08710 
08711 }
08712 
08713 }
08714 
08715 } else
08716 {
08717 {
08718 IkReal j1array[1], cj1array[1], sj1array[1];
08719 bool j1valid[1]={false};
08720 _nj1 = 1;
08721 IkReal x2403=((cj5)*(sj4));
08722 IkReal x2404=((r21)*(sj4));
08723 IkReal x2405=((cj5)*(r21));
08724 IkReal x2406=((IkReal(0.707109999985348))*(cj2));
08725 IkReal x2407=((IkReal(0.707103562373095))*(sj2));
08726 IkReal x2408=((IkReal(0.707109999985348))*(sj2));
08727 IkReal x2409=((cj4)*(r22));
08728 IkReal x2410=((IkReal(0.707103562373095))*(cj2));
08729 IkReal x2411=((r20)*(x2406));
08730 IkReal x2412=((sj5)*(x2410));
08731 IkReal x2413=((sj5)*(x2408));
08732 if( IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(r20)*(x2412)))+(((IkReal(-1.00000000000000))*(r20)*(x2403)*(x2407)))+(((sj5)*(x2404)*(x2407)))+(((sj5)*(x2404)*(x2406)))+(((IkReal(-1.00000000000000))*(x2405)*(x2410)))+(((r20)*(x2413)))+(((x2405)*(x2408)))+(((IkReal(-1.00000000000000))*(x2403)*(x2411)))+(((x2406)*(x2409)))+(((x2407)*(x2409))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x2405)*(x2407)))+(((IkReal(-1.00000000000000))*(x2405)*(x2406)))+(((x2408)*(x2409)))+(((IkReal(-1.00000000000000))*(r20)*(x2403)*(x2408)))+(((x2404)*(x2413)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2407)))+(((IkReal(-1.00000000000000))*(x2404)*(x2412)))+(((r20)*(x2403)*(x2410)))+(((IkReal(-1.00000000000000))*(sj5)*(x2411)))+(((IkReal(-1.00000000000000))*(x2409)*(x2410))))))) < IKFAST_ATAN2_MAGTHRESH )
08733     continue;
08734 j1array[0]=IKatan2(((gconst46)*(((((IkReal(-1.00000000000000))*(r20)*(x2412)))+(((IkReal(-1.00000000000000))*(r20)*(x2403)*(x2407)))+(((sj5)*(x2404)*(x2407)))+(((sj5)*(x2404)*(x2406)))+(((IkReal(-1.00000000000000))*(x2405)*(x2410)))+(((r20)*(x2413)))+(((x2405)*(x2408)))+(((IkReal(-1.00000000000000))*(x2403)*(x2411)))+(((x2406)*(x2409)))+(((x2407)*(x2409)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(x2405)*(x2407)))+(((IkReal(-1.00000000000000))*(x2405)*(x2406)))+(((x2408)*(x2409)))+(((IkReal(-1.00000000000000))*(r20)*(x2403)*(x2408)))+(((x2404)*(x2413)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2407)))+(((IkReal(-1.00000000000000))*(x2404)*(x2412)))+(((r20)*(x2403)*(x2410)))+(((IkReal(-1.00000000000000))*(sj5)*(x2411)))+(((IkReal(-1.00000000000000))*(x2409)*(x2410)))))));
08735 sj1array[0]=IKsin(j1array[0]);
08736 cj1array[0]=IKcos(j1array[0]);
08737 if( j1array[0] > IKPI )
08738 {
08739     j1array[0]-=IK2PI;
08740 }
08741 else if( j1array[0] < -IKPI )
08742 {    j1array[0]+=IK2PI;
08743 }
08744 j1valid[0] = true;
08745 for(int ij1 = 0; ij1 < 1; ++ij1)
08746 {
08747 if( !j1valid[ij1] )
08748 {
08749     continue;
08750 }
08751 _ij1[0] = ij1; _ij1[1] = -1;
08752 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08753 {
08754 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08755 {
08756     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08757 }
08758 }
08759 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08760 {
08761 IkReal evalcond[4];
08762 IkReal x2414=IKsin(j1);
08763 IkReal x2415=IKcos(j1);
08764 IkReal x2416=((IkReal(0.707109999985348))*(cj2));
08765 IkReal x2417=((IkReal(1.00000000000000))*(cj0));
08766 IkReal x2418=((IkReal(0.707109999985348))*(sj2));
08767 IkReal x2419=((cj5)*(sj4));
08768 IkReal x2420=((sj4)*(sj5));
08769 IkReal x2421=((IkReal(1.00000000000000))*(sj0));
08770 IkReal x2422=((sj5)*(x2421));
08771 IkReal x2423=((IkReal(0.707103562373095))*(x2415));
08772 IkReal x2424=((IkReal(0.707103562373095))*(x2414));
08773 IkReal x2425=((x2414)*(x2416));
08774 IkReal x2426=((sj2)*(x2424));
08775 IkReal x2427=((x2415)*(x2418));
08776 IkReal x2428=((cj2)*(x2423));
08777 IkReal x2429=((sj2)*(x2423));
08778 IkReal x2430=((cj2)*(x2424));
08779 IkReal x2431=((x2415)*(x2416));
08780 IkReal x2432=((x2414)*(x2418));
08781 IkReal x2433=((x2431)+(x2430)+(x2429));
08782 IkReal x2434=((x2425)+(x2426)+(x2427));
08783 evalcond[0]=((((cj5)*(r21)))+(x2432)+(((IkReal(-1.00000000000000))*(x2433)))+(((r20)*(sj5))));
08784 evalcond[1]=((x2434)+(((r21)*(x2420)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2419)))+(((IkReal(-1.00000000000000))*(x2428))));
08785 evalcond[2]=((x2434)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2417)))+(((IkReal(-1.00000000000000))*(r10)*(x2422)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2421)))+(((IkReal(-1.00000000000000))*(x2428)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2417))));
08786 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x2420)*(x2421)))+(x2433)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2421)))+(((cj0)*(r00)*(x2419)))+(((IkReal(-1.00000000000000))*(x2432)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2417)))+(((r10)*(sj0)*(x2419)))+(((IkReal(-1.00000000000000))*(r01)*(x2417)*(x2420))));
08787 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
08788 {
08789 continue;
08790 }
08791 }
08792 
08793 {
08794 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08795 vinfos[0].jointtype = 1;
08796 vinfos[0].foffset = j0;
08797 vinfos[0].indices[0] = _ij0[0];
08798 vinfos[0].indices[1] = _ij0[1];
08799 vinfos[0].maxsolutions = _nj0;
08800 vinfos[1].jointtype = 1;
08801 vinfos[1].foffset = j1;
08802 vinfos[1].indices[0] = _ij1[0];
08803 vinfos[1].indices[1] = _ij1[1];
08804 vinfos[1].maxsolutions = _nj1;
08805 vinfos[2].jointtype = 1;
08806 vinfos[2].foffset = j2;
08807 vinfos[2].indices[0] = _ij2[0];
08808 vinfos[2].indices[1] = _ij2[1];
08809 vinfos[2].maxsolutions = _nj2;
08810 vinfos[3].jointtype = 1;
08811 vinfos[3].foffset = j3;
08812 vinfos[3].indices[0] = _ij3[0];
08813 vinfos[3].indices[1] = _ij3[1];
08814 vinfos[3].maxsolutions = _nj3;
08815 vinfos[4].jointtype = 1;
08816 vinfos[4].foffset = j4;
08817 vinfos[4].indices[0] = _ij4[0];
08818 vinfos[4].indices[1] = _ij4[1];
08819 vinfos[4].maxsolutions = _nj4;
08820 vinfos[5].jointtype = 1;
08821 vinfos[5].foffset = j5;
08822 vinfos[5].indices[0] = _ij5[0];
08823 vinfos[5].indices[1] = _ij5[1];
08824 vinfos[5].maxsolutions = _nj5;
08825 std::vector<int> vfree(0);
08826 solutions.AddSolution(vinfos,vfree);
08827 }
08828 }
08829 }
08830 
08831 }
08832 
08833 }
08834 }
08835 }
08836 
08837 } else
08838 {
08839 IkReal x2435=((sj0)*(sj4));
08840 IkReal x2436=((IkReal(1.00000000000000))*(r12));
08841 IkReal x2437=((IkReal(1.00000000000000))*(cj0));
08842 IkReal x2438=((cj4)*(cj5));
08843 IkReal x2439=((r11)*(sj5));
08844 IkReal x2440=((cj4)*(sj0));
08845 IkReal x2441=((IkReal(1.00000000000000))*(sj5));
08846 IkReal x2442=((cj0)*(cj4));
08847 IkReal x2443=((r00)*(sj0));
08848 IkReal x2444=((cj0)*(sj4));
08849 IkReal x2445=((r01)*(sj5));
08850 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
08851 evalcond[1]=((((sj5)*(x2443)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2437)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2437)))+(((cj5)*(r01)*(sj0))));
08852 evalcond[2]=((IkReal(-0.00600000000000000))+(((npx)*(x2438)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x2441)))+(((npz)*(sj4))));
08853 evalcond[3]=((((r02)*(x2440)))+(((IkReal(-1.00000000000000))*(sj4)*(x2437)*(x2439)))+(((cj5)*(r10)*(x2444)))+(((IkReal(-1.00000000000000))*(x2436)*(x2442)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2435)))+(((x2435)*(x2445))));
08854 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x2440)*(x2441)))+(((IkReal(-1.00000000000000))*(x2436)*(x2444)))+(((r02)*(x2435)))+(((IkReal(-1.00000000000000))*(r10)*(x2437)*(x2438)))+(((x2439)*(x2442)))+(((x2438)*(x2443))));
08855 evalcond[5]=((((r20)*(x2438)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x2441))));
08856 evalcond[6]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2438)))+(((x2442)*(x2445)))+(((IkReal(-1.00000000000000))*(r00)*(x2437)*(x2438)))+(((IkReal(-1.00000000000000))*(x2435)*(x2436)))+(((x2439)*(x2440)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2437))));
08857 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  )
08858 {
08859 {
08860 IkReal j2array[1], cj2array[1], sj2array[1];
08861 bool j2valid[1]={false};
08862 _nj2 = 1;
08863 IkReal x2446=((cj4)*(npz));
08864 IkReal x2447=((IkReal(2.94476514910275))*(cj5));
08865 IkReal x2448=((npx)*(sj4));
08866 IkReal x2449=((IkReal(2.34381456633434))*(sj5));
08867 IkReal x2450=((npy)*(sj4));
08868 IkReal x2451=((IkReal(2.94476514910275))*(sj5));
08869 IkReal x2452=((IkReal(2.34381456633434))*(cj5));
08870 if( IKabs(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x2449)*(x2450)))+(((x2448)*(x2452)))+(((npx)*(x2451)))+(((npy)*(x2447)))+(((IkReal(-2.34381456633434))*(x2446))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.844144773271807))+(((x2450)*(x2451)))+(((IkReal(-1.00000000000000))*(x2447)*(x2448)))+(((npx)*(x2449)))+(((npy)*(x2452)))+(((IkReal(2.94476514910275))*(x2446))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x2449)*(x2450)))+(((x2448)*(x2452)))+(((npx)*(x2451)))+(((npy)*(x2447)))+(((IkReal(-2.34381456633434))*(x2446)))))+IKsqr(((IkReal(-0.844144773271807))+(((x2450)*(x2451)))+(((IkReal(-1.00000000000000))*(x2447)*(x2448)))+(((npx)*(x2449)))+(((npy)*(x2452)))+(((IkReal(2.94476514910275))*(x2446)))))-1) <= IKFAST_SINCOS_THRESH )
08871     continue;
08872 j2array[0]=IKatan2(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x2449)*(x2450)))+(((x2448)*(x2452)))+(((npx)*(x2451)))+(((npy)*(x2447)))+(((IkReal(-2.34381456633434))*(x2446)))), ((IkReal(-0.844144773271807))+(((x2450)*(x2451)))+(((IkReal(-1.00000000000000))*(x2447)*(x2448)))+(((npx)*(x2449)))+(((npy)*(x2452)))+(((IkReal(2.94476514910275))*(x2446)))));
08873 sj2array[0]=IKsin(j2array[0]);
08874 cj2array[0]=IKcos(j2array[0]);
08875 if( j2array[0] > IKPI )
08876 {
08877     j2array[0]-=IK2PI;
08878 }
08879 else if( j2array[0] < -IKPI )
08880 {    j2array[0]+=IK2PI;
08881 }
08882 j2valid[0] = true;
08883 for(int ij2 = 0; ij2 < 1; ++ij2)
08884 {
08885 if( !j2valid[ij2] )
08886 {
08887     continue;
08888 }
08889 _ij2[0] = ij2; _ij2[1] = -1;
08890 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
08891 {
08892 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
08893 {
08894     j2valid[iij2]=false; _ij2[1] = iij2; break; 
08895 }
08896 }
08897 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
08898 {
08899 IkReal evalcond[2];
08900 IkReal x2453=IKcos(j2);
08901 IkReal x2454=IKsin(j2);
08902 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(x2453)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(x2454))));
08903 evalcond[1]=((IkReal(-0.0360035672348961))+(((IkReal(-0.165463933124939))*(x2453)))+(((npx)*(sj5)))+(((IkReal(-0.207888640466058))*(x2454)))+(((cj5)*(npy))));
08904 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
08905 {
08906 continue;
08907 }
08908 }
08909 
08910 {
08911 IkReal dummyeval[1];
08912 IkReal gconst48;
08913 gconst48=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
08914 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
08915 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08916 {
08917 {
08918 IkReal dummyeval[1];
08919 IkReal gconst49;
08920 gconst49=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
08921 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
08922 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08923 {
08924 continue;
08925 
08926 } else
08927 {
08928 {
08929 IkReal j1array[1], cj1array[1], sj1array[1];
08930 bool j1valid[1]={false};
08931 _nj1 = 1;
08932 IkReal x2455=((cj5)*(r11));
08933 IkReal x2456=((r10)*(sj0));
08934 IkReal x2457=((IkReal(0.707103562373095))*(cj2));
08935 IkReal x2458=((r20)*(sj5));
08936 IkReal x2459=((IkReal(0.707103562373095))*(sj2));
08937 IkReal x2460=((IkReal(0.707109999985348))*(cj2));
08938 IkReal x2461=((cj0)*(r00));
08939 IkReal x2462=((IkReal(0.707109999985348))*(sj2));
08940 IkReal x2463=((cj5)*(r21));
08941 IkReal x2464=((sj0)*(x2459));
08942 IkReal x2465=((sj5)*(x2460));
08943 IkReal x2466=((cj0)*(cj5)*(r01));
08944 if( IKabs(((gconst49)*(((((x2458)*(x2462)))+(((IkReal(-1.00000000000000))*(x2457)*(x2463)))+(((IkReal(-1.00000000000000))*(sj5)*(x2459)*(x2461)))+(((IkReal(-1.00000000000000))*(x2456)*(x2465)))+(((IkReal(-1.00000000000000))*(sj5)*(x2456)*(x2459)))+(((x2462)*(x2463)))+(((IkReal(-1.00000000000000))*(x2457)*(x2458)))+(((IkReal(-1.00000000000000))*(x2455)*(x2464)))+(((IkReal(-1.00000000000000))*(sj0)*(x2455)*(x2460)))+(((IkReal(-1.00000000000000))*(x2460)*(x2466)))+(((IkReal(-1.00000000000000))*(x2461)*(x2465)))+(((IkReal(-1.00000000000000))*(x2459)*(x2466))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((sj5)*(x2457)*(x2461)))+(((IkReal(-1.00000000000000))*(sj5)*(x2461)*(x2462)))+(((sj0)*(x2455)*(x2457)))+(((IkReal(-1.00000000000000))*(x2458)*(x2459)))+(((x2457)*(x2466)))+(((IkReal(-1.00000000000000))*(sj0)*(x2455)*(x2462)))+(((IkReal(-1.00000000000000))*(x2460)*(x2463)))+(((sj5)*(x2456)*(x2457)))+(((IkReal(-1.00000000000000))*(sj5)*(x2456)*(x2462)))+(((IkReal(-1.00000000000000))*(x2459)*(x2463)))+(((IkReal(-1.00000000000000))*(x2458)*(x2460)))+(((IkReal(-1.00000000000000))*(x2462)*(x2466))))))) < IKFAST_ATAN2_MAGTHRESH )
08945     continue;
08946 j1array[0]=IKatan2(((gconst49)*(((((x2458)*(x2462)))+(((IkReal(-1.00000000000000))*(x2457)*(x2463)))+(((IkReal(-1.00000000000000))*(sj5)*(x2459)*(x2461)))+(((IkReal(-1.00000000000000))*(x2456)*(x2465)))+(((IkReal(-1.00000000000000))*(sj5)*(x2456)*(x2459)))+(((x2462)*(x2463)))+(((IkReal(-1.00000000000000))*(x2457)*(x2458)))+(((IkReal(-1.00000000000000))*(x2455)*(x2464)))+(((IkReal(-1.00000000000000))*(sj0)*(x2455)*(x2460)))+(((IkReal(-1.00000000000000))*(x2460)*(x2466)))+(((IkReal(-1.00000000000000))*(x2461)*(x2465)))+(((IkReal(-1.00000000000000))*(x2459)*(x2466)))))), ((gconst49)*(((((sj5)*(x2457)*(x2461)))+(((IkReal(-1.00000000000000))*(sj5)*(x2461)*(x2462)))+(((sj0)*(x2455)*(x2457)))+(((IkReal(-1.00000000000000))*(x2458)*(x2459)))+(((x2457)*(x2466)))+(((IkReal(-1.00000000000000))*(sj0)*(x2455)*(x2462)))+(((IkReal(-1.00000000000000))*(x2460)*(x2463)))+(((sj5)*(x2456)*(x2457)))+(((IkReal(-1.00000000000000))*(sj5)*(x2456)*(x2462)))+(((IkReal(-1.00000000000000))*(x2459)*(x2463)))+(((IkReal(-1.00000000000000))*(x2458)*(x2460)))+(((IkReal(-1.00000000000000))*(x2462)*(x2466)))))));
08947 sj1array[0]=IKsin(j1array[0]);
08948 cj1array[0]=IKcos(j1array[0]);
08949 if( j1array[0] > IKPI )
08950 {
08951     j1array[0]-=IK2PI;
08952 }
08953 else if( j1array[0] < -IKPI )
08954 {    j1array[0]+=IK2PI;
08955 }
08956 j1valid[0] = true;
08957 for(int ij1 = 0; ij1 < 1; ++ij1)
08958 {
08959 if( !j1valid[ij1] )
08960 {
08961     continue;
08962 }
08963 _ij1[0] = ij1; _ij1[1] = -1;
08964 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
08965 {
08966 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
08967 {
08968     j1valid[iij1]=false; _ij1[1] = iij1; break; 
08969 }
08970 }
08971 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
08972 {
08973 IkReal evalcond[4];
08974 IkReal x2467=IKsin(j1);
08975 IkReal x2468=IKcos(j1);
08976 IkReal x2469=((IkReal(0.707109999985348))*(cj2));
08977 IkReal x2470=((IkReal(1.00000000000000))*(cj0));
08978 IkReal x2471=((IkReal(0.707109999985348))*(sj2));
08979 IkReal x2472=((cj5)*(sj4));
08980 IkReal x2473=((sj4)*(sj5));
08981 IkReal x2474=((IkReal(1.00000000000000))*(sj0));
08982 IkReal x2475=((sj5)*(x2474));
08983 IkReal x2476=((IkReal(0.707103562373095))*(x2468));
08984 IkReal x2477=((IkReal(0.707103562373095))*(x2467));
08985 IkReal x2478=((x2467)*(x2469));
08986 IkReal x2479=((sj2)*(x2477));
08987 IkReal x2480=((x2468)*(x2471));
08988 IkReal x2481=((cj2)*(x2476));
08989 IkReal x2482=((sj2)*(x2476));
08990 IkReal x2483=((cj2)*(x2477));
08991 IkReal x2484=((x2468)*(x2469));
08992 IkReal x2485=((x2467)*(x2471));
08993 IkReal x2486=((x2484)+(x2482)+(x2483));
08994 IkReal x2487=((x2480)+(x2479)+(x2478));
08995 evalcond[0]=((((cj5)*(r21)))+(x2485)+(((IkReal(-1.00000000000000))*(x2486)))+(((r20)*(sj5))));
08996 evalcond[1]=((x2487)+(((cj4)*(r22)))+(((r21)*(x2473)))+(((IkReal(-1.00000000000000))*(x2481)))+(((IkReal(-1.00000000000000))*(r20)*(x2472))));
08997 evalcond[2]=((x2487)+(((IkReal(-1.00000000000000))*(x2481)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2470)))+(((IkReal(-1.00000000000000))*(r10)*(x2475)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2470)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2474))));
08998 evalcond[3]=((((cj0)*(r00)*(x2472)))+(x2486)+(((r10)*(sj0)*(x2472)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2474)))+(((IkReal(-1.00000000000000))*(x2485)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2470)))+(((IkReal(-1.00000000000000))*(r01)*(x2470)*(x2473)))+(((IkReal(-1.00000000000000))*(r11)*(x2473)*(x2474))));
08999 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09000 {
09001 continue;
09002 }
09003 }
09004 
09005 {
09006 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09007 vinfos[0].jointtype = 1;
09008 vinfos[0].foffset = j0;
09009 vinfos[0].indices[0] = _ij0[0];
09010 vinfos[0].indices[1] = _ij0[1];
09011 vinfos[0].maxsolutions = _nj0;
09012 vinfos[1].jointtype = 1;
09013 vinfos[1].foffset = j1;
09014 vinfos[1].indices[0] = _ij1[0];
09015 vinfos[1].indices[1] = _ij1[1];
09016 vinfos[1].maxsolutions = _nj1;
09017 vinfos[2].jointtype = 1;
09018 vinfos[2].foffset = j2;
09019 vinfos[2].indices[0] = _ij2[0];
09020 vinfos[2].indices[1] = _ij2[1];
09021 vinfos[2].maxsolutions = _nj2;
09022 vinfos[3].jointtype = 1;
09023 vinfos[3].foffset = j3;
09024 vinfos[3].indices[0] = _ij3[0];
09025 vinfos[3].indices[1] = _ij3[1];
09026 vinfos[3].maxsolutions = _nj3;
09027 vinfos[4].jointtype = 1;
09028 vinfos[4].foffset = j4;
09029 vinfos[4].indices[0] = _ij4[0];
09030 vinfos[4].indices[1] = _ij4[1];
09031 vinfos[4].maxsolutions = _nj4;
09032 vinfos[5].jointtype = 1;
09033 vinfos[5].foffset = j5;
09034 vinfos[5].indices[0] = _ij5[0];
09035 vinfos[5].indices[1] = _ij5[1];
09036 vinfos[5].maxsolutions = _nj5;
09037 std::vector<int> vfree(0);
09038 solutions.AddSolution(vinfos,vfree);
09039 }
09040 }
09041 }
09042 
09043 }
09044 
09045 }
09046 
09047 } else
09048 {
09049 {
09050 IkReal j1array[1], cj1array[1], sj1array[1];
09051 bool j1valid[1]={false};
09052 _nj1 = 1;
09053 IkReal x2488=((cj5)*(sj4));
09054 IkReal x2489=((r21)*(sj4));
09055 IkReal x2490=((cj5)*(r21));
09056 IkReal x2491=((IkReal(0.707109999985348))*(cj2));
09057 IkReal x2492=((IkReal(0.707103562373095))*(sj2));
09058 IkReal x2493=((IkReal(0.707109999985348))*(sj2));
09059 IkReal x2494=((cj4)*(r22));
09060 IkReal x2495=((IkReal(0.707103562373095))*(cj2));
09061 IkReal x2496=((r20)*(x2491));
09062 IkReal x2497=((sj5)*(x2495));
09063 IkReal x2498=((sj5)*(x2493));
09064 if( IKabs(((gconst48)*(((((x2492)*(x2494)))+(((IkReal(-1.00000000000000))*(r20)*(x2488)*(x2492)))+(((IkReal(-1.00000000000000))*(x2490)*(x2495)))+(((x2490)*(x2493)))+(((IkReal(-1.00000000000000))*(r20)*(x2497)))+(((IkReal(-1.00000000000000))*(x2488)*(x2496)))+(((sj5)*(x2489)*(x2491)))+(((sj5)*(x2489)*(x2492)))+(((x2491)*(x2494)))+(((r20)*(x2498))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x2488)*(x2493)))+(((IkReal(-1.00000000000000))*(x2490)*(x2492)))+(((IkReal(-1.00000000000000))*(x2490)*(x2491)))+(((IkReal(-1.00000000000000))*(x2494)*(x2495)))+(((x2493)*(x2494)))+(((r20)*(x2488)*(x2495)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2492)))+(((IkReal(-1.00000000000000))*(x2489)*(x2497)))+(((IkReal(-1.00000000000000))*(sj5)*(x2496)))+(((x2489)*(x2498))))))) < IKFAST_ATAN2_MAGTHRESH )
09065     continue;
09066 j1array[0]=IKatan2(((gconst48)*(((((x2492)*(x2494)))+(((IkReal(-1.00000000000000))*(r20)*(x2488)*(x2492)))+(((IkReal(-1.00000000000000))*(x2490)*(x2495)))+(((x2490)*(x2493)))+(((IkReal(-1.00000000000000))*(r20)*(x2497)))+(((IkReal(-1.00000000000000))*(x2488)*(x2496)))+(((sj5)*(x2489)*(x2491)))+(((sj5)*(x2489)*(x2492)))+(((x2491)*(x2494)))+(((r20)*(x2498)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(r20)*(x2488)*(x2493)))+(((IkReal(-1.00000000000000))*(x2490)*(x2492)))+(((IkReal(-1.00000000000000))*(x2490)*(x2491)))+(((IkReal(-1.00000000000000))*(x2494)*(x2495)))+(((x2493)*(x2494)))+(((r20)*(x2488)*(x2495)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2492)))+(((IkReal(-1.00000000000000))*(x2489)*(x2497)))+(((IkReal(-1.00000000000000))*(sj5)*(x2496)))+(((x2489)*(x2498)))))));
09067 sj1array[0]=IKsin(j1array[0]);
09068 cj1array[0]=IKcos(j1array[0]);
09069 if( j1array[0] > IKPI )
09070 {
09071     j1array[0]-=IK2PI;
09072 }
09073 else if( j1array[0] < -IKPI )
09074 {    j1array[0]+=IK2PI;
09075 }
09076 j1valid[0] = true;
09077 for(int ij1 = 0; ij1 < 1; ++ij1)
09078 {
09079 if( !j1valid[ij1] )
09080 {
09081     continue;
09082 }
09083 _ij1[0] = ij1; _ij1[1] = -1;
09084 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
09085 {
09086 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
09087 {
09088     j1valid[iij1]=false; _ij1[1] = iij1; break; 
09089 }
09090 }
09091 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
09092 {
09093 IkReal evalcond[4];
09094 IkReal x2499=IKsin(j1);
09095 IkReal x2500=IKcos(j1);
09096 IkReal x2501=((IkReal(0.707109999985348))*(cj2));
09097 IkReal x2502=((IkReal(1.00000000000000))*(cj0));
09098 IkReal x2503=((IkReal(0.707109999985348))*(sj2));
09099 IkReal x2504=((cj5)*(sj4));
09100 IkReal x2505=((sj4)*(sj5));
09101 IkReal x2506=((IkReal(1.00000000000000))*(sj0));
09102 IkReal x2507=((sj5)*(x2506));
09103 IkReal x2508=((IkReal(0.707103562373095))*(x2500));
09104 IkReal x2509=((IkReal(0.707103562373095))*(x2499));
09105 IkReal x2510=((x2499)*(x2501));
09106 IkReal x2511=((sj2)*(x2509));
09107 IkReal x2512=((x2500)*(x2503));
09108 IkReal x2513=((cj2)*(x2508));
09109 IkReal x2514=((sj2)*(x2508));
09110 IkReal x2515=((cj2)*(x2509));
09111 IkReal x2516=((x2500)*(x2501));
09112 IkReal x2517=((x2499)*(x2503));
09113 IkReal x2518=((x2514)+(x2515)+(x2516));
09114 IkReal x2519=((x2510)+(x2511)+(x2512));
09115 evalcond[0]=((((cj5)*(r21)))+(x2517)+(((IkReal(-1.00000000000000))*(x2518)))+(((r20)*(sj5))));
09116 evalcond[1]=((x2519)+(((IkReal(-1.00000000000000))*(x2513)))+(((cj4)*(r22)))+(((r21)*(x2505)))+(((IkReal(-1.00000000000000))*(r20)*(x2504))));
09117 evalcond[2]=((x2519)+(((IkReal(-1.00000000000000))*(x2513)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2502)))+(((IkReal(-1.00000000000000))*(r10)*(x2507)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2502)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2506))));
09118 evalcond[3]=((((r10)*(sj0)*(x2504)))+(x2518)+(((IkReal(-1.00000000000000))*(x2517)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2502)))+(((IkReal(-1.00000000000000))*(r11)*(x2505)*(x2506)))+(((cj0)*(r00)*(x2504)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2506)))+(((IkReal(-1.00000000000000))*(r01)*(x2502)*(x2505))));
09119 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09120 {
09121 continue;
09122 }
09123 }
09124 
09125 {
09126 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09127 vinfos[0].jointtype = 1;
09128 vinfos[0].foffset = j0;
09129 vinfos[0].indices[0] = _ij0[0];
09130 vinfos[0].indices[1] = _ij0[1];
09131 vinfos[0].maxsolutions = _nj0;
09132 vinfos[1].jointtype = 1;
09133 vinfos[1].foffset = j1;
09134 vinfos[1].indices[0] = _ij1[0];
09135 vinfos[1].indices[1] = _ij1[1];
09136 vinfos[1].maxsolutions = _nj1;
09137 vinfos[2].jointtype = 1;
09138 vinfos[2].foffset = j2;
09139 vinfos[2].indices[0] = _ij2[0];
09140 vinfos[2].indices[1] = _ij2[1];
09141 vinfos[2].maxsolutions = _nj2;
09142 vinfos[3].jointtype = 1;
09143 vinfos[3].foffset = j3;
09144 vinfos[3].indices[0] = _ij3[0];
09145 vinfos[3].indices[1] = _ij3[1];
09146 vinfos[3].maxsolutions = _nj3;
09147 vinfos[4].jointtype = 1;
09148 vinfos[4].foffset = j4;
09149 vinfos[4].indices[0] = _ij4[0];
09150 vinfos[4].indices[1] = _ij4[1];
09151 vinfos[4].maxsolutions = _nj4;
09152 vinfos[5].jointtype = 1;
09153 vinfos[5].foffset = j5;
09154 vinfos[5].indices[0] = _ij5[0];
09155 vinfos[5].indices[1] = _ij5[1];
09156 vinfos[5].maxsolutions = _nj5;
09157 std::vector<int> vfree(0);
09158 solutions.AddSolution(vinfos,vfree);
09159 }
09160 }
09161 }
09162 
09163 }
09164 
09165 }
09166 }
09167 }
09168 
09169 } else
09170 {
09171 IkReal x2520=((sj0)*(sj4));
09172 IkReal x2521=((IkReal(1.00000000000000))*(r12));
09173 IkReal x2522=((IkReal(1.00000000000000))*(cj0));
09174 IkReal x2523=((cj4)*(cj5));
09175 IkReal x2524=((r11)*(sj5));
09176 IkReal x2525=((cj4)*(sj0));
09177 IkReal x2526=((IkReal(1.00000000000000))*(sj5));
09178 IkReal x2527=((cj0)*(cj4));
09179 IkReal x2528=((r00)*(sj0));
09180 IkReal x2529=((cj0)*(sj4));
09181 IkReal x2530=((r01)*(sj5));
09182 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
09183 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x2528)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2522)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2522))));
09184 evalcond[2]=((IkReal(0.00600000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x2526)))+(((npx)*(x2523)))+(((npz)*(sj4))));
09185 evalcond[3]=((((r02)*(x2525)))+(((IkReal(-1.00000000000000))*(sj4)*(x2522)*(x2524)))+(((x2520)*(x2530)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2520)))+(((cj5)*(r10)*(x2529)))+(((IkReal(-1.00000000000000))*(x2521)*(x2527))));
09186 evalcond[4]=((IkReal(-1.00000000000000))+(((r02)*(x2520)))+(((IkReal(-1.00000000000000))*(r01)*(x2525)*(x2526)))+(((IkReal(-1.00000000000000))*(r10)*(x2522)*(x2523)))+(((x2523)*(x2528)))+(((x2524)*(x2527)))+(((IkReal(-1.00000000000000))*(x2521)*(x2529))));
09187 evalcond[5]=((((r22)*(sj4)))+(((r20)*(x2523)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x2526))));
09188 evalcond[6]=((((IkReal(-1.00000000000000))*(x2520)*(x2521)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2522)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2523)))+(((x2527)*(x2530)))+(((x2524)*(x2525)))+(((IkReal(-1.00000000000000))*(r00)*(x2522)*(x2523))));
09189 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  )
09190 {
09191 {
09192 IkReal j2array[1], cj2array[1], sj2array[1];
09193 bool j2valid[1]={false};
09194 _nj2 = 1;
09195 IkReal x2531=((cj4)*(npz));
09196 IkReal x2532=((IkReal(2.94476514910275))*(cj5));
09197 IkReal x2533=((npx)*(sj4));
09198 IkReal x2534=((IkReal(2.34381456633434))*(sj5));
09199 IkReal x2535=((npy)*(sj4));
09200 IkReal x2536=((IkReal(2.94476514910275))*(sj5));
09201 IkReal x2537=((IkReal(2.34381456633434))*(cj5));
09202 if( IKabs(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x2531)))+(((IkReal(-1.00000000000000))*(x2534)*(x2535)))+(((IkReal(-1.00000000000000))*(npx)*(x2536)))+(((x2533)*(x2537)))+(((IkReal(-1.00000000000000))*(npy)*(x2532))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x2531)))+(((IkReal(-1.00000000000000))*(npx)*(x2534)))+(((IkReal(-1.00000000000000))*(npy)*(x2537)))+(((IkReal(-1.00000000000000))*(x2532)*(x2533)))+(((x2535)*(x2536))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x2531)))+(((IkReal(-1.00000000000000))*(x2534)*(x2535)))+(((IkReal(-1.00000000000000))*(npx)*(x2536)))+(((x2533)*(x2537)))+(((IkReal(-1.00000000000000))*(npy)*(x2532)))))+IKsqr(((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x2531)))+(((IkReal(-1.00000000000000))*(npx)*(x2534)))+(((IkReal(-1.00000000000000))*(npy)*(x2537)))+(((IkReal(-1.00000000000000))*(x2532)*(x2533)))+(((x2535)*(x2536)))))-1) <= IKFAST_SINCOS_THRESH )
09203     continue;
09204 j2array[0]=IKatan2(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x2531)))+(((IkReal(-1.00000000000000))*(x2534)*(x2535)))+(((IkReal(-1.00000000000000))*(npx)*(x2536)))+(((x2533)*(x2537)))+(((IkReal(-1.00000000000000))*(npy)*(x2532)))), ((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x2531)))+(((IkReal(-1.00000000000000))*(npx)*(x2534)))+(((IkReal(-1.00000000000000))*(npy)*(x2537)))+(((IkReal(-1.00000000000000))*(x2532)*(x2533)))+(((x2535)*(x2536)))));
09205 sj2array[0]=IKsin(j2array[0]);
09206 cj2array[0]=IKcos(j2array[0]);
09207 if( j2array[0] > IKPI )
09208 {
09209     j2array[0]-=IK2PI;
09210 }
09211 else if( j2array[0] < -IKPI )
09212 {    j2array[0]+=IK2PI;
09213 }
09214 j2valid[0] = true;
09215 for(int ij2 = 0; ij2 < 1; ++ij2)
09216 {
09217 if( !j2valid[ij2] )
09218 {
09219     continue;
09220 }
09221 _ij2[0] = ij2; _ij2[1] = -1;
09222 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
09223 {
09224 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
09225 {
09226     j2valid[iij2]=false; _ij2[1] = iij2; break; 
09227 }
09228 }
09229 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
09230 {
09231 IkReal evalcond[2];
09232 IkReal x2538=IKcos(j2);
09233 IkReal x2539=IKsin(j2);
09234 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((IkReal(0.165463933124939))*(x2539)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x2538))));
09235 evalcond[1]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.165463933124939))*(x2538)))+(((cj5)*(npy)))+(((IkReal(0.207888640466058))*(x2539))));
09236 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09237 {
09238 continue;
09239 }
09240 }
09241 
09242 {
09243 IkReal dummyeval[1];
09244 IkReal gconst50;
09245 gconst50=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
09246 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
09247 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09248 {
09249 {
09250 IkReal dummyeval[1];
09251 IkReal gconst51;
09252 gconst51=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
09253 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
09254 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09255 {
09256 continue;
09257 
09258 } else
09259 {
09260 {
09261 IkReal j1array[1], cj1array[1], sj1array[1];
09262 bool j1valid[1]={false};
09263 _nj1 = 1;
09264 IkReal x2540=((cj5)*(r11));
09265 IkReal x2541=((r10)*(sj0));
09266 IkReal x2542=((IkReal(0.707103562373095))*(cj2));
09267 IkReal x2543=((r20)*(sj5));
09268 IkReal x2544=((IkReal(0.707103562373095))*(sj2));
09269 IkReal x2545=((IkReal(0.707109999985348))*(cj2));
09270 IkReal x2546=((cj0)*(r00));
09271 IkReal x2547=((IkReal(0.707109999985348))*(sj2));
09272 IkReal x2548=((cj5)*(r21));
09273 IkReal x2549=((sj0)*(x2544));
09274 IkReal x2550=((sj5)*(x2545));
09275 IkReal x2551=((cj0)*(cj5)*(r01));
09276 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x2543)*(x2547)))+(((sj5)*(x2544)*(x2546)))+(((sj0)*(x2540)*(x2545)))+(((x2542)*(x2548)))+(((x2542)*(x2543)))+(((sj5)*(x2541)*(x2544)))+(((x2541)*(x2550)))+(((x2540)*(x2549)))+(((x2544)*(x2551)))+(((x2545)*(x2551)))+(((IkReal(-1.00000000000000))*(x2547)*(x2548)))+(((x2546)*(x2550))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(sj5)*(x2541)*(x2542)))+(((sj5)*(x2546)*(x2547)))+(((IkReal(-1.00000000000000))*(x2542)*(x2551)))+(((x2547)*(x2551)))+(((IkReal(-1.00000000000000))*(sj5)*(x2542)*(x2546)))+(((x2543)*(x2544)))+(((x2543)*(x2545)))+(((sj0)*(x2540)*(x2547)))+(((sj5)*(x2541)*(x2547)))+(((x2545)*(x2548)))+(((IkReal(-1.00000000000000))*(sj0)*(x2540)*(x2542)))+(((x2544)*(x2548))))))) < IKFAST_ATAN2_MAGTHRESH )
09277     continue;
09278 j1array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x2543)*(x2547)))+(((sj5)*(x2544)*(x2546)))+(((sj0)*(x2540)*(x2545)))+(((x2542)*(x2548)))+(((x2542)*(x2543)))+(((sj5)*(x2541)*(x2544)))+(((x2541)*(x2550)))+(((x2540)*(x2549)))+(((x2544)*(x2551)))+(((x2545)*(x2551)))+(((IkReal(-1.00000000000000))*(x2547)*(x2548)))+(((x2546)*(x2550)))))), ((gconst51)*(((((IkReal(-1.00000000000000))*(sj5)*(x2541)*(x2542)))+(((sj5)*(x2546)*(x2547)))+(((IkReal(-1.00000000000000))*(x2542)*(x2551)))+(((x2547)*(x2551)))+(((IkReal(-1.00000000000000))*(sj5)*(x2542)*(x2546)))+(((x2543)*(x2544)))+(((x2543)*(x2545)))+(((sj0)*(x2540)*(x2547)))+(((sj5)*(x2541)*(x2547)))+(((x2545)*(x2548)))+(((IkReal(-1.00000000000000))*(sj0)*(x2540)*(x2542)))+(((x2544)*(x2548)))))));
09279 sj1array[0]=IKsin(j1array[0]);
09280 cj1array[0]=IKcos(j1array[0]);
09281 if( j1array[0] > IKPI )
09282 {
09283     j1array[0]-=IK2PI;
09284 }
09285 else if( j1array[0] < -IKPI )
09286 {    j1array[0]+=IK2PI;
09287 }
09288 j1valid[0] = true;
09289 for(int ij1 = 0; ij1 < 1; ++ij1)
09290 {
09291 if( !j1valid[ij1] )
09292 {
09293     continue;
09294 }
09295 _ij1[0] = ij1; _ij1[1] = -1;
09296 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
09297 {
09298 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
09299 {
09300     j1valid[iij1]=false; _ij1[1] = iij1; break; 
09301 }
09302 }
09303 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
09304 {
09305 IkReal evalcond[4];
09306 IkReal x2552=IKcos(j1);
09307 IkReal x2553=IKsin(j1);
09308 IkReal x2554=((IkReal(0.707109999985348))*(cj2));
09309 IkReal x2555=((IkReal(1.00000000000000))*(cj0));
09310 IkReal x2556=((IkReal(0.707109999985348))*(sj2));
09311 IkReal x2557=((cj5)*(sj4));
09312 IkReal x2558=((sj4)*(sj5));
09313 IkReal x2559=((IkReal(1.00000000000000))*(sj0));
09314 IkReal x2560=((sj5)*(x2559));
09315 IkReal x2561=((IkReal(0.707103562373095))*(x2552));
09316 IkReal x2562=((IkReal(0.707103562373095))*(x2553));
09317 IkReal x2563=((cj2)*(x2561));
09318 IkReal x2564=((x2553)*(x2554));
09319 IkReal x2565=((sj2)*(x2562));
09320 IkReal x2566=((x2552)*(x2556));
09321 IkReal x2567=((sj2)*(x2561));
09322 IkReal x2568=((cj2)*(x2562));
09323 IkReal x2569=((x2552)*(x2554));
09324 IkReal x2570=((x2553)*(x2556));
09325 IkReal x2571=((x2569)+(x2568)+(x2567));
09326 IkReal x2572=((x2565)+(x2564)+(x2566));
09327 evalcond[0]=((((cj5)*(r21)))+(x2571)+(((IkReal(-1.00000000000000))*(x2570)))+(((r20)*(sj5))));
09328 evalcond[1]=((x2572)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2557)))+(((IkReal(-1.00000000000000))*(x2563)))+(((r21)*(x2558))));
09329 evalcond[2]=((x2563)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2559)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2555)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2555)))+(((IkReal(-1.00000000000000))*(x2572)))+(((IkReal(-1.00000000000000))*(r10)*(x2560))));
09330 evalcond[3]=((x2571)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2559)))+(((cj0)*(r00)*(x2557)))+(((IkReal(-1.00000000000000))*(x2570)))+(((IkReal(-1.00000000000000))*(r01)*(x2555)*(x2558)))+(((r10)*(sj0)*(x2557)))+(((IkReal(-1.00000000000000))*(r11)*(x2558)*(x2559)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2555))));
09331 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09332 {
09333 continue;
09334 }
09335 }
09336 
09337 {
09338 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09339 vinfos[0].jointtype = 1;
09340 vinfos[0].foffset = j0;
09341 vinfos[0].indices[0] = _ij0[0];
09342 vinfos[0].indices[1] = _ij0[1];
09343 vinfos[0].maxsolutions = _nj0;
09344 vinfos[1].jointtype = 1;
09345 vinfos[1].foffset = j1;
09346 vinfos[1].indices[0] = _ij1[0];
09347 vinfos[1].indices[1] = _ij1[1];
09348 vinfos[1].maxsolutions = _nj1;
09349 vinfos[2].jointtype = 1;
09350 vinfos[2].foffset = j2;
09351 vinfos[2].indices[0] = _ij2[0];
09352 vinfos[2].indices[1] = _ij2[1];
09353 vinfos[2].maxsolutions = _nj2;
09354 vinfos[3].jointtype = 1;
09355 vinfos[3].foffset = j3;
09356 vinfos[3].indices[0] = _ij3[0];
09357 vinfos[3].indices[1] = _ij3[1];
09358 vinfos[3].maxsolutions = _nj3;
09359 vinfos[4].jointtype = 1;
09360 vinfos[4].foffset = j4;
09361 vinfos[4].indices[0] = _ij4[0];
09362 vinfos[4].indices[1] = _ij4[1];
09363 vinfos[4].maxsolutions = _nj4;
09364 vinfos[5].jointtype = 1;
09365 vinfos[5].foffset = j5;
09366 vinfos[5].indices[0] = _ij5[0];
09367 vinfos[5].indices[1] = _ij5[1];
09368 vinfos[5].maxsolutions = _nj5;
09369 std::vector<int> vfree(0);
09370 solutions.AddSolution(vinfos,vfree);
09371 }
09372 }
09373 }
09374 
09375 }
09376 
09377 }
09378 
09379 } else
09380 {
09381 {
09382 IkReal j1array[1], cj1array[1], sj1array[1];
09383 bool j1valid[1]={false};
09384 _nj1 = 1;
09385 IkReal x2573=((cj5)*(sj4));
09386 IkReal x2574=((r21)*(sj4));
09387 IkReal x2575=((cj5)*(r21));
09388 IkReal x2576=((IkReal(0.707109999985348))*(cj2));
09389 IkReal x2577=((IkReal(0.707103562373095))*(sj2));
09390 IkReal x2578=((IkReal(0.707109999985348))*(sj2));
09391 IkReal x2579=((cj4)*(r22));
09392 IkReal x2580=((IkReal(0.707103562373095))*(cj2));
09393 IkReal x2581=((r20)*(x2576));
09394 IkReal x2582=((sj5)*(x2580));
09395 IkReal x2583=((sj5)*(x2578));
09396 if( IKabs(((gconst50)*(((((r20)*(x2573)*(x2577)))+(((x2575)*(x2578)))+(((IkReal(-1.00000000000000))*(r20)*(x2582)))+(((r20)*(x2583)))+(((IkReal(-1.00000000000000))*(sj5)*(x2574)*(x2576)))+(((IkReal(-1.00000000000000))*(sj5)*(x2574)*(x2577)))+(((x2573)*(x2581)))+(((IkReal(-1.00000000000000))*(x2575)*(x2580)))+(((IkReal(-1.00000000000000))*(x2577)*(x2579)))+(((IkReal(-1.00000000000000))*(x2576)*(x2579))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x2575)*(x2577)))+(((IkReal(-1.00000000000000))*(x2575)*(x2576)))+(((r20)*(x2573)*(x2578)))+(((x2574)*(x2582)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2577)))+(((IkReal(-1.00000000000000))*(sj5)*(x2581)))+(((IkReal(-1.00000000000000))*(x2578)*(x2579)))+(((IkReal(-1.00000000000000))*(r20)*(x2573)*(x2580)))+(((x2579)*(x2580)))+(((IkReal(-1.00000000000000))*(x2574)*(x2583))))))) < IKFAST_ATAN2_MAGTHRESH )
09397     continue;
09398 j1array[0]=IKatan2(((gconst50)*(((((r20)*(x2573)*(x2577)))+(((x2575)*(x2578)))+(((IkReal(-1.00000000000000))*(r20)*(x2582)))+(((r20)*(x2583)))+(((IkReal(-1.00000000000000))*(sj5)*(x2574)*(x2576)))+(((IkReal(-1.00000000000000))*(sj5)*(x2574)*(x2577)))+(((x2573)*(x2581)))+(((IkReal(-1.00000000000000))*(x2575)*(x2580)))+(((IkReal(-1.00000000000000))*(x2577)*(x2579)))+(((IkReal(-1.00000000000000))*(x2576)*(x2579)))))), ((gconst50)*(((((IkReal(-1.00000000000000))*(x2575)*(x2577)))+(((IkReal(-1.00000000000000))*(x2575)*(x2576)))+(((r20)*(x2573)*(x2578)))+(((x2574)*(x2582)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2577)))+(((IkReal(-1.00000000000000))*(sj5)*(x2581)))+(((IkReal(-1.00000000000000))*(x2578)*(x2579)))+(((IkReal(-1.00000000000000))*(r20)*(x2573)*(x2580)))+(((x2579)*(x2580)))+(((IkReal(-1.00000000000000))*(x2574)*(x2583)))))));
09399 sj1array[0]=IKsin(j1array[0]);
09400 cj1array[0]=IKcos(j1array[0]);
09401 if( j1array[0] > IKPI )
09402 {
09403     j1array[0]-=IK2PI;
09404 }
09405 else if( j1array[0] < -IKPI )
09406 {    j1array[0]+=IK2PI;
09407 }
09408 j1valid[0] = true;
09409 for(int ij1 = 0; ij1 < 1; ++ij1)
09410 {
09411 if( !j1valid[ij1] )
09412 {
09413     continue;
09414 }
09415 _ij1[0] = ij1; _ij1[1] = -1;
09416 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
09417 {
09418 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
09419 {
09420     j1valid[iij1]=false; _ij1[1] = iij1; break; 
09421 }
09422 }
09423 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
09424 {
09425 IkReal evalcond[4];
09426 IkReal x2584=IKcos(j1);
09427 IkReal x2585=IKsin(j1);
09428 IkReal x2586=((IkReal(0.707109999985348))*(cj2));
09429 IkReal x2587=((IkReal(1.00000000000000))*(cj0));
09430 IkReal x2588=((IkReal(0.707109999985348))*(sj2));
09431 IkReal x2589=((cj5)*(sj4));
09432 IkReal x2590=((sj4)*(sj5));
09433 IkReal x2591=((IkReal(1.00000000000000))*(sj0));
09434 IkReal x2592=((sj5)*(x2591));
09435 IkReal x2593=((IkReal(0.707103562373095))*(x2584));
09436 IkReal x2594=((IkReal(0.707103562373095))*(x2585));
09437 IkReal x2595=((cj2)*(x2593));
09438 IkReal x2596=((x2585)*(x2586));
09439 IkReal x2597=((sj2)*(x2594));
09440 IkReal x2598=((x2584)*(x2588));
09441 IkReal x2599=((sj2)*(x2593));
09442 IkReal x2600=((cj2)*(x2594));
09443 IkReal x2601=((x2584)*(x2586));
09444 IkReal x2602=((x2585)*(x2588));
09445 IkReal x2603=((x2599)+(x2600)+(x2601));
09446 IkReal x2604=((x2596)+(x2597)+(x2598));
09447 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2602)))+(((r20)*(sj5)))+(x2603));
09448 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2595)))+(((IkReal(-1.00000000000000))*(r20)*(x2589)))+(x2604)+(((r21)*(x2590))));
09449 evalcond[2]=((x2595)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2591)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2587)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2587)))+(((IkReal(-1.00000000000000))*(x2604)))+(((IkReal(-1.00000000000000))*(r10)*(x2592))));
09450 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2591)))+(((IkReal(-1.00000000000000))*(r01)*(x2587)*(x2590)))+(((IkReal(-1.00000000000000))*(r11)*(x2590)*(x2591)))+(((cj0)*(r00)*(x2589)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2587)))+(((IkReal(-1.00000000000000))*(x2602)))+(((r10)*(sj0)*(x2589)))+(x2603));
09451 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09452 {
09453 continue;
09454 }
09455 }
09456 
09457 {
09458 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09459 vinfos[0].jointtype = 1;
09460 vinfos[0].foffset = j0;
09461 vinfos[0].indices[0] = _ij0[0];
09462 vinfos[0].indices[1] = _ij0[1];
09463 vinfos[0].maxsolutions = _nj0;
09464 vinfos[1].jointtype = 1;
09465 vinfos[1].foffset = j1;
09466 vinfos[1].indices[0] = _ij1[0];
09467 vinfos[1].indices[1] = _ij1[1];
09468 vinfos[1].maxsolutions = _nj1;
09469 vinfos[2].jointtype = 1;
09470 vinfos[2].foffset = j2;
09471 vinfos[2].indices[0] = _ij2[0];
09472 vinfos[2].indices[1] = _ij2[1];
09473 vinfos[2].maxsolutions = _nj2;
09474 vinfos[3].jointtype = 1;
09475 vinfos[3].foffset = j3;
09476 vinfos[3].indices[0] = _ij3[0];
09477 vinfos[3].indices[1] = _ij3[1];
09478 vinfos[3].maxsolutions = _nj3;
09479 vinfos[4].jointtype = 1;
09480 vinfos[4].foffset = j4;
09481 vinfos[4].indices[0] = _ij4[0];
09482 vinfos[4].indices[1] = _ij4[1];
09483 vinfos[4].maxsolutions = _nj4;
09484 vinfos[5].jointtype = 1;
09485 vinfos[5].foffset = j5;
09486 vinfos[5].indices[0] = _ij5[0];
09487 vinfos[5].indices[1] = _ij5[1];
09488 vinfos[5].maxsolutions = _nj5;
09489 std::vector<int> vfree(0);
09490 solutions.AddSolution(vinfos,vfree);
09491 }
09492 }
09493 }
09494 
09495 }
09496 
09497 }
09498 }
09499 }
09500 
09501 } else
09502 {
09503 IkReal x2605=((sj0)*(sj4));
09504 IkReal x2606=((IkReal(1.00000000000000))*(r12));
09505 IkReal x2607=((IkReal(1.00000000000000))*(cj0));
09506 IkReal x2608=((cj4)*(cj5));
09507 IkReal x2609=((r11)*(sj5));
09508 IkReal x2610=((cj4)*(sj0));
09509 IkReal x2611=((IkReal(1.00000000000000))*(sj5));
09510 IkReal x2612=((cj0)*(cj4));
09511 IkReal x2613=((r00)*(sj0));
09512 IkReal x2614=((cj0)*(sj4));
09513 IkReal x2615=((r01)*(sj5));
09514 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
09515 evalcond[1]=((((sj5)*(x2613)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2607)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2607))));
09516 evalcond[2]=((IkReal(0.00600000000000000))+(((npx)*(x2608)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x2611)))+(((npz)*(sj4))));
09517 evalcond[3]=((((IkReal(-1.00000000000000))*(x2606)*(x2612)))+(((cj5)*(r10)*(x2614)))+(((r02)*(x2610)))+(((x2605)*(x2615)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x2605)))+(((IkReal(-1.00000000000000))*(sj4)*(x2607)*(x2609))));
09518 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x2606)*(x2614)))+(((IkReal(-1.00000000000000))*(r01)*(x2610)*(x2611)))+(((x2608)*(x2613)))+(((r02)*(x2605)))+(((x2609)*(x2612)))+(((IkReal(-1.00000000000000))*(r10)*(x2607)*(x2608))));
09519 evalcond[5]=((((r20)*(x2608)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x2611))));
09520 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2607)))+(((x2609)*(x2610)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x2608)))+(((IkReal(-1.00000000000000))*(r00)*(x2607)*(x2608)))+(((x2612)*(x2615)))+(((IkReal(-1.00000000000000))*(x2605)*(x2606))));
09521 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  )
09522 {
09523 {
09524 IkReal j2array[1], cj2array[1], sj2array[1];
09525 bool j2valid[1]={false};
09526 _nj2 = 1;
09527 IkReal x2616=((cj4)*(npz));
09528 IkReal x2617=((IkReal(2.94476514910275))*(cj5));
09529 IkReal x2618=((npx)*(sj4));
09530 IkReal x2619=((IkReal(2.34381456633434))*(sj5));
09531 IkReal x2620=((npy)*(sj4));
09532 IkReal x2621=((IkReal(2.94476514910275))*(sj5));
09533 IkReal x2622=((IkReal(2.34381456633434))*(cj5));
09534 if( IKabs(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(x2619)*(x2620)))+(((IkReal(-1.00000000000000))*(npx)*(x2621)))+(((IkReal(-1.00000000000000))*(npy)*(x2617)))+(((x2618)*(x2622)))+(((IkReal(-2.34381456633434))*(x2616))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(x2617)*(x2618)))+(((IkReal(-1.00000000000000))*(npx)*(x2619)))+(((IkReal(-1.00000000000000))*(npy)*(x2622)))+(((x2620)*(x2621)))+(((IkReal(2.94476514910275))*(x2616))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(x2619)*(x2620)))+(((IkReal(-1.00000000000000))*(npx)*(x2621)))+(((IkReal(-1.00000000000000))*(npy)*(x2617)))+(((x2618)*(x2622)))+(((IkReal(-2.34381456633434))*(x2616)))))+IKsqr(((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(x2617)*(x2618)))+(((IkReal(-1.00000000000000))*(npx)*(x2619)))+(((IkReal(-1.00000000000000))*(npy)*(x2622)))+(((x2620)*(x2621)))+(((IkReal(2.94476514910275))*(x2616)))))-1) <= IKFAST_SINCOS_THRESH )
09535     continue;
09536 j2array[0]=IKatan2(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(x2619)*(x2620)))+(((IkReal(-1.00000000000000))*(npx)*(x2621)))+(((IkReal(-1.00000000000000))*(npy)*(x2617)))+(((x2618)*(x2622)))+(((IkReal(-2.34381456633434))*(x2616)))), ((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(x2617)*(x2618)))+(((IkReal(-1.00000000000000))*(npx)*(x2619)))+(((IkReal(-1.00000000000000))*(npy)*(x2622)))+(((x2620)*(x2621)))+(((IkReal(2.94476514910275))*(x2616)))));
09537 sj2array[0]=IKsin(j2array[0]);
09538 cj2array[0]=IKcos(j2array[0]);
09539 if( j2array[0] > IKPI )
09540 {
09541     j2array[0]-=IK2PI;
09542 }
09543 else if( j2array[0] < -IKPI )
09544 {    j2array[0]+=IK2PI;
09545 }
09546 j2valid[0] = true;
09547 for(int ij2 = 0; ij2 < 1; ++ij2)
09548 {
09549 if( !j2valid[ij2] )
09550 {
09551     continue;
09552 }
09553 _ij2[0] = ij2; _ij2[1] = -1;
09554 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
09555 {
09556 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
09557 {
09558     j2valid[iij2]=false; _ij2[1] = iij2; break; 
09559 }
09560 }
09561 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
09562 {
09563 IkReal evalcond[2];
09564 IkReal x2623=IKcos(j2);
09565 IkReal x2624=IKsin(j2);
09566 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(x2623)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((IkReal(0.165463933124939))*(x2624)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz))));
09567 evalcond[1]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.165463933124939))*(x2623)))+(((cj5)*(npy)))+(((IkReal(0.207888640466058))*(x2624))));
09568 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09569 {
09570 continue;
09571 }
09572 }
09573 
09574 {
09575 IkReal dummyeval[1];
09576 IkReal gconst52;
09577 gconst52=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
09578 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
09579 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09580 {
09581 {
09582 IkReal dummyeval[1];
09583 IkReal gconst53;
09584 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
09585 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
09586 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09587 {
09588 continue;
09589 
09590 } else
09591 {
09592 {
09593 IkReal j1array[1], cj1array[1], sj1array[1];
09594 bool j1valid[1]={false};
09595 _nj1 = 1;
09596 IkReal x2625=((cj5)*(r11));
09597 IkReal x2626=((r10)*(sj0));
09598 IkReal x2627=((IkReal(0.707103562373095))*(cj2));
09599 IkReal x2628=((r20)*(sj5));
09600 IkReal x2629=((IkReal(0.707103562373095))*(sj2));
09601 IkReal x2630=((IkReal(0.707109999985348))*(cj2));
09602 IkReal x2631=((cj0)*(r00));
09603 IkReal x2632=((IkReal(0.707109999985348))*(sj2));
09604 IkReal x2633=((cj5)*(r21));
09605 IkReal x2634=((sj0)*(x2629));
09606 IkReal x2635=((sj5)*(x2630));
09607 IkReal x2636=((cj0)*(cj5)*(r01));
09608 if( IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(x2628)*(x2632)))+(((sj0)*(x2625)*(x2630)))+(((x2627)*(x2628)))+(((x2625)*(x2634)))+(((sj5)*(x2629)*(x2631)))+(((IkReal(-1.00000000000000))*(x2632)*(x2633)))+(((x2630)*(x2636)))+(((sj5)*(x2626)*(x2629)))+(((x2631)*(x2635)))+(((x2627)*(x2633)))+(((x2626)*(x2635)))+(((x2629)*(x2636))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((x2628)*(x2629)))+(((IkReal(-1.00000000000000))*(sj5)*(x2626)*(x2627)))+(((IkReal(-1.00000000000000))*(sj0)*(x2625)*(x2627)))+(((sj5)*(x2626)*(x2632)))+(((sj0)*(x2625)*(x2632)))+(((sj5)*(x2631)*(x2632)))+(((x2632)*(x2636)))+(((x2628)*(x2630)))+(((IkReal(-1.00000000000000))*(sj5)*(x2627)*(x2631)))+(((x2630)*(x2633)))+(((x2629)*(x2633)))+(((IkReal(-1.00000000000000))*(x2627)*(x2636))))))) < IKFAST_ATAN2_MAGTHRESH )
09609     continue;
09610 j1array[0]=IKatan2(((gconst53)*(((((IkReal(-1.00000000000000))*(x2628)*(x2632)))+(((sj0)*(x2625)*(x2630)))+(((x2627)*(x2628)))+(((x2625)*(x2634)))+(((sj5)*(x2629)*(x2631)))+(((IkReal(-1.00000000000000))*(x2632)*(x2633)))+(((x2630)*(x2636)))+(((sj5)*(x2626)*(x2629)))+(((x2631)*(x2635)))+(((x2627)*(x2633)))+(((x2626)*(x2635)))+(((x2629)*(x2636)))))), ((gconst53)*(((((x2628)*(x2629)))+(((IkReal(-1.00000000000000))*(sj5)*(x2626)*(x2627)))+(((IkReal(-1.00000000000000))*(sj0)*(x2625)*(x2627)))+(((sj5)*(x2626)*(x2632)))+(((sj0)*(x2625)*(x2632)))+(((sj5)*(x2631)*(x2632)))+(((x2632)*(x2636)))+(((x2628)*(x2630)))+(((IkReal(-1.00000000000000))*(sj5)*(x2627)*(x2631)))+(((x2630)*(x2633)))+(((x2629)*(x2633)))+(((IkReal(-1.00000000000000))*(x2627)*(x2636)))))));
09611 sj1array[0]=IKsin(j1array[0]);
09612 cj1array[0]=IKcos(j1array[0]);
09613 if( j1array[0] > IKPI )
09614 {
09615     j1array[0]-=IK2PI;
09616 }
09617 else if( j1array[0] < -IKPI )
09618 {    j1array[0]+=IK2PI;
09619 }
09620 j1valid[0] = true;
09621 for(int ij1 = 0; ij1 < 1; ++ij1)
09622 {
09623 if( !j1valid[ij1] )
09624 {
09625     continue;
09626 }
09627 _ij1[0] = ij1; _ij1[1] = -1;
09628 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
09629 {
09630 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
09631 {
09632     j1valid[iij1]=false; _ij1[1] = iij1; break; 
09633 }
09634 }
09635 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
09636 {
09637 IkReal evalcond[4];
09638 IkReal x2637=IKcos(j1);
09639 IkReal x2638=IKsin(j1);
09640 IkReal x2639=((IkReal(0.707109999985348))*(cj2));
09641 IkReal x2640=((IkReal(1.00000000000000))*(cj0));
09642 IkReal x2641=((IkReal(0.707109999985348))*(sj2));
09643 IkReal x2642=((cj5)*(sj4));
09644 IkReal x2643=((sj4)*(sj5));
09645 IkReal x2644=((IkReal(1.00000000000000))*(sj0));
09646 IkReal x2645=((sj5)*(x2644));
09647 IkReal x2646=((IkReal(0.707103562373095))*(x2637));
09648 IkReal x2647=((IkReal(0.707103562373095))*(x2638));
09649 IkReal x2648=((cj2)*(x2646));
09650 IkReal x2649=((x2638)*(x2639));
09651 IkReal x2650=((sj2)*(x2647));
09652 IkReal x2651=((x2637)*(x2641));
09653 IkReal x2652=((sj2)*(x2646));
09654 IkReal x2653=((cj2)*(x2647));
09655 IkReal x2654=((x2637)*(x2639));
09656 IkReal x2655=((x2638)*(x2641));
09657 IkReal x2656=((x2653)+(x2652)+(x2654));
09658 IkReal x2657=((x2649)+(x2651)+(x2650));
09659 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2655)))+(((r20)*(sj5)))+(x2656));
09660 evalcond[1]=((((r21)*(x2643)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2648)))+(((IkReal(-1.00000000000000))*(r20)*(x2642)))+(x2657));
09661 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2640)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2644)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2640)))+(((IkReal(-1.00000000000000))*(x2657)))+(((IkReal(-1.00000000000000))*(r10)*(x2645)))+(x2648));
09662 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2640)*(x2643)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2644)))+(((IkReal(-1.00000000000000))*(r11)*(x2643)*(x2644)))+(((cj0)*(r00)*(x2642)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2640)))+(((IkReal(-1.00000000000000))*(x2655)))+(((r10)*(sj0)*(x2642)))+(x2656));
09663 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09664 {
09665 continue;
09666 }
09667 }
09668 
09669 {
09670 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09671 vinfos[0].jointtype = 1;
09672 vinfos[0].foffset = j0;
09673 vinfos[0].indices[0] = _ij0[0];
09674 vinfos[0].indices[1] = _ij0[1];
09675 vinfos[0].maxsolutions = _nj0;
09676 vinfos[1].jointtype = 1;
09677 vinfos[1].foffset = j1;
09678 vinfos[1].indices[0] = _ij1[0];
09679 vinfos[1].indices[1] = _ij1[1];
09680 vinfos[1].maxsolutions = _nj1;
09681 vinfos[2].jointtype = 1;
09682 vinfos[2].foffset = j2;
09683 vinfos[2].indices[0] = _ij2[0];
09684 vinfos[2].indices[1] = _ij2[1];
09685 vinfos[2].maxsolutions = _nj2;
09686 vinfos[3].jointtype = 1;
09687 vinfos[3].foffset = j3;
09688 vinfos[3].indices[0] = _ij3[0];
09689 vinfos[3].indices[1] = _ij3[1];
09690 vinfos[3].maxsolutions = _nj3;
09691 vinfos[4].jointtype = 1;
09692 vinfos[4].foffset = j4;
09693 vinfos[4].indices[0] = _ij4[0];
09694 vinfos[4].indices[1] = _ij4[1];
09695 vinfos[4].maxsolutions = _nj4;
09696 vinfos[5].jointtype = 1;
09697 vinfos[5].foffset = j5;
09698 vinfos[5].indices[0] = _ij5[0];
09699 vinfos[5].indices[1] = _ij5[1];
09700 vinfos[5].maxsolutions = _nj5;
09701 std::vector<int> vfree(0);
09702 solutions.AddSolution(vinfos,vfree);
09703 }
09704 }
09705 }
09706 
09707 }
09708 
09709 }
09710 
09711 } else
09712 {
09713 {
09714 IkReal j1array[1], cj1array[1], sj1array[1];
09715 bool j1valid[1]={false};
09716 _nj1 = 1;
09717 IkReal x2658=((cj5)*(sj4));
09718 IkReal x2659=((r21)*(sj4));
09719 IkReal x2660=((cj5)*(r21));
09720 IkReal x2661=((IkReal(0.707109999985348))*(cj2));
09721 IkReal x2662=((IkReal(0.707103562373095))*(sj2));
09722 IkReal x2663=((IkReal(0.707109999985348))*(sj2));
09723 IkReal x2664=((cj4)*(r22));
09724 IkReal x2665=((IkReal(0.707103562373095))*(cj2));
09725 IkReal x2666=((r20)*(x2661));
09726 IkReal x2667=((sj5)*(x2665));
09727 IkReal x2668=((sj5)*(x2663));
09728 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x2660)*(x2665)))+(((x2658)*(x2666)))+(((IkReal(-1.00000000000000))*(sj5)*(x2659)*(x2662)))+(((IkReal(-1.00000000000000))*(sj5)*(x2659)*(x2661)))+(((r20)*(x2658)*(x2662)))+(((IkReal(-1.00000000000000))*(x2662)*(x2664)))+(((IkReal(-1.00000000000000))*(r20)*(x2667)))+(((x2660)*(x2663)))+(((r20)*(x2668)))+(((IkReal(-1.00000000000000))*(x2661)*(x2664))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x2660)*(x2662)))+(((IkReal(-1.00000000000000))*(x2660)*(x2661)))+(((x2659)*(x2667)))+(((IkReal(-1.00000000000000))*(r20)*(x2658)*(x2665)))+(((r20)*(x2658)*(x2663)))+(((x2664)*(x2665)))+(((IkReal(-1.00000000000000))*(x2663)*(x2664)))+(((IkReal(-1.00000000000000))*(x2659)*(x2668)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2662)))+(((IkReal(-1.00000000000000))*(sj5)*(x2666))))))) < IKFAST_ATAN2_MAGTHRESH )
09729     continue;
09730 j1array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(x2660)*(x2665)))+(((x2658)*(x2666)))+(((IkReal(-1.00000000000000))*(sj5)*(x2659)*(x2662)))+(((IkReal(-1.00000000000000))*(sj5)*(x2659)*(x2661)))+(((r20)*(x2658)*(x2662)))+(((IkReal(-1.00000000000000))*(x2662)*(x2664)))+(((IkReal(-1.00000000000000))*(r20)*(x2667)))+(((x2660)*(x2663)))+(((r20)*(x2668)))+(((IkReal(-1.00000000000000))*(x2661)*(x2664)))))), ((gconst52)*(((((IkReal(-1.00000000000000))*(x2660)*(x2662)))+(((IkReal(-1.00000000000000))*(x2660)*(x2661)))+(((x2659)*(x2667)))+(((IkReal(-1.00000000000000))*(r20)*(x2658)*(x2665)))+(((r20)*(x2658)*(x2663)))+(((x2664)*(x2665)))+(((IkReal(-1.00000000000000))*(x2663)*(x2664)))+(((IkReal(-1.00000000000000))*(x2659)*(x2668)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2662)))+(((IkReal(-1.00000000000000))*(sj5)*(x2666)))))));
09731 sj1array[0]=IKsin(j1array[0]);
09732 cj1array[0]=IKcos(j1array[0]);
09733 if( j1array[0] > IKPI )
09734 {
09735     j1array[0]-=IK2PI;
09736 }
09737 else if( j1array[0] < -IKPI )
09738 {    j1array[0]+=IK2PI;
09739 }
09740 j1valid[0] = true;
09741 for(int ij1 = 0; ij1 < 1; ++ij1)
09742 {
09743 if( !j1valid[ij1] )
09744 {
09745     continue;
09746 }
09747 _ij1[0] = ij1; _ij1[1] = -1;
09748 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
09749 {
09750 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
09751 {
09752     j1valid[iij1]=false; _ij1[1] = iij1; break; 
09753 }
09754 }
09755 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
09756 {
09757 IkReal evalcond[4];
09758 IkReal x2669=IKcos(j1);
09759 IkReal x2670=IKsin(j1);
09760 IkReal x2671=((IkReal(0.707109999985348))*(cj2));
09761 IkReal x2672=((IkReal(1.00000000000000))*(cj0));
09762 IkReal x2673=((IkReal(0.707109999985348))*(sj2));
09763 IkReal x2674=((cj5)*(sj4));
09764 IkReal x2675=((sj4)*(sj5));
09765 IkReal x2676=((IkReal(1.00000000000000))*(sj0));
09766 IkReal x2677=((sj5)*(x2676));
09767 IkReal x2678=((IkReal(0.707103562373095))*(x2669));
09768 IkReal x2679=((IkReal(0.707103562373095))*(x2670));
09769 IkReal x2680=((cj2)*(x2678));
09770 IkReal x2681=((x2670)*(x2671));
09771 IkReal x2682=((sj2)*(x2679));
09772 IkReal x2683=((x2669)*(x2673));
09773 IkReal x2684=((sj2)*(x2678));
09774 IkReal x2685=((cj2)*(x2679));
09775 IkReal x2686=((x2669)*(x2671));
09776 IkReal x2687=((x2670)*(x2673));
09777 IkReal x2688=((x2684)+(x2685)+(x2686));
09778 IkReal x2689=((x2681)+(x2682)+(x2683));
09779 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2687)))+(((r20)*(sj5)))+(x2688));
09780 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x2675)))+(((IkReal(-1.00000000000000))*(x2680)))+(((IkReal(-1.00000000000000))*(r20)*(x2674)))+(x2689));
09781 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2676)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2672)))+(((IkReal(-1.00000000000000))*(x2689)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2672)))+(((IkReal(-1.00000000000000))*(r10)*(x2677)))+(x2680));
09782 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2672)*(x2675)))+(((IkReal(-1.00000000000000))*(x2687)))+(((r10)*(sj0)*(x2674)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2672)))+(((IkReal(-1.00000000000000))*(r11)*(x2675)*(x2676)))+(((cj0)*(r00)*(x2674)))+(x2688)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2676))));
09783 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09784 {
09785 continue;
09786 }
09787 }
09788 
09789 {
09790 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09791 vinfos[0].jointtype = 1;
09792 vinfos[0].foffset = j0;
09793 vinfos[0].indices[0] = _ij0[0];
09794 vinfos[0].indices[1] = _ij0[1];
09795 vinfos[0].maxsolutions = _nj0;
09796 vinfos[1].jointtype = 1;
09797 vinfos[1].foffset = j1;
09798 vinfos[1].indices[0] = _ij1[0];
09799 vinfos[1].indices[1] = _ij1[1];
09800 vinfos[1].maxsolutions = _nj1;
09801 vinfos[2].jointtype = 1;
09802 vinfos[2].foffset = j2;
09803 vinfos[2].indices[0] = _ij2[0];
09804 vinfos[2].indices[1] = _ij2[1];
09805 vinfos[2].maxsolutions = _nj2;
09806 vinfos[3].jointtype = 1;
09807 vinfos[3].foffset = j3;
09808 vinfos[3].indices[0] = _ij3[0];
09809 vinfos[3].indices[1] = _ij3[1];
09810 vinfos[3].maxsolutions = _nj3;
09811 vinfos[4].jointtype = 1;
09812 vinfos[4].foffset = j4;
09813 vinfos[4].indices[0] = _ij4[0];
09814 vinfos[4].indices[1] = _ij4[1];
09815 vinfos[4].maxsolutions = _nj4;
09816 vinfos[5].jointtype = 1;
09817 vinfos[5].foffset = j5;
09818 vinfos[5].indices[0] = _ij5[0];
09819 vinfos[5].indices[1] = _ij5[1];
09820 vinfos[5].maxsolutions = _nj5;
09821 std::vector<int> vfree(0);
09822 solutions.AddSolution(vinfos,vfree);
09823 }
09824 }
09825 }
09826 
09827 }
09828 
09829 }
09830 }
09831 }
09832 
09833 } else
09834 {
09835 if( 1 )
09836 {
09837 continue;
09838 
09839 } else
09840 {
09841 }
09842 }
09843 }
09844 }
09845 }
09846 }
09847 
09848 } else
09849 {
09850 {
09851 IkReal j2array[1], cj2array[1], sj2array[1];
09852 bool j2valid[1]={false};
09853 _nj2 = 1;
09854 IkReal x2690=((cj5)*(npx));
09855 IkReal x2691=((IkReal(8.66210554726807e+23))*(cj4));
09856 IkReal x2692=((npz)*(sj4));
09857 IkReal x2693=((IkReal(6.89439331452234e+23))*(cj3));
09858 IkReal x2694=((npy)*(sj5));
09859 IkReal x2695=((IkReal(6.89439331452234e+23))*(cj4));
09860 IkReal x2696=((IkReal(8.66210554726807e+23))*(cj3)*(sj4));
09861 if( IKabs(((gconst35)*(((((IkReal(-1.00000000000000))*(cj4)*(npz)*(x2693)))+(((x2691)*(x2694)))+(((IkReal(5.19726332836084e+21))*(sj3)))+(((sj4)*(x2690)*(x2693)))+(((IkReal(-1.00000000000000))*(sj4)*(x2693)*(x2694)))+(((IkReal(-8.66210554726807e+23))*(x2692)))+(((IkReal(-1.00000000000000))*(x2690)*(x2691)))+(((IkReal(1.51888207091656e+23))*(cj3))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((IkReal(-6.89439331452234e+23))*(x2692)))+(((IkReal(-2.44170809699545e+23))*(cj3)))+(((cj3)*(npz)*(x2691)))+(((IkReal(4.13663598871341e+21))*(sj3)))+(((x2694)*(x2695)))+(((x2694)*(x2696)))+(((IkReal(-1.00000000000000))*(x2690)*(x2696)))+(((IkReal(-1.00000000000000))*(x2690)*(x2695))))))) < IKFAST_ATAN2_MAGTHRESH )
09862     continue;
09863 j2array[0]=IKatan2(((gconst35)*(((((IkReal(-1.00000000000000))*(cj4)*(npz)*(x2693)))+(((x2691)*(x2694)))+(((IkReal(5.19726332836084e+21))*(sj3)))+(((sj4)*(x2690)*(x2693)))+(((IkReal(-1.00000000000000))*(sj4)*(x2693)*(x2694)))+(((IkReal(-8.66210554726807e+23))*(x2692)))+(((IkReal(-1.00000000000000))*(x2690)*(x2691)))+(((IkReal(1.51888207091656e+23))*(cj3)))))), ((gconst35)*(((((IkReal(-6.89439331452234e+23))*(x2692)))+(((IkReal(-2.44170809699545e+23))*(cj3)))+(((cj3)*(npz)*(x2691)))+(((IkReal(4.13663598871341e+21))*(sj3)))+(((x2694)*(x2695)))+(((x2694)*(x2696)))+(((IkReal(-1.00000000000000))*(x2690)*(x2696)))+(((IkReal(-1.00000000000000))*(x2690)*(x2695)))))));
09864 sj2array[0]=IKsin(j2array[0]);
09865 cj2array[0]=IKcos(j2array[0]);
09866 if( j2array[0] > IKPI )
09867 {
09868     j2array[0]-=IK2PI;
09869 }
09870 else if( j2array[0] < -IKPI )
09871 {    j2array[0]+=IK2PI;
09872 }
09873 j2valid[0] = true;
09874 for(int ij2 = 0; ij2 < 1; ++ij2)
09875 {
09876 if( !j2valid[ij2] )
09877 {
09878     continue;
09879 }
09880 _ij2[0] = ij2; _ij2[1] = -1;
09881 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
09882 {
09883 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
09884 {
09885     j2valid[iij2]=false; _ij2[1] = iij2; break; 
09886 }
09887 }
09888 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
09889 {
09890 IkReal evalcond[3];
09891 IkReal x2697=IKsin(j2);
09892 IkReal x2698=IKcos(j2);
09893 IkReal x2699=((cj5)*(npx));
09894 IkReal x2700=((npy)*(sj5));
09895 IkReal x2701=((IkReal(0.165463933124939))*(x2698));
09896 IkReal x2702=((IkReal(0.207888640466058))*(x2697));
09897 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(sj4)*(x2699)))+(((sj4)*(x2700)))+(((IkReal(0.165463933124939))*(x2697)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x2698))));
09898 evalcond[1]=((IkReal(-0.00600000000000000))+(((IkReal(-0.0300035672348961))*(sj3)))+(((npx)*(sj5)))+(((IkReal(-0.00600000000000000))*(cj3)))+(((cj5)*(npy)))+(((IkReal(-1.00000000000000))*(sj3)*(x2702)))+(((IkReal(-1.00000000000000))*(sj3)*(x2701))));
09899 evalcond[2]=((((npz)*(sj4)))+(((cj4)*(x2699)))+(((IkReal(-0.00600000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(cj4)*(x2700)))+(((cj3)*(x2701)))+(((cj3)*(x2702)))+(((IkReal(0.0300035672348961))*(cj3))));
09900 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
09901 {
09902 continue;
09903 }
09904 }
09905 
09906 {
09907 IkReal dummyeval[1];
09908 IkReal gconst36;
09909 IkReal x2703=((IkReal(1.00000000000000))*(sj3));
09910 gconst36=IKsign(((((IkReal(-1.00000000000000))*(x2703)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x2703)*((cj2)*(cj2))))));
09911 IkReal x2704=((IkReal(1.00000000000000))*(sj3));
09912 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2704)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x2704)*((sj2)*(sj2)))));
09913 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09914 {
09915 {
09916 IkReal dummyeval[1];
09917 IkReal gconst37;
09918 IkReal x2705=((IkReal(1.00000000000000))*(cj3));
09919 gconst37=IKsign(((((IkReal(-1.00000000000000))*(x2705)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x2705)*((sj2)*(sj2))))));
09920 IkReal x2706=((IkReal(1.00000000000000))*(cj3));
09921 dummyeval[0]=((((IkReal(-1.00000000000000))*(x2706)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x2706)*((sj2)*(sj2)))));
09922 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09923 {
09924 {
09925 IkReal evalcond[9];
09926 IkReal x2707=((sj0)*(sj4));
09927 IkReal x2708=((IkReal(1.00000000000000))*(r12));
09928 IkReal x2709=((cj0)*(cj4));
09929 IkReal x2710=((r01)*(sj5));
09930 IkReal x2711=((IkReal(1.00000000000000))*(cj5));
09931 IkReal x2712=((cj4)*(cj5));
09932 IkReal x2713=((IkReal(1.00000000000000))*(cj0));
09933 IkReal x2714=((cj4)*(sj0));
09934 IkReal x2715=((r00)*(sj0));
09935 IkReal x2716=((npy)*(sj5));
09936 IkReal x2717=((IkReal(1.00000000000000))*(cj4));
09937 IkReal x2718=((cj0)*(sj4));
09938 IkReal x2719=((r11)*(sj5));
09939 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
09940 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2713)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2711)))+(((sj5)*(x2715))));
09941 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2711)))+(((sj4)*(x2716)))+(((IkReal(0.165463933124939))*(sj2))));
09942 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
09943 evalcond[4]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x2716)*(x2717)))+(((npx)*(x2712))));
09944 evalcond[5]=((((IkReal(-1.00000000000000))*(x2708)*(x2709)))+(((cj5)*(r10)*(x2718)))+(((x2707)*(x2710)))+(((r02)*(x2714)))+(((IkReal(-1.00000000000000))*(sj4)*(x2713)*(x2719)))+(((IkReal(-1.00000000000000))*(r00)*(x2707)*(x2711))));
09945 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2709)*(x2711)))+(((x2712)*(x2715)))+(((x2709)*(x2719)))+(((IkReal(-1.00000000000000))*(x2710)*(x2714)))+(((IkReal(-1.00000000000000))*(x2708)*(x2718)))+(((r02)*(x2707))));
09946 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2717)))+(((r20)*(x2712))));
09947 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x2709)*(x2711)))+(((x2709)*(x2710)))+(((IkReal(-1.00000000000000))*(x2707)*(x2708)))+(((IkReal(-1.00000000000000))*(r10)*(x2711)*(x2714)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2713)))+(((x2714)*(x2719))));
09948 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  )
09949 {
09950 {
09951 IkReal dummyeval[1];
09952 IkReal gconst38;
09953 gconst38=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
09954 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
09955 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09956 {
09957 {
09958 IkReal dummyeval[1];
09959 IkReal gconst39;
09960 gconst39=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
09961 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
09962 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09963 {
09964 continue;
09965 
09966 } else
09967 {
09968 {
09969 IkReal j1array[1], cj1array[1], sj1array[1];
09970 bool j1valid[1]={false};
09971 _nj1 = 1;
09972 IkReal x2720=((cj5)*(r11));
09973 IkReal x2721=((r10)*(sj0));
09974 IkReal x2722=((IkReal(0.707103562373095))*(cj2));
09975 IkReal x2723=((r20)*(sj5));
09976 IkReal x2724=((IkReal(0.707103562373095))*(sj2));
09977 IkReal x2725=((IkReal(0.707109999985348))*(cj2));
09978 IkReal x2726=((cj0)*(r00));
09979 IkReal x2727=((IkReal(0.707109999985348))*(sj2));
09980 IkReal x2728=((cj5)*(r21));
09981 IkReal x2729=((sj0)*(x2724));
09982 IkReal x2730=((sj5)*(x2725));
09983 IkReal x2731=((cj0)*(cj5)*(r01));
09984 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(x2726)*(x2730)))+(((IkReal(-1.00000000000000))*(x2724)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2721)*(x2724)))+(((IkReal(-1.00000000000000))*(x2725)*(x2731)))+(((IkReal(-1.00000000000000))*(x2722)*(x2728)))+(((IkReal(-1.00000000000000))*(x2722)*(x2723)))+(((IkReal(-1.00000000000000))*(x2720)*(x2729)))+(((x2727)*(x2728)))+(((IkReal(-1.00000000000000))*(sj5)*(x2724)*(x2726)))+(((IkReal(-1.00000000000000))*(x2721)*(x2730)))+(((x2723)*(x2727)))+(((IkReal(-1.00000000000000))*(sj0)*(x2720)*(x2725))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(x2725)*(x2728)))+(((IkReal(-1.00000000000000))*(x2724)*(x2728)))+(((IkReal(-1.00000000000000))*(x2727)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2721)*(x2727)))+(((sj5)*(x2721)*(x2722)))+(((sj0)*(x2720)*(x2722)))+(((IkReal(-1.00000000000000))*(x2723)*(x2724)))+(((IkReal(-1.00000000000000))*(x2723)*(x2725)))+(((sj5)*(x2722)*(x2726)))+(((x2722)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2726)*(x2727)))+(((IkReal(-1.00000000000000))*(sj0)*(x2720)*(x2727))))))) < IKFAST_ATAN2_MAGTHRESH )
09985     continue;
09986 j1array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(x2726)*(x2730)))+(((IkReal(-1.00000000000000))*(x2724)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2721)*(x2724)))+(((IkReal(-1.00000000000000))*(x2725)*(x2731)))+(((IkReal(-1.00000000000000))*(x2722)*(x2728)))+(((IkReal(-1.00000000000000))*(x2722)*(x2723)))+(((IkReal(-1.00000000000000))*(x2720)*(x2729)))+(((x2727)*(x2728)))+(((IkReal(-1.00000000000000))*(sj5)*(x2724)*(x2726)))+(((IkReal(-1.00000000000000))*(x2721)*(x2730)))+(((x2723)*(x2727)))+(((IkReal(-1.00000000000000))*(sj0)*(x2720)*(x2725)))))), ((gconst39)*(((((IkReal(-1.00000000000000))*(x2725)*(x2728)))+(((IkReal(-1.00000000000000))*(x2724)*(x2728)))+(((IkReal(-1.00000000000000))*(x2727)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2721)*(x2727)))+(((sj5)*(x2721)*(x2722)))+(((sj0)*(x2720)*(x2722)))+(((IkReal(-1.00000000000000))*(x2723)*(x2724)))+(((IkReal(-1.00000000000000))*(x2723)*(x2725)))+(((sj5)*(x2722)*(x2726)))+(((x2722)*(x2731)))+(((IkReal(-1.00000000000000))*(sj5)*(x2726)*(x2727)))+(((IkReal(-1.00000000000000))*(sj0)*(x2720)*(x2727)))))));
09987 sj1array[0]=IKsin(j1array[0]);
09988 cj1array[0]=IKcos(j1array[0]);
09989 if( j1array[0] > IKPI )
09990 {
09991     j1array[0]-=IK2PI;
09992 }
09993 else if( j1array[0] < -IKPI )
09994 {    j1array[0]+=IK2PI;
09995 }
09996 j1valid[0] = true;
09997 for(int ij1 = 0; ij1 < 1; ++ij1)
09998 {
09999 if( !j1valid[ij1] )
10000 {
10001     continue;
10002 }
10003 _ij1[0] = ij1; _ij1[1] = -1;
10004 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10005 {
10006 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10007 {
10008     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10009 }
10010 }
10011 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10012 {
10013 IkReal evalcond[4];
10014 IkReal x2732=IKsin(j1);
10015 IkReal x2733=IKcos(j1);
10016 IkReal x2734=((IkReal(0.707109999985348))*(cj2));
10017 IkReal x2735=((IkReal(1.00000000000000))*(cj0));
10018 IkReal x2736=((IkReal(0.707109999985348))*(sj2));
10019 IkReal x2737=((cj5)*(sj4));
10020 IkReal x2738=((sj4)*(sj5));
10021 IkReal x2739=((IkReal(1.00000000000000))*(sj0));
10022 IkReal x2740=((sj5)*(x2739));
10023 IkReal x2741=((IkReal(0.707103562373095))*(x2733));
10024 IkReal x2742=((IkReal(0.707103562373095))*(x2732));
10025 IkReal x2743=((x2732)*(x2734));
10026 IkReal x2744=((sj2)*(x2742));
10027 IkReal x2745=((x2733)*(x2736));
10028 IkReal x2746=((cj2)*(x2741));
10029 IkReal x2747=((sj2)*(x2741));
10030 IkReal x2748=((cj2)*(x2742));
10031 IkReal x2749=((x2733)*(x2734));
10032 IkReal x2750=((x2732)*(x2736));
10033 IkReal x2751=((x2747)+(x2749)+(x2748));
10034 IkReal x2752=((x2743)+(x2745)+(x2744));
10035 evalcond[0]=((x2750)+(((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2751)))+(((r20)*(sj5))));
10036 evalcond[1]=((x2752)+(((cj4)*(r22)))+(((r21)*(x2738)))+(((IkReal(-1.00000000000000))*(r20)*(x2737)))+(((IkReal(-1.00000000000000))*(x2746))));
10037 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2739)))+(x2752)+(((IkReal(-1.00000000000000))*(r10)*(x2740)))+(((IkReal(-1.00000000000000))*(x2746)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2735)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2735))));
10038 evalcond[3]=((x2751)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2739)))+(((IkReal(-1.00000000000000))*(r11)*(x2738)*(x2739)))+(((cj0)*(r00)*(x2737)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2735)))+(((IkReal(-1.00000000000000))*(x2750)))+(((IkReal(-1.00000000000000))*(r01)*(x2735)*(x2738)))+(((r10)*(sj0)*(x2737))));
10039 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10040 {
10041 continue;
10042 }
10043 }
10044 
10045 {
10046 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10047 vinfos[0].jointtype = 1;
10048 vinfos[0].foffset = j0;
10049 vinfos[0].indices[0] = _ij0[0];
10050 vinfos[0].indices[1] = _ij0[1];
10051 vinfos[0].maxsolutions = _nj0;
10052 vinfos[1].jointtype = 1;
10053 vinfos[1].foffset = j1;
10054 vinfos[1].indices[0] = _ij1[0];
10055 vinfos[1].indices[1] = _ij1[1];
10056 vinfos[1].maxsolutions = _nj1;
10057 vinfos[2].jointtype = 1;
10058 vinfos[2].foffset = j2;
10059 vinfos[2].indices[0] = _ij2[0];
10060 vinfos[2].indices[1] = _ij2[1];
10061 vinfos[2].maxsolutions = _nj2;
10062 vinfos[3].jointtype = 1;
10063 vinfos[3].foffset = j3;
10064 vinfos[3].indices[0] = _ij3[0];
10065 vinfos[3].indices[1] = _ij3[1];
10066 vinfos[3].maxsolutions = _nj3;
10067 vinfos[4].jointtype = 1;
10068 vinfos[4].foffset = j4;
10069 vinfos[4].indices[0] = _ij4[0];
10070 vinfos[4].indices[1] = _ij4[1];
10071 vinfos[4].maxsolutions = _nj4;
10072 vinfos[5].jointtype = 1;
10073 vinfos[5].foffset = j5;
10074 vinfos[5].indices[0] = _ij5[0];
10075 vinfos[5].indices[1] = _ij5[1];
10076 vinfos[5].maxsolutions = _nj5;
10077 std::vector<int> vfree(0);
10078 solutions.AddSolution(vinfos,vfree);
10079 }
10080 }
10081 }
10082 
10083 }
10084 
10085 }
10086 
10087 } else
10088 {
10089 {
10090 IkReal j1array[1], cj1array[1], sj1array[1];
10091 bool j1valid[1]={false};
10092 _nj1 = 1;
10093 IkReal x2753=((cj5)*(sj4));
10094 IkReal x2754=((r21)*(sj4));
10095 IkReal x2755=((cj5)*(r21));
10096 IkReal x2756=((IkReal(0.707109999985348))*(cj2));
10097 IkReal x2757=((IkReal(0.707103562373095))*(sj2));
10098 IkReal x2758=((IkReal(0.707109999985348))*(sj2));
10099 IkReal x2759=((cj4)*(r22));
10100 IkReal x2760=((IkReal(0.707103562373095))*(cj2));
10101 IkReal x2761=((r20)*(x2756));
10102 IkReal x2762=((sj5)*(x2760));
10103 IkReal x2763=((sj5)*(x2758));
10104 if( IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(x2755)*(x2760)))+(((sj5)*(x2754)*(x2756)))+(((sj5)*(x2754)*(x2757)))+(((x2756)*(x2759)))+(((x2757)*(x2759)))+(((r20)*(x2763)))+(((x2755)*(x2758)))+(((IkReal(-1.00000000000000))*(x2753)*(x2761)))+(((IkReal(-1.00000000000000))*(r20)*(x2753)*(x2757)))+(((IkReal(-1.00000000000000))*(r20)*(x2762))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((x2754)*(x2763)))+(((x2758)*(x2759)))+(((IkReal(-1.00000000000000))*(x2759)*(x2760)))+(((r20)*(x2753)*(x2760)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2757)))+(((IkReal(-1.00000000000000))*(r20)*(x2753)*(x2758)))+(((IkReal(-1.00000000000000))*(x2755)*(x2757)))+(((IkReal(-1.00000000000000))*(x2755)*(x2756)))+(((IkReal(-1.00000000000000))*(sj5)*(x2761)))+(((IkReal(-1.00000000000000))*(x2754)*(x2762))))))) < IKFAST_ATAN2_MAGTHRESH )
10105     continue;
10106 j1array[0]=IKatan2(((gconst38)*(((((IkReal(-1.00000000000000))*(x2755)*(x2760)))+(((sj5)*(x2754)*(x2756)))+(((sj5)*(x2754)*(x2757)))+(((x2756)*(x2759)))+(((x2757)*(x2759)))+(((r20)*(x2763)))+(((x2755)*(x2758)))+(((IkReal(-1.00000000000000))*(x2753)*(x2761)))+(((IkReal(-1.00000000000000))*(r20)*(x2753)*(x2757)))+(((IkReal(-1.00000000000000))*(r20)*(x2762)))))), ((gconst38)*(((((x2754)*(x2763)))+(((x2758)*(x2759)))+(((IkReal(-1.00000000000000))*(x2759)*(x2760)))+(((r20)*(x2753)*(x2760)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2757)))+(((IkReal(-1.00000000000000))*(r20)*(x2753)*(x2758)))+(((IkReal(-1.00000000000000))*(x2755)*(x2757)))+(((IkReal(-1.00000000000000))*(x2755)*(x2756)))+(((IkReal(-1.00000000000000))*(sj5)*(x2761)))+(((IkReal(-1.00000000000000))*(x2754)*(x2762)))))));
10107 sj1array[0]=IKsin(j1array[0]);
10108 cj1array[0]=IKcos(j1array[0]);
10109 if( j1array[0] > IKPI )
10110 {
10111     j1array[0]-=IK2PI;
10112 }
10113 else if( j1array[0] < -IKPI )
10114 {    j1array[0]+=IK2PI;
10115 }
10116 j1valid[0] = true;
10117 for(int ij1 = 0; ij1 < 1; ++ij1)
10118 {
10119 if( !j1valid[ij1] )
10120 {
10121     continue;
10122 }
10123 _ij1[0] = ij1; _ij1[1] = -1;
10124 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10125 {
10126 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10127 {
10128     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10129 }
10130 }
10131 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10132 {
10133 IkReal evalcond[4];
10134 IkReal x2764=IKsin(j1);
10135 IkReal x2765=IKcos(j1);
10136 IkReal x2766=((IkReal(0.707109999985348))*(cj2));
10137 IkReal x2767=((IkReal(1.00000000000000))*(cj0));
10138 IkReal x2768=((IkReal(0.707109999985348))*(sj2));
10139 IkReal x2769=((cj5)*(sj4));
10140 IkReal x2770=((sj4)*(sj5));
10141 IkReal x2771=((IkReal(1.00000000000000))*(sj0));
10142 IkReal x2772=((sj5)*(x2771));
10143 IkReal x2773=((IkReal(0.707103562373095))*(x2765));
10144 IkReal x2774=((IkReal(0.707103562373095))*(x2764));
10145 IkReal x2775=((x2764)*(x2766));
10146 IkReal x2776=((sj2)*(x2774));
10147 IkReal x2777=((x2765)*(x2768));
10148 IkReal x2778=((cj2)*(x2773));
10149 IkReal x2779=((sj2)*(x2773));
10150 IkReal x2780=((cj2)*(x2774));
10151 IkReal x2781=((x2765)*(x2766));
10152 IkReal x2782=((x2764)*(x2768));
10153 IkReal x2783=((x2779)+(x2781)+(x2780));
10154 IkReal x2784=((x2775)+(x2776)+(x2777));
10155 evalcond[0]=((((IkReal(-1.00000000000000))*(x2783)))+(x2782)+(((cj5)*(r21)))+(((r20)*(sj5))));
10156 evalcond[1]=((x2784)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2778)))+(((r21)*(x2770)))+(((IkReal(-1.00000000000000))*(r20)*(x2769))));
10157 evalcond[2]=((x2784)+(((IkReal(-1.00000000000000))*(r10)*(x2772)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2771)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2767)))+(((IkReal(-1.00000000000000))*(x2778)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2767))));
10158 evalcond[3]=((((IkReal(-1.00000000000000))*(x2782)))+(x2783)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2767)))+(((cj0)*(r00)*(x2769)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2771)))+(((r10)*(sj0)*(x2769)))+(((IkReal(-1.00000000000000))*(r11)*(x2770)*(x2771)))+(((IkReal(-1.00000000000000))*(r01)*(x2767)*(x2770))));
10159 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10160 {
10161 continue;
10162 }
10163 }
10164 
10165 {
10166 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10167 vinfos[0].jointtype = 1;
10168 vinfos[0].foffset = j0;
10169 vinfos[0].indices[0] = _ij0[0];
10170 vinfos[0].indices[1] = _ij0[1];
10171 vinfos[0].maxsolutions = _nj0;
10172 vinfos[1].jointtype = 1;
10173 vinfos[1].foffset = j1;
10174 vinfos[1].indices[0] = _ij1[0];
10175 vinfos[1].indices[1] = _ij1[1];
10176 vinfos[1].maxsolutions = _nj1;
10177 vinfos[2].jointtype = 1;
10178 vinfos[2].foffset = j2;
10179 vinfos[2].indices[0] = _ij2[0];
10180 vinfos[2].indices[1] = _ij2[1];
10181 vinfos[2].maxsolutions = _nj2;
10182 vinfos[3].jointtype = 1;
10183 vinfos[3].foffset = j3;
10184 vinfos[3].indices[0] = _ij3[0];
10185 vinfos[3].indices[1] = _ij3[1];
10186 vinfos[3].maxsolutions = _nj3;
10187 vinfos[4].jointtype = 1;
10188 vinfos[4].foffset = j4;
10189 vinfos[4].indices[0] = _ij4[0];
10190 vinfos[4].indices[1] = _ij4[1];
10191 vinfos[4].maxsolutions = _nj4;
10192 vinfos[5].jointtype = 1;
10193 vinfos[5].foffset = j5;
10194 vinfos[5].indices[0] = _ij5[0];
10195 vinfos[5].indices[1] = _ij5[1];
10196 vinfos[5].maxsolutions = _nj5;
10197 std::vector<int> vfree(0);
10198 solutions.AddSolution(vinfos,vfree);
10199 }
10200 }
10201 }
10202 
10203 }
10204 
10205 }
10206 
10207 } else
10208 {
10209 IkReal x2785=((sj0)*(sj4));
10210 IkReal x2786=((IkReal(1.00000000000000))*(r12));
10211 IkReal x2787=((cj0)*(cj4));
10212 IkReal x2788=((r01)*(sj5));
10213 IkReal x2789=((IkReal(1.00000000000000))*(cj5));
10214 IkReal x2790=((cj4)*(cj5));
10215 IkReal x2791=((IkReal(1.00000000000000))*(cj0));
10216 IkReal x2792=((cj4)*(sj0));
10217 IkReal x2793=((r00)*(sj0));
10218 IkReal x2794=((npy)*(sj5));
10219 IkReal x2795=((IkReal(1.00000000000000))*(cj4));
10220 IkReal x2796=((cj0)*(sj4));
10221 IkReal x2797=((r11)*(sj5));
10222 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
10223 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x2793)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2789)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2791))));
10224 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2789)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x2794)))+(((IkReal(0.165463933124939))*(sj2))));
10225 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
10226 evalcond[4]=((IkReal(-0.00600000000000000))+(((npx)*(x2790)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x2794)*(x2795))));
10227 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x2785)*(x2789)))+(((IkReal(-1.00000000000000))*(x2786)*(x2787)))+(((x2785)*(x2788)))+(((cj5)*(r10)*(x2796)))+(((r02)*(x2792)))+(((IkReal(-1.00000000000000))*(sj4)*(x2791)*(x2797))));
10228 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x2787)*(x2789)))+(((IkReal(-1.00000000000000))*(x2786)*(x2796)))+(((IkReal(-1.00000000000000))*(x2788)*(x2792)))+(((x2787)*(x2797)))+(((r02)*(x2785)))+(((x2790)*(x2793))));
10229 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2795)))+(((r20)*(x2790))));
10230 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x2787)*(x2789)))+(((IkReal(-1.00000000000000))*(r10)*(x2789)*(x2792)))+(((x2787)*(x2788)))+(((x2792)*(x2797)))+(((IkReal(-1.00000000000000))*(x2785)*(x2786)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2791))));
10231 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  )
10232 {
10233 {
10234 IkReal dummyeval[1];
10235 IkReal gconst40;
10236 gconst40=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
10237 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
10238 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10239 {
10240 {
10241 IkReal dummyeval[1];
10242 IkReal gconst41;
10243 gconst41=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
10244 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
10245 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10246 {
10247 continue;
10248 
10249 } else
10250 {
10251 {
10252 IkReal j1array[1], cj1array[1], sj1array[1];
10253 bool j1valid[1]={false};
10254 _nj1 = 1;
10255 IkReal x2798=((cj5)*(r11));
10256 IkReal x2799=((r10)*(sj0));
10257 IkReal x2800=((IkReal(0.707103562373095))*(cj2));
10258 IkReal x2801=((r20)*(sj5));
10259 IkReal x2802=((IkReal(0.707103562373095))*(sj2));
10260 IkReal x2803=((IkReal(0.707109999985348))*(cj2));
10261 IkReal x2804=((cj0)*(r00));
10262 IkReal x2805=((IkReal(0.707109999985348))*(sj2));
10263 IkReal x2806=((cj5)*(r21));
10264 IkReal x2807=((sj0)*(x2802));
10265 IkReal x2808=((sj5)*(x2803));
10266 IkReal x2809=((cj0)*(cj5)*(r01));
10267 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x2799)*(x2802)))+(((IkReal(-1.00000000000000))*(sj5)*(x2802)*(x2804)))+(((x2805)*(x2806)))+(((IkReal(-1.00000000000000))*(sj0)*(x2798)*(x2803)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)))+(((IkReal(-1.00000000000000))*(x2800)*(x2806)))+(((IkReal(-1.00000000000000))*(x2803)*(x2809)))+(((IkReal(-1.00000000000000))*(x2802)*(x2809)))+(((x2801)*(x2805)))+(((IkReal(-1.00000000000000))*(x2799)*(x2808)))+(((IkReal(-1.00000000000000))*(x2804)*(x2808)))+(((IkReal(-1.00000000000000))*(x2798)*(x2807))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x2799)*(x2805)))+(((sj5)*(x2799)*(x2800)))+(((IkReal(-1.00000000000000))*(x2805)*(x2809)))+(((IkReal(-1.00000000000000))*(sj0)*(x2798)*(x2805)))+(((IkReal(-1.00000000000000))*(x2803)*(x2806)))+(((IkReal(-1.00000000000000))*(x2802)*(x2806)))+(((sj0)*(x2798)*(x2800)))+(((IkReal(-1.00000000000000))*(sj5)*(x2804)*(x2805)))+(((x2800)*(x2809)))+(((sj5)*(x2800)*(x2804)))+(((IkReal(-1.00000000000000))*(x2801)*(x2802)))+(((IkReal(-1.00000000000000))*(x2801)*(x2803))))))) < IKFAST_ATAN2_MAGTHRESH )
10268     continue;
10269 j1array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x2799)*(x2802)))+(((IkReal(-1.00000000000000))*(sj5)*(x2802)*(x2804)))+(((x2805)*(x2806)))+(((IkReal(-1.00000000000000))*(sj0)*(x2798)*(x2803)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)))+(((IkReal(-1.00000000000000))*(x2800)*(x2806)))+(((IkReal(-1.00000000000000))*(x2803)*(x2809)))+(((IkReal(-1.00000000000000))*(x2802)*(x2809)))+(((x2801)*(x2805)))+(((IkReal(-1.00000000000000))*(x2799)*(x2808)))+(((IkReal(-1.00000000000000))*(x2804)*(x2808)))+(((IkReal(-1.00000000000000))*(x2798)*(x2807)))))), ((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x2799)*(x2805)))+(((sj5)*(x2799)*(x2800)))+(((IkReal(-1.00000000000000))*(x2805)*(x2809)))+(((IkReal(-1.00000000000000))*(sj0)*(x2798)*(x2805)))+(((IkReal(-1.00000000000000))*(x2803)*(x2806)))+(((IkReal(-1.00000000000000))*(x2802)*(x2806)))+(((sj0)*(x2798)*(x2800)))+(((IkReal(-1.00000000000000))*(sj5)*(x2804)*(x2805)))+(((x2800)*(x2809)))+(((sj5)*(x2800)*(x2804)))+(((IkReal(-1.00000000000000))*(x2801)*(x2802)))+(((IkReal(-1.00000000000000))*(x2801)*(x2803)))))));
10270 sj1array[0]=IKsin(j1array[0]);
10271 cj1array[0]=IKcos(j1array[0]);
10272 if( j1array[0] > IKPI )
10273 {
10274     j1array[0]-=IK2PI;
10275 }
10276 else if( j1array[0] < -IKPI )
10277 {    j1array[0]+=IK2PI;
10278 }
10279 j1valid[0] = true;
10280 for(int ij1 = 0; ij1 < 1; ++ij1)
10281 {
10282 if( !j1valid[ij1] )
10283 {
10284     continue;
10285 }
10286 _ij1[0] = ij1; _ij1[1] = -1;
10287 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10288 {
10289 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10290 {
10291     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10292 }
10293 }
10294 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10295 {
10296 IkReal evalcond[4];
10297 IkReal x2810=IKsin(j1);
10298 IkReal x2811=IKcos(j1);
10299 IkReal x2812=((IkReal(0.707109999985348))*(cj2));
10300 IkReal x2813=((IkReal(1.00000000000000))*(cj0));
10301 IkReal x2814=((IkReal(0.707109999985348))*(sj2));
10302 IkReal x2815=((cj5)*(sj4));
10303 IkReal x2816=((sj4)*(sj5));
10304 IkReal x2817=((IkReal(1.00000000000000))*(sj0));
10305 IkReal x2818=((sj5)*(x2817));
10306 IkReal x2819=((IkReal(0.707103562373095))*(x2811));
10307 IkReal x2820=((IkReal(0.707103562373095))*(x2810));
10308 IkReal x2821=((x2810)*(x2812));
10309 IkReal x2822=((sj2)*(x2820));
10310 IkReal x2823=((x2811)*(x2814));
10311 IkReal x2824=((cj2)*(x2819));
10312 IkReal x2825=((sj2)*(x2819));
10313 IkReal x2826=((cj2)*(x2820));
10314 IkReal x2827=((x2811)*(x2812));
10315 IkReal x2828=((x2810)*(x2814));
10316 IkReal x2829=((x2825)+(x2826)+(x2827));
10317 IkReal x2830=((x2821)+(x2822)+(x2823));
10318 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2829)))+(x2828)+(((r20)*(sj5))));
10319 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x2816)))+(((IkReal(-1.00000000000000))*(r20)*(x2815)))+(((IkReal(-1.00000000000000))*(x2824)))+(x2830));
10320 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2813)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2817)))+(((IkReal(-1.00000000000000))*(x2824)))+(x2830)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2813)))+(((IkReal(-1.00000000000000))*(r10)*(x2818))));
10321 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2813)*(x2816)))+(((IkReal(-1.00000000000000))*(r11)*(x2816)*(x2817)))+(((r10)*(sj0)*(x2815)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2817)))+(((cj0)*(r00)*(x2815)))+(((IkReal(-1.00000000000000))*(x2828)))+(x2829)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2813))));
10322 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10323 {
10324 continue;
10325 }
10326 }
10327 
10328 {
10329 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10330 vinfos[0].jointtype = 1;
10331 vinfos[0].foffset = j0;
10332 vinfos[0].indices[0] = _ij0[0];
10333 vinfos[0].indices[1] = _ij0[1];
10334 vinfos[0].maxsolutions = _nj0;
10335 vinfos[1].jointtype = 1;
10336 vinfos[1].foffset = j1;
10337 vinfos[1].indices[0] = _ij1[0];
10338 vinfos[1].indices[1] = _ij1[1];
10339 vinfos[1].maxsolutions = _nj1;
10340 vinfos[2].jointtype = 1;
10341 vinfos[2].foffset = j2;
10342 vinfos[2].indices[0] = _ij2[0];
10343 vinfos[2].indices[1] = _ij2[1];
10344 vinfos[2].maxsolutions = _nj2;
10345 vinfos[3].jointtype = 1;
10346 vinfos[3].foffset = j3;
10347 vinfos[3].indices[0] = _ij3[0];
10348 vinfos[3].indices[1] = _ij3[1];
10349 vinfos[3].maxsolutions = _nj3;
10350 vinfos[4].jointtype = 1;
10351 vinfos[4].foffset = j4;
10352 vinfos[4].indices[0] = _ij4[0];
10353 vinfos[4].indices[1] = _ij4[1];
10354 vinfos[4].maxsolutions = _nj4;
10355 vinfos[5].jointtype = 1;
10356 vinfos[5].foffset = j5;
10357 vinfos[5].indices[0] = _ij5[0];
10358 vinfos[5].indices[1] = _ij5[1];
10359 vinfos[5].maxsolutions = _nj5;
10360 std::vector<int> vfree(0);
10361 solutions.AddSolution(vinfos,vfree);
10362 }
10363 }
10364 }
10365 
10366 }
10367 
10368 }
10369 
10370 } else
10371 {
10372 {
10373 IkReal j1array[1], cj1array[1], sj1array[1];
10374 bool j1valid[1]={false};
10375 _nj1 = 1;
10376 IkReal x2831=((cj5)*(sj4));
10377 IkReal x2832=((r21)*(sj4));
10378 IkReal x2833=((cj5)*(r21));
10379 IkReal x2834=((IkReal(0.707109999985348))*(cj2));
10380 IkReal x2835=((IkReal(0.707103562373095))*(sj2));
10381 IkReal x2836=((IkReal(0.707109999985348))*(sj2));
10382 IkReal x2837=((cj4)*(r22));
10383 IkReal x2838=((IkReal(0.707103562373095))*(cj2));
10384 IkReal x2839=((r20)*(x2834));
10385 IkReal x2840=((sj5)*(x2838));
10386 IkReal x2841=((sj5)*(x2836));
10387 if( IKabs(((gconst40)*(((((x2834)*(x2837)))+(((IkReal(-1.00000000000000))*(r20)*(x2840)))+(((r20)*(x2841)))+(((IkReal(-1.00000000000000))*(r20)*(x2831)*(x2835)))+(((IkReal(-1.00000000000000))*(x2833)*(x2838)))+(((sj5)*(x2832)*(x2835)))+(((sj5)*(x2832)*(x2834)))+(((x2835)*(x2837)))+(((x2833)*(x2836)))+(((IkReal(-1.00000000000000))*(x2831)*(x2839))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((x2836)*(x2837)))+(((r20)*(x2831)*(x2838)))+(((IkReal(-1.00000000000000))*(sj5)*(x2839)))+(((IkReal(-1.00000000000000))*(r20)*(x2831)*(x2836)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2835)))+(((IkReal(-1.00000000000000))*(x2833)*(x2834)))+(((IkReal(-1.00000000000000))*(x2833)*(x2835)))+(((IkReal(-1.00000000000000))*(x2837)*(x2838)))+(((x2832)*(x2841)))+(((IkReal(-1.00000000000000))*(x2832)*(x2840))))))) < IKFAST_ATAN2_MAGTHRESH )
10388     continue;
10389 j1array[0]=IKatan2(((gconst40)*(((((x2834)*(x2837)))+(((IkReal(-1.00000000000000))*(r20)*(x2840)))+(((r20)*(x2841)))+(((IkReal(-1.00000000000000))*(r20)*(x2831)*(x2835)))+(((IkReal(-1.00000000000000))*(x2833)*(x2838)))+(((sj5)*(x2832)*(x2835)))+(((sj5)*(x2832)*(x2834)))+(((x2835)*(x2837)))+(((x2833)*(x2836)))+(((IkReal(-1.00000000000000))*(x2831)*(x2839)))))), ((gconst40)*(((((x2836)*(x2837)))+(((r20)*(x2831)*(x2838)))+(((IkReal(-1.00000000000000))*(sj5)*(x2839)))+(((IkReal(-1.00000000000000))*(r20)*(x2831)*(x2836)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2835)))+(((IkReal(-1.00000000000000))*(x2833)*(x2834)))+(((IkReal(-1.00000000000000))*(x2833)*(x2835)))+(((IkReal(-1.00000000000000))*(x2837)*(x2838)))+(((x2832)*(x2841)))+(((IkReal(-1.00000000000000))*(x2832)*(x2840)))))));
10390 sj1array[0]=IKsin(j1array[0]);
10391 cj1array[0]=IKcos(j1array[0]);
10392 if( j1array[0] > IKPI )
10393 {
10394     j1array[0]-=IK2PI;
10395 }
10396 else if( j1array[0] < -IKPI )
10397 {    j1array[0]+=IK2PI;
10398 }
10399 j1valid[0] = true;
10400 for(int ij1 = 0; ij1 < 1; ++ij1)
10401 {
10402 if( !j1valid[ij1] )
10403 {
10404     continue;
10405 }
10406 _ij1[0] = ij1; _ij1[1] = -1;
10407 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10408 {
10409 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10410 {
10411     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10412 }
10413 }
10414 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10415 {
10416 IkReal evalcond[4];
10417 IkReal x2842=IKsin(j1);
10418 IkReal x2843=IKcos(j1);
10419 IkReal x2844=((IkReal(0.707109999985348))*(cj2));
10420 IkReal x2845=((IkReal(1.00000000000000))*(cj0));
10421 IkReal x2846=((IkReal(0.707109999985348))*(sj2));
10422 IkReal x2847=((cj5)*(sj4));
10423 IkReal x2848=((sj4)*(sj5));
10424 IkReal x2849=((IkReal(1.00000000000000))*(sj0));
10425 IkReal x2850=((sj5)*(x2849));
10426 IkReal x2851=((IkReal(0.707103562373095))*(x2843));
10427 IkReal x2852=((IkReal(0.707103562373095))*(x2842));
10428 IkReal x2853=((x2842)*(x2844));
10429 IkReal x2854=((sj2)*(x2852));
10430 IkReal x2855=((x2843)*(x2846));
10431 IkReal x2856=((cj2)*(x2851));
10432 IkReal x2857=((sj2)*(x2851));
10433 IkReal x2858=((cj2)*(x2852));
10434 IkReal x2859=((x2843)*(x2844));
10435 IkReal x2860=((x2842)*(x2846));
10436 IkReal x2861=((x2859)+(x2858)+(x2857));
10437 IkReal x2862=((x2853)+(x2855)+(x2854));
10438 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2861)))+(x2860)+(((r20)*(sj5))));
10439 evalcond[1]=((((r21)*(x2848)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x2847)))+(x2862)+(((IkReal(-1.00000000000000))*(x2856))));
10440 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2845)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2849)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2845)))+(((IkReal(-1.00000000000000))*(r10)*(x2850)))+(x2862)+(((IkReal(-1.00000000000000))*(x2856))));
10441 evalcond[3]=((((cj0)*(r00)*(x2847)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2849)))+(((IkReal(-1.00000000000000))*(r11)*(x2848)*(x2849)))+(((IkReal(-1.00000000000000))*(x2860)))+(((r10)*(sj0)*(x2847)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2845)))+(x2861)+(((IkReal(-1.00000000000000))*(r01)*(x2845)*(x2848))));
10442 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10443 {
10444 continue;
10445 }
10446 }
10447 
10448 {
10449 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10450 vinfos[0].jointtype = 1;
10451 vinfos[0].foffset = j0;
10452 vinfos[0].indices[0] = _ij0[0];
10453 vinfos[0].indices[1] = _ij0[1];
10454 vinfos[0].maxsolutions = _nj0;
10455 vinfos[1].jointtype = 1;
10456 vinfos[1].foffset = j1;
10457 vinfos[1].indices[0] = _ij1[0];
10458 vinfos[1].indices[1] = _ij1[1];
10459 vinfos[1].maxsolutions = _nj1;
10460 vinfos[2].jointtype = 1;
10461 vinfos[2].foffset = j2;
10462 vinfos[2].indices[0] = _ij2[0];
10463 vinfos[2].indices[1] = _ij2[1];
10464 vinfos[2].maxsolutions = _nj2;
10465 vinfos[3].jointtype = 1;
10466 vinfos[3].foffset = j3;
10467 vinfos[3].indices[0] = _ij3[0];
10468 vinfos[3].indices[1] = _ij3[1];
10469 vinfos[3].maxsolutions = _nj3;
10470 vinfos[4].jointtype = 1;
10471 vinfos[4].foffset = j4;
10472 vinfos[4].indices[0] = _ij4[0];
10473 vinfos[4].indices[1] = _ij4[1];
10474 vinfos[4].maxsolutions = _nj4;
10475 vinfos[5].jointtype = 1;
10476 vinfos[5].foffset = j5;
10477 vinfos[5].indices[0] = _ij5[0];
10478 vinfos[5].indices[1] = _ij5[1];
10479 vinfos[5].maxsolutions = _nj5;
10480 std::vector<int> vfree(0);
10481 solutions.AddSolution(vinfos,vfree);
10482 }
10483 }
10484 }
10485 
10486 }
10487 
10488 }
10489 
10490 } else
10491 {
10492 IkReal x2863=((sj0)*(sj4));
10493 IkReal x2864=((IkReal(1.00000000000000))*(r12));
10494 IkReal x2865=((cj0)*(cj4));
10495 IkReal x2866=((r01)*(sj5));
10496 IkReal x2867=((IkReal(1.00000000000000))*(cj5));
10497 IkReal x2868=((cj4)*(cj5));
10498 IkReal x2869=((IkReal(1.00000000000000))*(cj0));
10499 IkReal x2870=((cj4)*(sj0));
10500 IkReal x2871=((r00)*(sj0));
10501 IkReal x2872=((npy)*(sj5));
10502 IkReal x2873=((IkReal(1.00000000000000))*(cj4));
10503 IkReal x2874=((cj0)*(sj4));
10504 IkReal x2875=((r11)*(sj5));
10505 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
10506 evalcond[1]=((((sj5)*(x2871)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2867)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2869))));
10507 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x2872)))+(((IkReal(-0.207888640466058))*(cj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2867)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2))));
10508 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
10509 evalcond[4]=((IkReal(0.00600000000000000))+(((npx)*(x2868)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x2872)*(x2873))));
10510 evalcond[5]=((((IkReal(-1.00000000000000))*(x2864)*(x2865)))+(((x2863)*(x2866)))+(((r02)*(x2870)))+(((IkReal(-1.00000000000000))*(r00)*(x2863)*(x2867)))+(((IkReal(-1.00000000000000))*(sj4)*(x2869)*(x2875)))+(((cj5)*(r10)*(x2874))));
10511 evalcond[6]=((IkReal(-1.00000000000000))+(((x2865)*(x2875)))+(((x2868)*(x2871)))+(((IkReal(-1.00000000000000))*(x2864)*(x2874)))+(((r02)*(x2863)))+(((IkReal(-1.00000000000000))*(r10)*(x2865)*(x2867)))+(((IkReal(-1.00000000000000))*(x2866)*(x2870))));
10512 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2873)))+(((r20)*(x2868))));
10513 evalcond[8]=((((IkReal(-1.00000000000000))*(r10)*(x2867)*(x2870)))+(((x2865)*(x2866)))+(((x2870)*(x2875)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2869)))+(((IkReal(-1.00000000000000))*(r00)*(x2865)*(x2867)))+(((IkReal(-1.00000000000000))*(x2863)*(x2864))));
10514 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  )
10515 {
10516 {
10517 IkReal dummyeval[1];
10518 IkReal gconst42;
10519 gconst42=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
10520 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
10521 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10522 {
10523 {
10524 IkReal dummyeval[1];
10525 IkReal gconst43;
10526 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
10527 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
10528 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10529 {
10530 continue;
10531 
10532 } else
10533 {
10534 {
10535 IkReal j1array[1], cj1array[1], sj1array[1];
10536 bool j1valid[1]={false};
10537 _nj1 = 1;
10538 IkReal x2876=((cj5)*(r11));
10539 IkReal x2877=((r10)*(sj0));
10540 IkReal x2878=((IkReal(0.707103562373095))*(cj2));
10541 IkReal x2879=((r20)*(sj5));
10542 IkReal x2880=((IkReal(0.707103562373095))*(sj2));
10543 IkReal x2881=((IkReal(0.707109999985348))*(cj2));
10544 IkReal x2882=((cj0)*(r00));
10545 IkReal x2883=((IkReal(0.707109999985348))*(sj2));
10546 IkReal x2884=((cj5)*(r21));
10547 IkReal x2885=((sj0)*(x2880));
10548 IkReal x2886=((sj5)*(x2881));
10549 IkReal x2887=((cj0)*(cj5)*(r01));
10550 if( IKabs(((gconst43)*(((((x2877)*(x2886)))+(((IkReal(-1.00000000000000))*(x2883)*(x2884)))+(((sj5)*(x2880)*(x2882)))+(((x2880)*(x2887)))+(((sj0)*(x2876)*(x2881)))+(((x2876)*(x2885)))+(((IkReal(-1.00000000000000))*(x2879)*(x2883)))+(((x2878)*(x2884)))+(((x2881)*(x2887)))+(((x2878)*(x2879)))+(((sj5)*(x2877)*(x2880)))+(((x2882)*(x2886))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((x2880)*(x2884)))+(((sj0)*(x2876)*(x2883)))+(((x2879)*(x2881)))+(((x2879)*(x2880)))+(((IkReal(-1.00000000000000))*(sj5)*(x2878)*(x2882)))+(((IkReal(-1.00000000000000))*(sj0)*(x2876)*(x2878)))+(((x2881)*(x2884)))+(((IkReal(-1.00000000000000))*(sj5)*(x2877)*(x2878)))+(((IkReal(-1.00000000000000))*(x2878)*(x2887)))+(((sj5)*(x2877)*(x2883)))+(((sj5)*(x2882)*(x2883)))+(((x2883)*(x2887))))))) < IKFAST_ATAN2_MAGTHRESH )
10551     continue;
10552 j1array[0]=IKatan2(((gconst43)*(((((x2877)*(x2886)))+(((IkReal(-1.00000000000000))*(x2883)*(x2884)))+(((sj5)*(x2880)*(x2882)))+(((x2880)*(x2887)))+(((sj0)*(x2876)*(x2881)))+(((x2876)*(x2885)))+(((IkReal(-1.00000000000000))*(x2879)*(x2883)))+(((x2878)*(x2884)))+(((x2881)*(x2887)))+(((x2878)*(x2879)))+(((sj5)*(x2877)*(x2880)))+(((x2882)*(x2886)))))), ((gconst43)*(((((x2880)*(x2884)))+(((sj0)*(x2876)*(x2883)))+(((x2879)*(x2881)))+(((x2879)*(x2880)))+(((IkReal(-1.00000000000000))*(sj5)*(x2878)*(x2882)))+(((IkReal(-1.00000000000000))*(sj0)*(x2876)*(x2878)))+(((x2881)*(x2884)))+(((IkReal(-1.00000000000000))*(sj5)*(x2877)*(x2878)))+(((IkReal(-1.00000000000000))*(x2878)*(x2887)))+(((sj5)*(x2877)*(x2883)))+(((sj5)*(x2882)*(x2883)))+(((x2883)*(x2887)))))));
10553 sj1array[0]=IKsin(j1array[0]);
10554 cj1array[0]=IKcos(j1array[0]);
10555 if( j1array[0] > IKPI )
10556 {
10557     j1array[0]-=IK2PI;
10558 }
10559 else if( j1array[0] < -IKPI )
10560 {    j1array[0]+=IK2PI;
10561 }
10562 j1valid[0] = true;
10563 for(int ij1 = 0; ij1 < 1; ++ij1)
10564 {
10565 if( !j1valid[ij1] )
10566 {
10567     continue;
10568 }
10569 _ij1[0] = ij1; _ij1[1] = -1;
10570 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10571 {
10572 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10573 {
10574     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10575 }
10576 }
10577 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10578 {
10579 IkReal evalcond[4];
10580 IkReal x2888=IKcos(j1);
10581 IkReal x2889=IKsin(j1);
10582 IkReal x2890=((IkReal(0.707109999985348))*(cj2));
10583 IkReal x2891=((IkReal(1.00000000000000))*(cj0));
10584 IkReal x2892=((IkReal(0.707109999985348))*(sj2));
10585 IkReal x2893=((cj5)*(sj4));
10586 IkReal x2894=((sj4)*(sj5));
10587 IkReal x2895=((IkReal(1.00000000000000))*(sj0));
10588 IkReal x2896=((sj5)*(x2895));
10589 IkReal x2897=((IkReal(0.707103562373095))*(x2888));
10590 IkReal x2898=((IkReal(0.707103562373095))*(x2889));
10591 IkReal x2899=((cj2)*(x2897));
10592 IkReal x2900=((x2889)*(x2890));
10593 IkReal x2901=((sj2)*(x2898));
10594 IkReal x2902=((x2888)*(x2892));
10595 IkReal x2903=((sj2)*(x2897));
10596 IkReal x2904=((cj2)*(x2898));
10597 IkReal x2905=((x2888)*(x2890));
10598 IkReal x2906=((x2889)*(x2892));
10599 IkReal x2907=((x2903)+(x2905)+(x2904));
10600 IkReal x2908=((x2902)+(x2901)+(x2900));
10601 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2906)))+(((r20)*(sj5)))+(x2907));
10602 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x2893)))+(((cj4)*(r22)))+(((r21)*(x2894)))+(((IkReal(-1.00000000000000))*(x2899)))+(x2908));
10603 evalcond[2]=((((IkReal(-1.00000000000000))*(x2908)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2895)))+(x2899)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2891)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2891)))+(((IkReal(-1.00000000000000))*(r10)*(x2896))));
10604 evalcond[3]=((((r10)*(sj0)*(x2893)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2895)))+(((IkReal(-1.00000000000000))*(x2906)))+(((cj0)*(r00)*(x2893)))+(((IkReal(-1.00000000000000))*(r01)*(x2891)*(x2894)))+(x2907)+(((IkReal(-1.00000000000000))*(r11)*(x2894)*(x2895)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2891))));
10605 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10606 {
10607 continue;
10608 }
10609 }
10610 
10611 {
10612 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10613 vinfos[0].jointtype = 1;
10614 vinfos[0].foffset = j0;
10615 vinfos[0].indices[0] = _ij0[0];
10616 vinfos[0].indices[1] = _ij0[1];
10617 vinfos[0].maxsolutions = _nj0;
10618 vinfos[1].jointtype = 1;
10619 vinfos[1].foffset = j1;
10620 vinfos[1].indices[0] = _ij1[0];
10621 vinfos[1].indices[1] = _ij1[1];
10622 vinfos[1].maxsolutions = _nj1;
10623 vinfos[2].jointtype = 1;
10624 vinfos[2].foffset = j2;
10625 vinfos[2].indices[0] = _ij2[0];
10626 vinfos[2].indices[1] = _ij2[1];
10627 vinfos[2].maxsolutions = _nj2;
10628 vinfos[3].jointtype = 1;
10629 vinfos[3].foffset = j3;
10630 vinfos[3].indices[0] = _ij3[0];
10631 vinfos[3].indices[1] = _ij3[1];
10632 vinfos[3].maxsolutions = _nj3;
10633 vinfos[4].jointtype = 1;
10634 vinfos[4].foffset = j4;
10635 vinfos[4].indices[0] = _ij4[0];
10636 vinfos[4].indices[1] = _ij4[1];
10637 vinfos[4].maxsolutions = _nj4;
10638 vinfos[5].jointtype = 1;
10639 vinfos[5].foffset = j5;
10640 vinfos[5].indices[0] = _ij5[0];
10641 vinfos[5].indices[1] = _ij5[1];
10642 vinfos[5].maxsolutions = _nj5;
10643 std::vector<int> vfree(0);
10644 solutions.AddSolution(vinfos,vfree);
10645 }
10646 }
10647 }
10648 
10649 }
10650 
10651 }
10652 
10653 } else
10654 {
10655 {
10656 IkReal j1array[1], cj1array[1], sj1array[1];
10657 bool j1valid[1]={false};
10658 _nj1 = 1;
10659 IkReal x2909=((cj5)*(sj4));
10660 IkReal x2910=((r21)*(sj4));
10661 IkReal x2911=((cj5)*(r21));
10662 IkReal x2912=((IkReal(0.707109999985348))*(cj2));
10663 IkReal x2913=((IkReal(0.707103562373095))*(sj2));
10664 IkReal x2914=((IkReal(0.707109999985348))*(sj2));
10665 IkReal x2915=((cj4)*(r22));
10666 IkReal x2916=((IkReal(0.707103562373095))*(cj2));
10667 IkReal x2917=((r20)*(x2912));
10668 IkReal x2918=((sj5)*(x2916));
10669 IkReal x2919=((sj5)*(x2914));
10670 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x2913)*(x2915)))+(((IkReal(-1.00000000000000))*(x2912)*(x2915)))+(((r20)*(x2919)))+(((x2909)*(x2917)))+(((r20)*(x2909)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2910)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2910)*(x2912)))+(((IkReal(-1.00000000000000))*(x2911)*(x2916)))+(((x2911)*(x2914)))+(((IkReal(-1.00000000000000))*(r20)*(x2918))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2917)))+(((r20)*(x2909)*(x2914)))+(((IkReal(-1.00000000000000))*(x2914)*(x2915)))+(((x2915)*(x2916)))+(((IkReal(-1.00000000000000))*(x2911)*(x2913)))+(((IkReal(-1.00000000000000))*(x2911)*(x2912)))+(((IkReal(-1.00000000000000))*(x2910)*(x2919)))+(((x2910)*(x2918)))+(((IkReal(-1.00000000000000))*(r20)*(x2909)*(x2916))))))) < IKFAST_ATAN2_MAGTHRESH )
10671     continue;
10672 j1array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(x2913)*(x2915)))+(((IkReal(-1.00000000000000))*(x2912)*(x2915)))+(((r20)*(x2919)))+(((x2909)*(x2917)))+(((r20)*(x2909)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2910)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2910)*(x2912)))+(((IkReal(-1.00000000000000))*(x2911)*(x2916)))+(((x2911)*(x2914)))+(((IkReal(-1.00000000000000))*(r20)*(x2918)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2913)))+(((IkReal(-1.00000000000000))*(sj5)*(x2917)))+(((r20)*(x2909)*(x2914)))+(((IkReal(-1.00000000000000))*(x2914)*(x2915)))+(((x2915)*(x2916)))+(((IkReal(-1.00000000000000))*(x2911)*(x2913)))+(((IkReal(-1.00000000000000))*(x2911)*(x2912)))+(((IkReal(-1.00000000000000))*(x2910)*(x2919)))+(((x2910)*(x2918)))+(((IkReal(-1.00000000000000))*(r20)*(x2909)*(x2916)))))));
10673 sj1array[0]=IKsin(j1array[0]);
10674 cj1array[0]=IKcos(j1array[0]);
10675 if( j1array[0] > IKPI )
10676 {
10677     j1array[0]-=IK2PI;
10678 }
10679 else if( j1array[0] < -IKPI )
10680 {    j1array[0]+=IK2PI;
10681 }
10682 j1valid[0] = true;
10683 for(int ij1 = 0; ij1 < 1; ++ij1)
10684 {
10685 if( !j1valid[ij1] )
10686 {
10687     continue;
10688 }
10689 _ij1[0] = ij1; _ij1[1] = -1;
10690 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10691 {
10692 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10693 {
10694     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10695 }
10696 }
10697 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10698 {
10699 IkReal evalcond[4];
10700 IkReal x2920=IKcos(j1);
10701 IkReal x2921=IKsin(j1);
10702 IkReal x2922=((IkReal(0.707109999985348))*(cj2));
10703 IkReal x2923=((IkReal(1.00000000000000))*(cj0));
10704 IkReal x2924=((IkReal(0.707109999985348))*(sj2));
10705 IkReal x2925=((cj5)*(sj4));
10706 IkReal x2926=((sj4)*(sj5));
10707 IkReal x2927=((IkReal(1.00000000000000))*(sj0));
10708 IkReal x2928=((sj5)*(x2927));
10709 IkReal x2929=((IkReal(0.707103562373095))*(x2920));
10710 IkReal x2930=((IkReal(0.707103562373095))*(x2921));
10711 IkReal x2931=((cj2)*(x2929));
10712 IkReal x2932=((x2921)*(x2922));
10713 IkReal x2933=((sj2)*(x2930));
10714 IkReal x2934=((x2920)*(x2924));
10715 IkReal x2935=((sj2)*(x2929));
10716 IkReal x2936=((cj2)*(x2930));
10717 IkReal x2937=((x2920)*(x2922));
10718 IkReal x2938=((x2921)*(x2924));
10719 IkReal x2939=((x2936)+(x2937)+(x2935));
10720 IkReal x2940=((x2934)+(x2932)+(x2933));
10721 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2938)))+(((r20)*(sj5)))+(x2939));
10722 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2931)))+(((r21)*(x2926)))+(((IkReal(-1.00000000000000))*(r20)*(x2925)))+(x2940));
10723 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2927)))+(((IkReal(-1.00000000000000))*(r10)*(x2928)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2923)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2923)))+(((IkReal(-1.00000000000000))*(x2940)))+(x2931));
10724 evalcond[3]=((((cj0)*(r00)*(x2925)))+(((r10)*(sj0)*(x2925)))+(((IkReal(-1.00000000000000))*(x2938)))+(((IkReal(-1.00000000000000))*(r01)*(x2923)*(x2926)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2927)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2923)))+(((IkReal(-1.00000000000000))*(r11)*(x2926)*(x2927)))+(x2939));
10725 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10726 {
10727 continue;
10728 }
10729 }
10730 
10731 {
10732 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10733 vinfos[0].jointtype = 1;
10734 vinfos[0].foffset = j0;
10735 vinfos[0].indices[0] = _ij0[0];
10736 vinfos[0].indices[1] = _ij0[1];
10737 vinfos[0].maxsolutions = _nj0;
10738 vinfos[1].jointtype = 1;
10739 vinfos[1].foffset = j1;
10740 vinfos[1].indices[0] = _ij1[0];
10741 vinfos[1].indices[1] = _ij1[1];
10742 vinfos[1].maxsolutions = _nj1;
10743 vinfos[2].jointtype = 1;
10744 vinfos[2].foffset = j2;
10745 vinfos[2].indices[0] = _ij2[0];
10746 vinfos[2].indices[1] = _ij2[1];
10747 vinfos[2].maxsolutions = _nj2;
10748 vinfos[3].jointtype = 1;
10749 vinfos[3].foffset = j3;
10750 vinfos[3].indices[0] = _ij3[0];
10751 vinfos[3].indices[1] = _ij3[1];
10752 vinfos[3].maxsolutions = _nj3;
10753 vinfos[4].jointtype = 1;
10754 vinfos[4].foffset = j4;
10755 vinfos[4].indices[0] = _ij4[0];
10756 vinfos[4].indices[1] = _ij4[1];
10757 vinfos[4].maxsolutions = _nj4;
10758 vinfos[5].jointtype = 1;
10759 vinfos[5].foffset = j5;
10760 vinfos[5].indices[0] = _ij5[0];
10761 vinfos[5].indices[1] = _ij5[1];
10762 vinfos[5].maxsolutions = _nj5;
10763 std::vector<int> vfree(0);
10764 solutions.AddSolution(vinfos,vfree);
10765 }
10766 }
10767 }
10768 
10769 }
10770 
10771 }
10772 
10773 } else
10774 {
10775 IkReal x2941=((sj0)*(sj4));
10776 IkReal x2942=((IkReal(1.00000000000000))*(r12));
10777 IkReal x2943=((cj0)*(cj4));
10778 IkReal x2944=((r01)*(sj5));
10779 IkReal x2945=((IkReal(1.00000000000000))*(cj5));
10780 IkReal x2946=((cj4)*(cj5));
10781 IkReal x2947=((IkReal(1.00000000000000))*(cj0));
10782 IkReal x2948=((cj4)*(sj0));
10783 IkReal x2949=((r00)*(sj0));
10784 IkReal x2950=((npy)*(sj5));
10785 IkReal x2951=((IkReal(1.00000000000000))*(cj4));
10786 IkReal x2952=((cj0)*(sj4));
10787 IkReal x2953=((r11)*(sj5));
10788 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
10789 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(sj5)*(x2947)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x2949)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x2945))));
10790 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2)))+(((sj4)*(x2950)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x2945))));
10791 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
10792 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((npx)*(x2946)))+(((IkReal(-1.00000000000000))*(x2950)*(x2951))));
10793 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x2941)*(x2945)))+(((x2941)*(x2944)))+(((r02)*(x2948)))+(((IkReal(-1.00000000000000))*(x2942)*(x2943)))+(((IkReal(-1.00000000000000))*(sj4)*(x2947)*(x2953)))+(((cj5)*(r10)*(x2952))));
10794 evalcond[6]=((IkReal(-1.00000000000000))+(((x2946)*(x2949)))+(((IkReal(-1.00000000000000))*(r10)*(x2943)*(x2945)))+(((IkReal(-1.00000000000000))*(x2942)*(x2952)))+(((IkReal(-1.00000000000000))*(x2944)*(x2948)))+(((r02)*(x2941)))+(((x2943)*(x2953))));
10795 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x2951)))+(((r20)*(x2946))));
10796 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x2947)))+(((IkReal(-1.00000000000000))*(r00)*(x2943)*(x2945)))+(((x2948)*(x2953)))+(((IkReal(-1.00000000000000))*(r10)*(x2945)*(x2948)))+(((x2943)*(x2944)))+(((IkReal(-1.00000000000000))*(x2941)*(x2942))));
10797 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  )
10798 {
10799 {
10800 IkReal dummyeval[1];
10801 IkReal gconst44;
10802 gconst44=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
10803 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
10804 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10805 {
10806 {
10807 IkReal dummyeval[1];
10808 IkReal gconst45;
10809 gconst45=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
10810 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
10811 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10812 {
10813 continue;
10814 
10815 } else
10816 {
10817 {
10818 IkReal j1array[1], cj1array[1], sj1array[1];
10819 bool j1valid[1]={false};
10820 _nj1 = 1;
10821 IkReal x2954=((cj5)*(r11));
10822 IkReal x2955=((r10)*(sj0));
10823 IkReal x2956=((IkReal(0.707103562373095))*(cj2));
10824 IkReal x2957=((r20)*(sj5));
10825 IkReal x2958=((IkReal(0.707103562373095))*(sj2));
10826 IkReal x2959=((IkReal(0.707109999985348))*(cj2));
10827 IkReal x2960=((cj0)*(r00));
10828 IkReal x2961=((IkReal(0.707109999985348))*(sj2));
10829 IkReal x2962=((cj5)*(r21));
10830 IkReal x2963=((sj0)*(x2958));
10831 IkReal x2964=((sj5)*(x2959));
10832 IkReal x2965=((cj0)*(cj5)*(r01));
10833 if( IKabs(((gconst45)*(((((IkReal(-1.00000000000000))*(x2957)*(x2961)))+(((x2956)*(x2962)))+(((x2954)*(x2963)))+(((x2955)*(x2964)))+(((x2960)*(x2964)))+(((x2959)*(x2965)))+(((sj5)*(x2958)*(x2960)))+(((sj0)*(x2954)*(x2959)))+(((IkReal(-1.00000000000000))*(x2961)*(x2962)))+(((x2958)*(x2965)))+(((x2956)*(x2957)))+(((sj5)*(x2955)*(x2958))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((sj5)*(x2960)*(x2961)))+(((IkReal(-1.00000000000000))*(sj5)*(x2956)*(x2960)))+(((IkReal(-1.00000000000000))*(sj0)*(x2954)*(x2956)))+(((x2957)*(x2959)))+(((x2957)*(x2958)))+(((sj5)*(x2955)*(x2961)))+(((IkReal(-1.00000000000000))*(sj5)*(x2955)*(x2956)))+(((x2961)*(x2965)))+(((x2959)*(x2962)))+(((sj0)*(x2954)*(x2961)))+(((x2958)*(x2962)))+(((IkReal(-1.00000000000000))*(x2956)*(x2965))))))) < IKFAST_ATAN2_MAGTHRESH )
10834     continue;
10835 j1array[0]=IKatan2(((gconst45)*(((((IkReal(-1.00000000000000))*(x2957)*(x2961)))+(((x2956)*(x2962)))+(((x2954)*(x2963)))+(((x2955)*(x2964)))+(((x2960)*(x2964)))+(((x2959)*(x2965)))+(((sj5)*(x2958)*(x2960)))+(((sj0)*(x2954)*(x2959)))+(((IkReal(-1.00000000000000))*(x2961)*(x2962)))+(((x2958)*(x2965)))+(((x2956)*(x2957)))+(((sj5)*(x2955)*(x2958)))))), ((gconst45)*(((((sj5)*(x2960)*(x2961)))+(((IkReal(-1.00000000000000))*(sj5)*(x2956)*(x2960)))+(((IkReal(-1.00000000000000))*(sj0)*(x2954)*(x2956)))+(((x2957)*(x2959)))+(((x2957)*(x2958)))+(((sj5)*(x2955)*(x2961)))+(((IkReal(-1.00000000000000))*(sj5)*(x2955)*(x2956)))+(((x2961)*(x2965)))+(((x2959)*(x2962)))+(((sj0)*(x2954)*(x2961)))+(((x2958)*(x2962)))+(((IkReal(-1.00000000000000))*(x2956)*(x2965)))))));
10836 sj1array[0]=IKsin(j1array[0]);
10837 cj1array[0]=IKcos(j1array[0]);
10838 if( j1array[0] > IKPI )
10839 {
10840     j1array[0]-=IK2PI;
10841 }
10842 else if( j1array[0] < -IKPI )
10843 {    j1array[0]+=IK2PI;
10844 }
10845 j1valid[0] = true;
10846 for(int ij1 = 0; ij1 < 1; ++ij1)
10847 {
10848 if( !j1valid[ij1] )
10849 {
10850     continue;
10851 }
10852 _ij1[0] = ij1; _ij1[1] = -1;
10853 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10854 {
10855 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10856 {
10857     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10858 }
10859 }
10860 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10861 {
10862 IkReal evalcond[4];
10863 IkReal x2966=IKcos(j1);
10864 IkReal x2967=IKsin(j1);
10865 IkReal x2968=((IkReal(0.707109999985348))*(cj2));
10866 IkReal x2969=((IkReal(1.00000000000000))*(cj0));
10867 IkReal x2970=((IkReal(0.707109999985348))*(sj2));
10868 IkReal x2971=((cj5)*(sj4));
10869 IkReal x2972=((sj4)*(sj5));
10870 IkReal x2973=((IkReal(1.00000000000000))*(sj0));
10871 IkReal x2974=((sj5)*(x2973));
10872 IkReal x2975=((IkReal(0.707103562373095))*(x2966));
10873 IkReal x2976=((IkReal(0.707103562373095))*(x2967));
10874 IkReal x2977=((cj2)*(x2975));
10875 IkReal x2978=((x2967)*(x2968));
10876 IkReal x2979=((sj2)*(x2976));
10877 IkReal x2980=((x2966)*(x2970));
10878 IkReal x2981=((sj2)*(x2975));
10879 IkReal x2982=((cj2)*(x2976));
10880 IkReal x2983=((x2966)*(x2968));
10881 IkReal x2984=((x2967)*(x2970));
10882 IkReal x2985=((x2983)+(x2982)+(x2981));
10883 IkReal x2986=((x2980)+(x2978)+(x2979));
10884 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x2984)))+(((r20)*(sj5)))+(x2985));
10885 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x2977)))+(((IkReal(-1.00000000000000))*(r20)*(x2971)))+(x2986)+(((r21)*(x2972))));
10886 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x2973)))+(((IkReal(-1.00000000000000))*(x2986)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x2969)))+(((IkReal(-1.00000000000000))*(r10)*(x2974)))+(x2977)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x2969))));
10887 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x2972)*(x2973)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x2973)))+(((IkReal(-1.00000000000000))*(x2984)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x2969)))+(((cj0)*(r00)*(x2971)))+(((IkReal(-1.00000000000000))*(r01)*(x2969)*(x2972)))+(((r10)*(sj0)*(x2971)))+(x2985));
10888 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10889 {
10890 continue;
10891 }
10892 }
10893 
10894 {
10895 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10896 vinfos[0].jointtype = 1;
10897 vinfos[0].foffset = j0;
10898 vinfos[0].indices[0] = _ij0[0];
10899 vinfos[0].indices[1] = _ij0[1];
10900 vinfos[0].maxsolutions = _nj0;
10901 vinfos[1].jointtype = 1;
10902 vinfos[1].foffset = j1;
10903 vinfos[1].indices[0] = _ij1[0];
10904 vinfos[1].indices[1] = _ij1[1];
10905 vinfos[1].maxsolutions = _nj1;
10906 vinfos[2].jointtype = 1;
10907 vinfos[2].foffset = j2;
10908 vinfos[2].indices[0] = _ij2[0];
10909 vinfos[2].indices[1] = _ij2[1];
10910 vinfos[2].maxsolutions = _nj2;
10911 vinfos[3].jointtype = 1;
10912 vinfos[3].foffset = j3;
10913 vinfos[3].indices[0] = _ij3[0];
10914 vinfos[3].indices[1] = _ij3[1];
10915 vinfos[3].maxsolutions = _nj3;
10916 vinfos[4].jointtype = 1;
10917 vinfos[4].foffset = j4;
10918 vinfos[4].indices[0] = _ij4[0];
10919 vinfos[4].indices[1] = _ij4[1];
10920 vinfos[4].maxsolutions = _nj4;
10921 vinfos[5].jointtype = 1;
10922 vinfos[5].foffset = j5;
10923 vinfos[5].indices[0] = _ij5[0];
10924 vinfos[5].indices[1] = _ij5[1];
10925 vinfos[5].maxsolutions = _nj5;
10926 std::vector<int> vfree(0);
10927 solutions.AddSolution(vinfos,vfree);
10928 }
10929 }
10930 }
10931 
10932 }
10933 
10934 }
10935 
10936 } else
10937 {
10938 {
10939 IkReal j1array[1], cj1array[1], sj1array[1];
10940 bool j1valid[1]={false};
10941 _nj1 = 1;
10942 IkReal x2987=((cj5)*(sj4));
10943 IkReal x2988=((r21)*(sj4));
10944 IkReal x2989=((cj5)*(r21));
10945 IkReal x2990=((IkReal(0.707109999985348))*(cj2));
10946 IkReal x2991=((IkReal(0.707103562373095))*(sj2));
10947 IkReal x2992=((IkReal(0.707109999985348))*(sj2));
10948 IkReal x2993=((cj4)*(r22));
10949 IkReal x2994=((IkReal(0.707103562373095))*(cj2));
10950 IkReal x2995=((r20)*(x2990));
10951 IkReal x2996=((sj5)*(x2994));
10952 IkReal x2997=((sj5)*(x2992));
10953 if( IKabs(((gconst44)*(((((x2987)*(x2995)))+(((r20)*(x2997)))+(((r20)*(x2987)*(x2991)))+(((IkReal(-1.00000000000000))*(x2989)*(x2994)))+(((IkReal(-1.00000000000000))*(sj5)*(x2988)*(x2990)))+(((IkReal(-1.00000000000000))*(sj5)*(x2988)*(x2991)))+(((IkReal(-1.00000000000000))*(x2991)*(x2993)))+(((x2989)*(x2992)))+(((IkReal(-1.00000000000000))*(r20)*(x2996)))+(((IkReal(-1.00000000000000))*(x2990)*(x2993))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((IkReal(-1.00000000000000))*(x2992)*(x2993)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2991)))+(((r20)*(x2987)*(x2992)))+(((IkReal(-1.00000000000000))*(sj5)*(x2995)))+(((IkReal(-1.00000000000000))*(x2989)*(x2990)))+(((IkReal(-1.00000000000000))*(x2989)*(x2991)))+(((IkReal(-1.00000000000000))*(x2988)*(x2997)))+(((IkReal(-1.00000000000000))*(r20)*(x2987)*(x2994)))+(((x2993)*(x2994)))+(((x2988)*(x2996))))))) < IKFAST_ATAN2_MAGTHRESH )
10954     continue;
10955 j1array[0]=IKatan2(((gconst44)*(((((x2987)*(x2995)))+(((r20)*(x2997)))+(((r20)*(x2987)*(x2991)))+(((IkReal(-1.00000000000000))*(x2989)*(x2994)))+(((IkReal(-1.00000000000000))*(sj5)*(x2988)*(x2990)))+(((IkReal(-1.00000000000000))*(sj5)*(x2988)*(x2991)))+(((IkReal(-1.00000000000000))*(x2991)*(x2993)))+(((x2989)*(x2992)))+(((IkReal(-1.00000000000000))*(r20)*(x2996)))+(((IkReal(-1.00000000000000))*(x2990)*(x2993)))))), ((gconst44)*(((((IkReal(-1.00000000000000))*(x2992)*(x2993)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x2991)))+(((r20)*(x2987)*(x2992)))+(((IkReal(-1.00000000000000))*(sj5)*(x2995)))+(((IkReal(-1.00000000000000))*(x2989)*(x2990)))+(((IkReal(-1.00000000000000))*(x2989)*(x2991)))+(((IkReal(-1.00000000000000))*(x2988)*(x2997)))+(((IkReal(-1.00000000000000))*(r20)*(x2987)*(x2994)))+(((x2993)*(x2994)))+(((x2988)*(x2996)))))));
10956 sj1array[0]=IKsin(j1array[0]);
10957 cj1array[0]=IKcos(j1array[0]);
10958 if( j1array[0] > IKPI )
10959 {
10960     j1array[0]-=IK2PI;
10961 }
10962 else if( j1array[0] < -IKPI )
10963 {    j1array[0]+=IK2PI;
10964 }
10965 j1valid[0] = true;
10966 for(int ij1 = 0; ij1 < 1; ++ij1)
10967 {
10968 if( !j1valid[ij1] )
10969 {
10970     continue;
10971 }
10972 _ij1[0] = ij1; _ij1[1] = -1;
10973 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
10974 {
10975 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
10976 {
10977     j1valid[iij1]=false; _ij1[1] = iij1; break; 
10978 }
10979 }
10980 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
10981 {
10982 IkReal evalcond[4];
10983 IkReal x2998=IKcos(j1);
10984 IkReal x2999=IKsin(j1);
10985 IkReal x3000=((IkReal(0.707109999985348))*(cj2));
10986 IkReal x3001=((IkReal(1.00000000000000))*(cj0));
10987 IkReal x3002=((IkReal(0.707109999985348))*(sj2));
10988 IkReal x3003=((cj5)*(sj4));
10989 IkReal x3004=((sj4)*(sj5));
10990 IkReal x3005=((IkReal(1.00000000000000))*(sj0));
10991 IkReal x3006=((sj5)*(x3005));
10992 IkReal x3007=((IkReal(0.707103562373095))*(x2998));
10993 IkReal x3008=((IkReal(0.707103562373095))*(x2999));
10994 IkReal x3009=((cj2)*(x3007));
10995 IkReal x3010=((x2999)*(x3000));
10996 IkReal x3011=((sj2)*(x3008));
10997 IkReal x3012=((x2998)*(x3002));
10998 IkReal x3013=((sj2)*(x3007));
10999 IkReal x3014=((cj2)*(x3008));
11000 IkReal x3015=((x2998)*(x3000));
11001 IkReal x3016=((x2999)*(x3002));
11002 IkReal x3017=((x3013)+(x3014)+(x3015));
11003 IkReal x3018=((x3012)+(x3010)+(x3011));
11004 evalcond[0]=((((cj5)*(r21)))+(x3017)+(((IkReal(-1.00000000000000))*(x3016)))+(((r20)*(sj5))));
11005 evalcond[1]=((((cj4)*(r22)))+(x3018)+(((IkReal(-1.00000000000000))*(x3009)))+(((IkReal(-1.00000000000000))*(r20)*(x3003)))+(((r21)*(x3004))));
11006 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3006)))+(x3009)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3001)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3001)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3005)))+(((IkReal(-1.00000000000000))*(x3018))));
11007 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3001)))+(x3017)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3005)))+(((cj0)*(r00)*(x3003)))+(((IkReal(-1.00000000000000))*(x3016)))+(((r10)*(sj0)*(x3003)))+(((IkReal(-1.00000000000000))*(r11)*(x3004)*(x3005)))+(((IkReal(-1.00000000000000))*(r01)*(x3001)*(x3004))));
11008 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11009 {
11010 continue;
11011 }
11012 }
11013 
11014 {
11015 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11016 vinfos[0].jointtype = 1;
11017 vinfos[0].foffset = j0;
11018 vinfos[0].indices[0] = _ij0[0];
11019 vinfos[0].indices[1] = _ij0[1];
11020 vinfos[0].maxsolutions = _nj0;
11021 vinfos[1].jointtype = 1;
11022 vinfos[1].foffset = j1;
11023 vinfos[1].indices[0] = _ij1[0];
11024 vinfos[1].indices[1] = _ij1[1];
11025 vinfos[1].maxsolutions = _nj1;
11026 vinfos[2].jointtype = 1;
11027 vinfos[2].foffset = j2;
11028 vinfos[2].indices[0] = _ij2[0];
11029 vinfos[2].indices[1] = _ij2[1];
11030 vinfos[2].maxsolutions = _nj2;
11031 vinfos[3].jointtype = 1;
11032 vinfos[3].foffset = j3;
11033 vinfos[3].indices[0] = _ij3[0];
11034 vinfos[3].indices[1] = _ij3[1];
11035 vinfos[3].maxsolutions = _nj3;
11036 vinfos[4].jointtype = 1;
11037 vinfos[4].foffset = j4;
11038 vinfos[4].indices[0] = _ij4[0];
11039 vinfos[4].indices[1] = _ij4[1];
11040 vinfos[4].maxsolutions = _nj4;
11041 vinfos[5].jointtype = 1;
11042 vinfos[5].foffset = j5;
11043 vinfos[5].indices[0] = _ij5[0];
11044 vinfos[5].indices[1] = _ij5[1];
11045 vinfos[5].maxsolutions = _nj5;
11046 std::vector<int> vfree(0);
11047 solutions.AddSolution(vinfos,vfree);
11048 }
11049 }
11050 }
11051 
11052 }
11053 
11054 }
11055 
11056 } else
11057 {
11058 if( 1 )
11059 {
11060 continue;
11061 
11062 } else
11063 {
11064 }
11065 }
11066 }
11067 }
11068 }
11069 }
11070 
11071 } else
11072 {
11073 {
11074 IkReal j1array[1], cj1array[1], sj1array[1];
11075 bool j1valid[1]={false};
11076 _nj1 = 1;
11077 IkReal x3019=((IkReal(0.707109999985348))*(sj2));
11078 IkReal x3020=((r22)*(sj4));
11079 IkReal x3021=((cj5)*(r20));
11080 IkReal x3022=((r21)*(sj5));
11081 IkReal x3023=((IkReal(0.707109999985348))*(cj2));
11082 IkReal x3024=((cj3)*(r22));
11083 IkReal x3025=((cj3)*(sj4));
11084 IkReal x3026=((IkReal(0.707103562373095))*(cj4)*(sj2));
11085 IkReal x3027=((IkReal(0.707103562373095))*(x3025));
11086 IkReal x3028=((IkReal(0.707103562373095))*(cj2)*(cj4));
11087 if( IKabs(((gconst37)*(((((IkReal(0.707103562373095))*(cj2)*(x3020)))+(((sj2)*(x3022)*(x3027)))+(((IkReal(-1.00000000000000))*(x3019)*(x3020)))+(((IkReal(-1.00000000000000))*(sj2)*(x3021)*(x3027)))+(((x3021)*(x3028)))+(((IkReal(-1.00000000000000))*(x3021)*(x3023)*(x3025)))+(((cj4)*(x3023)*(x3024)))+(((IkReal(-1.00000000000000))*(cj4)*(x3019)*(x3021)))+(((x3022)*(x3023)*(x3025)))+(((IkReal(-1.00000000000000))*(x3022)*(x3028)))+(((x3024)*(x3026)))+(((cj4)*(x3019)*(x3022))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((IkReal(-1.00000000000000))*(cj2)*(x3022)*(x3027)))+(((x3021)*(x3026)))+(((x3019)*(x3022)*(x3025)))+(((x3020)*(x3023)))+(((cj4)*(x3021)*(x3023)))+(((IkReal(-1.00000000000000))*(cj4)*(x3022)*(x3023)))+(((cj2)*(x3021)*(x3027)))+(((IkReal(0.707103562373095))*(sj2)*(x3020)))+(((IkReal(-1.00000000000000))*(x3024)*(x3028)))+(((IkReal(-1.00000000000000))*(x3022)*(x3026)))+(((cj4)*(x3019)*(x3024)))+(((IkReal(-1.00000000000000))*(x3019)*(x3021)*(x3025))))))) < IKFAST_ATAN2_MAGTHRESH )
11088     continue;
11089 j1array[0]=IKatan2(((gconst37)*(((((IkReal(0.707103562373095))*(cj2)*(x3020)))+(((sj2)*(x3022)*(x3027)))+(((IkReal(-1.00000000000000))*(x3019)*(x3020)))+(((IkReal(-1.00000000000000))*(sj2)*(x3021)*(x3027)))+(((x3021)*(x3028)))+(((IkReal(-1.00000000000000))*(x3021)*(x3023)*(x3025)))+(((cj4)*(x3023)*(x3024)))+(((IkReal(-1.00000000000000))*(cj4)*(x3019)*(x3021)))+(((x3022)*(x3023)*(x3025)))+(((IkReal(-1.00000000000000))*(x3022)*(x3028)))+(((x3024)*(x3026)))+(((cj4)*(x3019)*(x3022)))))), ((gconst37)*(((((IkReal(-1.00000000000000))*(cj2)*(x3022)*(x3027)))+(((x3021)*(x3026)))+(((x3019)*(x3022)*(x3025)))+(((x3020)*(x3023)))+(((cj4)*(x3021)*(x3023)))+(((IkReal(-1.00000000000000))*(cj4)*(x3022)*(x3023)))+(((cj2)*(x3021)*(x3027)))+(((IkReal(0.707103562373095))*(sj2)*(x3020)))+(((IkReal(-1.00000000000000))*(x3024)*(x3028)))+(((IkReal(-1.00000000000000))*(x3022)*(x3026)))+(((cj4)*(x3019)*(x3024)))+(((IkReal(-1.00000000000000))*(x3019)*(x3021)*(x3025)))))));
11090 sj1array[0]=IKsin(j1array[0]);
11091 cj1array[0]=IKcos(j1array[0]);
11092 if( j1array[0] > IKPI )
11093 {
11094     j1array[0]-=IK2PI;
11095 }
11096 else if( j1array[0] < -IKPI )
11097 {    j1array[0]+=IK2PI;
11098 }
11099 j1valid[0] = true;
11100 for(int ij1 = 0; ij1 < 1; ++ij1)
11101 {
11102 if( !j1valid[ij1] )
11103 {
11104     continue;
11105 }
11106 _ij1[0] = ij1; _ij1[1] = -1;
11107 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11108 {
11109 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11110 {
11111     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11112 }
11113 }
11114 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11115 {
11116 IkReal evalcond[6];
11117 IkReal x3029=IKcos(j1);
11118 IkReal x3030=IKsin(j1);
11119 IkReal x3031=((cj0)*(cj4));
11120 IkReal x3032=((r01)*(sj5));
11121 IkReal x3033=((IkReal(1.00000000000000))*(cj4));
11122 IkReal x3034=((IkReal(1.00000000000000))*(r02));
11123 IkReal x3035=((IkReal(0.707109999985348))*(sj3));
11124 IkReal x3036=((IkReal(0.707103562373095))*(sj3));
11125 IkReal x3037=((IkReal(1.00000000000000))*(sj4));
11126 IkReal x3038=((cj5)*(r20));
11127 IkReal x3039=((cj5)*(sj0));
11128 IkReal x3040=((IkReal(1.00000000000000))*(cj0));
11129 IkReal x3041=((r12)*(sj0));
11130 IkReal x3042=((cj2)*(cj3));
11131 IkReal x3043=((IkReal(0.707103562373095))*(cj3));
11132 IkReal x3044=((r21)*(sj5));
11133 IkReal x3045=((IkReal(0.707109999985348))*(cj3));
11134 IkReal x3046=((IkReal(1.00000000000000))*(sj0)*(sj5));
11135 IkReal x3047=((sj2)*(x3029));
11136 IkReal x3048=((cj2)*(x3029));
11137 IkReal x3049=((cj0)*(cj5)*(r00));
11138 IkReal x3050=((IkReal(0.707103562373095))*(x3030));
11139 IkReal x3051=((cj2)*(x3030));
11140 IkReal x3052=((IkReal(0.707109999985348))*(sj2)*(x3030));
11141 evalcond[0]=((((cj5)*(r21)))+(((sj2)*(x3030)*(x3035)))+(((IkReal(-1.00000000000000))*(x3036)*(x3051)))+(((IkReal(-1.00000000000000))*(x3035)*(x3048)))+(((IkReal(-1.00000000000000))*(x3036)*(x3047)))+(((r20)*(sj5))));
11142 evalcond[1]=((((IkReal(0.707109999985348))*(x3051)))+(((cj4)*(r22)))+(((IkReal(-0.707103562373095))*(x3048)))+(((IkReal(-1.00000000000000))*(x3037)*(x3038)))+(((IkReal(0.707109999985348))*(x3047)))+(((sj4)*(x3044)))+(((sj2)*(x3050))));
11143 evalcond[2]=((((x3043)*(x3047)))+(((IkReal(-1.00000000000000))*(x3033)*(x3044)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x3030)*(x3045)))+(((IkReal(0.707109999985348))*(x3029)*(x3042)))+(((x3042)*(x3050)))+(((cj4)*(x3038))));
11144 evalcond[3]=((((sj2)*(x3030)*(x3036)))+(((x3035)*(x3051)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3040)))+(((IkReal(-1.00000000000000))*(r10)*(x3046)))+(((IkReal(-1.00000000000000))*(r11)*(x3039)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3040)))+(((IkReal(-1.00000000000000))*(x3036)*(x3048)))+(((x3035)*(x3047))));
11145 evalcond[4]=((((r10)*(sj4)*(x3039)))+(((IkReal(-1.00000000000000))*(x3033)*(x3041)))+(((IkReal(0.707103562373095))*(x3047)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x3037)))+(((cj2)*(x3050)))+(((IkReal(-1.00000000000000))*(cj0)*(x3032)*(x3037)))+(((IkReal(0.707109999985348))*(x3048)))+(((sj4)*(x3049)))+(((IkReal(-1.00000000000000))*(x3031)*(x3034)))+(((IkReal(-1.00000000000000))*(x3052))));
11146 evalcond[5]=((((IkReal(-1.00000000000000))*(x3045)*(x3047)))+(((IkReal(0.707103562373095))*(x3029)*(x3042)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x3034)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3031)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(sj2)*(x3030)*(x3043)))+(((IkReal(-0.707109999985348))*(x3030)*(x3042)))+(((x3031)*(x3032)))+(((IkReal(-1.00000000000000))*(x3037)*(x3041)))+(((IkReal(-1.00000000000000))*(r10)*(x3033)*(x3039))));
11147 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  )
11148 {
11149 continue;
11150 }
11151 }
11152 
11153 {
11154 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11155 vinfos[0].jointtype = 1;
11156 vinfos[0].foffset = j0;
11157 vinfos[0].indices[0] = _ij0[0];
11158 vinfos[0].indices[1] = _ij0[1];
11159 vinfos[0].maxsolutions = _nj0;
11160 vinfos[1].jointtype = 1;
11161 vinfos[1].foffset = j1;
11162 vinfos[1].indices[0] = _ij1[0];
11163 vinfos[1].indices[1] = _ij1[1];
11164 vinfos[1].maxsolutions = _nj1;
11165 vinfos[2].jointtype = 1;
11166 vinfos[2].foffset = j2;
11167 vinfos[2].indices[0] = _ij2[0];
11168 vinfos[2].indices[1] = _ij2[1];
11169 vinfos[2].maxsolutions = _nj2;
11170 vinfos[3].jointtype = 1;
11171 vinfos[3].foffset = j3;
11172 vinfos[3].indices[0] = _ij3[0];
11173 vinfos[3].indices[1] = _ij3[1];
11174 vinfos[3].maxsolutions = _nj3;
11175 vinfos[4].jointtype = 1;
11176 vinfos[4].foffset = j4;
11177 vinfos[4].indices[0] = _ij4[0];
11178 vinfos[4].indices[1] = _ij4[1];
11179 vinfos[4].maxsolutions = _nj4;
11180 vinfos[5].jointtype = 1;
11181 vinfos[5].foffset = j5;
11182 vinfos[5].indices[0] = _ij5[0];
11183 vinfos[5].indices[1] = _ij5[1];
11184 vinfos[5].maxsolutions = _nj5;
11185 std::vector<int> vfree(0);
11186 solutions.AddSolution(vinfos,vfree);
11187 }
11188 }
11189 }
11190 
11191 }
11192 
11193 }
11194 
11195 } else
11196 {
11197 {
11198 IkReal j1array[1], cj1array[1], sj1array[1];
11199 bool j1valid[1]={false};
11200 _nj1 = 1;
11201 IkReal x3053=((sj2)*(sj3));
11202 IkReal x3054=((cj4)*(r22));
11203 IkReal x3055=((r20)*(sj5));
11204 IkReal x3056=((IkReal(0.707103562373095))*(cj2));
11205 IkReal x3057=((IkReal(0.707109999985348))*(sj2));
11206 IkReal x3058=((IkReal(0.707109999985348))*(cj2));
11207 IkReal x3059=((cj5)*(r21));
11208 IkReal x3060=((IkReal(0.707103562373095))*(sj2));
11209 IkReal x3061=((r21)*(sj4)*(sj5));
11210 IkReal x3062=((cj5)*(r20)*(sj4));
11211 if( IKabs(((gconst36)*(((((IkReal(0.707103562373095))*(x3053)*(x3061)))+(((IkReal(-0.707103562373095))*(x3053)*(x3062)))+(((IkReal(-1.00000000000000))*(sj3)*(x3058)*(x3062)))+(((IkReal(-1.00000000000000))*(x3055)*(x3056)))+(((IkReal(0.707103562373095))*(x3053)*(x3054)))+(((sj3)*(x3058)*(x3061)))+(((x3057)*(x3059)))+(((IkReal(-1.00000000000000))*(x3056)*(x3059)))+(((sj3)*(x3054)*(x3058)))+(((x3055)*(x3057))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(x3055)*(x3058)))+(((sj3)*(x3056)*(x3062)))+(((IkReal(-1.00000000000000))*(x3058)*(x3059)))+(((IkReal(0.707109999985348))*(x3053)*(x3061)))+(((IkReal(-1.00000000000000))*(sj3)*(x3056)*(x3061)))+(((IkReal(-0.707109999985348))*(x3053)*(x3062)))+(((IkReal(-1.00000000000000))*(x3055)*(x3060)))+(((IkReal(-1.00000000000000))*(sj3)*(x3054)*(x3056)))+(((IkReal(-1.00000000000000))*(x3059)*(x3060)))+(((IkReal(0.707109999985348))*(x3053)*(x3054))))))) < IKFAST_ATAN2_MAGTHRESH )
11212     continue;
11213 j1array[0]=IKatan2(((gconst36)*(((((IkReal(0.707103562373095))*(x3053)*(x3061)))+(((IkReal(-0.707103562373095))*(x3053)*(x3062)))+(((IkReal(-1.00000000000000))*(sj3)*(x3058)*(x3062)))+(((IkReal(-1.00000000000000))*(x3055)*(x3056)))+(((IkReal(0.707103562373095))*(x3053)*(x3054)))+(((sj3)*(x3058)*(x3061)))+(((x3057)*(x3059)))+(((IkReal(-1.00000000000000))*(x3056)*(x3059)))+(((sj3)*(x3054)*(x3058)))+(((x3055)*(x3057)))))), ((gconst36)*(((((IkReal(-1.00000000000000))*(x3055)*(x3058)))+(((sj3)*(x3056)*(x3062)))+(((IkReal(-1.00000000000000))*(x3058)*(x3059)))+(((IkReal(0.707109999985348))*(x3053)*(x3061)))+(((IkReal(-1.00000000000000))*(sj3)*(x3056)*(x3061)))+(((IkReal(-0.707109999985348))*(x3053)*(x3062)))+(((IkReal(-1.00000000000000))*(x3055)*(x3060)))+(((IkReal(-1.00000000000000))*(sj3)*(x3054)*(x3056)))+(((IkReal(-1.00000000000000))*(x3059)*(x3060)))+(((IkReal(0.707109999985348))*(x3053)*(x3054)))))));
11214 sj1array[0]=IKsin(j1array[0]);
11215 cj1array[0]=IKcos(j1array[0]);
11216 if( j1array[0] > IKPI )
11217 {
11218     j1array[0]-=IK2PI;
11219 }
11220 else if( j1array[0] < -IKPI )
11221 {    j1array[0]+=IK2PI;
11222 }
11223 j1valid[0] = true;
11224 for(int ij1 = 0; ij1 < 1; ++ij1)
11225 {
11226 if( !j1valid[ij1] )
11227 {
11228     continue;
11229 }
11230 _ij1[0] = ij1; _ij1[1] = -1;
11231 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11232 {
11233 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11234 {
11235     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11236 }
11237 }
11238 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11239 {
11240 IkReal evalcond[6];
11241 IkReal x3063=IKcos(j1);
11242 IkReal x3064=IKsin(j1);
11243 IkReal x3065=((cj0)*(cj4));
11244 IkReal x3066=((r01)*(sj5));
11245 IkReal x3067=((IkReal(1.00000000000000))*(cj4));
11246 IkReal x3068=((IkReal(1.00000000000000))*(r02));
11247 IkReal x3069=((IkReal(0.707109999985348))*(sj3));
11248 IkReal x3070=((IkReal(0.707103562373095))*(sj3));
11249 IkReal x3071=((IkReal(1.00000000000000))*(sj4));
11250 IkReal x3072=((cj5)*(r20));
11251 IkReal x3073=((cj5)*(sj0));
11252 IkReal x3074=((IkReal(1.00000000000000))*(cj0));
11253 IkReal x3075=((r12)*(sj0));
11254 IkReal x3076=((cj2)*(cj3));
11255 IkReal x3077=((IkReal(0.707103562373095))*(cj3));
11256 IkReal x3078=((r21)*(sj5));
11257 IkReal x3079=((IkReal(0.707109999985348))*(cj3));
11258 IkReal x3080=((IkReal(1.00000000000000))*(sj0)*(sj5));
11259 IkReal x3081=((sj2)*(x3063));
11260 IkReal x3082=((cj2)*(x3063));
11261 IkReal x3083=((cj0)*(cj5)*(r00));
11262 IkReal x3084=((IkReal(0.707103562373095))*(x3064));
11263 IkReal x3085=((cj2)*(x3064));
11264 IkReal x3086=((IkReal(0.707109999985348))*(sj2)*(x3064));
11265 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3070)*(x3081)))+(((IkReal(-1.00000000000000))*(x3070)*(x3085)))+(((IkReal(-1.00000000000000))*(x3069)*(x3082)))+(((sj2)*(x3064)*(x3069)))+(((r20)*(sj5))));
11266 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-0.707103562373095))*(x3082)))+(((IkReal(-1.00000000000000))*(x3071)*(x3072)))+(((IkReal(0.707109999985348))*(x3081)))+(((IkReal(0.707109999985348))*(x3085)))+(((sj4)*(x3078)))+(((sj2)*(x3084))));
11267 evalcond[2]=((((cj4)*(x3072)))+(((IkReal(-1.00000000000000))*(x3067)*(x3078)))+(((r22)*(sj4)))+(((IkReal(0.707109999985348))*(x3063)*(x3076)))+(((x3076)*(x3084)))+(((x3077)*(x3081)))+(((IkReal(-1.00000000000000))*(sj2)*(x3064)*(x3079))));
11268 evalcond[3]=((((x3069)*(x3085)))+(((x3069)*(x3081)))+(((sj2)*(x3064)*(x3070)))+(((IkReal(-1.00000000000000))*(r11)*(x3073)))+(((IkReal(-1.00000000000000))*(x3070)*(x3082)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3074)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3074)))+(((IkReal(-1.00000000000000))*(r10)*(x3080))));
11269 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x3071)))+(((IkReal(-1.00000000000000))*(x3086)))+(((cj2)*(x3084)))+(((IkReal(-1.00000000000000))*(x3067)*(x3075)))+(((IkReal(-1.00000000000000))*(cj0)*(x3066)*(x3071)))+(((sj4)*(x3083)))+(((r10)*(sj4)*(x3073)))+(((IkReal(-1.00000000000000))*(x3065)*(x3068)))+(((IkReal(0.707103562373095))*(x3081)))+(((IkReal(0.707109999985348))*(x3082))));
11270 evalcond[5]=((((IkReal(-1.00000000000000))*(r10)*(x3067)*(x3073)))+(((IkReal(-1.00000000000000))*(x3079)*(x3081)))+(((x3065)*(x3066)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x3068)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x3071)*(x3075)))+(((IkReal(-0.707109999985348))*(x3064)*(x3076)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3065)))+(((IkReal(0.707103562373095))*(x3063)*(x3076)))+(((IkReal(-1.00000000000000))*(sj2)*(x3064)*(x3077))));
11271 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  )
11272 {
11273 continue;
11274 }
11275 }
11276 
11277 {
11278 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11279 vinfos[0].jointtype = 1;
11280 vinfos[0].foffset = j0;
11281 vinfos[0].indices[0] = _ij0[0];
11282 vinfos[0].indices[1] = _ij0[1];
11283 vinfos[0].maxsolutions = _nj0;
11284 vinfos[1].jointtype = 1;
11285 vinfos[1].foffset = j1;
11286 vinfos[1].indices[0] = _ij1[0];
11287 vinfos[1].indices[1] = _ij1[1];
11288 vinfos[1].maxsolutions = _nj1;
11289 vinfos[2].jointtype = 1;
11290 vinfos[2].foffset = j2;
11291 vinfos[2].indices[0] = _ij2[0];
11292 vinfos[2].indices[1] = _ij2[1];
11293 vinfos[2].maxsolutions = _nj2;
11294 vinfos[3].jointtype = 1;
11295 vinfos[3].foffset = j3;
11296 vinfos[3].indices[0] = _ij3[0];
11297 vinfos[3].indices[1] = _ij3[1];
11298 vinfos[3].maxsolutions = _nj3;
11299 vinfos[4].jointtype = 1;
11300 vinfos[4].foffset = j4;
11301 vinfos[4].indices[0] = _ij4[0];
11302 vinfos[4].indices[1] = _ij4[1];
11303 vinfos[4].maxsolutions = _nj4;
11304 vinfos[5].jointtype = 1;
11305 vinfos[5].foffset = j5;
11306 vinfos[5].indices[0] = _ij5[0];
11307 vinfos[5].indices[1] = _ij5[1];
11308 vinfos[5].maxsolutions = _nj5;
11309 std::vector<int> vfree(0);
11310 solutions.AddSolution(vinfos,vfree);
11311 }
11312 }
11313 }
11314 
11315 }
11316 
11317 }
11318 }
11319 }
11320 
11321 }
11322 
11323 }
11324 
11325 } else
11326 {
11327 {
11328 IkReal j2array[1], cj2array[1], sj2array[1];
11329 bool j2valid[1]={false};
11330 _nj2 = 1;
11331 IkReal x3087=((cj5)*(npy));
11332 IkReal x3088=((IkReal(8.66210554726807e+23))*(npx));
11333 IkReal x3089=((IkReal(6.89439331452234e+23))*(npx));
11334 IkReal x3090=((IkReal(8.66210554726807e+23))*(sj3));
11335 IkReal x3091=((cj4)*(npz));
11336 IkReal x3092=((IkReal(6.89439331452234e+23))*(sj3));
11337 IkReal x3093=((cj5)*(sj3)*(sj4));
11338 IkReal x3094=((npy)*(sj4)*(sj5));
11339 if( IKabs(((gconst34)*(((IkReal(-5.19726332836084e+21))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((IkReal(-1.00000000000000))*(x3092)*(x3094)))+(((IkReal(8.66210554726807e+23))*(x3087)))+(((IkReal(-1.00000000000000))*(x3091)*(x3092)))+(((x3089)*(x3093)))+(((sj5)*(x3088))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((IkReal(-4.13663598871341e+21))+(((IkReal(6.89439331452234e+23))*(x3087)))+(((x3090)*(x3091)))+(((x3090)*(x3094)))+(((IkReal(-1.00000000000000))*(x3088)*(x3093)))+(((sj5)*(x3089)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3))))))) < IKFAST_ATAN2_MAGTHRESH )
11340     continue;
11341 j2array[0]=IKatan2(((gconst34)*(((IkReal(-5.19726332836084e+21))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((IkReal(-1.00000000000000))*(x3092)*(x3094)))+(((IkReal(8.66210554726807e+23))*(x3087)))+(((IkReal(-1.00000000000000))*(x3091)*(x3092)))+(((x3089)*(x3093)))+(((sj5)*(x3088)))))), ((gconst34)*(((IkReal(-4.13663598871341e+21))+(((IkReal(6.89439331452234e+23))*(x3087)))+(((x3090)*(x3091)))+(((x3090)*(x3094)))+(((IkReal(-1.00000000000000))*(x3088)*(x3093)))+(((sj5)*(x3089)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3)))))));
11342 sj2array[0]=IKsin(j2array[0]);
11343 cj2array[0]=IKcos(j2array[0]);
11344 if( j2array[0] > IKPI )
11345 {
11346     j2array[0]-=IK2PI;
11347 }
11348 else if( j2array[0] < -IKPI )
11349 {    j2array[0]+=IK2PI;
11350 }
11351 j2valid[0] = true;
11352 for(int ij2 = 0; ij2 < 1; ++ij2)
11353 {
11354 if( !j2valid[ij2] )
11355 {
11356     continue;
11357 }
11358 _ij2[0] = ij2; _ij2[1] = -1;
11359 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
11360 {
11361 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
11362 {
11363     j2valid[iij2]=false; _ij2[1] = iij2; break; 
11364 }
11365 }
11366 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
11367 {
11368 IkReal evalcond[3];
11369 IkReal x3095=IKsin(j2);
11370 IkReal x3096=IKcos(j2);
11371 IkReal x3097=((cj5)*(npx));
11372 IkReal x3098=((npy)*(sj5));
11373 IkReal x3099=((IkReal(0.165463933124939))*(x3096));
11374 IkReal x3100=((IkReal(0.207888640466058))*(x3095));
11375 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(0.165463933124939))*(x3095)))+(((IkReal(-0.207888640466058))*(x3096)))+(((cj4)*(npz)))+(((sj4)*(x3098)))+(((IkReal(-1.00000000000000))*(sj4)*(x3097))));
11376 evalcond[1]=((IkReal(-0.00600000000000000))+(((IkReal(-0.0300035672348961))*(sj3)))+(((npx)*(sj5)))+(((IkReal(-1.00000000000000))*(sj3)*(x3100)))+(((IkReal(-0.00600000000000000))*(cj3)))+(((cj5)*(npy)))+(((IkReal(-1.00000000000000))*(sj3)*(x3099))));
11377 evalcond[2]=((((cj4)*(x3097)))+(((npz)*(sj4)))+(((IkReal(-0.00600000000000000))*(sj3)))+(((cj3)*(x3100)))+(((IkReal(-1.00000000000000))*(cj4)*(x3098)))+(((cj3)*(x3099)))+(((IkReal(0.0300035672348961))*(cj3))));
11378 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
11379 {
11380 continue;
11381 }
11382 }
11383 
11384 {
11385 IkReal dummyeval[1];
11386 IkReal gconst36;
11387 IkReal x3101=((IkReal(1.00000000000000))*(sj3));
11388 gconst36=IKsign(((((IkReal(-1.00000000000000))*(x3101)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3101)*((sj2)*(sj2))))));
11389 IkReal x3102=((IkReal(1.00000000000000))*(sj3));
11390 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3102)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x3102)*((cj2)*(cj2)))));
11391 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11392 {
11393 {
11394 IkReal dummyeval[1];
11395 IkReal gconst37;
11396 IkReal x3103=((IkReal(1.00000000000000))*(cj3));
11397 gconst37=IKsign(((((IkReal(-1.00000000000000))*(x3103)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x3103)*((cj2)*(cj2))))));
11398 IkReal x3104=((IkReal(1.00000000000000))*(cj3));
11399 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3104)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3104)*((sj2)*(sj2)))));
11400 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11401 {
11402 {
11403 IkReal evalcond[9];
11404 IkReal x3105=((sj0)*(sj4));
11405 IkReal x3106=((IkReal(1.00000000000000))*(r12));
11406 IkReal x3107=((cj0)*(cj4));
11407 IkReal x3108=((r01)*(sj5));
11408 IkReal x3109=((IkReal(1.00000000000000))*(cj5));
11409 IkReal x3110=((cj4)*(cj5));
11410 IkReal x3111=((IkReal(1.00000000000000))*(cj0));
11411 IkReal x3112=((cj4)*(sj0));
11412 IkReal x3113=((r00)*(sj0));
11413 IkReal x3114=((npy)*(sj5));
11414 IkReal x3115=((IkReal(1.00000000000000))*(cj4));
11415 IkReal x3116=((cj0)*(sj4));
11416 IkReal x3117=((r11)*(sj5));
11417 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
11418 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3109)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x3113)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3111))));
11419 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3109)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x3114)))+(((IkReal(0.165463933124939))*(sj2))));
11420 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
11421 evalcond[4]=((IkReal(-0.00600000000000000))+(((npx)*(x3110)))+(((IkReal(-1.00000000000000))*(x3114)*(x3115)))+(((npz)*(sj4))));
11422 evalcond[5]=((((r02)*(x3112)))+(((IkReal(-1.00000000000000))*(x3106)*(x3107)))+(((x3105)*(x3108)))+(((IkReal(-1.00000000000000))*(r00)*(x3105)*(x3109)))+(((IkReal(-1.00000000000000))*(sj4)*(x3111)*(x3117)))+(((cj5)*(r10)*(x3116))));
11423 evalcond[6]=((IkReal(1.00000000000000))+(((x3107)*(x3117)))+(((IkReal(-1.00000000000000))*(x3108)*(x3112)))+(((IkReal(-1.00000000000000))*(r10)*(x3107)*(x3109)))+(((r02)*(x3105)))+(((x3110)*(x3113)))+(((IkReal(-1.00000000000000))*(x3106)*(x3116))));
11424 evalcond[7]=((((r22)*(sj4)))+(((r20)*(x3110)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3115))));
11425 evalcond[8]=((((IkReal(-1.00000000000000))*(r10)*(x3109)*(x3112)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3111)))+(((x3107)*(x3108)))+(((x3112)*(x3117)))+(((IkReal(-1.00000000000000))*(x3105)*(x3106)))+(((IkReal(-1.00000000000000))*(r00)*(x3107)*(x3109))));
11426 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  )
11427 {
11428 {
11429 IkReal dummyeval[1];
11430 IkReal gconst38;
11431 gconst38=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
11432 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
11433 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11434 {
11435 {
11436 IkReal dummyeval[1];
11437 IkReal gconst39;
11438 gconst39=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
11439 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
11440 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11441 {
11442 continue;
11443 
11444 } else
11445 {
11446 {
11447 IkReal j1array[1], cj1array[1], sj1array[1];
11448 bool j1valid[1]={false};
11449 _nj1 = 1;
11450 IkReal x3118=((cj5)*(r11));
11451 IkReal x3119=((r10)*(sj0));
11452 IkReal x3120=((IkReal(0.707103562373095))*(cj2));
11453 IkReal x3121=((r20)*(sj5));
11454 IkReal x3122=((IkReal(0.707103562373095))*(sj2));
11455 IkReal x3123=((IkReal(0.707109999985348))*(cj2));
11456 IkReal x3124=((cj0)*(r00));
11457 IkReal x3125=((IkReal(0.707109999985348))*(sj2));
11458 IkReal x3126=((cj5)*(r21));
11459 IkReal x3127=((sj0)*(x3122));
11460 IkReal x3128=((sj5)*(x3123));
11461 IkReal x3129=((cj0)*(cj5)*(r01));
11462 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3119)*(x3122)))+(((IkReal(-1.00000000000000))*(sj5)*(x3122)*(x3124)))+(((IkReal(-1.00000000000000))*(x3124)*(x3128)))+(((x3125)*(x3126)))+(((IkReal(-1.00000000000000))*(x3122)*(x3129)))+(((x3121)*(x3125)))+(((IkReal(-1.00000000000000))*(x3123)*(x3129)))+(((IkReal(-1.00000000000000))*(x3120)*(x3126)))+(((IkReal(-1.00000000000000))*(x3120)*(x3121)))+(((IkReal(-1.00000000000000))*(sj0)*(x3118)*(x3123)))+(((IkReal(-1.00000000000000))*(x3119)*(x3128)))+(((IkReal(-1.00000000000000))*(x3118)*(x3127))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3119)*(x3125)))+(((x3120)*(x3129)))+(((IkReal(-1.00000000000000))*(x3125)*(x3129)))+(((IkReal(-1.00000000000000))*(sj5)*(x3124)*(x3125)))+(((IkReal(-1.00000000000000))*(x3122)*(x3126)))+(((IkReal(-1.00000000000000))*(x3123)*(x3126)))+(((IkReal(-1.00000000000000))*(sj0)*(x3118)*(x3125)))+(((IkReal(-1.00000000000000))*(x3121)*(x3122)))+(((IkReal(-1.00000000000000))*(x3121)*(x3123)))+(((sj5)*(x3119)*(x3120)))+(((sj0)*(x3118)*(x3120)))+(((sj5)*(x3120)*(x3124))))))) < IKFAST_ATAN2_MAGTHRESH )
11463     continue;
11464 j1array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3119)*(x3122)))+(((IkReal(-1.00000000000000))*(sj5)*(x3122)*(x3124)))+(((IkReal(-1.00000000000000))*(x3124)*(x3128)))+(((x3125)*(x3126)))+(((IkReal(-1.00000000000000))*(x3122)*(x3129)))+(((x3121)*(x3125)))+(((IkReal(-1.00000000000000))*(x3123)*(x3129)))+(((IkReal(-1.00000000000000))*(x3120)*(x3126)))+(((IkReal(-1.00000000000000))*(x3120)*(x3121)))+(((IkReal(-1.00000000000000))*(sj0)*(x3118)*(x3123)))+(((IkReal(-1.00000000000000))*(x3119)*(x3128)))+(((IkReal(-1.00000000000000))*(x3118)*(x3127)))))), ((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3119)*(x3125)))+(((x3120)*(x3129)))+(((IkReal(-1.00000000000000))*(x3125)*(x3129)))+(((IkReal(-1.00000000000000))*(sj5)*(x3124)*(x3125)))+(((IkReal(-1.00000000000000))*(x3122)*(x3126)))+(((IkReal(-1.00000000000000))*(x3123)*(x3126)))+(((IkReal(-1.00000000000000))*(sj0)*(x3118)*(x3125)))+(((IkReal(-1.00000000000000))*(x3121)*(x3122)))+(((IkReal(-1.00000000000000))*(x3121)*(x3123)))+(((sj5)*(x3119)*(x3120)))+(((sj0)*(x3118)*(x3120)))+(((sj5)*(x3120)*(x3124)))))));
11465 sj1array[0]=IKsin(j1array[0]);
11466 cj1array[0]=IKcos(j1array[0]);
11467 if( j1array[0] > IKPI )
11468 {
11469     j1array[0]-=IK2PI;
11470 }
11471 else if( j1array[0] < -IKPI )
11472 {    j1array[0]+=IK2PI;
11473 }
11474 j1valid[0] = true;
11475 for(int ij1 = 0; ij1 < 1; ++ij1)
11476 {
11477 if( !j1valid[ij1] )
11478 {
11479     continue;
11480 }
11481 _ij1[0] = ij1; _ij1[1] = -1;
11482 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11483 {
11484 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11485 {
11486     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11487 }
11488 }
11489 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11490 {
11491 IkReal evalcond[4];
11492 IkReal x3130=IKsin(j1);
11493 IkReal x3131=IKcos(j1);
11494 IkReal x3132=((IkReal(0.707109999985348))*(cj2));
11495 IkReal x3133=((IkReal(1.00000000000000))*(cj0));
11496 IkReal x3134=((IkReal(0.707109999985348))*(sj2));
11497 IkReal x3135=((cj5)*(sj4));
11498 IkReal x3136=((sj4)*(sj5));
11499 IkReal x3137=((IkReal(1.00000000000000))*(sj0));
11500 IkReal x3138=((sj5)*(x3137));
11501 IkReal x3139=((IkReal(0.707103562373095))*(x3131));
11502 IkReal x3140=((IkReal(0.707103562373095))*(x3130));
11503 IkReal x3141=((x3130)*(x3132));
11504 IkReal x3142=((sj2)*(x3140));
11505 IkReal x3143=((x3131)*(x3134));
11506 IkReal x3144=((cj2)*(x3139));
11507 IkReal x3145=((sj2)*(x3139));
11508 IkReal x3146=((cj2)*(x3140));
11509 IkReal x3147=((x3131)*(x3132));
11510 IkReal x3148=((x3130)*(x3134));
11511 IkReal x3149=((x3145)+(x3146)+(x3147));
11512 IkReal x3150=((x3141)+(x3142)+(x3143));
11513 evalcond[0]=((x3148)+(((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3149)))+(((r20)*(sj5))));
11514 evalcond[1]=((x3150)+(((IkReal(-1.00000000000000))*(x3144)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x3135)))+(((r21)*(x3136))));
11515 evalcond[2]=((x3150)+(((IkReal(-1.00000000000000))*(x3144)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3137)))+(((IkReal(-1.00000000000000))*(r10)*(x3138)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3133)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3133))));
11516 evalcond[3]=((x3149)+(((IkReal(-1.00000000000000))*(x3148)))+(((r10)*(sj0)*(x3135)))+(((cj0)*(r00)*(x3135)))+(((IkReal(-1.00000000000000))*(r01)*(x3133)*(x3136)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3137)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3133)))+(((IkReal(-1.00000000000000))*(r11)*(x3136)*(x3137))));
11517 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11518 {
11519 continue;
11520 }
11521 }
11522 
11523 {
11524 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11525 vinfos[0].jointtype = 1;
11526 vinfos[0].foffset = j0;
11527 vinfos[0].indices[0] = _ij0[0];
11528 vinfos[0].indices[1] = _ij0[1];
11529 vinfos[0].maxsolutions = _nj0;
11530 vinfos[1].jointtype = 1;
11531 vinfos[1].foffset = j1;
11532 vinfos[1].indices[0] = _ij1[0];
11533 vinfos[1].indices[1] = _ij1[1];
11534 vinfos[1].maxsolutions = _nj1;
11535 vinfos[2].jointtype = 1;
11536 vinfos[2].foffset = j2;
11537 vinfos[2].indices[0] = _ij2[0];
11538 vinfos[2].indices[1] = _ij2[1];
11539 vinfos[2].maxsolutions = _nj2;
11540 vinfos[3].jointtype = 1;
11541 vinfos[3].foffset = j3;
11542 vinfos[3].indices[0] = _ij3[0];
11543 vinfos[3].indices[1] = _ij3[1];
11544 vinfos[3].maxsolutions = _nj3;
11545 vinfos[4].jointtype = 1;
11546 vinfos[4].foffset = j4;
11547 vinfos[4].indices[0] = _ij4[0];
11548 vinfos[4].indices[1] = _ij4[1];
11549 vinfos[4].maxsolutions = _nj4;
11550 vinfos[5].jointtype = 1;
11551 vinfos[5].foffset = j5;
11552 vinfos[5].indices[0] = _ij5[0];
11553 vinfos[5].indices[1] = _ij5[1];
11554 vinfos[5].maxsolutions = _nj5;
11555 std::vector<int> vfree(0);
11556 solutions.AddSolution(vinfos,vfree);
11557 }
11558 }
11559 }
11560 
11561 }
11562 
11563 }
11564 
11565 } else
11566 {
11567 {
11568 IkReal j1array[1], cj1array[1], sj1array[1];
11569 bool j1valid[1]={false};
11570 _nj1 = 1;
11571 IkReal x3151=((cj5)*(sj4));
11572 IkReal x3152=((r21)*(sj4));
11573 IkReal x3153=((cj5)*(r21));
11574 IkReal x3154=((IkReal(0.707109999985348))*(cj2));
11575 IkReal x3155=((IkReal(0.707103562373095))*(sj2));
11576 IkReal x3156=((IkReal(0.707109999985348))*(sj2));
11577 IkReal x3157=((cj4)*(r22));
11578 IkReal x3158=((IkReal(0.707103562373095))*(cj2));
11579 IkReal x3159=((r20)*(x3154));
11580 IkReal x3160=((sj5)*(x3158));
11581 IkReal x3161=((sj5)*(x3156));
11582 if( IKabs(((gconst38)*(((((sj5)*(x3152)*(x3155)))+(((sj5)*(x3152)*(x3154)))+(((IkReal(-1.00000000000000))*(x3153)*(x3158)))+(((x3155)*(x3157)))+(((x3154)*(x3157)))+(((r20)*(x3161)))+(((x3153)*(x3156)))+(((IkReal(-1.00000000000000))*(r20)*(x3160)))+(((IkReal(-1.00000000000000))*(r20)*(x3151)*(x3155)))+(((IkReal(-1.00000000000000))*(x3151)*(x3159))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(x3152)*(x3160)))+(((IkReal(-1.00000000000000))*(x3157)*(x3158)))+(((x3152)*(x3161)))+(((IkReal(-1.00000000000000))*(x3153)*(x3155)))+(((IkReal(-1.00000000000000))*(x3153)*(x3154)))+(((x3156)*(x3157)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3155)))+(((IkReal(-1.00000000000000))*(sj5)*(x3159)))+(((IkReal(-1.00000000000000))*(r20)*(x3151)*(x3156)))+(((r20)*(x3151)*(x3158))))))) < IKFAST_ATAN2_MAGTHRESH )
11583     continue;
11584 j1array[0]=IKatan2(((gconst38)*(((((sj5)*(x3152)*(x3155)))+(((sj5)*(x3152)*(x3154)))+(((IkReal(-1.00000000000000))*(x3153)*(x3158)))+(((x3155)*(x3157)))+(((x3154)*(x3157)))+(((r20)*(x3161)))+(((x3153)*(x3156)))+(((IkReal(-1.00000000000000))*(r20)*(x3160)))+(((IkReal(-1.00000000000000))*(r20)*(x3151)*(x3155)))+(((IkReal(-1.00000000000000))*(x3151)*(x3159)))))), ((gconst38)*(((((IkReal(-1.00000000000000))*(x3152)*(x3160)))+(((IkReal(-1.00000000000000))*(x3157)*(x3158)))+(((x3152)*(x3161)))+(((IkReal(-1.00000000000000))*(x3153)*(x3155)))+(((IkReal(-1.00000000000000))*(x3153)*(x3154)))+(((x3156)*(x3157)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3155)))+(((IkReal(-1.00000000000000))*(sj5)*(x3159)))+(((IkReal(-1.00000000000000))*(r20)*(x3151)*(x3156)))+(((r20)*(x3151)*(x3158)))))));
11585 sj1array[0]=IKsin(j1array[0]);
11586 cj1array[0]=IKcos(j1array[0]);
11587 if( j1array[0] > IKPI )
11588 {
11589     j1array[0]-=IK2PI;
11590 }
11591 else if( j1array[0] < -IKPI )
11592 {    j1array[0]+=IK2PI;
11593 }
11594 j1valid[0] = true;
11595 for(int ij1 = 0; ij1 < 1; ++ij1)
11596 {
11597 if( !j1valid[ij1] )
11598 {
11599     continue;
11600 }
11601 _ij1[0] = ij1; _ij1[1] = -1;
11602 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11603 {
11604 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11605 {
11606     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11607 }
11608 }
11609 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11610 {
11611 IkReal evalcond[4];
11612 IkReal x3162=IKsin(j1);
11613 IkReal x3163=IKcos(j1);
11614 IkReal x3164=((IkReal(0.707109999985348))*(cj2));
11615 IkReal x3165=((IkReal(1.00000000000000))*(cj0));
11616 IkReal x3166=((IkReal(0.707109999985348))*(sj2));
11617 IkReal x3167=((cj5)*(sj4));
11618 IkReal x3168=((sj4)*(sj5));
11619 IkReal x3169=((IkReal(1.00000000000000))*(sj0));
11620 IkReal x3170=((sj5)*(x3169));
11621 IkReal x3171=((IkReal(0.707103562373095))*(x3163));
11622 IkReal x3172=((IkReal(0.707103562373095))*(x3162));
11623 IkReal x3173=((x3162)*(x3164));
11624 IkReal x3174=((sj2)*(x3172));
11625 IkReal x3175=((x3163)*(x3166));
11626 IkReal x3176=((cj2)*(x3171));
11627 IkReal x3177=((sj2)*(x3171));
11628 IkReal x3178=((cj2)*(x3172));
11629 IkReal x3179=((x3163)*(x3164));
11630 IkReal x3180=((x3162)*(x3166));
11631 IkReal x3181=((x3179)+(x3178)+(x3177));
11632 IkReal x3182=((x3173)+(x3175)+(x3174));
11633 evalcond[0]=((x3180)+(((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3181)))+(((r20)*(sj5))));
11634 evalcond[1]=((x3182)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3176)))+(((IkReal(-1.00000000000000))*(r20)*(x3167)))+(((r21)*(x3168))));
11635 evalcond[2]=((x3182)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3165)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3165)))+(((IkReal(-1.00000000000000))*(r10)*(x3170)))+(((IkReal(-1.00000000000000))*(x3176)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3169))));
11636 evalcond[3]=((x3181)+(((IkReal(-1.00000000000000))*(r11)*(x3168)*(x3169)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3169)))+(((IkReal(-1.00000000000000))*(r01)*(x3165)*(x3168)))+(((r10)*(sj0)*(x3167)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3165)))+(((IkReal(-1.00000000000000))*(x3180)))+(((cj0)*(r00)*(x3167))));
11637 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11638 {
11639 continue;
11640 }
11641 }
11642 
11643 {
11644 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11645 vinfos[0].jointtype = 1;
11646 vinfos[0].foffset = j0;
11647 vinfos[0].indices[0] = _ij0[0];
11648 vinfos[0].indices[1] = _ij0[1];
11649 vinfos[0].maxsolutions = _nj0;
11650 vinfos[1].jointtype = 1;
11651 vinfos[1].foffset = j1;
11652 vinfos[1].indices[0] = _ij1[0];
11653 vinfos[1].indices[1] = _ij1[1];
11654 vinfos[1].maxsolutions = _nj1;
11655 vinfos[2].jointtype = 1;
11656 vinfos[2].foffset = j2;
11657 vinfos[2].indices[0] = _ij2[0];
11658 vinfos[2].indices[1] = _ij2[1];
11659 vinfos[2].maxsolutions = _nj2;
11660 vinfos[3].jointtype = 1;
11661 vinfos[3].foffset = j3;
11662 vinfos[3].indices[0] = _ij3[0];
11663 vinfos[3].indices[1] = _ij3[1];
11664 vinfos[3].maxsolutions = _nj3;
11665 vinfos[4].jointtype = 1;
11666 vinfos[4].foffset = j4;
11667 vinfos[4].indices[0] = _ij4[0];
11668 vinfos[4].indices[1] = _ij4[1];
11669 vinfos[4].maxsolutions = _nj4;
11670 vinfos[5].jointtype = 1;
11671 vinfos[5].foffset = j5;
11672 vinfos[5].indices[0] = _ij5[0];
11673 vinfos[5].indices[1] = _ij5[1];
11674 vinfos[5].maxsolutions = _nj5;
11675 std::vector<int> vfree(0);
11676 solutions.AddSolution(vinfos,vfree);
11677 }
11678 }
11679 }
11680 
11681 }
11682 
11683 }
11684 
11685 } else
11686 {
11687 IkReal x3183=((sj0)*(sj4));
11688 IkReal x3184=((IkReal(1.00000000000000))*(r12));
11689 IkReal x3185=((cj0)*(cj4));
11690 IkReal x3186=((r01)*(sj5));
11691 IkReal x3187=((IkReal(1.00000000000000))*(cj5));
11692 IkReal x3188=((cj4)*(cj5));
11693 IkReal x3189=((IkReal(1.00000000000000))*(cj0));
11694 IkReal x3190=((cj4)*(sj0));
11695 IkReal x3191=((r00)*(sj0));
11696 IkReal x3192=((npy)*(sj5));
11697 IkReal x3193=((IkReal(1.00000000000000))*(cj4));
11698 IkReal x3194=((cj0)*(sj4));
11699 IkReal x3195=((r11)*(sj5));
11700 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
11701 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3187)))+(((sj5)*(x3191)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3189))));
11702 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x3192)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3187)))+(((IkReal(0.165463933124939))*(sj2))));
11703 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
11704 evalcond[4]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x3192)*(x3193)))+(((npx)*(x3188))));
11705 evalcond[5]=((((IkReal(-1.00000000000000))*(x3184)*(x3185)))+(((IkReal(-1.00000000000000))*(r00)*(x3183)*(x3187)))+(((cj5)*(r10)*(x3194)))+(((x3183)*(x3186)))+(((IkReal(-1.00000000000000))*(sj4)*(x3189)*(x3195)))+(((r02)*(x3190))));
11706 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x3184)*(x3194)))+(((IkReal(-1.00000000000000))*(x3186)*(x3190)))+(((x3185)*(x3195)))+(((IkReal(-1.00000000000000))*(r10)*(x3185)*(x3187)))+(((x3188)*(x3191)))+(((r02)*(x3183))));
11707 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3193)))+(((r20)*(x3188))));
11708 evalcond[8]=((((IkReal(-1.00000000000000))*(x3183)*(x3184)))+(((IkReal(-1.00000000000000))*(r00)*(x3185)*(x3187)))+(((x3185)*(x3186)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3189)))+(((x3190)*(x3195)))+(((IkReal(-1.00000000000000))*(r10)*(x3187)*(x3190))));
11709 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  )
11710 {
11711 {
11712 IkReal dummyeval[1];
11713 IkReal gconst40;
11714 gconst40=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
11715 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
11716 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11717 {
11718 {
11719 IkReal dummyeval[1];
11720 IkReal gconst41;
11721 gconst41=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
11722 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
11723 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11724 {
11725 continue;
11726 
11727 } else
11728 {
11729 {
11730 IkReal j1array[1], cj1array[1], sj1array[1];
11731 bool j1valid[1]={false};
11732 _nj1 = 1;
11733 IkReal x3196=((cj5)*(r11));
11734 IkReal x3197=((r10)*(sj0));
11735 IkReal x3198=((IkReal(0.707103562373095))*(cj2));
11736 IkReal x3199=((r20)*(sj5));
11737 IkReal x3200=((IkReal(0.707103562373095))*(sj2));
11738 IkReal x3201=((IkReal(0.707109999985348))*(cj2));
11739 IkReal x3202=((cj0)*(r00));
11740 IkReal x3203=((IkReal(0.707109999985348))*(sj2));
11741 IkReal x3204=((cj5)*(r21));
11742 IkReal x3205=((sj0)*(x3200));
11743 IkReal x3206=((sj5)*(x3201));
11744 IkReal x3207=((cj0)*(cj5)*(r01));
11745 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(x3196)*(x3205)))+(((IkReal(-1.00000000000000))*(sj0)*(x3196)*(x3201)))+(((IkReal(-1.00000000000000))*(x3200)*(x3207)))+(((IkReal(-1.00000000000000))*(sj5)*(x3200)*(x3202)))+(((IkReal(-1.00000000000000))*(x3198)*(x3199)))+(((x3199)*(x3203)))+(((IkReal(-1.00000000000000))*(x3202)*(x3206)))+(((IkReal(-1.00000000000000))*(x3201)*(x3207)))+(((IkReal(-1.00000000000000))*(x3197)*(x3206)))+(((IkReal(-1.00000000000000))*(sj5)*(x3197)*(x3200)))+(((x3203)*(x3204)))+(((IkReal(-1.00000000000000))*(x3198)*(x3204))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((sj0)*(x3196)*(x3198)))+(((IkReal(-1.00000000000000))*(sj0)*(x3196)*(x3203)))+(((x3198)*(x3207)))+(((IkReal(-1.00000000000000))*(x3199)*(x3200)))+(((IkReal(-1.00000000000000))*(x3199)*(x3201)))+(((IkReal(-1.00000000000000))*(sj5)*(x3202)*(x3203)))+(((IkReal(-1.00000000000000))*(x3200)*(x3204)))+(((sj5)*(x3198)*(x3202)))+(((IkReal(-1.00000000000000))*(x3201)*(x3204)))+(((IkReal(-1.00000000000000))*(x3203)*(x3207)))+(((IkReal(-1.00000000000000))*(sj5)*(x3197)*(x3203)))+(((sj5)*(x3197)*(x3198))))))) < IKFAST_ATAN2_MAGTHRESH )
11746     continue;
11747 j1array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(x3196)*(x3205)))+(((IkReal(-1.00000000000000))*(sj0)*(x3196)*(x3201)))+(((IkReal(-1.00000000000000))*(x3200)*(x3207)))+(((IkReal(-1.00000000000000))*(sj5)*(x3200)*(x3202)))+(((IkReal(-1.00000000000000))*(x3198)*(x3199)))+(((x3199)*(x3203)))+(((IkReal(-1.00000000000000))*(x3202)*(x3206)))+(((IkReal(-1.00000000000000))*(x3201)*(x3207)))+(((IkReal(-1.00000000000000))*(x3197)*(x3206)))+(((IkReal(-1.00000000000000))*(sj5)*(x3197)*(x3200)))+(((x3203)*(x3204)))+(((IkReal(-1.00000000000000))*(x3198)*(x3204)))))), ((gconst41)*(((((sj0)*(x3196)*(x3198)))+(((IkReal(-1.00000000000000))*(sj0)*(x3196)*(x3203)))+(((x3198)*(x3207)))+(((IkReal(-1.00000000000000))*(x3199)*(x3200)))+(((IkReal(-1.00000000000000))*(x3199)*(x3201)))+(((IkReal(-1.00000000000000))*(sj5)*(x3202)*(x3203)))+(((IkReal(-1.00000000000000))*(x3200)*(x3204)))+(((sj5)*(x3198)*(x3202)))+(((IkReal(-1.00000000000000))*(x3201)*(x3204)))+(((IkReal(-1.00000000000000))*(x3203)*(x3207)))+(((IkReal(-1.00000000000000))*(sj5)*(x3197)*(x3203)))+(((sj5)*(x3197)*(x3198)))))));
11748 sj1array[0]=IKsin(j1array[0]);
11749 cj1array[0]=IKcos(j1array[0]);
11750 if( j1array[0] > IKPI )
11751 {
11752     j1array[0]-=IK2PI;
11753 }
11754 else if( j1array[0] < -IKPI )
11755 {    j1array[0]+=IK2PI;
11756 }
11757 j1valid[0] = true;
11758 for(int ij1 = 0; ij1 < 1; ++ij1)
11759 {
11760 if( !j1valid[ij1] )
11761 {
11762     continue;
11763 }
11764 _ij1[0] = ij1; _ij1[1] = -1;
11765 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11766 {
11767 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11768 {
11769     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11770 }
11771 }
11772 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11773 {
11774 IkReal evalcond[4];
11775 IkReal x3208=IKsin(j1);
11776 IkReal x3209=IKcos(j1);
11777 IkReal x3210=((IkReal(0.707109999985348))*(cj2));
11778 IkReal x3211=((IkReal(1.00000000000000))*(cj0));
11779 IkReal x3212=((IkReal(0.707109999985348))*(sj2));
11780 IkReal x3213=((cj5)*(sj4));
11781 IkReal x3214=((sj4)*(sj5));
11782 IkReal x3215=((IkReal(1.00000000000000))*(sj0));
11783 IkReal x3216=((sj5)*(x3215));
11784 IkReal x3217=((IkReal(0.707103562373095))*(x3209));
11785 IkReal x3218=((IkReal(0.707103562373095))*(x3208));
11786 IkReal x3219=((x3208)*(x3210));
11787 IkReal x3220=((sj2)*(x3218));
11788 IkReal x3221=((x3209)*(x3212));
11789 IkReal x3222=((cj2)*(x3217));
11790 IkReal x3223=((sj2)*(x3217));
11791 IkReal x3224=((cj2)*(x3218));
11792 IkReal x3225=((x3209)*(x3210));
11793 IkReal x3226=((x3208)*(x3212));
11794 IkReal x3227=((x3225)+(x3224)+(x3223));
11795 IkReal x3228=((x3219)+(x3221)+(x3220));
11796 evalcond[0]=((((cj5)*(r21)))+(x3226)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x3227))));
11797 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3213)))+(((cj4)*(r22)))+(x3228)+(((r21)*(x3214)))+(((IkReal(-1.00000000000000))*(x3222))));
11798 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3216)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3215)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3211)))+(x3228)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3211)))+(((IkReal(-1.00000000000000))*(x3222))));
11799 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3211)*(x3214)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3211)))+(x3227)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3215)))+(((IkReal(-1.00000000000000))*(r11)*(x3214)*(x3215)))+(((r10)*(sj0)*(x3213)))+(((cj0)*(r00)*(x3213)))+(((IkReal(-1.00000000000000))*(x3226))));
11800 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11801 {
11802 continue;
11803 }
11804 }
11805 
11806 {
11807 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11808 vinfos[0].jointtype = 1;
11809 vinfos[0].foffset = j0;
11810 vinfos[0].indices[0] = _ij0[0];
11811 vinfos[0].indices[1] = _ij0[1];
11812 vinfos[0].maxsolutions = _nj0;
11813 vinfos[1].jointtype = 1;
11814 vinfos[1].foffset = j1;
11815 vinfos[1].indices[0] = _ij1[0];
11816 vinfos[1].indices[1] = _ij1[1];
11817 vinfos[1].maxsolutions = _nj1;
11818 vinfos[2].jointtype = 1;
11819 vinfos[2].foffset = j2;
11820 vinfos[2].indices[0] = _ij2[0];
11821 vinfos[2].indices[1] = _ij2[1];
11822 vinfos[2].maxsolutions = _nj2;
11823 vinfos[3].jointtype = 1;
11824 vinfos[3].foffset = j3;
11825 vinfos[3].indices[0] = _ij3[0];
11826 vinfos[3].indices[1] = _ij3[1];
11827 vinfos[3].maxsolutions = _nj3;
11828 vinfos[4].jointtype = 1;
11829 vinfos[4].foffset = j4;
11830 vinfos[4].indices[0] = _ij4[0];
11831 vinfos[4].indices[1] = _ij4[1];
11832 vinfos[4].maxsolutions = _nj4;
11833 vinfos[5].jointtype = 1;
11834 vinfos[5].foffset = j5;
11835 vinfos[5].indices[0] = _ij5[0];
11836 vinfos[5].indices[1] = _ij5[1];
11837 vinfos[5].maxsolutions = _nj5;
11838 std::vector<int> vfree(0);
11839 solutions.AddSolution(vinfos,vfree);
11840 }
11841 }
11842 }
11843 
11844 }
11845 
11846 }
11847 
11848 } else
11849 {
11850 {
11851 IkReal j1array[1], cj1array[1], sj1array[1];
11852 bool j1valid[1]={false};
11853 _nj1 = 1;
11854 IkReal x3229=((cj5)*(sj4));
11855 IkReal x3230=((r21)*(sj4));
11856 IkReal x3231=((cj5)*(r21));
11857 IkReal x3232=((IkReal(0.707109999985348))*(cj2));
11858 IkReal x3233=((IkReal(0.707103562373095))*(sj2));
11859 IkReal x3234=((IkReal(0.707109999985348))*(sj2));
11860 IkReal x3235=((cj4)*(r22));
11861 IkReal x3236=((IkReal(0.707103562373095))*(cj2));
11862 IkReal x3237=((r20)*(x3232));
11863 IkReal x3238=((sj5)*(x3236));
11864 IkReal x3239=((sj5)*(x3234));
11865 if( IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3229)*(x3233)))+(((IkReal(-1.00000000000000))*(x3229)*(x3237)))+(((x3232)*(x3235)))+(((IkReal(-1.00000000000000))*(x3231)*(x3236)))+(((r20)*(x3239)))+(((x3231)*(x3234)))+(((IkReal(-1.00000000000000))*(r20)*(x3238)))+(((sj5)*(x3230)*(x3232)))+(((sj5)*(x3230)*(x3233)))+(((x3233)*(x3235))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3229)*(x3234)))+(((x3234)*(x3235)))+(((IkReal(-1.00000000000000))*(x3230)*(x3238)))+(((IkReal(-1.00000000000000))*(x3235)*(x3236)))+(((IkReal(-1.00000000000000))*(x3231)*(x3233)))+(((IkReal(-1.00000000000000))*(x3231)*(x3232)))+(((r20)*(x3229)*(x3236)))+(((IkReal(-1.00000000000000))*(sj5)*(x3237)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3233)))+(((x3230)*(x3239))))))) < IKFAST_ATAN2_MAGTHRESH )
11866     continue;
11867 j1array[0]=IKatan2(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3229)*(x3233)))+(((IkReal(-1.00000000000000))*(x3229)*(x3237)))+(((x3232)*(x3235)))+(((IkReal(-1.00000000000000))*(x3231)*(x3236)))+(((r20)*(x3239)))+(((x3231)*(x3234)))+(((IkReal(-1.00000000000000))*(r20)*(x3238)))+(((sj5)*(x3230)*(x3232)))+(((sj5)*(x3230)*(x3233)))+(((x3233)*(x3235)))))), ((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3229)*(x3234)))+(((x3234)*(x3235)))+(((IkReal(-1.00000000000000))*(x3230)*(x3238)))+(((IkReal(-1.00000000000000))*(x3235)*(x3236)))+(((IkReal(-1.00000000000000))*(x3231)*(x3233)))+(((IkReal(-1.00000000000000))*(x3231)*(x3232)))+(((r20)*(x3229)*(x3236)))+(((IkReal(-1.00000000000000))*(sj5)*(x3237)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3233)))+(((x3230)*(x3239)))))));
11868 sj1array[0]=IKsin(j1array[0]);
11869 cj1array[0]=IKcos(j1array[0]);
11870 if( j1array[0] > IKPI )
11871 {
11872     j1array[0]-=IK2PI;
11873 }
11874 else if( j1array[0] < -IKPI )
11875 {    j1array[0]+=IK2PI;
11876 }
11877 j1valid[0] = true;
11878 for(int ij1 = 0; ij1 < 1; ++ij1)
11879 {
11880 if( !j1valid[ij1] )
11881 {
11882     continue;
11883 }
11884 _ij1[0] = ij1; _ij1[1] = -1;
11885 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
11886 {
11887 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
11888 {
11889     j1valid[iij1]=false; _ij1[1] = iij1; break; 
11890 }
11891 }
11892 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
11893 {
11894 IkReal evalcond[4];
11895 IkReal x3240=IKsin(j1);
11896 IkReal x3241=IKcos(j1);
11897 IkReal x3242=((IkReal(0.707109999985348))*(cj2));
11898 IkReal x3243=((IkReal(1.00000000000000))*(cj0));
11899 IkReal x3244=((IkReal(0.707109999985348))*(sj2));
11900 IkReal x3245=((cj5)*(sj4));
11901 IkReal x3246=((sj4)*(sj5));
11902 IkReal x3247=((IkReal(1.00000000000000))*(sj0));
11903 IkReal x3248=((sj5)*(x3247));
11904 IkReal x3249=((IkReal(0.707103562373095))*(x3241));
11905 IkReal x3250=((IkReal(0.707103562373095))*(x3240));
11906 IkReal x3251=((x3240)*(x3242));
11907 IkReal x3252=((sj2)*(x3250));
11908 IkReal x3253=((x3241)*(x3244));
11909 IkReal x3254=((cj2)*(x3249));
11910 IkReal x3255=((sj2)*(x3249));
11911 IkReal x3256=((cj2)*(x3250));
11912 IkReal x3257=((x3241)*(x3242));
11913 IkReal x3258=((x3240)*(x3244));
11914 IkReal x3259=((x3255)+(x3256)+(x3257));
11915 IkReal x3260=((x3251)+(x3252)+(x3253));
11916 evalcond[0]=((((cj5)*(r21)))+(x3258)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x3259))));
11917 evalcond[1]=((((r21)*(x3246)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x3245)))+(x3260)+(((IkReal(-1.00000000000000))*(x3254))));
11918 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3243)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3243)))+(x3260)+(((IkReal(-1.00000000000000))*(r10)*(x3248)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3247)))+(((IkReal(-1.00000000000000))*(x3254))));
11919 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x3246)*(x3247)))+(x3259)+(((r10)*(sj0)*(x3245)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3243)))+(((cj0)*(r00)*(x3245)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3247)))+(((IkReal(-1.00000000000000))*(x3258)))+(((IkReal(-1.00000000000000))*(r01)*(x3243)*(x3246))));
11920 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11921 {
11922 continue;
11923 }
11924 }
11925 
11926 {
11927 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11928 vinfos[0].jointtype = 1;
11929 vinfos[0].foffset = j0;
11930 vinfos[0].indices[0] = _ij0[0];
11931 vinfos[0].indices[1] = _ij0[1];
11932 vinfos[0].maxsolutions = _nj0;
11933 vinfos[1].jointtype = 1;
11934 vinfos[1].foffset = j1;
11935 vinfos[1].indices[0] = _ij1[0];
11936 vinfos[1].indices[1] = _ij1[1];
11937 vinfos[1].maxsolutions = _nj1;
11938 vinfos[2].jointtype = 1;
11939 vinfos[2].foffset = j2;
11940 vinfos[2].indices[0] = _ij2[0];
11941 vinfos[2].indices[1] = _ij2[1];
11942 vinfos[2].maxsolutions = _nj2;
11943 vinfos[3].jointtype = 1;
11944 vinfos[3].foffset = j3;
11945 vinfos[3].indices[0] = _ij3[0];
11946 vinfos[3].indices[1] = _ij3[1];
11947 vinfos[3].maxsolutions = _nj3;
11948 vinfos[4].jointtype = 1;
11949 vinfos[4].foffset = j4;
11950 vinfos[4].indices[0] = _ij4[0];
11951 vinfos[4].indices[1] = _ij4[1];
11952 vinfos[4].maxsolutions = _nj4;
11953 vinfos[5].jointtype = 1;
11954 vinfos[5].foffset = j5;
11955 vinfos[5].indices[0] = _ij5[0];
11956 vinfos[5].indices[1] = _ij5[1];
11957 vinfos[5].maxsolutions = _nj5;
11958 std::vector<int> vfree(0);
11959 solutions.AddSolution(vinfos,vfree);
11960 }
11961 }
11962 }
11963 
11964 }
11965 
11966 }
11967 
11968 } else
11969 {
11970 IkReal x3261=((sj0)*(sj4));
11971 IkReal x3262=((IkReal(1.00000000000000))*(r12));
11972 IkReal x3263=((cj0)*(cj4));
11973 IkReal x3264=((r01)*(sj5));
11974 IkReal x3265=((IkReal(1.00000000000000))*(cj5));
11975 IkReal x3266=((cj4)*(cj5));
11976 IkReal x3267=((IkReal(1.00000000000000))*(cj0));
11977 IkReal x3268=((cj4)*(sj0));
11978 IkReal x3269=((r00)*(sj0));
11979 IkReal x3270=((npy)*(sj5));
11980 IkReal x3271=((IkReal(1.00000000000000))*(cj4));
11981 IkReal x3272=((cj0)*(sj4));
11982 IkReal x3273=((r11)*(sj5));
11983 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
11984 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x3269)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3267)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3265))));
11985 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x3270)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3265))));
11986 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
11987 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x3270)*(x3271)))+(((npx)*(x3266))));
11988 evalcond[5]=((((cj5)*(r10)*(x3272)))+(((r02)*(x3268)))+(((IkReal(-1.00000000000000))*(x3262)*(x3263)))+(((IkReal(-1.00000000000000))*(sj4)*(x3267)*(x3273)))+(((x3261)*(x3264)))+(((IkReal(-1.00000000000000))*(r00)*(x3261)*(x3265))));
11989 evalcond[6]=((IkReal(-1.00000000000000))+(((x3263)*(x3273)))+(((IkReal(-1.00000000000000))*(r10)*(x3263)*(x3265)))+(((IkReal(-1.00000000000000))*(x3264)*(x3268)))+(((r02)*(x3261)))+(((IkReal(-1.00000000000000))*(x3262)*(x3272)))+(((x3266)*(x3269))));
11990 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3271)))+(((r22)*(sj4)))+(((r20)*(x3266))));
11991 evalcond[8]=((((IkReal(-1.00000000000000))*(x3261)*(x3262)))+(((x3263)*(x3264)))+(((IkReal(-1.00000000000000))*(r00)*(x3263)*(x3265)))+(((IkReal(-1.00000000000000))*(r10)*(x3265)*(x3268)))+(((x3268)*(x3273)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3267))));
11992 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  )
11993 {
11994 {
11995 IkReal dummyeval[1];
11996 IkReal gconst42;
11997 gconst42=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
11998 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
11999 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12000 {
12001 {
12002 IkReal dummyeval[1];
12003 IkReal gconst43;
12004 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
12005 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
12006 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12007 {
12008 continue;
12009 
12010 } else
12011 {
12012 {
12013 IkReal j1array[1], cj1array[1], sj1array[1];
12014 bool j1valid[1]={false};
12015 _nj1 = 1;
12016 IkReal x3274=((cj5)*(r11));
12017 IkReal x3275=((r10)*(sj0));
12018 IkReal x3276=((IkReal(0.707103562373095))*(cj2));
12019 IkReal x3277=((r20)*(sj5));
12020 IkReal x3278=((IkReal(0.707103562373095))*(sj2));
12021 IkReal x3279=((IkReal(0.707109999985348))*(cj2));
12022 IkReal x3280=((cj0)*(r00));
12023 IkReal x3281=((IkReal(0.707109999985348))*(sj2));
12024 IkReal x3282=((cj5)*(r21));
12025 IkReal x3283=((sj0)*(x3278));
12026 IkReal x3284=((sj5)*(x3279));
12027 IkReal x3285=((cj0)*(cj5)*(r01));
12028 if( IKabs(((gconst43)*(((((x3279)*(x3285)))+(((sj5)*(x3278)*(x3280)))+(((sj5)*(x3275)*(x3278)))+(((IkReal(-1.00000000000000))*(x3281)*(x3282)))+(((sj0)*(x3274)*(x3279)))+(((x3280)*(x3284)))+(((IkReal(-1.00000000000000))*(x3277)*(x3281)))+(((x3276)*(x3282)))+(((x3275)*(x3284)))+(((x3274)*(x3283)))+(((x3276)*(x3277)))+(((x3278)*(x3285))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((x3279)*(x3282)))+(((sj5)*(x3280)*(x3281)))+(((sj0)*(x3274)*(x3281)))+(((IkReal(-1.00000000000000))*(sj5)*(x3276)*(x3280)))+(((x3277)*(x3278)))+(((x3277)*(x3279)))+(((IkReal(-1.00000000000000))*(x3276)*(x3285)))+(((sj5)*(x3275)*(x3281)))+(((IkReal(-1.00000000000000))*(sj5)*(x3275)*(x3276)))+(((x3281)*(x3285)))+(((x3278)*(x3282)))+(((IkReal(-1.00000000000000))*(sj0)*(x3274)*(x3276))))))) < IKFAST_ATAN2_MAGTHRESH )
12029     continue;
12030 j1array[0]=IKatan2(((gconst43)*(((((x3279)*(x3285)))+(((sj5)*(x3278)*(x3280)))+(((sj5)*(x3275)*(x3278)))+(((IkReal(-1.00000000000000))*(x3281)*(x3282)))+(((sj0)*(x3274)*(x3279)))+(((x3280)*(x3284)))+(((IkReal(-1.00000000000000))*(x3277)*(x3281)))+(((x3276)*(x3282)))+(((x3275)*(x3284)))+(((x3274)*(x3283)))+(((x3276)*(x3277)))+(((x3278)*(x3285)))))), ((gconst43)*(((((x3279)*(x3282)))+(((sj5)*(x3280)*(x3281)))+(((sj0)*(x3274)*(x3281)))+(((IkReal(-1.00000000000000))*(sj5)*(x3276)*(x3280)))+(((x3277)*(x3278)))+(((x3277)*(x3279)))+(((IkReal(-1.00000000000000))*(x3276)*(x3285)))+(((sj5)*(x3275)*(x3281)))+(((IkReal(-1.00000000000000))*(sj5)*(x3275)*(x3276)))+(((x3281)*(x3285)))+(((x3278)*(x3282)))+(((IkReal(-1.00000000000000))*(sj0)*(x3274)*(x3276)))))));
12031 sj1array[0]=IKsin(j1array[0]);
12032 cj1array[0]=IKcos(j1array[0]);
12033 if( j1array[0] > IKPI )
12034 {
12035     j1array[0]-=IK2PI;
12036 }
12037 else if( j1array[0] < -IKPI )
12038 {    j1array[0]+=IK2PI;
12039 }
12040 j1valid[0] = true;
12041 for(int ij1 = 0; ij1 < 1; ++ij1)
12042 {
12043 if( !j1valid[ij1] )
12044 {
12045     continue;
12046 }
12047 _ij1[0] = ij1; _ij1[1] = -1;
12048 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12049 {
12050 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12051 {
12052     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12053 }
12054 }
12055 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12056 {
12057 IkReal evalcond[4];
12058 IkReal x3286=IKcos(j1);
12059 IkReal x3287=IKsin(j1);
12060 IkReal x3288=((IkReal(0.707109999985348))*(cj2));
12061 IkReal x3289=((IkReal(1.00000000000000))*(cj0));
12062 IkReal x3290=((IkReal(0.707109999985348))*(sj2));
12063 IkReal x3291=((cj5)*(sj4));
12064 IkReal x3292=((sj4)*(sj5));
12065 IkReal x3293=((IkReal(1.00000000000000))*(sj0));
12066 IkReal x3294=((sj5)*(x3293));
12067 IkReal x3295=((IkReal(0.707103562373095))*(x3286));
12068 IkReal x3296=((IkReal(0.707103562373095))*(x3287));
12069 IkReal x3297=((cj2)*(x3295));
12070 IkReal x3298=((x3287)*(x3288));
12071 IkReal x3299=((sj2)*(x3296));
12072 IkReal x3300=((x3286)*(x3290));
12073 IkReal x3301=((sj2)*(x3295));
12074 IkReal x3302=((cj2)*(x3296));
12075 IkReal x3303=((x3286)*(x3288));
12076 IkReal x3304=((x3287)*(x3290));
12077 IkReal x3305=((x3302)+(x3303)+(x3301));
12078 IkReal x3306=((x3300)+(x3298)+(x3299));
12079 evalcond[0]=((((cj5)*(r21)))+(x3305)+(((IkReal(-1.00000000000000))*(x3304)))+(((r20)*(sj5))));
12080 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3291)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3297)))+(x3306)+(((r21)*(x3292))));
12081 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3294)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3289)))+(x3297)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3289)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3293)))+(((IkReal(-1.00000000000000))*(x3306))));
12082 evalcond[3]=((((cj0)*(r00)*(x3291)))+(((IkReal(-1.00000000000000))*(r11)*(x3292)*(x3293)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3293)))+(x3305)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3289)))+(((IkReal(-1.00000000000000))*(x3304)))+(((r10)*(sj0)*(x3291)))+(((IkReal(-1.00000000000000))*(r01)*(x3289)*(x3292))));
12083 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12084 {
12085 continue;
12086 }
12087 }
12088 
12089 {
12090 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12091 vinfos[0].jointtype = 1;
12092 vinfos[0].foffset = j0;
12093 vinfos[0].indices[0] = _ij0[0];
12094 vinfos[0].indices[1] = _ij0[1];
12095 vinfos[0].maxsolutions = _nj0;
12096 vinfos[1].jointtype = 1;
12097 vinfos[1].foffset = j1;
12098 vinfos[1].indices[0] = _ij1[0];
12099 vinfos[1].indices[1] = _ij1[1];
12100 vinfos[1].maxsolutions = _nj1;
12101 vinfos[2].jointtype = 1;
12102 vinfos[2].foffset = j2;
12103 vinfos[2].indices[0] = _ij2[0];
12104 vinfos[2].indices[1] = _ij2[1];
12105 vinfos[2].maxsolutions = _nj2;
12106 vinfos[3].jointtype = 1;
12107 vinfos[3].foffset = j3;
12108 vinfos[3].indices[0] = _ij3[0];
12109 vinfos[3].indices[1] = _ij3[1];
12110 vinfos[3].maxsolutions = _nj3;
12111 vinfos[4].jointtype = 1;
12112 vinfos[4].foffset = j4;
12113 vinfos[4].indices[0] = _ij4[0];
12114 vinfos[4].indices[1] = _ij4[1];
12115 vinfos[4].maxsolutions = _nj4;
12116 vinfos[5].jointtype = 1;
12117 vinfos[5].foffset = j5;
12118 vinfos[5].indices[0] = _ij5[0];
12119 vinfos[5].indices[1] = _ij5[1];
12120 vinfos[5].maxsolutions = _nj5;
12121 std::vector<int> vfree(0);
12122 solutions.AddSolution(vinfos,vfree);
12123 }
12124 }
12125 }
12126 
12127 }
12128 
12129 }
12130 
12131 } else
12132 {
12133 {
12134 IkReal j1array[1], cj1array[1], sj1array[1];
12135 bool j1valid[1]={false};
12136 _nj1 = 1;
12137 IkReal x3307=((cj5)*(sj4));
12138 IkReal x3308=((r21)*(sj4));
12139 IkReal x3309=((cj5)*(r21));
12140 IkReal x3310=((IkReal(0.707109999985348))*(cj2));
12141 IkReal x3311=((IkReal(0.707103562373095))*(sj2));
12142 IkReal x3312=((IkReal(0.707109999985348))*(sj2));
12143 IkReal x3313=((cj4)*(r22));
12144 IkReal x3314=((IkReal(0.707103562373095))*(cj2));
12145 IkReal x3315=((r20)*(x3310));
12146 IkReal x3316=((sj5)*(x3314));
12147 IkReal x3317=((sj5)*(x3312));
12148 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x3308)*(x3311)))+(((IkReal(-1.00000000000000))*(sj5)*(x3308)*(x3310)))+(((r20)*(x3307)*(x3311)))+(((IkReal(-1.00000000000000))*(r20)*(x3316)))+(((IkReal(-1.00000000000000))*(x3309)*(x3314)))+(((IkReal(-1.00000000000000))*(x3310)*(x3313)))+(((x3307)*(x3315)))+(((IkReal(-1.00000000000000))*(x3311)*(x3313)))+(((r20)*(x3317)))+(((x3309)*(x3312))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((r20)*(x3307)*(x3312)))+(((x3313)*(x3314)))+(((IkReal(-1.00000000000000))*(x3312)*(x3313)))+(((IkReal(-1.00000000000000))*(x3309)*(x3311)))+(((IkReal(-1.00000000000000))*(x3309)*(x3310)))+(((IkReal(-1.00000000000000))*(x3308)*(x3317)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3311)))+(((IkReal(-1.00000000000000))*(sj5)*(x3315)))+(((x3308)*(x3316)))+(((IkReal(-1.00000000000000))*(r20)*(x3307)*(x3314))))))) < IKFAST_ATAN2_MAGTHRESH )
12149     continue;
12150 j1array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x3308)*(x3311)))+(((IkReal(-1.00000000000000))*(sj5)*(x3308)*(x3310)))+(((r20)*(x3307)*(x3311)))+(((IkReal(-1.00000000000000))*(r20)*(x3316)))+(((IkReal(-1.00000000000000))*(x3309)*(x3314)))+(((IkReal(-1.00000000000000))*(x3310)*(x3313)))+(((x3307)*(x3315)))+(((IkReal(-1.00000000000000))*(x3311)*(x3313)))+(((r20)*(x3317)))+(((x3309)*(x3312)))))), ((gconst42)*(((((r20)*(x3307)*(x3312)))+(((x3313)*(x3314)))+(((IkReal(-1.00000000000000))*(x3312)*(x3313)))+(((IkReal(-1.00000000000000))*(x3309)*(x3311)))+(((IkReal(-1.00000000000000))*(x3309)*(x3310)))+(((IkReal(-1.00000000000000))*(x3308)*(x3317)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3311)))+(((IkReal(-1.00000000000000))*(sj5)*(x3315)))+(((x3308)*(x3316)))+(((IkReal(-1.00000000000000))*(r20)*(x3307)*(x3314)))))));
12151 sj1array[0]=IKsin(j1array[0]);
12152 cj1array[0]=IKcos(j1array[0]);
12153 if( j1array[0] > IKPI )
12154 {
12155     j1array[0]-=IK2PI;
12156 }
12157 else if( j1array[0] < -IKPI )
12158 {    j1array[0]+=IK2PI;
12159 }
12160 j1valid[0] = true;
12161 for(int ij1 = 0; ij1 < 1; ++ij1)
12162 {
12163 if( !j1valid[ij1] )
12164 {
12165     continue;
12166 }
12167 _ij1[0] = ij1; _ij1[1] = -1;
12168 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12169 {
12170 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12171 {
12172     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12173 }
12174 }
12175 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12176 {
12177 IkReal evalcond[4];
12178 IkReal x3318=IKcos(j1);
12179 IkReal x3319=IKsin(j1);
12180 IkReal x3320=((IkReal(0.707109999985348))*(cj2));
12181 IkReal x3321=((IkReal(1.00000000000000))*(cj0));
12182 IkReal x3322=((IkReal(0.707109999985348))*(sj2));
12183 IkReal x3323=((cj5)*(sj4));
12184 IkReal x3324=((sj4)*(sj5));
12185 IkReal x3325=((IkReal(1.00000000000000))*(sj0));
12186 IkReal x3326=((sj5)*(x3325));
12187 IkReal x3327=((IkReal(0.707103562373095))*(x3318));
12188 IkReal x3328=((IkReal(0.707103562373095))*(x3319));
12189 IkReal x3329=((cj2)*(x3327));
12190 IkReal x3330=((x3319)*(x3320));
12191 IkReal x3331=((sj2)*(x3328));
12192 IkReal x3332=((x3318)*(x3322));
12193 IkReal x3333=((sj2)*(x3327));
12194 IkReal x3334=((cj2)*(x3328));
12195 IkReal x3335=((x3318)*(x3320));
12196 IkReal x3336=((x3319)*(x3322));
12197 IkReal x3337=((x3333)+(x3335)+(x3334));
12198 IkReal x3338=((x3332)+(x3331)+(x3330));
12199 evalcond[0]=((((cj5)*(r21)))+(x3337)+(((IkReal(-1.00000000000000))*(x3336)))+(((r20)*(sj5))));
12200 evalcond[1]=((((IkReal(-1.00000000000000))*(x3329)))+(((cj4)*(r22)))+(x3338)+(((r21)*(x3324)))+(((IkReal(-1.00000000000000))*(r20)*(x3323))));
12201 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3321)))+(x3329)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3325)))+(((IkReal(-1.00000000000000))*(r10)*(x3326)))+(((IkReal(-1.00000000000000))*(x3338)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3321))));
12202 evalcond[3]=((x3337)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3325)))+(((IkReal(-1.00000000000000))*(r11)*(x3324)*(x3325)))+(((cj0)*(r00)*(x3323)))+(((IkReal(-1.00000000000000))*(x3336)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3321)))+(((IkReal(-1.00000000000000))*(r01)*(x3321)*(x3324)))+(((r10)*(sj0)*(x3323))));
12203 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12204 {
12205 continue;
12206 }
12207 }
12208 
12209 {
12210 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12211 vinfos[0].jointtype = 1;
12212 vinfos[0].foffset = j0;
12213 vinfos[0].indices[0] = _ij0[0];
12214 vinfos[0].indices[1] = _ij0[1];
12215 vinfos[0].maxsolutions = _nj0;
12216 vinfos[1].jointtype = 1;
12217 vinfos[1].foffset = j1;
12218 vinfos[1].indices[0] = _ij1[0];
12219 vinfos[1].indices[1] = _ij1[1];
12220 vinfos[1].maxsolutions = _nj1;
12221 vinfos[2].jointtype = 1;
12222 vinfos[2].foffset = j2;
12223 vinfos[2].indices[0] = _ij2[0];
12224 vinfos[2].indices[1] = _ij2[1];
12225 vinfos[2].maxsolutions = _nj2;
12226 vinfos[3].jointtype = 1;
12227 vinfos[3].foffset = j3;
12228 vinfos[3].indices[0] = _ij3[0];
12229 vinfos[3].indices[1] = _ij3[1];
12230 vinfos[3].maxsolutions = _nj3;
12231 vinfos[4].jointtype = 1;
12232 vinfos[4].foffset = j4;
12233 vinfos[4].indices[0] = _ij4[0];
12234 vinfos[4].indices[1] = _ij4[1];
12235 vinfos[4].maxsolutions = _nj4;
12236 vinfos[5].jointtype = 1;
12237 vinfos[5].foffset = j5;
12238 vinfos[5].indices[0] = _ij5[0];
12239 vinfos[5].indices[1] = _ij5[1];
12240 vinfos[5].maxsolutions = _nj5;
12241 std::vector<int> vfree(0);
12242 solutions.AddSolution(vinfos,vfree);
12243 }
12244 }
12245 }
12246 
12247 }
12248 
12249 }
12250 
12251 } else
12252 {
12253 IkReal x3339=((sj0)*(sj4));
12254 IkReal x3340=((IkReal(1.00000000000000))*(r12));
12255 IkReal x3341=((cj0)*(cj4));
12256 IkReal x3342=((r01)*(sj5));
12257 IkReal x3343=((IkReal(1.00000000000000))*(cj5));
12258 IkReal x3344=((cj4)*(cj5));
12259 IkReal x3345=((IkReal(1.00000000000000))*(cj0));
12260 IkReal x3346=((cj4)*(sj0));
12261 IkReal x3347=((r00)*(sj0));
12262 IkReal x3348=((npy)*(sj5));
12263 IkReal x3349=((IkReal(1.00000000000000))*(cj4));
12264 IkReal x3350=((cj0)*(sj4));
12265 IkReal x3351=((r11)*(sj5));
12266 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
12267 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3343)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3345)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x3347))));
12268 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x3348)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3343)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2))));
12269 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
12270 evalcond[4]=((IkReal(0.00600000000000000))+(((npx)*(x3344)))+(((IkReal(-1.00000000000000))*(x3348)*(x3349)))+(((npz)*(sj4))));
12271 evalcond[5]=((((IkReal(-1.00000000000000))*(x3340)*(x3341)))+(((IkReal(-1.00000000000000))*(sj4)*(x3345)*(x3351)))+(((r02)*(x3346)))+(((IkReal(-1.00000000000000))*(r00)*(x3339)*(x3343)))+(((cj5)*(r10)*(x3350)))+(((x3339)*(x3342))));
12272 evalcond[6]=((IkReal(-1.00000000000000))+(((x3344)*(x3347)))+(((IkReal(-1.00000000000000))*(x3342)*(x3346)))+(((r02)*(x3339)))+(((IkReal(-1.00000000000000))*(x3340)*(x3350)))+(((IkReal(-1.00000000000000))*(r10)*(x3341)*(x3343)))+(((x3341)*(x3351))));
12273 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3349)))+(((r22)*(sj4)))+(((r20)*(x3344))));
12274 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x3341)*(x3343)))+(((x3341)*(x3342)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3345)))+(((IkReal(-1.00000000000000))*(r10)*(x3343)*(x3346)))+(((IkReal(-1.00000000000000))*(x3339)*(x3340)))+(((x3346)*(x3351))));
12275 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  )
12276 {
12277 {
12278 IkReal dummyeval[1];
12279 IkReal gconst44;
12280 gconst44=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
12281 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
12282 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12283 {
12284 {
12285 IkReal dummyeval[1];
12286 IkReal gconst45;
12287 gconst45=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
12288 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
12289 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12290 {
12291 continue;
12292 
12293 } else
12294 {
12295 {
12296 IkReal j1array[1], cj1array[1], sj1array[1];
12297 bool j1valid[1]={false};
12298 _nj1 = 1;
12299 IkReal x3352=((cj5)*(r11));
12300 IkReal x3353=((r10)*(sj0));
12301 IkReal x3354=((IkReal(0.707103562373095))*(cj2));
12302 IkReal x3355=((r20)*(sj5));
12303 IkReal x3356=((IkReal(0.707103562373095))*(sj2));
12304 IkReal x3357=((IkReal(0.707109999985348))*(cj2));
12305 IkReal x3358=((cj0)*(r00));
12306 IkReal x3359=((IkReal(0.707109999985348))*(sj2));
12307 IkReal x3360=((cj5)*(r21));
12308 IkReal x3361=((sj0)*(x3356));
12309 IkReal x3362=((sj5)*(x3357));
12310 IkReal x3363=((cj0)*(cj5)*(r01));
12311 if( IKabs(((gconst45)*(((((x3356)*(x3363)))+(((IkReal(-1.00000000000000))*(x3359)*(x3360)))+(((x3353)*(x3362)))+(((x3358)*(x3362)))+(((x3352)*(x3361)))+(((IkReal(-1.00000000000000))*(x3355)*(x3359)))+(((x3354)*(x3360)))+(((sj5)*(x3356)*(x3358)))+(((x3357)*(x3363)))+(((x3354)*(x3355)))+(((sj5)*(x3353)*(x3356)))+(((sj0)*(x3352)*(x3357))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((x3356)*(x3360)))+(((sj5)*(x3358)*(x3359)))+(((IkReal(-1.00000000000000))*(x3354)*(x3363)))+(((x3357)*(x3360)))+(((x3359)*(x3363)))+(((x3355)*(x3357)))+(((x3355)*(x3356)))+(((IkReal(-1.00000000000000))*(sj0)*(x3352)*(x3354)))+(((sj5)*(x3353)*(x3359)))+(((IkReal(-1.00000000000000))*(sj5)*(x3354)*(x3358)))+(((sj0)*(x3352)*(x3359)))+(((IkReal(-1.00000000000000))*(sj5)*(x3353)*(x3354))))))) < IKFAST_ATAN2_MAGTHRESH )
12312     continue;
12313 j1array[0]=IKatan2(((gconst45)*(((((x3356)*(x3363)))+(((IkReal(-1.00000000000000))*(x3359)*(x3360)))+(((x3353)*(x3362)))+(((x3358)*(x3362)))+(((x3352)*(x3361)))+(((IkReal(-1.00000000000000))*(x3355)*(x3359)))+(((x3354)*(x3360)))+(((sj5)*(x3356)*(x3358)))+(((x3357)*(x3363)))+(((x3354)*(x3355)))+(((sj5)*(x3353)*(x3356)))+(((sj0)*(x3352)*(x3357)))))), ((gconst45)*(((((x3356)*(x3360)))+(((sj5)*(x3358)*(x3359)))+(((IkReal(-1.00000000000000))*(x3354)*(x3363)))+(((x3357)*(x3360)))+(((x3359)*(x3363)))+(((x3355)*(x3357)))+(((x3355)*(x3356)))+(((IkReal(-1.00000000000000))*(sj0)*(x3352)*(x3354)))+(((sj5)*(x3353)*(x3359)))+(((IkReal(-1.00000000000000))*(sj5)*(x3354)*(x3358)))+(((sj0)*(x3352)*(x3359)))+(((IkReal(-1.00000000000000))*(sj5)*(x3353)*(x3354)))))));
12314 sj1array[0]=IKsin(j1array[0]);
12315 cj1array[0]=IKcos(j1array[0]);
12316 if( j1array[0] > IKPI )
12317 {
12318     j1array[0]-=IK2PI;
12319 }
12320 else if( j1array[0] < -IKPI )
12321 {    j1array[0]+=IK2PI;
12322 }
12323 j1valid[0] = true;
12324 for(int ij1 = 0; ij1 < 1; ++ij1)
12325 {
12326 if( !j1valid[ij1] )
12327 {
12328     continue;
12329 }
12330 _ij1[0] = ij1; _ij1[1] = -1;
12331 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12332 {
12333 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12334 {
12335     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12336 }
12337 }
12338 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12339 {
12340 IkReal evalcond[4];
12341 IkReal x3364=IKcos(j1);
12342 IkReal x3365=IKsin(j1);
12343 IkReal x3366=((IkReal(0.707109999985348))*(cj2));
12344 IkReal x3367=((IkReal(1.00000000000000))*(cj0));
12345 IkReal x3368=((IkReal(0.707109999985348))*(sj2));
12346 IkReal x3369=((cj5)*(sj4));
12347 IkReal x3370=((sj4)*(sj5));
12348 IkReal x3371=((IkReal(1.00000000000000))*(sj0));
12349 IkReal x3372=((sj5)*(x3371));
12350 IkReal x3373=((IkReal(0.707103562373095))*(x3364));
12351 IkReal x3374=((IkReal(0.707103562373095))*(x3365));
12352 IkReal x3375=((cj2)*(x3373));
12353 IkReal x3376=((x3365)*(x3366));
12354 IkReal x3377=((sj2)*(x3374));
12355 IkReal x3378=((x3364)*(x3368));
12356 IkReal x3379=((sj2)*(x3373));
12357 IkReal x3380=((cj2)*(x3374));
12358 IkReal x3381=((x3364)*(x3366));
12359 IkReal x3382=((x3365)*(x3368));
12360 IkReal x3383=((x3379)+(x3380)+(x3381));
12361 IkReal x3384=((x3378)+(x3377)+(x3376));
12362 evalcond[0]=((((cj5)*(r21)))+(x3383)+(((IkReal(-1.00000000000000))*(x3382)))+(((r20)*(sj5))));
12363 evalcond[1]=((((cj4)*(r22)))+(x3384)+(((IkReal(-1.00000000000000))*(x3375)))+(((IkReal(-1.00000000000000))*(r20)*(x3369)))+(((r21)*(x3370))));
12364 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3372)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3371)))+(x3375)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3367)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3367)))+(((IkReal(-1.00000000000000))*(x3384))));
12365 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3371)))+(((r10)*(sj0)*(x3369)))+(((IkReal(-1.00000000000000))*(r01)*(x3367)*(x3370)))+(x3383)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3367)))+(((cj0)*(r00)*(x3369)))+(((IkReal(-1.00000000000000))*(x3382)))+(((IkReal(-1.00000000000000))*(r11)*(x3370)*(x3371))));
12366 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12367 {
12368 continue;
12369 }
12370 }
12371 
12372 {
12373 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12374 vinfos[0].jointtype = 1;
12375 vinfos[0].foffset = j0;
12376 vinfos[0].indices[0] = _ij0[0];
12377 vinfos[0].indices[1] = _ij0[1];
12378 vinfos[0].maxsolutions = _nj0;
12379 vinfos[1].jointtype = 1;
12380 vinfos[1].foffset = j1;
12381 vinfos[1].indices[0] = _ij1[0];
12382 vinfos[1].indices[1] = _ij1[1];
12383 vinfos[1].maxsolutions = _nj1;
12384 vinfos[2].jointtype = 1;
12385 vinfos[2].foffset = j2;
12386 vinfos[2].indices[0] = _ij2[0];
12387 vinfos[2].indices[1] = _ij2[1];
12388 vinfos[2].maxsolutions = _nj2;
12389 vinfos[3].jointtype = 1;
12390 vinfos[3].foffset = j3;
12391 vinfos[3].indices[0] = _ij3[0];
12392 vinfos[3].indices[1] = _ij3[1];
12393 vinfos[3].maxsolutions = _nj3;
12394 vinfos[4].jointtype = 1;
12395 vinfos[4].foffset = j4;
12396 vinfos[4].indices[0] = _ij4[0];
12397 vinfos[4].indices[1] = _ij4[1];
12398 vinfos[4].maxsolutions = _nj4;
12399 vinfos[5].jointtype = 1;
12400 vinfos[5].foffset = j5;
12401 vinfos[5].indices[0] = _ij5[0];
12402 vinfos[5].indices[1] = _ij5[1];
12403 vinfos[5].maxsolutions = _nj5;
12404 std::vector<int> vfree(0);
12405 solutions.AddSolution(vinfos,vfree);
12406 }
12407 }
12408 }
12409 
12410 }
12411 
12412 }
12413 
12414 } else
12415 {
12416 {
12417 IkReal j1array[1], cj1array[1], sj1array[1];
12418 bool j1valid[1]={false};
12419 _nj1 = 1;
12420 IkReal x3385=((cj5)*(sj4));
12421 IkReal x3386=((r21)*(sj4));
12422 IkReal x3387=((cj5)*(r21));
12423 IkReal x3388=((IkReal(0.707109999985348))*(cj2));
12424 IkReal x3389=((IkReal(0.707103562373095))*(sj2));
12425 IkReal x3390=((IkReal(0.707109999985348))*(sj2));
12426 IkReal x3391=((cj4)*(r22));
12427 IkReal x3392=((IkReal(0.707103562373095))*(cj2));
12428 IkReal x3393=((r20)*(x3388));
12429 IkReal x3394=((sj5)*(x3392));
12430 IkReal x3395=((sj5)*(x3390));
12431 if( IKabs(((gconst44)*(((((IkReal(-1.00000000000000))*(x3387)*(x3392)))+(((r20)*(x3395)))+(((r20)*(x3385)*(x3389)))+(((IkReal(-1.00000000000000))*(x3389)*(x3391)))+(((x3387)*(x3390)))+(((IkReal(-1.00000000000000))*(x3388)*(x3391)))+(((IkReal(-1.00000000000000))*(sj5)*(x3386)*(x3389)))+(((IkReal(-1.00000000000000))*(sj5)*(x3386)*(x3388)))+(((IkReal(-1.00000000000000))*(r20)*(x3394)))+(((x3385)*(x3393))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((x3386)*(x3394)))+(((IkReal(-1.00000000000000))*(sj5)*(x3393)))+(((x3391)*(x3392)))+(((IkReal(-1.00000000000000))*(r20)*(x3385)*(x3392)))+(((IkReal(-1.00000000000000))*(x3387)*(x3388)))+(((IkReal(-1.00000000000000))*(x3387)*(x3389)))+(((r20)*(x3385)*(x3390)))+(((IkReal(-1.00000000000000))*(x3386)*(x3395)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3389)))+(((IkReal(-1.00000000000000))*(x3390)*(x3391))))))) < IKFAST_ATAN2_MAGTHRESH )
12432     continue;
12433 j1array[0]=IKatan2(((gconst44)*(((((IkReal(-1.00000000000000))*(x3387)*(x3392)))+(((r20)*(x3395)))+(((r20)*(x3385)*(x3389)))+(((IkReal(-1.00000000000000))*(x3389)*(x3391)))+(((x3387)*(x3390)))+(((IkReal(-1.00000000000000))*(x3388)*(x3391)))+(((IkReal(-1.00000000000000))*(sj5)*(x3386)*(x3389)))+(((IkReal(-1.00000000000000))*(sj5)*(x3386)*(x3388)))+(((IkReal(-1.00000000000000))*(r20)*(x3394)))+(((x3385)*(x3393)))))), ((gconst44)*(((((x3386)*(x3394)))+(((IkReal(-1.00000000000000))*(sj5)*(x3393)))+(((x3391)*(x3392)))+(((IkReal(-1.00000000000000))*(r20)*(x3385)*(x3392)))+(((IkReal(-1.00000000000000))*(x3387)*(x3388)))+(((IkReal(-1.00000000000000))*(x3387)*(x3389)))+(((r20)*(x3385)*(x3390)))+(((IkReal(-1.00000000000000))*(x3386)*(x3395)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3389)))+(((IkReal(-1.00000000000000))*(x3390)*(x3391)))))));
12434 sj1array[0]=IKsin(j1array[0]);
12435 cj1array[0]=IKcos(j1array[0]);
12436 if( j1array[0] > IKPI )
12437 {
12438     j1array[0]-=IK2PI;
12439 }
12440 else if( j1array[0] < -IKPI )
12441 {    j1array[0]+=IK2PI;
12442 }
12443 j1valid[0] = true;
12444 for(int ij1 = 0; ij1 < 1; ++ij1)
12445 {
12446 if( !j1valid[ij1] )
12447 {
12448     continue;
12449 }
12450 _ij1[0] = ij1; _ij1[1] = -1;
12451 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12452 {
12453 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12454 {
12455     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12456 }
12457 }
12458 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12459 {
12460 IkReal evalcond[4];
12461 IkReal x3396=IKcos(j1);
12462 IkReal x3397=IKsin(j1);
12463 IkReal x3398=((IkReal(0.707109999985348))*(cj2));
12464 IkReal x3399=((IkReal(1.00000000000000))*(cj0));
12465 IkReal x3400=((IkReal(0.707109999985348))*(sj2));
12466 IkReal x3401=((cj5)*(sj4));
12467 IkReal x3402=((sj4)*(sj5));
12468 IkReal x3403=((IkReal(1.00000000000000))*(sj0));
12469 IkReal x3404=((sj5)*(x3403));
12470 IkReal x3405=((IkReal(0.707103562373095))*(x3396));
12471 IkReal x3406=((IkReal(0.707103562373095))*(x3397));
12472 IkReal x3407=((cj2)*(x3405));
12473 IkReal x3408=((x3397)*(x3398));
12474 IkReal x3409=((sj2)*(x3406));
12475 IkReal x3410=((x3396)*(x3400));
12476 IkReal x3411=((sj2)*(x3405));
12477 IkReal x3412=((cj2)*(x3406));
12478 IkReal x3413=((x3396)*(x3398));
12479 IkReal x3414=((x3397)*(x3400));
12480 IkReal x3415=((x3412)+(x3413)+(x3411));
12481 IkReal x3416=((x3410)+(x3409)+(x3408));
12482 evalcond[0]=((((cj5)*(r21)))+(x3415)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x3414))));
12483 evalcond[1]=((((cj4)*(r22)))+(x3416)+(((r21)*(x3402)))+(((IkReal(-1.00000000000000))*(r20)*(x3401)))+(((IkReal(-1.00000000000000))*(x3407))));
12484 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3403)))+(x3407)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3399)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3399)))+(((IkReal(-1.00000000000000))*(r10)*(x3404)))+(((IkReal(-1.00000000000000))*(x3416))));
12485 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3399)*(x3402)))+(x3415)+(((IkReal(-1.00000000000000))*(r11)*(x3402)*(x3403)))+(((r10)*(sj0)*(x3401)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3403)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3399)))+(((cj0)*(r00)*(x3401)))+(((IkReal(-1.00000000000000))*(x3414))));
12486 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12487 {
12488 continue;
12489 }
12490 }
12491 
12492 {
12493 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12494 vinfos[0].jointtype = 1;
12495 vinfos[0].foffset = j0;
12496 vinfos[0].indices[0] = _ij0[0];
12497 vinfos[0].indices[1] = _ij0[1];
12498 vinfos[0].maxsolutions = _nj0;
12499 vinfos[1].jointtype = 1;
12500 vinfos[1].foffset = j1;
12501 vinfos[1].indices[0] = _ij1[0];
12502 vinfos[1].indices[1] = _ij1[1];
12503 vinfos[1].maxsolutions = _nj1;
12504 vinfos[2].jointtype = 1;
12505 vinfos[2].foffset = j2;
12506 vinfos[2].indices[0] = _ij2[0];
12507 vinfos[2].indices[1] = _ij2[1];
12508 vinfos[2].maxsolutions = _nj2;
12509 vinfos[3].jointtype = 1;
12510 vinfos[3].foffset = j3;
12511 vinfos[3].indices[0] = _ij3[0];
12512 vinfos[3].indices[1] = _ij3[1];
12513 vinfos[3].maxsolutions = _nj3;
12514 vinfos[4].jointtype = 1;
12515 vinfos[4].foffset = j4;
12516 vinfos[4].indices[0] = _ij4[0];
12517 vinfos[4].indices[1] = _ij4[1];
12518 vinfos[4].maxsolutions = _nj4;
12519 vinfos[5].jointtype = 1;
12520 vinfos[5].foffset = j5;
12521 vinfos[5].indices[0] = _ij5[0];
12522 vinfos[5].indices[1] = _ij5[1];
12523 vinfos[5].maxsolutions = _nj5;
12524 std::vector<int> vfree(0);
12525 solutions.AddSolution(vinfos,vfree);
12526 }
12527 }
12528 }
12529 
12530 }
12531 
12532 }
12533 
12534 } else
12535 {
12536 if( 1 )
12537 {
12538 continue;
12539 
12540 } else
12541 {
12542 }
12543 }
12544 }
12545 }
12546 }
12547 }
12548 
12549 } else
12550 {
12551 {
12552 IkReal j1array[1], cj1array[1], sj1array[1];
12553 bool j1valid[1]={false};
12554 _nj1 = 1;
12555 IkReal x3417=((IkReal(0.707109999985348))*(sj2));
12556 IkReal x3418=((r22)*(sj4));
12557 IkReal x3419=((cj5)*(r20));
12558 IkReal x3420=((r21)*(sj5));
12559 IkReal x3421=((IkReal(0.707109999985348))*(cj2));
12560 IkReal x3422=((cj3)*(r22));
12561 IkReal x3423=((cj3)*(sj4));
12562 IkReal x3424=((IkReal(0.707103562373095))*(cj4)*(sj2));
12563 IkReal x3425=((IkReal(0.707103562373095))*(x3423));
12564 IkReal x3426=((IkReal(0.707103562373095))*(cj2)*(cj4));
12565 if( IKabs(((gconst37)*(((((IkReal(0.707103562373095))*(cj2)*(x3418)))+(((IkReal(-1.00000000000000))*(x3420)*(x3426)))+(((IkReal(-1.00000000000000))*(cj4)*(x3417)*(x3419)))+(((cj4)*(x3421)*(x3422)))+(((x3420)*(x3421)*(x3423)))+(((x3422)*(x3424)))+(((IkReal(-1.00000000000000))*(x3419)*(x3421)*(x3423)))+(((IkReal(-1.00000000000000))*(x3417)*(x3418)))+(((sj2)*(x3420)*(x3425)))+(((cj4)*(x3417)*(x3420)))+(((x3419)*(x3426)))+(((IkReal(-1.00000000000000))*(sj2)*(x3419)*(x3425))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((IkReal(-1.00000000000000))*(x3417)*(x3419)*(x3423)))+(((IkReal(-1.00000000000000))*(x3420)*(x3424)))+(((x3418)*(x3421)))+(((cj2)*(x3419)*(x3425)))+(((IkReal(-1.00000000000000))*(cj4)*(x3420)*(x3421)))+(((x3417)*(x3420)*(x3423)))+(((IkReal(-1.00000000000000))*(x3422)*(x3426)))+(((IkReal(0.707103562373095))*(sj2)*(x3418)))+(((cj4)*(x3419)*(x3421)))+(((IkReal(-1.00000000000000))*(cj2)*(x3420)*(x3425)))+(((cj4)*(x3417)*(x3422)))+(((x3419)*(x3424))))))) < IKFAST_ATAN2_MAGTHRESH )
12566     continue;
12567 j1array[0]=IKatan2(((gconst37)*(((((IkReal(0.707103562373095))*(cj2)*(x3418)))+(((IkReal(-1.00000000000000))*(x3420)*(x3426)))+(((IkReal(-1.00000000000000))*(cj4)*(x3417)*(x3419)))+(((cj4)*(x3421)*(x3422)))+(((x3420)*(x3421)*(x3423)))+(((x3422)*(x3424)))+(((IkReal(-1.00000000000000))*(x3419)*(x3421)*(x3423)))+(((IkReal(-1.00000000000000))*(x3417)*(x3418)))+(((sj2)*(x3420)*(x3425)))+(((cj4)*(x3417)*(x3420)))+(((x3419)*(x3426)))+(((IkReal(-1.00000000000000))*(sj2)*(x3419)*(x3425)))))), ((gconst37)*(((((IkReal(-1.00000000000000))*(x3417)*(x3419)*(x3423)))+(((IkReal(-1.00000000000000))*(x3420)*(x3424)))+(((x3418)*(x3421)))+(((cj2)*(x3419)*(x3425)))+(((IkReal(-1.00000000000000))*(cj4)*(x3420)*(x3421)))+(((x3417)*(x3420)*(x3423)))+(((IkReal(-1.00000000000000))*(x3422)*(x3426)))+(((IkReal(0.707103562373095))*(sj2)*(x3418)))+(((cj4)*(x3419)*(x3421)))+(((IkReal(-1.00000000000000))*(cj2)*(x3420)*(x3425)))+(((cj4)*(x3417)*(x3422)))+(((x3419)*(x3424)))))));
12568 sj1array[0]=IKsin(j1array[0]);
12569 cj1array[0]=IKcos(j1array[0]);
12570 if( j1array[0] > IKPI )
12571 {
12572     j1array[0]-=IK2PI;
12573 }
12574 else if( j1array[0] < -IKPI )
12575 {    j1array[0]+=IK2PI;
12576 }
12577 j1valid[0] = true;
12578 for(int ij1 = 0; ij1 < 1; ++ij1)
12579 {
12580 if( !j1valid[ij1] )
12581 {
12582     continue;
12583 }
12584 _ij1[0] = ij1; _ij1[1] = -1;
12585 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12586 {
12587 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12588 {
12589     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12590 }
12591 }
12592 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12593 {
12594 IkReal evalcond[6];
12595 IkReal x3427=IKcos(j1);
12596 IkReal x3428=IKsin(j1);
12597 IkReal x3429=((cj0)*(cj4));
12598 IkReal x3430=((r01)*(sj5));
12599 IkReal x3431=((IkReal(1.00000000000000))*(cj4));
12600 IkReal x3432=((IkReal(1.00000000000000))*(r02));
12601 IkReal x3433=((IkReal(0.707109999985348))*(sj3));
12602 IkReal x3434=((IkReal(0.707103562373095))*(sj3));
12603 IkReal x3435=((IkReal(1.00000000000000))*(sj4));
12604 IkReal x3436=((cj5)*(r20));
12605 IkReal x3437=((cj5)*(sj0));
12606 IkReal x3438=((IkReal(1.00000000000000))*(cj0));
12607 IkReal x3439=((r12)*(sj0));
12608 IkReal x3440=((cj2)*(cj3));
12609 IkReal x3441=((IkReal(0.707103562373095))*(cj3));
12610 IkReal x3442=((r21)*(sj5));
12611 IkReal x3443=((IkReal(0.707109999985348))*(cj3));
12612 IkReal x3444=((IkReal(1.00000000000000))*(sj0)*(sj5));
12613 IkReal x3445=((sj2)*(x3427));
12614 IkReal x3446=((cj2)*(x3427));
12615 IkReal x3447=((cj0)*(cj5)*(r00));
12616 IkReal x3448=((IkReal(0.707103562373095))*(x3428));
12617 IkReal x3449=((cj2)*(x3428));
12618 IkReal x3450=((IkReal(0.707109999985348))*(sj2)*(x3428));
12619 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3433)*(x3446)))+(((IkReal(-1.00000000000000))*(x3434)*(x3445)))+(((IkReal(-1.00000000000000))*(x3434)*(x3449)))+(((sj2)*(x3428)*(x3433)))+(((r20)*(sj5))));
12620 evalcond[1]=((((cj4)*(r22)))+(((sj4)*(x3442)))+(((IkReal(0.707109999985348))*(x3449)))+(((IkReal(0.707109999985348))*(x3445)))+(((IkReal(-0.707103562373095))*(x3446)))+(((IkReal(-1.00000000000000))*(x3435)*(x3436)))+(((sj2)*(x3448))));
12621 evalcond[2]=((((r22)*(sj4)))+(((IkReal(0.707109999985348))*(x3427)*(x3440)))+(((cj4)*(x3436)))+(((IkReal(-1.00000000000000))*(sj2)*(x3428)*(x3443)))+(((IkReal(-1.00000000000000))*(x3431)*(x3442)))+(((x3440)*(x3448)))+(((x3441)*(x3445))));
12622 evalcond[3]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3438)))+(((IkReal(-1.00000000000000))*(x3434)*(x3446)))+(((IkReal(-1.00000000000000))*(r10)*(x3444)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3438)))+(((x3433)*(x3445)))+(((x3433)*(x3449)))+(((sj2)*(x3428)*(x3434)))+(((IkReal(-1.00000000000000))*(r11)*(x3437))));
12623 evalcond[4]=((((IkReal(-1.00000000000000))*(x3450)))+(((sj4)*(x3447)))+(((IkReal(-1.00000000000000))*(x3431)*(x3439)))+(((IkReal(0.707109999985348))*(x3446)))+(((IkReal(-1.00000000000000))*(cj0)*(x3430)*(x3435)))+(((r10)*(sj4)*(x3437)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x3435)))+(((IkReal(0.707103562373095))*(x3445)))+(((cj2)*(x3448)))+(((IkReal(-1.00000000000000))*(x3429)*(x3432))));
12624 evalcond[5]=((((x3429)*(x3430)))+(((IkReal(0.707103562373095))*(x3427)*(x3440)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x3432)))+(((IkReal(-1.00000000000000))*(sj2)*(x3428)*(x3441)))+(((IkReal(-1.00000000000000))*(x3435)*(x3439)))+(((IkReal(-1.00000000000000))*(r10)*(x3431)*(x3437)))+(((IkReal(-1.00000000000000))*(x3443)*(x3445)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3429)))+(((IkReal(-0.707109999985348))*(x3428)*(x3440))));
12625 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  )
12626 {
12627 continue;
12628 }
12629 }
12630 
12631 {
12632 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12633 vinfos[0].jointtype = 1;
12634 vinfos[0].foffset = j0;
12635 vinfos[0].indices[0] = _ij0[0];
12636 vinfos[0].indices[1] = _ij0[1];
12637 vinfos[0].maxsolutions = _nj0;
12638 vinfos[1].jointtype = 1;
12639 vinfos[1].foffset = j1;
12640 vinfos[1].indices[0] = _ij1[0];
12641 vinfos[1].indices[1] = _ij1[1];
12642 vinfos[1].maxsolutions = _nj1;
12643 vinfos[2].jointtype = 1;
12644 vinfos[2].foffset = j2;
12645 vinfos[2].indices[0] = _ij2[0];
12646 vinfos[2].indices[1] = _ij2[1];
12647 vinfos[2].maxsolutions = _nj2;
12648 vinfos[3].jointtype = 1;
12649 vinfos[3].foffset = j3;
12650 vinfos[3].indices[0] = _ij3[0];
12651 vinfos[3].indices[1] = _ij3[1];
12652 vinfos[3].maxsolutions = _nj3;
12653 vinfos[4].jointtype = 1;
12654 vinfos[4].foffset = j4;
12655 vinfos[4].indices[0] = _ij4[0];
12656 vinfos[4].indices[1] = _ij4[1];
12657 vinfos[4].maxsolutions = _nj4;
12658 vinfos[5].jointtype = 1;
12659 vinfos[5].foffset = j5;
12660 vinfos[5].indices[0] = _ij5[0];
12661 vinfos[5].indices[1] = _ij5[1];
12662 vinfos[5].maxsolutions = _nj5;
12663 std::vector<int> vfree(0);
12664 solutions.AddSolution(vinfos,vfree);
12665 }
12666 }
12667 }
12668 
12669 }
12670 
12671 }
12672 
12673 } else
12674 {
12675 {
12676 IkReal j1array[1], cj1array[1], sj1array[1];
12677 bool j1valid[1]={false};
12678 _nj1 = 1;
12679 IkReal x3451=((sj2)*(sj3));
12680 IkReal x3452=((cj4)*(r22));
12681 IkReal x3453=((r20)*(sj5));
12682 IkReal x3454=((IkReal(0.707103562373095))*(cj2));
12683 IkReal x3455=((IkReal(0.707109999985348))*(sj2));
12684 IkReal x3456=((IkReal(0.707109999985348))*(cj2));
12685 IkReal x3457=((cj5)*(r21));
12686 IkReal x3458=((IkReal(0.707103562373095))*(sj2));
12687 IkReal x3459=((r21)*(sj4)*(sj5));
12688 IkReal x3460=((cj5)*(r20)*(sj4));
12689 if( IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(x3453)*(x3454)))+(((IkReal(-1.00000000000000))*(sj3)*(x3456)*(x3460)))+(((x3453)*(x3455)))+(((IkReal(0.707103562373095))*(x3451)*(x3452)))+(((IkReal(0.707103562373095))*(x3451)*(x3459)))+(((x3455)*(x3457)))+(((IkReal(-1.00000000000000))*(x3454)*(x3457)))+(((IkReal(-0.707103562373095))*(x3451)*(x3460)))+(((sj3)*(x3456)*(x3459)))+(((sj3)*(x3452)*(x3456))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(x3453)*(x3458)))+(((IkReal(-1.00000000000000))*(x3453)*(x3456)))+(((IkReal(-1.00000000000000))*(sj3)*(x3452)*(x3454)))+(((IkReal(-1.00000000000000))*(x3457)*(x3458)))+(((IkReal(-1.00000000000000))*(sj3)*(x3454)*(x3459)))+(((IkReal(0.707109999985348))*(x3451)*(x3452)))+(((IkReal(0.707109999985348))*(x3451)*(x3459)))+(((sj3)*(x3454)*(x3460)))+(((IkReal(-0.707109999985348))*(x3451)*(x3460)))+(((IkReal(-1.00000000000000))*(x3456)*(x3457))))))) < IKFAST_ATAN2_MAGTHRESH )
12690     continue;
12691 j1array[0]=IKatan2(((gconst36)*(((((IkReal(-1.00000000000000))*(x3453)*(x3454)))+(((IkReal(-1.00000000000000))*(sj3)*(x3456)*(x3460)))+(((x3453)*(x3455)))+(((IkReal(0.707103562373095))*(x3451)*(x3452)))+(((IkReal(0.707103562373095))*(x3451)*(x3459)))+(((x3455)*(x3457)))+(((IkReal(-1.00000000000000))*(x3454)*(x3457)))+(((IkReal(-0.707103562373095))*(x3451)*(x3460)))+(((sj3)*(x3456)*(x3459)))+(((sj3)*(x3452)*(x3456)))))), ((gconst36)*(((((IkReal(-1.00000000000000))*(x3453)*(x3458)))+(((IkReal(-1.00000000000000))*(x3453)*(x3456)))+(((IkReal(-1.00000000000000))*(sj3)*(x3452)*(x3454)))+(((IkReal(-1.00000000000000))*(x3457)*(x3458)))+(((IkReal(-1.00000000000000))*(sj3)*(x3454)*(x3459)))+(((IkReal(0.707109999985348))*(x3451)*(x3452)))+(((IkReal(0.707109999985348))*(x3451)*(x3459)))+(((sj3)*(x3454)*(x3460)))+(((IkReal(-0.707109999985348))*(x3451)*(x3460)))+(((IkReal(-1.00000000000000))*(x3456)*(x3457)))))));
12692 sj1array[0]=IKsin(j1array[0]);
12693 cj1array[0]=IKcos(j1array[0]);
12694 if( j1array[0] > IKPI )
12695 {
12696     j1array[0]-=IK2PI;
12697 }
12698 else if( j1array[0] < -IKPI )
12699 {    j1array[0]+=IK2PI;
12700 }
12701 j1valid[0] = true;
12702 for(int ij1 = 0; ij1 < 1; ++ij1)
12703 {
12704 if( !j1valid[ij1] )
12705 {
12706     continue;
12707 }
12708 _ij1[0] = ij1; _ij1[1] = -1;
12709 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
12710 {
12711 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
12712 {
12713     j1valid[iij1]=false; _ij1[1] = iij1; break; 
12714 }
12715 }
12716 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
12717 {
12718 IkReal evalcond[6];
12719 IkReal x3461=IKcos(j1);
12720 IkReal x3462=IKsin(j1);
12721 IkReal x3463=((cj0)*(cj4));
12722 IkReal x3464=((r01)*(sj5));
12723 IkReal x3465=((IkReal(1.00000000000000))*(cj4));
12724 IkReal x3466=((IkReal(1.00000000000000))*(r02));
12725 IkReal x3467=((IkReal(0.707109999985348))*(sj3));
12726 IkReal x3468=((IkReal(0.707103562373095))*(sj3));
12727 IkReal x3469=((IkReal(1.00000000000000))*(sj4));
12728 IkReal x3470=((cj5)*(r20));
12729 IkReal x3471=((cj5)*(sj0));
12730 IkReal x3472=((IkReal(1.00000000000000))*(cj0));
12731 IkReal x3473=((r12)*(sj0));
12732 IkReal x3474=((cj2)*(cj3));
12733 IkReal x3475=((IkReal(0.707103562373095))*(cj3));
12734 IkReal x3476=((r21)*(sj5));
12735 IkReal x3477=((IkReal(0.707109999985348))*(cj3));
12736 IkReal x3478=((IkReal(1.00000000000000))*(sj0)*(sj5));
12737 IkReal x3479=((sj2)*(x3461));
12738 IkReal x3480=((cj2)*(x3461));
12739 IkReal x3481=((cj0)*(cj5)*(r00));
12740 IkReal x3482=((IkReal(0.707103562373095))*(x3462));
12741 IkReal x3483=((cj2)*(x3462));
12742 IkReal x3484=((IkReal(0.707109999985348))*(sj2)*(x3462));
12743 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3467)*(x3480)))+(((IkReal(-1.00000000000000))*(x3468)*(x3479)))+(((IkReal(-1.00000000000000))*(x3468)*(x3483)))+(((sj2)*(x3462)*(x3467)))+(((r20)*(sj5))));
12744 evalcond[1]=((((sj4)*(x3476)))+(((cj4)*(r22)))+(((sj2)*(x3482)))+(((IkReal(-1.00000000000000))*(x3469)*(x3470)))+(((IkReal(-0.707103562373095))*(x3480)))+(((IkReal(0.707109999985348))*(x3479)))+(((IkReal(0.707109999985348))*(x3483))));
12745 evalcond[2]=((((x3475)*(x3479)))+(((x3474)*(x3482)))+(((IkReal(-1.00000000000000))*(x3465)*(x3476)))+(((cj4)*(x3470)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x3462)*(x3477)))+(((IkReal(0.707109999985348))*(x3461)*(x3474))));
12746 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x3471)))+(((IkReal(-1.00000000000000))*(r10)*(x3478)))+(((x3467)*(x3479)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3472)))+(((x3467)*(x3483)))+(((IkReal(-1.00000000000000))*(x3468)*(x3480)))+(((sj2)*(x3462)*(x3468)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3472))));
12747 evalcond[4]=((((IkReal(-1.00000000000000))*(x3463)*(x3466)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x3469)))+(((IkReal(-1.00000000000000))*(x3465)*(x3473)))+(((r10)*(sj4)*(x3471)))+(((IkReal(-1.00000000000000))*(cj0)*(x3464)*(x3469)))+(((IkReal(0.707103562373095))*(x3479)))+(((cj2)*(x3482)))+(((IkReal(-1.00000000000000))*(x3484)))+(((IkReal(0.707109999985348))*(x3480)))+(((sj4)*(x3481))));
12748 evalcond[5]=((((x3463)*(x3464)))+(((IkReal(-1.00000000000000))*(r10)*(x3465)*(x3471)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x3469)*(x3473)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3463)))+(((IkReal(-1.00000000000000))*(sj2)*(x3462)*(x3475)))+(((IkReal(0.707103562373095))*(x3461)*(x3474)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x3466)))+(((IkReal(-1.00000000000000))*(x3477)*(x3479)))+(((IkReal(-0.707109999985348))*(x3462)*(x3474))));
12749 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  )
12750 {
12751 continue;
12752 }
12753 }
12754 
12755 {
12756 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12757 vinfos[0].jointtype = 1;
12758 vinfos[0].foffset = j0;
12759 vinfos[0].indices[0] = _ij0[0];
12760 vinfos[0].indices[1] = _ij0[1];
12761 vinfos[0].maxsolutions = _nj0;
12762 vinfos[1].jointtype = 1;
12763 vinfos[1].foffset = j1;
12764 vinfos[1].indices[0] = _ij1[0];
12765 vinfos[1].indices[1] = _ij1[1];
12766 vinfos[1].maxsolutions = _nj1;
12767 vinfos[2].jointtype = 1;
12768 vinfos[2].foffset = j2;
12769 vinfos[2].indices[0] = _ij2[0];
12770 vinfos[2].indices[1] = _ij2[1];
12771 vinfos[2].maxsolutions = _nj2;
12772 vinfos[3].jointtype = 1;
12773 vinfos[3].foffset = j3;
12774 vinfos[3].indices[0] = _ij3[0];
12775 vinfos[3].indices[1] = _ij3[1];
12776 vinfos[3].maxsolutions = _nj3;
12777 vinfos[4].jointtype = 1;
12778 vinfos[4].foffset = j4;
12779 vinfos[4].indices[0] = _ij4[0];
12780 vinfos[4].indices[1] = _ij4[1];
12781 vinfos[4].maxsolutions = _nj4;
12782 vinfos[5].jointtype = 1;
12783 vinfos[5].foffset = j5;
12784 vinfos[5].indices[0] = _ij5[0];
12785 vinfos[5].indices[1] = _ij5[1];
12786 vinfos[5].maxsolutions = _nj5;
12787 std::vector<int> vfree(0);
12788 solutions.AddSolution(vinfos,vfree);
12789 }
12790 }
12791 }
12792 
12793 }
12794 
12795 }
12796 }
12797 }
12798 
12799 }
12800 
12801 }
12802 }
12803 }
12804 
12805 }
12806 
12807 }
12808 
12809 } else
12810 {
12811 {
12812 IkReal j0array[1], cj0array[1], sj0array[1];
12813 bool j0valid[1]={false};
12814 _nj0 = 1;
12815 IkReal x3485=((cj3)*(sj4));
12816 IkReal x3486=((IkReal(1.00000000000000))*(sj5));
12817 IkReal x3487=((IkReal(1.00000000000000))*(cj3)*(cj4));
12818 if( IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(r12)*(x3487)))+(((cj5)*(r10)*(x3485)))+(((IkReal(-1.00000000000000))*(r11)*(x3485)*(x3486))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-1.00000000000000))*(r02)*(x3487)))+(((IkReal(-1.00000000000000))*(r01)*(x3485)*(x3486)))+(((cj5)*(r00)*(x3485))))))) < IKFAST_ATAN2_MAGTHRESH )
12819     continue;
12820 j0array[0]=IKatan2(((gconst0)*(((((IkReal(-1.00000000000000))*(r12)*(x3487)))+(((cj5)*(r10)*(x3485)))+(((IkReal(-1.00000000000000))*(r11)*(x3485)*(x3486)))))), ((gconst0)*(((((IkReal(-1.00000000000000))*(r02)*(x3487)))+(((IkReal(-1.00000000000000))*(r01)*(x3485)*(x3486)))+(((cj5)*(r00)*(x3485)))))));
12821 sj0array[0]=IKsin(j0array[0]);
12822 cj0array[0]=IKcos(j0array[0]);
12823 if( j0array[0] > IKPI )
12824 {
12825     j0array[0]-=IK2PI;
12826 }
12827 else if( j0array[0] < -IKPI )
12828 {    j0array[0]+=IK2PI;
12829 }
12830 j0valid[0] = true;
12831 for(int ij0 = 0; ij0 < 1; ++ij0)
12832 {
12833 if( !j0valid[ij0] )
12834 {
12835     continue;
12836 }
12837 _ij0[0] = ij0; _ij0[1] = -1;
12838 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
12839 {
12840 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
12841 {
12842     j0valid[iij0]=false; _ij0[1] = iij0; break; 
12843 }
12844 }
12845 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
12846 {
12847 IkReal evalcond[3];
12848 IkReal x3488=IKsin(j0);
12849 IkReal x3489=IKcos(j0);
12850 IkReal x3490=((cj5)*(r00));
12851 IkReal x3491=((r01)*(sj5));
12852 IkReal x3492=((cj5)*(r10));
12853 IkReal x3493=((IkReal(1.00000000000000))*(r12));
12854 IkReal x3494=((r11)*(sj5));
12855 IkReal x3495=((cj4)*(x3488));
12856 IkReal x3496=((sj4)*(x3488));
12857 IkReal x3497=((sj4)*(x3489));
12858 IkReal x3498=((cj4)*(x3489));
12859 IkReal x3499=((IkReal(1.00000000000000))*(x3489));
12860 evalcond[0]=((((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3499)))+(cj3)+(((r00)*(sj5)*(x3488)))+(((cj5)*(r01)*(x3488)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3499))));
12861 evalcond[1]=((((IkReal(-1.00000000000000))*(x3490)*(x3496)))+(((x3491)*(x3496)))+(((IkReal(-1.00000000000000))*(x3493)*(x3498)))+(((r02)*(x3495)))+(((IkReal(-1.00000000000000))*(x3494)*(x3497)))+(((x3492)*(x3497))));
12862 evalcond[2]=((((IkReal(-1.00000000000000))*(x3492)*(x3498)))+(sj3)+(((x3494)*(x3498)))+(((IkReal(-1.00000000000000))*(x3493)*(x3497)))+(((r02)*(x3496)))+(((IkReal(-1.00000000000000))*(x3491)*(x3495)))+(((x3490)*(x3495))));
12863 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
12864 {
12865 continue;
12866 }
12867 }
12868 
12869 {
12870 IkReal dummyeval[1];
12871 IkReal gconst34;
12872 gconst34=IKsign(sj3);
12873 dummyeval[0]=sj3;
12874 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12875 {
12876 {
12877 IkReal dummyeval[1];
12878 IkReal gconst35;
12879 gconst35=IKsign(cj3);
12880 dummyeval[0]=cj3;
12881 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12882 {
12883 {
12884 IkReal evalcond[7];
12885 IkReal x3500=((sj0)*(sj4));
12886 IkReal x3501=((IkReal(1.00000000000000))*(r12));
12887 IkReal x3502=((IkReal(1.00000000000000))*(cj0));
12888 IkReal x3503=((cj4)*(cj5));
12889 IkReal x3504=((r11)*(sj5));
12890 IkReal x3505=((cj4)*(sj0));
12891 IkReal x3506=((IkReal(1.00000000000000))*(sj5));
12892 IkReal x3507=((cj0)*(cj4));
12893 IkReal x3508=((r00)*(sj0));
12894 IkReal x3509=((cj0)*(sj4));
12895 IkReal x3510=((r01)*(sj5));
12896 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
12897 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3502)))+(((sj5)*(x3508)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3502))));
12898 evalcond[2]=((IkReal(-0.00600000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x3506)))+(((npx)*(x3503)))+(((npz)*(sj4))));
12899 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3500)))+(((r02)*(x3505)))+(((IkReal(-1.00000000000000))*(x3501)*(x3507)))+(((IkReal(-1.00000000000000))*(sj4)*(x3502)*(x3504)))+(((x3500)*(x3510)))+(((cj5)*(r10)*(x3509))));
12900 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3502)*(x3503)))+(((IkReal(-1.00000000000000))*(r01)*(x3505)*(x3506)))+(((r02)*(x3500)))+(((IkReal(-1.00000000000000))*(x3501)*(x3509)))+(((x3503)*(x3508)))+(((x3504)*(x3507))));
12901 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(r21)*(x3506)))+(((r22)*(sj4)))+(((r20)*(x3503))));
12902 evalcond[6]=((((x3507)*(x3510)))+(((IkReal(-1.00000000000000))*(r00)*(x3502)*(x3503)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3503)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3502)))+(((x3504)*(x3505)))+(((IkReal(-1.00000000000000))*(x3500)*(x3501))));
12903 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  )
12904 {
12905 {
12906 IkReal j2array[1], cj2array[1], sj2array[1];
12907 bool j2valid[1]={false};
12908 _nj2 = 1;
12909 IkReal x3511=((cj4)*(npz));
12910 IkReal x3512=((IkReal(2.94476514910275))*(cj5));
12911 IkReal x3513=((npx)*(sj4));
12912 IkReal x3514=((IkReal(2.34381456633434))*(sj5));
12913 IkReal x3515=((npy)*(sj4));
12914 IkReal x3516=((IkReal(2.94476514910275))*(sj5));
12915 IkReal x3517=((IkReal(2.34381456633434))*(cj5));
12916 if( IKabs(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x3514)*(x3515)))+(((npx)*(x3516)))+(((IkReal(-2.34381456633434))*(x3511)))+(((x3513)*(x3517)))+(((npy)*(x3512))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.844144773271807))+(((IkReal(-1.00000000000000))*(x3512)*(x3513)))+(((npx)*(x3514)))+(((IkReal(2.94476514910275))*(x3511)))+(((x3515)*(x3516)))+(((npy)*(x3517))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x3514)*(x3515)))+(((npx)*(x3516)))+(((IkReal(-2.34381456633434))*(x3511)))+(((x3513)*(x3517)))+(((npy)*(x3512)))))+IKsqr(((IkReal(-0.844144773271807))+(((IkReal(-1.00000000000000))*(x3512)*(x3513)))+(((npx)*(x3514)))+(((IkReal(2.94476514910275))*(x3511)))+(((x3515)*(x3516)))+(((npy)*(x3517)))))-1) <= IKFAST_SINCOS_THRESH )
12917     continue;
12918 j2array[0]=IKatan2(((IkReal(0.498689812223981))+(((IkReal(-1.00000000000000))*(x3514)*(x3515)))+(((npx)*(x3516)))+(((IkReal(-2.34381456633434))*(x3511)))+(((x3513)*(x3517)))+(((npy)*(x3512)))), ((IkReal(-0.844144773271807))+(((IkReal(-1.00000000000000))*(x3512)*(x3513)))+(((npx)*(x3514)))+(((IkReal(2.94476514910275))*(x3511)))+(((x3515)*(x3516)))+(((npy)*(x3517)))));
12919 sj2array[0]=IKsin(j2array[0]);
12920 cj2array[0]=IKcos(j2array[0]);
12921 if( j2array[0] > IKPI )
12922 {
12923     j2array[0]-=IK2PI;
12924 }
12925 else if( j2array[0] < -IKPI )
12926 {    j2array[0]+=IK2PI;
12927 }
12928 j2valid[0] = true;
12929 for(int ij2 = 0; ij2 < 1; ++ij2)
12930 {
12931 if( !j2valid[ij2] )
12932 {
12933     continue;
12934 }
12935 _ij2[0] = ij2; _ij2[1] = -1;
12936 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
12937 {
12938 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
12939 {
12940     j2valid[iij2]=false; _ij2[1] = iij2; break; 
12941 }
12942 }
12943 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
12944 {
12945 IkReal evalcond[2];
12946 IkReal x3518=IKcos(j2);
12947 IkReal x3519=IKsin(j2);
12948 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(x3518)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(x3519))));
12949 evalcond[1]=((IkReal(-0.0360035672348961))+(((IkReal(-0.207888640466058))*(x3519)))+(((npx)*(sj5)))+(((cj5)*(npy)))+(((IkReal(-0.165463933124939))*(x3518))));
12950 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
12951 {
12952 continue;
12953 }
12954 }
12955 
12956 {
12957 IkReal dummyeval[1];
12958 IkReal gconst46;
12959 gconst46=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
12960 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
12961 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12962 {
12963 {
12964 IkReal dummyeval[1];
12965 IkReal gconst47;
12966 gconst47=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
12967 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
12968 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12969 {
12970 continue;
12971 
12972 } else
12973 {
12974 {
12975 IkReal j1array[1], cj1array[1], sj1array[1];
12976 bool j1valid[1]={false};
12977 _nj1 = 1;
12978 IkReal x3520=((cj5)*(r11));
12979 IkReal x3521=((r10)*(sj0));
12980 IkReal x3522=((IkReal(0.707103562373095))*(cj2));
12981 IkReal x3523=((r20)*(sj5));
12982 IkReal x3524=((IkReal(0.707103562373095))*(sj2));
12983 IkReal x3525=((IkReal(0.707109999985348))*(cj2));
12984 IkReal x3526=((IkReal(0.707109999985348))*(sj2));
12985 IkReal x3527=((cj5)*(r21));
12986 IkReal x3528=((sj0)*(x3524));
12987 IkReal x3529=((sj5)*(x3525));
12988 IkReal x3530=((cj0)*(cj5)*(r01));
12989 IkReal x3531=((cj0)*(r00)*(sj5));
12990 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3522)*(x3527)))+(((IkReal(-1.00000000000000))*(x3522)*(x3523)))+(((IkReal(-1.00000000000000))*(sj0)*(x3520)*(x3525)))+(((IkReal(-1.00000000000000))*(sj5)*(x3521)*(x3524)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3529)))+(((IkReal(-1.00000000000000))*(x3525)*(x3530)))+(((x3526)*(x3527)))+(((IkReal(-1.00000000000000))*(x3524)*(x3530)))+(((IkReal(-1.00000000000000))*(x3524)*(x3531)))+(((x3523)*(x3526)))+(((IkReal(-1.00000000000000))*(x3521)*(x3529)))+(((IkReal(-1.00000000000000))*(x3520)*(x3528))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3525)*(x3527)))+(((IkReal(-1.00000000000000))*(sj0)*(x3520)*(x3526)))+(((IkReal(-1.00000000000000))*(x3524)*(x3527)))+(((IkReal(-1.00000000000000))*(sj5)*(x3521)*(x3526)))+(((IkReal(-1.00000000000000))*(x3526)*(x3531)))+(((IkReal(-1.00000000000000))*(x3526)*(x3530)))+(((sj5)*(x3521)*(x3522)))+(((sj0)*(x3520)*(x3522)))+(((IkReal(-1.00000000000000))*(x3523)*(x3524)))+(((IkReal(-1.00000000000000))*(x3523)*(x3525)))+(((x3522)*(x3530)))+(((x3522)*(x3531))))))) < IKFAST_ATAN2_MAGTHRESH )
12991     continue;
12992 j1array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(x3522)*(x3527)))+(((IkReal(-1.00000000000000))*(x3522)*(x3523)))+(((IkReal(-1.00000000000000))*(sj0)*(x3520)*(x3525)))+(((IkReal(-1.00000000000000))*(sj5)*(x3521)*(x3524)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x3529)))+(((IkReal(-1.00000000000000))*(x3525)*(x3530)))+(((x3526)*(x3527)))+(((IkReal(-1.00000000000000))*(x3524)*(x3530)))+(((IkReal(-1.00000000000000))*(x3524)*(x3531)))+(((x3523)*(x3526)))+(((IkReal(-1.00000000000000))*(x3521)*(x3529)))+(((IkReal(-1.00000000000000))*(x3520)*(x3528)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(x3525)*(x3527)))+(((IkReal(-1.00000000000000))*(sj0)*(x3520)*(x3526)))+(((IkReal(-1.00000000000000))*(x3524)*(x3527)))+(((IkReal(-1.00000000000000))*(sj5)*(x3521)*(x3526)))+(((IkReal(-1.00000000000000))*(x3526)*(x3531)))+(((IkReal(-1.00000000000000))*(x3526)*(x3530)))+(((sj5)*(x3521)*(x3522)))+(((sj0)*(x3520)*(x3522)))+(((IkReal(-1.00000000000000))*(x3523)*(x3524)))+(((IkReal(-1.00000000000000))*(x3523)*(x3525)))+(((x3522)*(x3530)))+(((x3522)*(x3531)))))));
12993 sj1array[0]=IKsin(j1array[0]);
12994 cj1array[0]=IKcos(j1array[0]);
12995 if( j1array[0] > IKPI )
12996 {
12997     j1array[0]-=IK2PI;
12998 }
12999 else if( j1array[0] < -IKPI )
13000 {    j1array[0]+=IK2PI;
13001 }
13002 j1valid[0] = true;
13003 for(int ij1 = 0; ij1 < 1; ++ij1)
13004 {
13005 if( !j1valid[ij1] )
13006 {
13007     continue;
13008 }
13009 _ij1[0] = ij1; _ij1[1] = -1;
13010 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13011 {
13012 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13013 {
13014     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13015 }
13016 }
13017 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13018 {
13019 IkReal evalcond[4];
13020 IkReal x3532=IKsin(j1);
13021 IkReal x3533=IKcos(j1);
13022 IkReal x3534=((IkReal(0.707109999985348))*(cj2));
13023 IkReal x3535=((IkReal(1.00000000000000))*(cj0));
13024 IkReal x3536=((IkReal(0.707109999985348))*(sj2));
13025 IkReal x3537=((cj5)*(sj4));
13026 IkReal x3538=((sj4)*(sj5));
13027 IkReal x3539=((IkReal(1.00000000000000))*(sj0));
13028 IkReal x3540=((sj5)*(x3539));
13029 IkReal x3541=((IkReal(0.707103562373095))*(x3533));
13030 IkReal x3542=((IkReal(0.707103562373095))*(x3532));
13031 IkReal x3543=((x3532)*(x3534));
13032 IkReal x3544=((sj2)*(x3542));
13033 IkReal x3545=((x3533)*(x3536));
13034 IkReal x3546=((cj2)*(x3541));
13035 IkReal x3547=((sj2)*(x3541));
13036 IkReal x3548=((cj2)*(x3542));
13037 IkReal x3549=((x3533)*(x3534));
13038 IkReal x3550=((x3532)*(x3536));
13039 IkReal x3551=((x3547)+(x3548)+(x3549));
13040 IkReal x3552=((x3544)+(x3545)+(x3543));
13041 evalcond[0]=((((cj5)*(r21)))+(x3550)+(((IkReal(-1.00000000000000))*(x3551)))+(((r20)*(sj5))));
13042 evalcond[1]=((((cj4)*(r22)))+(x3552)+(((r21)*(x3538)))+(((IkReal(-1.00000000000000))*(x3546)))+(((IkReal(-1.00000000000000))*(r20)*(x3537))));
13043 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3540)))+(x3552)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3539)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3535)))+(((IkReal(-1.00000000000000))*(x3546)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3535))));
13044 evalcond[3]=((x3551)+(((r10)*(sj0)*(x3537)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3539)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3535)))+(((cj0)*(r00)*(x3537)))+(((IkReal(-1.00000000000000))*(r01)*(x3535)*(x3538)))+(((IkReal(-1.00000000000000))*(x3550)))+(((IkReal(-1.00000000000000))*(r11)*(x3538)*(x3539))));
13045 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13046 {
13047 continue;
13048 }
13049 }
13050 
13051 {
13052 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13053 vinfos[0].jointtype = 1;
13054 vinfos[0].foffset = j0;
13055 vinfos[0].indices[0] = _ij0[0];
13056 vinfos[0].indices[1] = _ij0[1];
13057 vinfos[0].maxsolutions = _nj0;
13058 vinfos[1].jointtype = 1;
13059 vinfos[1].foffset = j1;
13060 vinfos[1].indices[0] = _ij1[0];
13061 vinfos[1].indices[1] = _ij1[1];
13062 vinfos[1].maxsolutions = _nj1;
13063 vinfos[2].jointtype = 1;
13064 vinfos[2].foffset = j2;
13065 vinfos[2].indices[0] = _ij2[0];
13066 vinfos[2].indices[1] = _ij2[1];
13067 vinfos[2].maxsolutions = _nj2;
13068 vinfos[3].jointtype = 1;
13069 vinfos[3].foffset = j3;
13070 vinfos[3].indices[0] = _ij3[0];
13071 vinfos[3].indices[1] = _ij3[1];
13072 vinfos[3].maxsolutions = _nj3;
13073 vinfos[4].jointtype = 1;
13074 vinfos[4].foffset = j4;
13075 vinfos[4].indices[0] = _ij4[0];
13076 vinfos[4].indices[1] = _ij4[1];
13077 vinfos[4].maxsolutions = _nj4;
13078 vinfos[5].jointtype = 1;
13079 vinfos[5].foffset = j5;
13080 vinfos[5].indices[0] = _ij5[0];
13081 vinfos[5].indices[1] = _ij5[1];
13082 vinfos[5].maxsolutions = _nj5;
13083 std::vector<int> vfree(0);
13084 solutions.AddSolution(vinfos,vfree);
13085 }
13086 }
13087 }
13088 
13089 }
13090 
13091 }
13092 
13093 } else
13094 {
13095 {
13096 IkReal j1array[1], cj1array[1], sj1array[1];
13097 bool j1valid[1]={false};
13098 _nj1 = 1;
13099 IkReal x3553=((cj5)*(sj4));
13100 IkReal x3554=((r21)*(sj4));
13101 IkReal x3555=((cj5)*(r21));
13102 IkReal x3556=((IkReal(0.707109999985348))*(cj2));
13103 IkReal x3557=((IkReal(0.707103562373095))*(sj2));
13104 IkReal x3558=((IkReal(0.707109999985348))*(sj2));
13105 IkReal x3559=((cj4)*(r22));
13106 IkReal x3560=((IkReal(0.707103562373095))*(cj2));
13107 IkReal x3561=((r20)*(x3556));
13108 IkReal x3562=((sj5)*(x3560));
13109 IkReal x3563=((sj5)*(x3558));
13110 if( IKabs(((gconst46)*(((((x3556)*(x3559)))+(((IkReal(-1.00000000000000))*(x3555)*(x3560)))+(((IkReal(-1.00000000000000))*(r20)*(x3562)))+(((IkReal(-1.00000000000000))*(x3553)*(x3561)))+(((x3557)*(x3559)))+(((sj5)*(x3554)*(x3556)))+(((sj5)*(x3554)*(x3557)))+(((x3555)*(x3558)))+(((IkReal(-1.00000000000000))*(r20)*(x3553)*(x3557)))+(((r20)*(x3563))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((r20)*(x3553)*(x3560)))+(((IkReal(-1.00000000000000))*(x3555)*(x3556)))+(((IkReal(-1.00000000000000))*(x3555)*(x3557)))+(((IkReal(-1.00000000000000))*(sj5)*(x3561)))+(((IkReal(-1.00000000000000))*(x3554)*(x3562)))+(((IkReal(-1.00000000000000))*(x3559)*(x3560)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3557)))+(((x3558)*(x3559)))+(((x3554)*(x3563)))+(((IkReal(-1.00000000000000))*(r20)*(x3553)*(x3558))))))) < IKFAST_ATAN2_MAGTHRESH )
13111     continue;
13112 j1array[0]=IKatan2(((gconst46)*(((((x3556)*(x3559)))+(((IkReal(-1.00000000000000))*(x3555)*(x3560)))+(((IkReal(-1.00000000000000))*(r20)*(x3562)))+(((IkReal(-1.00000000000000))*(x3553)*(x3561)))+(((x3557)*(x3559)))+(((sj5)*(x3554)*(x3556)))+(((sj5)*(x3554)*(x3557)))+(((x3555)*(x3558)))+(((IkReal(-1.00000000000000))*(r20)*(x3553)*(x3557)))+(((r20)*(x3563)))))), ((gconst46)*(((((r20)*(x3553)*(x3560)))+(((IkReal(-1.00000000000000))*(x3555)*(x3556)))+(((IkReal(-1.00000000000000))*(x3555)*(x3557)))+(((IkReal(-1.00000000000000))*(sj5)*(x3561)))+(((IkReal(-1.00000000000000))*(x3554)*(x3562)))+(((IkReal(-1.00000000000000))*(x3559)*(x3560)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3557)))+(((x3558)*(x3559)))+(((x3554)*(x3563)))+(((IkReal(-1.00000000000000))*(r20)*(x3553)*(x3558)))))));
13113 sj1array[0]=IKsin(j1array[0]);
13114 cj1array[0]=IKcos(j1array[0]);
13115 if( j1array[0] > IKPI )
13116 {
13117     j1array[0]-=IK2PI;
13118 }
13119 else if( j1array[0] < -IKPI )
13120 {    j1array[0]+=IK2PI;
13121 }
13122 j1valid[0] = true;
13123 for(int ij1 = 0; ij1 < 1; ++ij1)
13124 {
13125 if( !j1valid[ij1] )
13126 {
13127     continue;
13128 }
13129 _ij1[0] = ij1; _ij1[1] = -1;
13130 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13131 {
13132 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13133 {
13134     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13135 }
13136 }
13137 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13138 {
13139 IkReal evalcond[4];
13140 IkReal x3564=IKsin(j1);
13141 IkReal x3565=IKcos(j1);
13142 IkReal x3566=((IkReal(0.707109999985348))*(cj2));
13143 IkReal x3567=((IkReal(1.00000000000000))*(cj0));
13144 IkReal x3568=((IkReal(0.707109999985348))*(sj2));
13145 IkReal x3569=((cj5)*(sj4));
13146 IkReal x3570=((sj4)*(sj5));
13147 IkReal x3571=((IkReal(1.00000000000000))*(sj0));
13148 IkReal x3572=((sj5)*(x3571));
13149 IkReal x3573=((IkReal(0.707103562373095))*(x3565));
13150 IkReal x3574=((IkReal(0.707103562373095))*(x3564));
13151 IkReal x3575=((x3564)*(x3566));
13152 IkReal x3576=((sj2)*(x3574));
13153 IkReal x3577=((x3565)*(x3568));
13154 IkReal x3578=((cj2)*(x3573));
13155 IkReal x3579=((sj2)*(x3573));
13156 IkReal x3580=((cj2)*(x3574));
13157 IkReal x3581=((x3565)*(x3566));
13158 IkReal x3582=((x3564)*(x3568));
13159 IkReal x3583=((x3579)+(x3580)+(x3581));
13160 IkReal x3584=((x3575)+(x3577)+(x3576));
13161 evalcond[0]=((((cj5)*(r21)))+(x3582)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x3583))));
13162 evalcond[1]=((((r21)*(x3570)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x3569)))+(x3584)+(((IkReal(-1.00000000000000))*(x3578))));
13163 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3572)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3567)))+(x3584)+(((IkReal(-1.00000000000000))*(x3578)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3571)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3567))));
13164 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3567)*(x3570)))+(((cj0)*(r00)*(x3569)))+(x3583)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3571)))+(((IkReal(-1.00000000000000))*(r11)*(x3570)*(x3571)))+(((r10)*(sj0)*(x3569)))+(((IkReal(-1.00000000000000))*(x3582)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3567))));
13165 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13166 {
13167 continue;
13168 }
13169 }
13170 
13171 {
13172 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13173 vinfos[0].jointtype = 1;
13174 vinfos[0].foffset = j0;
13175 vinfos[0].indices[0] = _ij0[0];
13176 vinfos[0].indices[1] = _ij0[1];
13177 vinfos[0].maxsolutions = _nj0;
13178 vinfos[1].jointtype = 1;
13179 vinfos[1].foffset = j1;
13180 vinfos[1].indices[0] = _ij1[0];
13181 vinfos[1].indices[1] = _ij1[1];
13182 vinfos[1].maxsolutions = _nj1;
13183 vinfos[2].jointtype = 1;
13184 vinfos[2].foffset = j2;
13185 vinfos[2].indices[0] = _ij2[0];
13186 vinfos[2].indices[1] = _ij2[1];
13187 vinfos[2].maxsolutions = _nj2;
13188 vinfos[3].jointtype = 1;
13189 vinfos[3].foffset = j3;
13190 vinfos[3].indices[0] = _ij3[0];
13191 vinfos[3].indices[1] = _ij3[1];
13192 vinfos[3].maxsolutions = _nj3;
13193 vinfos[4].jointtype = 1;
13194 vinfos[4].foffset = j4;
13195 vinfos[4].indices[0] = _ij4[0];
13196 vinfos[4].indices[1] = _ij4[1];
13197 vinfos[4].maxsolutions = _nj4;
13198 vinfos[5].jointtype = 1;
13199 vinfos[5].foffset = j5;
13200 vinfos[5].indices[0] = _ij5[0];
13201 vinfos[5].indices[1] = _ij5[1];
13202 vinfos[5].maxsolutions = _nj5;
13203 std::vector<int> vfree(0);
13204 solutions.AddSolution(vinfos,vfree);
13205 }
13206 }
13207 }
13208 
13209 }
13210 
13211 }
13212 }
13213 }
13214 
13215 } else
13216 {
13217 IkReal x3585=((sj0)*(sj4));
13218 IkReal x3586=((IkReal(1.00000000000000))*(r12));
13219 IkReal x3587=((IkReal(1.00000000000000))*(cj0));
13220 IkReal x3588=((cj4)*(cj5));
13221 IkReal x3589=((r11)*(sj5));
13222 IkReal x3590=((cj4)*(sj0));
13223 IkReal x3591=((IkReal(1.00000000000000))*(sj5));
13224 IkReal x3592=((cj0)*(cj4));
13225 IkReal x3593=((r00)*(sj0));
13226 IkReal x3594=((cj0)*(sj4));
13227 IkReal x3595=((r01)*(sj5));
13228 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
13229 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3587)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x3593)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3587))));
13230 evalcond[2]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x3591)))+(((npx)*(x3588))));
13231 evalcond[3]=((((x3585)*(x3595)))+(((r02)*(x3590)))+(((cj5)*(r10)*(x3594)))+(((IkReal(-1.00000000000000))*(x3586)*(x3592)))+(((IkReal(-1.00000000000000))*(sj4)*(x3587)*(x3589)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3585))));
13232 evalcond[4]=((IkReal(1.00000000000000))+(((r02)*(x3585)))+(((x3589)*(x3592)))+(((x3588)*(x3593)))+(((IkReal(-1.00000000000000))*(x3586)*(x3594)))+(((IkReal(-1.00000000000000))*(r01)*(x3590)*(x3591)))+(((IkReal(-1.00000000000000))*(r10)*(x3587)*(x3588))));
13233 evalcond[5]=((((r22)*(sj4)))+(((r20)*(x3588)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x3591))));
13234 evalcond[6]=((((x3589)*(x3590)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3587)))+(((x3592)*(x3595)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3588)))+(((IkReal(-1.00000000000000))*(x3585)*(x3586)))+(((IkReal(-1.00000000000000))*(r00)*(x3587)*(x3588))));
13235 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  )
13236 {
13237 {
13238 IkReal j2array[1], cj2array[1], sj2array[1];
13239 bool j2valid[1]={false};
13240 _nj2 = 1;
13241 IkReal x3596=((cj4)*(npz));
13242 IkReal x3597=((IkReal(2.94476514910275))*(cj5));
13243 IkReal x3598=((npx)*(sj4));
13244 IkReal x3599=((IkReal(2.34381456633434))*(sj5));
13245 IkReal x3600=((npy)*(sj4));
13246 IkReal x3601=((IkReal(2.94476514910275))*(sj5));
13247 IkReal x3602=((IkReal(2.34381456633434))*(cj5));
13248 if( IKabs(((IkReal(0.498689812223981))+(((x3598)*(x3602)))+(((npy)*(x3597)))+(((IkReal(-1.00000000000000))*(x3599)*(x3600)))+(((npx)*(x3601)))+(((IkReal(-2.34381456633434))*(x3596))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.844144773271807))+(((IkReal(2.94476514910275))*(x3596)))+(((x3600)*(x3601)))+(((npy)*(x3602)))+(((IkReal(-1.00000000000000))*(x3597)*(x3598)))+(((npx)*(x3599))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.498689812223981))+(((x3598)*(x3602)))+(((npy)*(x3597)))+(((IkReal(-1.00000000000000))*(x3599)*(x3600)))+(((npx)*(x3601)))+(((IkReal(-2.34381456633434))*(x3596)))))+IKsqr(((IkReal(-0.844144773271807))+(((IkReal(2.94476514910275))*(x3596)))+(((x3600)*(x3601)))+(((npy)*(x3602)))+(((IkReal(-1.00000000000000))*(x3597)*(x3598)))+(((npx)*(x3599)))))-1) <= IKFAST_SINCOS_THRESH )
13249     continue;
13250 j2array[0]=IKatan2(((IkReal(0.498689812223981))+(((x3598)*(x3602)))+(((npy)*(x3597)))+(((IkReal(-1.00000000000000))*(x3599)*(x3600)))+(((npx)*(x3601)))+(((IkReal(-2.34381456633434))*(x3596)))), ((IkReal(-0.844144773271807))+(((IkReal(2.94476514910275))*(x3596)))+(((x3600)*(x3601)))+(((npy)*(x3602)))+(((IkReal(-1.00000000000000))*(x3597)*(x3598)))+(((npx)*(x3599)))));
13251 sj2array[0]=IKsin(j2array[0]);
13252 cj2array[0]=IKcos(j2array[0]);
13253 if( j2array[0] > IKPI )
13254 {
13255     j2array[0]-=IK2PI;
13256 }
13257 else if( j2array[0] < -IKPI )
13258 {    j2array[0]+=IK2PI;
13259 }
13260 j2valid[0] = true;
13261 for(int ij2 = 0; ij2 < 1; ++ij2)
13262 {
13263 if( !j2valid[ij2] )
13264 {
13265     continue;
13266 }
13267 _ij2[0] = ij2; _ij2[1] = -1;
13268 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
13269 {
13270 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
13271 {
13272     j2valid[iij2]=false; _ij2[1] = iij2; break; 
13273 }
13274 }
13275 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
13276 {
13277 IkReal evalcond[2];
13278 IkReal x3603=IKcos(j2);
13279 IkReal x3604=IKsin(j2);
13280 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(0.165463933124939))*(x3604)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x3603))));
13281 evalcond[1]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(x3604)))+(((IkReal(-0.165463933124939))*(x3603))));
13282 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13283 {
13284 continue;
13285 }
13286 }
13287 
13288 {
13289 IkReal dummyeval[1];
13290 IkReal gconst48;
13291 gconst48=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
13292 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
13293 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13294 {
13295 {
13296 IkReal dummyeval[1];
13297 IkReal gconst49;
13298 gconst49=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
13299 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
13300 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13301 {
13302 continue;
13303 
13304 } else
13305 {
13306 {
13307 IkReal j1array[1], cj1array[1], sj1array[1];
13308 bool j1valid[1]={false};
13309 _nj1 = 1;
13310 IkReal x3605=((cj5)*(r11));
13311 IkReal x3606=((r10)*(sj0));
13312 IkReal x3607=((IkReal(0.707103562373095))*(cj2));
13313 IkReal x3608=((r20)*(sj5));
13314 IkReal x3609=((IkReal(0.707103562373095))*(sj2));
13315 IkReal x3610=((IkReal(0.707109999985348))*(cj2));
13316 IkReal x3611=((cj0)*(r00));
13317 IkReal x3612=((IkReal(0.707109999985348))*(sj2));
13318 IkReal x3613=((cj5)*(r21));
13319 IkReal x3614=((sj0)*(x3609));
13320 IkReal x3615=((sj5)*(x3610));
13321 IkReal x3616=((cj0)*(cj5)*(r01));
13322 if( IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(x3605)*(x3614)))+(((x3612)*(x3613)))+(((IkReal(-1.00000000000000))*(x3611)*(x3615)))+(((x3608)*(x3612)))+(((IkReal(-1.00000000000000))*(x3607)*(x3608)))+(((IkReal(-1.00000000000000))*(x3607)*(x3613)))+(((IkReal(-1.00000000000000))*(sj0)*(x3605)*(x3610)))+(((IkReal(-1.00000000000000))*(sj5)*(x3609)*(x3611)))+(((IkReal(-1.00000000000000))*(x3609)*(x3616)))+(((IkReal(-1.00000000000000))*(x3610)*(x3616)))+(((IkReal(-1.00000000000000))*(sj5)*(x3606)*(x3609)))+(((IkReal(-1.00000000000000))*(x3606)*(x3615))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((sj0)*(x3605)*(x3607)))+(((IkReal(-1.00000000000000))*(x3612)*(x3616)))+(((x3607)*(x3616)))+(((IkReal(-1.00000000000000))*(sj0)*(x3605)*(x3612)))+(((IkReal(-1.00000000000000))*(x3608)*(x3609)))+(((IkReal(-1.00000000000000))*(sj5)*(x3611)*(x3612)))+(((IkReal(-1.00000000000000))*(x3609)*(x3613)))+(((IkReal(-1.00000000000000))*(x3608)*(x3610)))+(((IkReal(-1.00000000000000))*(x3610)*(x3613)))+(((sj5)*(x3607)*(x3611)))+(((sj5)*(x3606)*(x3607)))+(((IkReal(-1.00000000000000))*(sj5)*(x3606)*(x3612))))))) < IKFAST_ATAN2_MAGTHRESH )
13323     continue;
13324 j1array[0]=IKatan2(((gconst49)*(((((IkReal(-1.00000000000000))*(x3605)*(x3614)))+(((x3612)*(x3613)))+(((IkReal(-1.00000000000000))*(x3611)*(x3615)))+(((x3608)*(x3612)))+(((IkReal(-1.00000000000000))*(x3607)*(x3608)))+(((IkReal(-1.00000000000000))*(x3607)*(x3613)))+(((IkReal(-1.00000000000000))*(sj0)*(x3605)*(x3610)))+(((IkReal(-1.00000000000000))*(sj5)*(x3609)*(x3611)))+(((IkReal(-1.00000000000000))*(x3609)*(x3616)))+(((IkReal(-1.00000000000000))*(x3610)*(x3616)))+(((IkReal(-1.00000000000000))*(sj5)*(x3606)*(x3609)))+(((IkReal(-1.00000000000000))*(x3606)*(x3615)))))), ((gconst49)*(((((sj0)*(x3605)*(x3607)))+(((IkReal(-1.00000000000000))*(x3612)*(x3616)))+(((x3607)*(x3616)))+(((IkReal(-1.00000000000000))*(sj0)*(x3605)*(x3612)))+(((IkReal(-1.00000000000000))*(x3608)*(x3609)))+(((IkReal(-1.00000000000000))*(sj5)*(x3611)*(x3612)))+(((IkReal(-1.00000000000000))*(x3609)*(x3613)))+(((IkReal(-1.00000000000000))*(x3608)*(x3610)))+(((IkReal(-1.00000000000000))*(x3610)*(x3613)))+(((sj5)*(x3607)*(x3611)))+(((sj5)*(x3606)*(x3607)))+(((IkReal(-1.00000000000000))*(sj5)*(x3606)*(x3612)))))));
13325 sj1array[0]=IKsin(j1array[0]);
13326 cj1array[0]=IKcos(j1array[0]);
13327 if( j1array[0] > IKPI )
13328 {
13329     j1array[0]-=IK2PI;
13330 }
13331 else if( j1array[0] < -IKPI )
13332 {    j1array[0]+=IK2PI;
13333 }
13334 j1valid[0] = true;
13335 for(int ij1 = 0; ij1 < 1; ++ij1)
13336 {
13337 if( !j1valid[ij1] )
13338 {
13339     continue;
13340 }
13341 _ij1[0] = ij1; _ij1[1] = -1;
13342 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13343 {
13344 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13345 {
13346     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13347 }
13348 }
13349 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13350 {
13351 IkReal evalcond[4];
13352 IkReal x3617=IKsin(j1);
13353 IkReal x3618=IKcos(j1);
13354 IkReal x3619=((IkReal(0.707109999985348))*(cj2));
13355 IkReal x3620=((IkReal(1.00000000000000))*(cj0));
13356 IkReal x3621=((IkReal(0.707109999985348))*(sj2));
13357 IkReal x3622=((cj5)*(sj4));
13358 IkReal x3623=((sj4)*(sj5));
13359 IkReal x3624=((IkReal(1.00000000000000))*(sj0));
13360 IkReal x3625=((sj5)*(x3624));
13361 IkReal x3626=((IkReal(0.707103562373095))*(x3618));
13362 IkReal x3627=((IkReal(0.707103562373095))*(x3617));
13363 IkReal x3628=((x3617)*(x3619));
13364 IkReal x3629=((sj2)*(x3627));
13365 IkReal x3630=((x3618)*(x3621));
13366 IkReal x3631=((cj2)*(x3626));
13367 IkReal x3632=((sj2)*(x3626));
13368 IkReal x3633=((cj2)*(x3627));
13369 IkReal x3634=((x3618)*(x3619));
13370 IkReal x3635=((x3617)*(x3621));
13371 IkReal x3636=((x3634)+(x3632)+(x3633));
13372 IkReal x3637=((x3629)+(x3628)+(x3630));
13373 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3636)))+(x3635)+(((r20)*(sj5))));
13374 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x3623)))+(((IkReal(-1.00000000000000))*(x3631)))+(x3637)+(((IkReal(-1.00000000000000))*(r20)*(x3622))));
13375 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3620)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3620)))+(((IkReal(-1.00000000000000))*(x3631)))+(x3637)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3624)))+(((IkReal(-1.00000000000000))*(r10)*(x3625))));
13376 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3624)))+(((cj0)*(r00)*(x3622)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3620)))+(((IkReal(-1.00000000000000))*(r11)*(x3623)*(x3624)))+(((r10)*(sj0)*(x3622)))+(((IkReal(-1.00000000000000))*(x3635)))+(x3636)+(((IkReal(-1.00000000000000))*(r01)*(x3620)*(x3623))));
13377 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13378 {
13379 continue;
13380 }
13381 }
13382 
13383 {
13384 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13385 vinfos[0].jointtype = 1;
13386 vinfos[0].foffset = j0;
13387 vinfos[0].indices[0] = _ij0[0];
13388 vinfos[0].indices[1] = _ij0[1];
13389 vinfos[0].maxsolutions = _nj0;
13390 vinfos[1].jointtype = 1;
13391 vinfos[1].foffset = j1;
13392 vinfos[1].indices[0] = _ij1[0];
13393 vinfos[1].indices[1] = _ij1[1];
13394 vinfos[1].maxsolutions = _nj1;
13395 vinfos[2].jointtype = 1;
13396 vinfos[2].foffset = j2;
13397 vinfos[2].indices[0] = _ij2[0];
13398 vinfos[2].indices[1] = _ij2[1];
13399 vinfos[2].maxsolutions = _nj2;
13400 vinfos[3].jointtype = 1;
13401 vinfos[3].foffset = j3;
13402 vinfos[3].indices[0] = _ij3[0];
13403 vinfos[3].indices[1] = _ij3[1];
13404 vinfos[3].maxsolutions = _nj3;
13405 vinfos[4].jointtype = 1;
13406 vinfos[4].foffset = j4;
13407 vinfos[4].indices[0] = _ij4[0];
13408 vinfos[4].indices[1] = _ij4[1];
13409 vinfos[4].maxsolutions = _nj4;
13410 vinfos[5].jointtype = 1;
13411 vinfos[5].foffset = j5;
13412 vinfos[5].indices[0] = _ij5[0];
13413 vinfos[5].indices[1] = _ij5[1];
13414 vinfos[5].maxsolutions = _nj5;
13415 std::vector<int> vfree(0);
13416 solutions.AddSolution(vinfos,vfree);
13417 }
13418 }
13419 }
13420 
13421 }
13422 
13423 }
13424 
13425 } else
13426 {
13427 {
13428 IkReal j1array[1], cj1array[1], sj1array[1];
13429 bool j1valid[1]={false};
13430 _nj1 = 1;
13431 IkReal x3638=((cj5)*(sj4));
13432 IkReal x3639=((r21)*(sj4));
13433 IkReal x3640=((cj5)*(r21));
13434 IkReal x3641=((IkReal(0.707109999985348))*(cj2));
13435 IkReal x3642=((IkReal(0.707103562373095))*(sj2));
13436 IkReal x3643=((IkReal(0.707109999985348))*(sj2));
13437 IkReal x3644=((cj4)*(r22));
13438 IkReal x3645=((IkReal(0.707103562373095))*(cj2));
13439 IkReal x3646=((r20)*(x3641));
13440 IkReal x3647=((sj5)*(x3645));
13441 IkReal x3648=((sj5)*(x3643));
13442 if( IKabs(((gconst48)*(((((x3641)*(x3644)))+(((IkReal(-1.00000000000000))*(x3640)*(x3645)))+(((sj5)*(x3639)*(x3642)))+(((sj5)*(x3639)*(x3641)))+(((r20)*(x3648)))+(((IkReal(-1.00000000000000))*(r20)*(x3647)))+(((IkReal(-1.00000000000000))*(r20)*(x3638)*(x3642)))+(((IkReal(-1.00000000000000))*(x3638)*(x3646)))+(((x3642)*(x3644)))+(((x3640)*(x3643))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(x3640)*(x3642)))+(((IkReal(-1.00000000000000))*(x3640)*(x3641)))+(((x3643)*(x3644)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3642)))+(((IkReal(-1.00000000000000))*(x3639)*(x3647)))+(((IkReal(-1.00000000000000))*(x3644)*(x3645)))+(((x3639)*(x3648)))+(((IkReal(-1.00000000000000))*(r20)*(x3638)*(x3643)))+(((IkReal(-1.00000000000000))*(sj5)*(x3646)))+(((r20)*(x3638)*(x3645))))))) < IKFAST_ATAN2_MAGTHRESH )
13443     continue;
13444 j1array[0]=IKatan2(((gconst48)*(((((x3641)*(x3644)))+(((IkReal(-1.00000000000000))*(x3640)*(x3645)))+(((sj5)*(x3639)*(x3642)))+(((sj5)*(x3639)*(x3641)))+(((r20)*(x3648)))+(((IkReal(-1.00000000000000))*(r20)*(x3647)))+(((IkReal(-1.00000000000000))*(r20)*(x3638)*(x3642)))+(((IkReal(-1.00000000000000))*(x3638)*(x3646)))+(((x3642)*(x3644)))+(((x3640)*(x3643)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(x3640)*(x3642)))+(((IkReal(-1.00000000000000))*(x3640)*(x3641)))+(((x3643)*(x3644)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3642)))+(((IkReal(-1.00000000000000))*(x3639)*(x3647)))+(((IkReal(-1.00000000000000))*(x3644)*(x3645)))+(((x3639)*(x3648)))+(((IkReal(-1.00000000000000))*(r20)*(x3638)*(x3643)))+(((IkReal(-1.00000000000000))*(sj5)*(x3646)))+(((r20)*(x3638)*(x3645)))))));
13445 sj1array[0]=IKsin(j1array[0]);
13446 cj1array[0]=IKcos(j1array[0]);
13447 if( j1array[0] > IKPI )
13448 {
13449     j1array[0]-=IK2PI;
13450 }
13451 else if( j1array[0] < -IKPI )
13452 {    j1array[0]+=IK2PI;
13453 }
13454 j1valid[0] = true;
13455 for(int ij1 = 0; ij1 < 1; ++ij1)
13456 {
13457 if( !j1valid[ij1] )
13458 {
13459     continue;
13460 }
13461 _ij1[0] = ij1; _ij1[1] = -1;
13462 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13463 {
13464 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13465 {
13466     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13467 }
13468 }
13469 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13470 {
13471 IkReal evalcond[4];
13472 IkReal x3649=IKsin(j1);
13473 IkReal x3650=IKcos(j1);
13474 IkReal x3651=((IkReal(0.707109999985348))*(cj2));
13475 IkReal x3652=((IkReal(1.00000000000000))*(cj0));
13476 IkReal x3653=((IkReal(0.707109999985348))*(sj2));
13477 IkReal x3654=((cj5)*(sj4));
13478 IkReal x3655=((sj4)*(sj5));
13479 IkReal x3656=((IkReal(1.00000000000000))*(sj0));
13480 IkReal x3657=((sj5)*(x3656));
13481 IkReal x3658=((IkReal(0.707103562373095))*(x3650));
13482 IkReal x3659=((IkReal(0.707103562373095))*(x3649));
13483 IkReal x3660=((x3649)*(x3651));
13484 IkReal x3661=((sj2)*(x3659));
13485 IkReal x3662=((x3650)*(x3653));
13486 IkReal x3663=((cj2)*(x3658));
13487 IkReal x3664=((sj2)*(x3658));
13488 IkReal x3665=((cj2)*(x3659));
13489 IkReal x3666=((x3650)*(x3651));
13490 IkReal x3667=((x3649)*(x3653));
13491 IkReal x3668=((x3665)+(x3664)+(x3666));
13492 IkReal x3669=((x3661)+(x3660)+(x3662));
13493 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3668)))+(x3667)+(((r20)*(sj5))));
13494 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3654)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3663)))+(((r21)*(x3655)))+(x3669));
13495 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3652)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3656)))+(((IkReal(-1.00000000000000))*(x3663)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3652)))+(((IkReal(-1.00000000000000))*(r10)*(x3657)))+(x3669));
13496 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3652)*(x3655)))+(((IkReal(-1.00000000000000))*(x3667)))+(((IkReal(-1.00000000000000))*(r11)*(x3655)*(x3656)))+(x3668)+(((cj0)*(r00)*(x3654)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3652)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3656)))+(((r10)*(sj0)*(x3654))));
13497 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13498 {
13499 continue;
13500 }
13501 }
13502 
13503 {
13504 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13505 vinfos[0].jointtype = 1;
13506 vinfos[0].foffset = j0;
13507 vinfos[0].indices[0] = _ij0[0];
13508 vinfos[0].indices[1] = _ij0[1];
13509 vinfos[0].maxsolutions = _nj0;
13510 vinfos[1].jointtype = 1;
13511 vinfos[1].foffset = j1;
13512 vinfos[1].indices[0] = _ij1[0];
13513 vinfos[1].indices[1] = _ij1[1];
13514 vinfos[1].maxsolutions = _nj1;
13515 vinfos[2].jointtype = 1;
13516 vinfos[2].foffset = j2;
13517 vinfos[2].indices[0] = _ij2[0];
13518 vinfos[2].indices[1] = _ij2[1];
13519 vinfos[2].maxsolutions = _nj2;
13520 vinfos[3].jointtype = 1;
13521 vinfos[3].foffset = j3;
13522 vinfos[3].indices[0] = _ij3[0];
13523 vinfos[3].indices[1] = _ij3[1];
13524 vinfos[3].maxsolutions = _nj3;
13525 vinfos[4].jointtype = 1;
13526 vinfos[4].foffset = j4;
13527 vinfos[4].indices[0] = _ij4[0];
13528 vinfos[4].indices[1] = _ij4[1];
13529 vinfos[4].maxsolutions = _nj4;
13530 vinfos[5].jointtype = 1;
13531 vinfos[5].foffset = j5;
13532 vinfos[5].indices[0] = _ij5[0];
13533 vinfos[5].indices[1] = _ij5[1];
13534 vinfos[5].maxsolutions = _nj5;
13535 std::vector<int> vfree(0);
13536 solutions.AddSolution(vinfos,vfree);
13537 }
13538 }
13539 }
13540 
13541 }
13542 
13543 }
13544 }
13545 }
13546 
13547 } else
13548 {
13549 IkReal x3670=((sj0)*(sj4));
13550 IkReal x3671=((IkReal(1.00000000000000))*(r12));
13551 IkReal x3672=((IkReal(1.00000000000000))*(cj0));
13552 IkReal x3673=((cj4)*(cj5));
13553 IkReal x3674=((r11)*(sj5));
13554 IkReal x3675=((cj4)*(sj0));
13555 IkReal x3676=((IkReal(1.00000000000000))*(sj5));
13556 IkReal x3677=((cj0)*(cj4));
13557 IkReal x3678=((r00)*(sj0));
13558 IkReal x3679=((cj0)*(sj4));
13559 IkReal x3680=((r01)*(sj5));
13560 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
13561 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3672)))+(((sj5)*(x3678)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3672))));
13562 evalcond[2]=((IkReal(0.00600000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x3676)))+(((npx)*(x3673)))+(((npz)*(sj4))));
13563 evalcond[3]=((((cj5)*(r10)*(x3679)))+(((IkReal(-1.00000000000000))*(x3671)*(x3677)))+(((x3670)*(x3680)))+(((IkReal(-1.00000000000000))*(sj4)*(x3672)*(x3674)))+(((r02)*(x3675)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3670))));
13564 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x3671)*(x3679)))+(((IkReal(-1.00000000000000))*(r01)*(x3675)*(x3676)))+(((x3673)*(x3678)))+(((x3674)*(x3677)))+(((r02)*(x3670)))+(((IkReal(-1.00000000000000))*(r10)*(x3672)*(x3673))));
13565 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(r21)*(x3676)))+(((r20)*(x3673)))+(((r22)*(sj4))));
13566 evalcond[6]=((((IkReal(-1.00000000000000))*(x3670)*(x3671)))+(((IkReal(-1.00000000000000))*(r00)*(x3672)*(x3673)))+(((x3674)*(x3675)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3673)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3672)))+(((x3677)*(x3680))));
13567 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  )
13568 {
13569 {
13570 IkReal j2array[1], cj2array[1], sj2array[1];
13571 bool j2valid[1]={false};
13572 _nj2 = 1;
13573 IkReal x3681=((cj4)*(npz));
13574 IkReal x3682=((IkReal(2.94476514910275))*(cj5));
13575 IkReal x3683=((npx)*(sj4));
13576 IkReal x3684=((IkReal(2.34381456633434))*(sj5));
13577 IkReal x3685=((npy)*(sj4));
13578 IkReal x3686=((IkReal(2.94476514910275))*(sj5));
13579 IkReal x3687=((IkReal(2.34381456633434))*(cj5));
13580 if( IKabs(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(npx)*(x3686)))+(((IkReal(-1.00000000000000))*(npy)*(x3682)))+(((IkReal(-2.34381456633434))*(x3681)))+(((IkReal(-1.00000000000000))*(x3684)*(x3685)))+(((x3683)*(x3687))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(npx)*(x3684)))+(((IkReal(-1.00000000000000))*(npy)*(x3687)))+(((x3685)*(x3686)))+(((IkReal(-1.00000000000000))*(x3682)*(x3683)))+(((IkReal(2.94476514910275))*(x3681))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(npx)*(x3686)))+(((IkReal(-1.00000000000000))*(npy)*(x3682)))+(((IkReal(-2.34381456633434))*(x3681)))+(((IkReal(-1.00000000000000))*(x3684)*(x3685)))+(((x3683)*(x3687)))))+IKsqr(((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(npx)*(x3684)))+(((IkReal(-1.00000000000000))*(npy)*(x3687)))+(((x3685)*(x3686)))+(((IkReal(-1.00000000000000))*(x3682)*(x3683)))+(((IkReal(2.94476514910275))*(x3681)))))-1) <= IKFAST_SINCOS_THRESH )
13581     continue;
13582 j2array[0]=IKatan2(((IkReal(0.534026994013214))+(((IkReal(-1.00000000000000))*(npx)*(x3686)))+(((IkReal(-1.00000000000000))*(npy)*(x3682)))+(((IkReal(-2.34381456633434))*(x3681)))+(((IkReal(-1.00000000000000))*(x3684)*(x3685)))+(((x3683)*(x3687)))), ((IkReal(-0.816018998475795))+(((IkReal(-1.00000000000000))*(npx)*(x3684)))+(((IkReal(-1.00000000000000))*(npy)*(x3687)))+(((x3685)*(x3686)))+(((IkReal(-1.00000000000000))*(x3682)*(x3683)))+(((IkReal(2.94476514910275))*(x3681)))));
13583 sj2array[0]=IKsin(j2array[0]);
13584 cj2array[0]=IKcos(j2array[0]);
13585 if( j2array[0] > IKPI )
13586 {
13587     j2array[0]-=IK2PI;
13588 }
13589 else if( j2array[0] < -IKPI )
13590 {    j2array[0]+=IK2PI;
13591 }
13592 j2valid[0] = true;
13593 for(int ij2 = 0; ij2 < 1; ++ij2)
13594 {
13595 if( !j2valid[ij2] )
13596 {
13597     continue;
13598 }
13599 _ij2[0] = ij2; _ij2[1] = -1;
13600 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
13601 {
13602 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
13603 {
13604     j2valid[iij2]=false; _ij2[1] = iij2; break; 
13605 }
13606 }
13607 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
13608 {
13609 IkReal evalcond[2];
13610 IkReal x3688=IKcos(j2);
13611 IkReal x3689=IKsin(j2);
13612 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(x3688)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(x3689))));
13613 evalcond[1]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(x3689)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(x3688))));
13614 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13615 {
13616 continue;
13617 }
13618 }
13619 
13620 {
13621 IkReal dummyeval[1];
13622 IkReal gconst50;
13623 gconst50=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
13624 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
13625 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13626 {
13627 {
13628 IkReal dummyeval[1];
13629 IkReal gconst51;
13630 gconst51=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
13631 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
13632 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13633 {
13634 continue;
13635 
13636 } else
13637 {
13638 {
13639 IkReal j1array[1], cj1array[1], sj1array[1];
13640 bool j1valid[1]={false};
13641 _nj1 = 1;
13642 IkReal x3690=((cj5)*(r11));
13643 IkReal x3691=((r10)*(sj0));
13644 IkReal x3692=((IkReal(0.707103562373095))*(cj2));
13645 IkReal x3693=((r20)*(sj5));
13646 IkReal x3694=((IkReal(0.707103562373095))*(sj2));
13647 IkReal x3695=((IkReal(0.707109999985348))*(cj2));
13648 IkReal x3696=((cj0)*(r00));
13649 IkReal x3697=((IkReal(0.707109999985348))*(sj2));
13650 IkReal x3698=((cj5)*(r21));
13651 IkReal x3699=((sj0)*(x3694));
13652 IkReal x3700=((sj5)*(x3695));
13653 IkReal x3701=((cj0)*(cj5)*(r01));
13654 if( IKabs(((gconst51)*(((((sj0)*(x3690)*(x3695)))+(((x3696)*(x3700)))+(((x3695)*(x3701)))+(((sj5)*(x3694)*(x3696)))+(((x3692)*(x3698)))+(((x3692)*(x3693)))+(((IkReal(-1.00000000000000))*(x3697)*(x3698)))+(((x3694)*(x3701)))+(((x3690)*(x3699)))+(((x3691)*(x3700)))+(((IkReal(-1.00000000000000))*(x3693)*(x3697)))+(((sj5)*(x3691)*(x3694))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((sj0)*(x3690)*(x3697)))+(((IkReal(-1.00000000000000))*(x3692)*(x3701)))+(((x3695)*(x3698)))+(((x3697)*(x3701)))+(((IkReal(-1.00000000000000))*(sj0)*(x3690)*(x3692)))+(((x3694)*(x3698)))+(((IkReal(-1.00000000000000))*(sj5)*(x3692)*(x3696)))+(((x3693)*(x3694)))+(((x3693)*(x3695)))+(((IkReal(-1.00000000000000))*(sj5)*(x3691)*(x3692)))+(((sj5)*(x3696)*(x3697)))+(((sj5)*(x3691)*(x3697))))))) < IKFAST_ATAN2_MAGTHRESH )
13655     continue;
13656 j1array[0]=IKatan2(((gconst51)*(((((sj0)*(x3690)*(x3695)))+(((x3696)*(x3700)))+(((x3695)*(x3701)))+(((sj5)*(x3694)*(x3696)))+(((x3692)*(x3698)))+(((x3692)*(x3693)))+(((IkReal(-1.00000000000000))*(x3697)*(x3698)))+(((x3694)*(x3701)))+(((x3690)*(x3699)))+(((x3691)*(x3700)))+(((IkReal(-1.00000000000000))*(x3693)*(x3697)))+(((sj5)*(x3691)*(x3694)))))), ((gconst51)*(((((sj0)*(x3690)*(x3697)))+(((IkReal(-1.00000000000000))*(x3692)*(x3701)))+(((x3695)*(x3698)))+(((x3697)*(x3701)))+(((IkReal(-1.00000000000000))*(sj0)*(x3690)*(x3692)))+(((x3694)*(x3698)))+(((IkReal(-1.00000000000000))*(sj5)*(x3692)*(x3696)))+(((x3693)*(x3694)))+(((x3693)*(x3695)))+(((IkReal(-1.00000000000000))*(sj5)*(x3691)*(x3692)))+(((sj5)*(x3696)*(x3697)))+(((sj5)*(x3691)*(x3697)))))));
13657 sj1array[0]=IKsin(j1array[0]);
13658 cj1array[0]=IKcos(j1array[0]);
13659 if( j1array[0] > IKPI )
13660 {
13661     j1array[0]-=IK2PI;
13662 }
13663 else if( j1array[0] < -IKPI )
13664 {    j1array[0]+=IK2PI;
13665 }
13666 j1valid[0] = true;
13667 for(int ij1 = 0; ij1 < 1; ++ij1)
13668 {
13669 if( !j1valid[ij1] )
13670 {
13671     continue;
13672 }
13673 _ij1[0] = ij1; _ij1[1] = -1;
13674 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13675 {
13676 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13677 {
13678     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13679 }
13680 }
13681 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13682 {
13683 IkReal evalcond[4];
13684 IkReal x3702=IKcos(j1);
13685 IkReal x3703=IKsin(j1);
13686 IkReal x3704=((IkReal(0.707109999985348))*(cj2));
13687 IkReal x3705=((IkReal(1.00000000000000))*(cj0));
13688 IkReal x3706=((IkReal(0.707109999985348))*(sj2));
13689 IkReal x3707=((cj5)*(sj4));
13690 IkReal x3708=((sj4)*(sj5));
13691 IkReal x3709=((IkReal(1.00000000000000))*(sj0));
13692 IkReal x3710=((sj5)*(x3709));
13693 IkReal x3711=((IkReal(0.707103562373095))*(x3702));
13694 IkReal x3712=((IkReal(0.707103562373095))*(x3703));
13695 IkReal x3713=((cj2)*(x3711));
13696 IkReal x3714=((x3703)*(x3704));
13697 IkReal x3715=((sj2)*(x3712));
13698 IkReal x3716=((x3702)*(x3706));
13699 IkReal x3717=((sj2)*(x3711));
13700 IkReal x3718=((cj2)*(x3712));
13701 IkReal x3719=((x3702)*(x3704));
13702 IkReal x3720=((x3703)*(x3706));
13703 IkReal x3721=((x3717)+(x3719)+(x3718));
13704 IkReal x3722=((x3715)+(x3714)+(x3716));
13705 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3720)))+(x3721)+(((r20)*(sj5))));
13706 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3707)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3713)))+(((r21)*(x3708)))+(x3722));
13707 evalcond[2]=((((IkReal(-1.00000000000000))*(x3722)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3705)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3705)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3709)))+(((IkReal(-1.00000000000000))*(r10)*(x3710)))+(x3713));
13708 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x3708)*(x3709)))+(((IkReal(-1.00000000000000))*(x3720)))+(((cj0)*(r00)*(x3707)))+(x3721)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3705)))+(((IkReal(-1.00000000000000))*(r01)*(x3705)*(x3708)))+(((r10)*(sj0)*(x3707)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3709))));
13709 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13710 {
13711 continue;
13712 }
13713 }
13714 
13715 {
13716 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13717 vinfos[0].jointtype = 1;
13718 vinfos[0].foffset = j0;
13719 vinfos[0].indices[0] = _ij0[0];
13720 vinfos[0].indices[1] = _ij0[1];
13721 vinfos[0].maxsolutions = _nj0;
13722 vinfos[1].jointtype = 1;
13723 vinfos[1].foffset = j1;
13724 vinfos[1].indices[0] = _ij1[0];
13725 vinfos[1].indices[1] = _ij1[1];
13726 vinfos[1].maxsolutions = _nj1;
13727 vinfos[2].jointtype = 1;
13728 vinfos[2].foffset = j2;
13729 vinfos[2].indices[0] = _ij2[0];
13730 vinfos[2].indices[1] = _ij2[1];
13731 vinfos[2].maxsolutions = _nj2;
13732 vinfos[3].jointtype = 1;
13733 vinfos[3].foffset = j3;
13734 vinfos[3].indices[0] = _ij3[0];
13735 vinfos[3].indices[1] = _ij3[1];
13736 vinfos[3].maxsolutions = _nj3;
13737 vinfos[4].jointtype = 1;
13738 vinfos[4].foffset = j4;
13739 vinfos[4].indices[0] = _ij4[0];
13740 vinfos[4].indices[1] = _ij4[1];
13741 vinfos[4].maxsolutions = _nj4;
13742 vinfos[5].jointtype = 1;
13743 vinfos[5].foffset = j5;
13744 vinfos[5].indices[0] = _ij5[0];
13745 vinfos[5].indices[1] = _ij5[1];
13746 vinfos[5].maxsolutions = _nj5;
13747 std::vector<int> vfree(0);
13748 solutions.AddSolution(vinfos,vfree);
13749 }
13750 }
13751 }
13752 
13753 }
13754 
13755 }
13756 
13757 } else
13758 {
13759 {
13760 IkReal j1array[1], cj1array[1], sj1array[1];
13761 bool j1valid[1]={false};
13762 _nj1 = 1;
13763 IkReal x3723=((cj5)*(sj4));
13764 IkReal x3724=((r21)*(sj4));
13765 IkReal x3725=((cj5)*(r21));
13766 IkReal x3726=((IkReal(0.707109999985348))*(cj2));
13767 IkReal x3727=((IkReal(0.707103562373095))*(sj2));
13768 IkReal x3728=((IkReal(0.707109999985348))*(sj2));
13769 IkReal x3729=((cj4)*(r22));
13770 IkReal x3730=((IkReal(0.707103562373095))*(cj2));
13771 IkReal x3731=((r20)*(x3726));
13772 IkReal x3732=((sj5)*(x3730));
13773 IkReal x3733=((sj5)*(x3728));
13774 if( IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x3727)*(x3729)))+(((IkReal(-1.00000000000000))*(x3725)*(x3730)))+(((x3725)*(x3728)))+(((IkReal(-1.00000000000000))*(x3726)*(x3729)))+(((IkReal(-1.00000000000000))*(r20)*(x3732)))+(((x3723)*(x3731)))+(((IkReal(-1.00000000000000))*(sj5)*(x3724)*(x3727)))+(((IkReal(-1.00000000000000))*(sj5)*(x3724)*(x3726)))+(((r20)*(x3723)*(x3727)))+(((r20)*(x3733))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((x3729)*(x3730)))+(((IkReal(-1.00000000000000))*(r20)*(x3723)*(x3730)))+(((IkReal(-1.00000000000000))*(x3725)*(x3726)))+(((IkReal(-1.00000000000000))*(x3725)*(x3727)))+(((IkReal(-1.00000000000000))*(x3724)*(x3733)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3727)))+(((x3724)*(x3732)))+(((IkReal(-1.00000000000000))*(sj5)*(x3731)))+(((r20)*(x3723)*(x3728)))+(((IkReal(-1.00000000000000))*(x3728)*(x3729))))))) < IKFAST_ATAN2_MAGTHRESH )
13775     continue;
13776 j1array[0]=IKatan2(((gconst50)*(((((IkReal(-1.00000000000000))*(x3727)*(x3729)))+(((IkReal(-1.00000000000000))*(x3725)*(x3730)))+(((x3725)*(x3728)))+(((IkReal(-1.00000000000000))*(x3726)*(x3729)))+(((IkReal(-1.00000000000000))*(r20)*(x3732)))+(((x3723)*(x3731)))+(((IkReal(-1.00000000000000))*(sj5)*(x3724)*(x3727)))+(((IkReal(-1.00000000000000))*(sj5)*(x3724)*(x3726)))+(((r20)*(x3723)*(x3727)))+(((r20)*(x3733)))))), ((gconst50)*(((((x3729)*(x3730)))+(((IkReal(-1.00000000000000))*(r20)*(x3723)*(x3730)))+(((IkReal(-1.00000000000000))*(x3725)*(x3726)))+(((IkReal(-1.00000000000000))*(x3725)*(x3727)))+(((IkReal(-1.00000000000000))*(x3724)*(x3733)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3727)))+(((x3724)*(x3732)))+(((IkReal(-1.00000000000000))*(sj5)*(x3731)))+(((r20)*(x3723)*(x3728)))+(((IkReal(-1.00000000000000))*(x3728)*(x3729)))))));
13777 sj1array[0]=IKsin(j1array[0]);
13778 cj1array[0]=IKcos(j1array[0]);
13779 if( j1array[0] > IKPI )
13780 {
13781     j1array[0]-=IK2PI;
13782 }
13783 else if( j1array[0] < -IKPI )
13784 {    j1array[0]+=IK2PI;
13785 }
13786 j1valid[0] = true;
13787 for(int ij1 = 0; ij1 < 1; ++ij1)
13788 {
13789 if( !j1valid[ij1] )
13790 {
13791     continue;
13792 }
13793 _ij1[0] = ij1; _ij1[1] = -1;
13794 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
13795 {
13796 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
13797 {
13798     j1valid[iij1]=false; _ij1[1] = iij1; break; 
13799 }
13800 }
13801 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
13802 {
13803 IkReal evalcond[4];
13804 IkReal x3734=IKcos(j1);
13805 IkReal x3735=IKsin(j1);
13806 IkReal x3736=((IkReal(0.707109999985348))*(cj2));
13807 IkReal x3737=((IkReal(1.00000000000000))*(cj0));
13808 IkReal x3738=((IkReal(0.707109999985348))*(sj2));
13809 IkReal x3739=((cj5)*(sj4));
13810 IkReal x3740=((sj4)*(sj5));
13811 IkReal x3741=((IkReal(1.00000000000000))*(sj0));
13812 IkReal x3742=((sj5)*(x3741));
13813 IkReal x3743=((IkReal(0.707103562373095))*(x3734));
13814 IkReal x3744=((IkReal(0.707103562373095))*(x3735));
13815 IkReal x3745=((cj2)*(x3743));
13816 IkReal x3746=((x3735)*(x3736));
13817 IkReal x3747=((sj2)*(x3744));
13818 IkReal x3748=((x3734)*(x3738));
13819 IkReal x3749=((sj2)*(x3743));
13820 IkReal x3750=((cj2)*(x3744));
13821 IkReal x3751=((x3734)*(x3736));
13822 IkReal x3752=((x3735)*(x3738));
13823 IkReal x3753=((x3749)+(x3751)+(x3750));
13824 IkReal x3754=((x3748)+(x3746)+(x3747));
13825 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3752)))+(x3753)+(((r20)*(sj5))));
13826 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3739)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3745)))+(x3754)+(((r21)*(x3740))));
13827 evalcond[2]=((((IkReal(-1.00000000000000))*(x3754)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3737)))+(x3745)+(((IkReal(-1.00000000000000))*(r10)*(x3742)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3741)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3737))));
13828 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3737)*(x3740)))+(((IkReal(-1.00000000000000))*(r11)*(x3740)*(x3741)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3737)))+(((r10)*(sj0)*(x3739)))+(((IkReal(-1.00000000000000))*(x3752)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3741)))+(x3753)+(((cj0)*(r00)*(x3739))));
13829 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13830 {
13831 continue;
13832 }
13833 }
13834 
13835 {
13836 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13837 vinfos[0].jointtype = 1;
13838 vinfos[0].foffset = j0;
13839 vinfos[0].indices[0] = _ij0[0];
13840 vinfos[0].indices[1] = _ij0[1];
13841 vinfos[0].maxsolutions = _nj0;
13842 vinfos[1].jointtype = 1;
13843 vinfos[1].foffset = j1;
13844 vinfos[1].indices[0] = _ij1[0];
13845 vinfos[1].indices[1] = _ij1[1];
13846 vinfos[1].maxsolutions = _nj1;
13847 vinfos[2].jointtype = 1;
13848 vinfos[2].foffset = j2;
13849 vinfos[2].indices[0] = _ij2[0];
13850 vinfos[2].indices[1] = _ij2[1];
13851 vinfos[2].maxsolutions = _nj2;
13852 vinfos[3].jointtype = 1;
13853 vinfos[3].foffset = j3;
13854 vinfos[3].indices[0] = _ij3[0];
13855 vinfos[3].indices[1] = _ij3[1];
13856 vinfos[3].maxsolutions = _nj3;
13857 vinfos[4].jointtype = 1;
13858 vinfos[4].foffset = j4;
13859 vinfos[4].indices[0] = _ij4[0];
13860 vinfos[4].indices[1] = _ij4[1];
13861 vinfos[4].maxsolutions = _nj4;
13862 vinfos[5].jointtype = 1;
13863 vinfos[5].foffset = j5;
13864 vinfos[5].indices[0] = _ij5[0];
13865 vinfos[5].indices[1] = _ij5[1];
13866 vinfos[5].maxsolutions = _nj5;
13867 std::vector<int> vfree(0);
13868 solutions.AddSolution(vinfos,vfree);
13869 }
13870 }
13871 }
13872 
13873 }
13874 
13875 }
13876 }
13877 }
13878 
13879 } else
13880 {
13881 IkReal x3755=((sj0)*(sj4));
13882 IkReal x3756=((IkReal(1.00000000000000))*(r12));
13883 IkReal x3757=((IkReal(1.00000000000000))*(cj0));
13884 IkReal x3758=((cj4)*(cj5));
13885 IkReal x3759=((r11)*(sj5));
13886 IkReal x3760=((cj4)*(sj0));
13887 IkReal x3761=((IkReal(1.00000000000000))*(sj5));
13888 IkReal x3762=((cj0)*(cj4));
13889 IkReal x3763=((r00)*(sj0));
13890 IkReal x3764=((cj0)*(sj4));
13891 IkReal x3765=((r01)*(sj5));
13892 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
13893 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x3763)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3757)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3757))));
13894 evalcond[2]=((IkReal(0.00600000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x3761)))+(((npz)*(sj4)))+(((npx)*(x3758))));
13895 evalcond[3]=((((r02)*(x3760)))+(((IkReal(-1.00000000000000))*(sj4)*(x3757)*(x3759)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x3755)))+(((cj5)*(r10)*(x3764)))+(((IkReal(-1.00000000000000))*(x3756)*(x3762)))+(((x3755)*(x3765))));
13896 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3757)*(x3758)))+(((x3758)*(x3763)))+(((r02)*(x3755)))+(((x3759)*(x3762)))+(((IkReal(-1.00000000000000))*(x3756)*(x3764)))+(((IkReal(-1.00000000000000))*(r01)*(x3760)*(x3761))));
13897 evalcond[5]=((((r20)*(x3758)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x3761))));
13898 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3757)))+(((IkReal(-1.00000000000000))*(x3755)*(x3756)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x3758)))+(((IkReal(-1.00000000000000))*(r00)*(x3757)*(x3758)))+(((x3759)*(x3760)))+(((x3762)*(x3765))));
13899 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  )
13900 {
13901 {
13902 IkReal j2array[1], cj2array[1], sj2array[1];
13903 bool j2valid[1]={false};
13904 _nj2 = 1;
13905 IkReal x3766=((cj4)*(npz));
13906 IkReal x3767=((IkReal(2.94476514910275))*(cj5));
13907 IkReal x3768=((npx)*(sj4));
13908 IkReal x3769=((IkReal(2.34381456633434))*(sj5));
13909 IkReal x3770=((npy)*(sj4));
13910 IkReal x3771=((IkReal(2.94476514910275))*(sj5));
13911 IkReal x3772=((IkReal(2.34381456633434))*(cj5));
13912 if( IKabs(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x3766)))+(((x3768)*(x3772)))+(((IkReal(-1.00000000000000))*(npy)*(x3767)))+(((IkReal(-1.00000000000000))*(npx)*(x3771)))+(((IkReal(-1.00000000000000))*(x3769)*(x3770))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x3766)))+(((IkReal(-1.00000000000000))*(x3767)*(x3768)))+(((x3770)*(x3771)))+(((IkReal(-1.00000000000000))*(npy)*(x3772)))+(((IkReal(-1.00000000000000))*(npx)*(x3769))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x3766)))+(((x3768)*(x3772)))+(((IkReal(-1.00000000000000))*(npy)*(x3767)))+(((IkReal(-1.00000000000000))*(npx)*(x3771)))+(((IkReal(-1.00000000000000))*(x3769)*(x3770)))))+IKsqr(((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x3766)))+(((IkReal(-1.00000000000000))*(x3767)*(x3768)))+(((x3770)*(x3771)))+(((IkReal(-1.00000000000000))*(npy)*(x3772)))+(((IkReal(-1.00000000000000))*(npx)*(x3769)))))-1) <= IKFAST_SINCOS_THRESH )
13913     continue;
13914 j2array[0]=IKatan2(((IkReal(0.534026994013214))+(((IkReal(-2.34381456633434))*(x3766)))+(((x3768)*(x3772)))+(((IkReal(-1.00000000000000))*(npy)*(x3767)))+(((IkReal(-1.00000000000000))*(npx)*(x3771)))+(((IkReal(-1.00000000000000))*(x3769)*(x3770)))), ((IkReal(-0.816018998475795))+(((IkReal(2.94476514910275))*(x3766)))+(((IkReal(-1.00000000000000))*(x3767)*(x3768)))+(((x3770)*(x3771)))+(((IkReal(-1.00000000000000))*(npy)*(x3772)))+(((IkReal(-1.00000000000000))*(npx)*(x3769)))));
13915 sj2array[0]=IKsin(j2array[0]);
13916 cj2array[0]=IKcos(j2array[0]);
13917 if( j2array[0] > IKPI )
13918 {
13919     j2array[0]-=IK2PI;
13920 }
13921 else if( j2array[0] < -IKPI )
13922 {    j2array[0]+=IK2PI;
13923 }
13924 j2valid[0] = true;
13925 for(int ij2 = 0; ij2 < 1; ++ij2)
13926 {
13927 if( !j2valid[ij2] )
13928 {
13929     continue;
13930 }
13931 _ij2[0] = ij2; _ij2[1] = -1;
13932 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
13933 {
13934 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
13935 {
13936     j2valid[iij2]=false; _ij2[1] = iij2; break; 
13937 }
13938 }
13939 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
13940 {
13941 IkReal evalcond[2];
13942 IkReal x3773=IKcos(j2);
13943 IkReal x3774=IKsin(j2);
13944 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(sj4)))+(((IkReal(0.165463933124939))*(x3774)))+(((npy)*(sj4)*(sj5)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x3773))));
13945 evalcond[1]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(x3774)))+(((IkReal(0.165463933124939))*(x3773)))+(((cj5)*(npy))));
13946 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13947 {
13948 continue;
13949 }
13950 }
13951 
13952 {
13953 IkReal dummyeval[1];
13954 IkReal gconst52;
13955 gconst52=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
13956 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
13957 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13958 {
13959 {
13960 IkReal dummyeval[1];
13961 IkReal gconst53;
13962 gconst53=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
13963 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
13964 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13965 {
13966 continue;
13967 
13968 } else
13969 {
13970 {
13971 IkReal j1array[1], cj1array[1], sj1array[1];
13972 bool j1valid[1]={false};
13973 _nj1 = 1;
13974 IkReal x3775=((cj5)*(r11));
13975 IkReal x3776=((r10)*(sj0));
13976 IkReal x3777=((IkReal(0.707103562373095))*(cj2));
13977 IkReal x3778=((r20)*(sj5));
13978 IkReal x3779=((IkReal(0.707103562373095))*(sj2));
13979 IkReal x3780=((IkReal(0.707109999985348))*(cj2));
13980 IkReal x3781=((cj0)*(r00));
13981 IkReal x3782=((IkReal(0.707109999985348))*(sj2));
13982 IkReal x3783=((cj5)*(r21));
13983 IkReal x3784=((sj0)*(x3779));
13984 IkReal x3785=((sj5)*(x3780));
13985 IkReal x3786=((cj0)*(cj5)*(r01));
13986 if( IKabs(((gconst53)*(((((x3777)*(x3778)))+(((IkReal(-1.00000000000000))*(x3778)*(x3782)))+(((IkReal(-1.00000000000000))*(x3782)*(x3783)))+(((x3775)*(x3784)))+(((x3779)*(x3786)))+(((sj5)*(x3779)*(x3781)))+(((x3776)*(x3785)))+(((sj0)*(x3775)*(x3780)))+(((x3777)*(x3783)))+(((sj5)*(x3776)*(x3779)))+(((x3781)*(x3785)))+(((x3780)*(x3786))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(sj5)*(x3776)*(x3777)))+(((IkReal(-1.00000000000000))*(x3777)*(x3786)))+(((sj5)*(x3781)*(x3782)))+(((x3782)*(x3786)))+(((x3778)*(x3779)))+(((x3778)*(x3780)))+(((x3779)*(x3783)))+(((sj0)*(x3775)*(x3782)))+(((IkReal(-1.00000000000000))*(sj0)*(x3775)*(x3777)))+(((IkReal(-1.00000000000000))*(sj5)*(x3777)*(x3781)))+(((x3780)*(x3783)))+(((sj5)*(x3776)*(x3782))))))) < IKFAST_ATAN2_MAGTHRESH )
13987     continue;
13988 j1array[0]=IKatan2(((gconst53)*(((((x3777)*(x3778)))+(((IkReal(-1.00000000000000))*(x3778)*(x3782)))+(((IkReal(-1.00000000000000))*(x3782)*(x3783)))+(((x3775)*(x3784)))+(((x3779)*(x3786)))+(((sj5)*(x3779)*(x3781)))+(((x3776)*(x3785)))+(((sj0)*(x3775)*(x3780)))+(((x3777)*(x3783)))+(((sj5)*(x3776)*(x3779)))+(((x3781)*(x3785)))+(((x3780)*(x3786)))))), ((gconst53)*(((((IkReal(-1.00000000000000))*(sj5)*(x3776)*(x3777)))+(((IkReal(-1.00000000000000))*(x3777)*(x3786)))+(((sj5)*(x3781)*(x3782)))+(((x3782)*(x3786)))+(((x3778)*(x3779)))+(((x3778)*(x3780)))+(((x3779)*(x3783)))+(((sj0)*(x3775)*(x3782)))+(((IkReal(-1.00000000000000))*(sj0)*(x3775)*(x3777)))+(((IkReal(-1.00000000000000))*(sj5)*(x3777)*(x3781)))+(((x3780)*(x3783)))+(((sj5)*(x3776)*(x3782)))))));
13989 sj1array[0]=IKsin(j1array[0]);
13990 cj1array[0]=IKcos(j1array[0]);
13991 if( j1array[0] > IKPI )
13992 {
13993     j1array[0]-=IK2PI;
13994 }
13995 else if( j1array[0] < -IKPI )
13996 {    j1array[0]+=IK2PI;
13997 }
13998 j1valid[0] = true;
13999 for(int ij1 = 0; ij1 < 1; ++ij1)
14000 {
14001 if( !j1valid[ij1] )
14002 {
14003     continue;
14004 }
14005 _ij1[0] = ij1; _ij1[1] = -1;
14006 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14007 {
14008 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14009 {
14010     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14011 }
14012 }
14013 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14014 {
14015 IkReal evalcond[4];
14016 IkReal x3787=IKcos(j1);
14017 IkReal x3788=IKsin(j1);
14018 IkReal x3789=((IkReal(0.707109999985348))*(cj2));
14019 IkReal x3790=((IkReal(1.00000000000000))*(cj0));
14020 IkReal x3791=((IkReal(0.707109999985348))*(sj2));
14021 IkReal x3792=((cj5)*(sj4));
14022 IkReal x3793=((sj4)*(sj5));
14023 IkReal x3794=((IkReal(1.00000000000000))*(sj0));
14024 IkReal x3795=((sj5)*(x3794));
14025 IkReal x3796=((IkReal(0.707103562373095))*(x3787));
14026 IkReal x3797=((IkReal(0.707103562373095))*(x3788));
14027 IkReal x3798=((cj2)*(x3796));
14028 IkReal x3799=((x3788)*(x3789));
14029 IkReal x3800=((sj2)*(x3797));
14030 IkReal x3801=((x3787)*(x3791));
14031 IkReal x3802=((sj2)*(x3796));
14032 IkReal x3803=((cj2)*(x3797));
14033 IkReal x3804=((x3787)*(x3789));
14034 IkReal x3805=((x3788)*(x3791));
14035 IkReal x3806=((x3804)+(x3803)+(x3802));
14036 IkReal x3807=((x3799)+(x3801)+(x3800));
14037 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x3805)))+(x3806)+(((r20)*(sj5))));
14038 evalcond[1]=((((IkReal(-1.00000000000000))*(x3798)))+(((r21)*(x3793)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x3792)))+(x3807));
14039 evalcond[2]=((((IkReal(-1.00000000000000))*(x3807)))+(x3798)+(((IkReal(-1.00000000000000))*(r10)*(x3795)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3790)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3790)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3794))));
14040 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3790)))+(((r10)*(sj0)*(x3792)))+(((IkReal(-1.00000000000000))*(x3805)))+(x3806)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3794)))+(((cj0)*(r00)*(x3792)))+(((IkReal(-1.00000000000000))*(r11)*(x3793)*(x3794)))+(((IkReal(-1.00000000000000))*(r01)*(x3790)*(x3793))));
14041 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14042 {
14043 continue;
14044 }
14045 }
14046 
14047 {
14048 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14049 vinfos[0].jointtype = 1;
14050 vinfos[0].foffset = j0;
14051 vinfos[0].indices[0] = _ij0[0];
14052 vinfos[0].indices[1] = _ij0[1];
14053 vinfos[0].maxsolutions = _nj0;
14054 vinfos[1].jointtype = 1;
14055 vinfos[1].foffset = j1;
14056 vinfos[1].indices[0] = _ij1[0];
14057 vinfos[1].indices[1] = _ij1[1];
14058 vinfos[1].maxsolutions = _nj1;
14059 vinfos[2].jointtype = 1;
14060 vinfos[2].foffset = j2;
14061 vinfos[2].indices[0] = _ij2[0];
14062 vinfos[2].indices[1] = _ij2[1];
14063 vinfos[2].maxsolutions = _nj2;
14064 vinfos[3].jointtype = 1;
14065 vinfos[3].foffset = j3;
14066 vinfos[3].indices[0] = _ij3[0];
14067 vinfos[3].indices[1] = _ij3[1];
14068 vinfos[3].maxsolutions = _nj3;
14069 vinfos[4].jointtype = 1;
14070 vinfos[4].foffset = j4;
14071 vinfos[4].indices[0] = _ij4[0];
14072 vinfos[4].indices[1] = _ij4[1];
14073 vinfos[4].maxsolutions = _nj4;
14074 vinfos[5].jointtype = 1;
14075 vinfos[5].foffset = j5;
14076 vinfos[5].indices[0] = _ij5[0];
14077 vinfos[5].indices[1] = _ij5[1];
14078 vinfos[5].maxsolutions = _nj5;
14079 std::vector<int> vfree(0);
14080 solutions.AddSolution(vinfos,vfree);
14081 }
14082 }
14083 }
14084 
14085 }
14086 
14087 }
14088 
14089 } else
14090 {
14091 {
14092 IkReal j1array[1], cj1array[1], sj1array[1];
14093 bool j1valid[1]={false};
14094 _nj1 = 1;
14095 IkReal x3808=((cj5)*(sj4));
14096 IkReal x3809=((r21)*(sj4));
14097 IkReal x3810=((cj5)*(r21));
14098 IkReal x3811=((IkReal(0.707109999985348))*(cj2));
14099 IkReal x3812=((IkReal(0.707103562373095))*(sj2));
14100 IkReal x3813=((IkReal(0.707109999985348))*(sj2));
14101 IkReal x3814=((cj4)*(r22));
14102 IkReal x3815=((IkReal(0.707103562373095))*(cj2));
14103 IkReal x3816=((r20)*(x3811));
14104 IkReal x3817=((sj5)*(x3815));
14105 IkReal x3818=((sj5)*(x3813));
14106 if( IKabs(((gconst52)*(((((x3810)*(x3813)))+(((r20)*(x3808)*(x3812)))+(((IkReal(-1.00000000000000))*(x3810)*(x3815)))+(((IkReal(-1.00000000000000))*(x3812)*(x3814)))+(((IkReal(-1.00000000000000))*(x3811)*(x3814)))+(((x3808)*(x3816)))+(((IkReal(-1.00000000000000))*(r20)*(x3817)))+(((r20)*(x3818)))+(((IkReal(-1.00000000000000))*(sj5)*(x3809)*(x3812)))+(((IkReal(-1.00000000000000))*(sj5)*(x3809)*(x3811))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(sj5)*(x3816)))+(((r20)*(x3808)*(x3813)))+(((IkReal(-1.00000000000000))*(x3810)*(x3811)))+(((IkReal(-1.00000000000000))*(x3810)*(x3812)))+(((IkReal(-1.00000000000000))*(x3813)*(x3814)))+(((IkReal(-1.00000000000000))*(x3809)*(x3818)))+(((x3809)*(x3817)))+(((x3814)*(x3815)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3812)))+(((IkReal(-1.00000000000000))*(r20)*(x3808)*(x3815))))))) < IKFAST_ATAN2_MAGTHRESH )
14107     continue;
14108 j1array[0]=IKatan2(((gconst52)*(((((x3810)*(x3813)))+(((r20)*(x3808)*(x3812)))+(((IkReal(-1.00000000000000))*(x3810)*(x3815)))+(((IkReal(-1.00000000000000))*(x3812)*(x3814)))+(((IkReal(-1.00000000000000))*(x3811)*(x3814)))+(((x3808)*(x3816)))+(((IkReal(-1.00000000000000))*(r20)*(x3817)))+(((r20)*(x3818)))+(((IkReal(-1.00000000000000))*(sj5)*(x3809)*(x3812)))+(((IkReal(-1.00000000000000))*(sj5)*(x3809)*(x3811)))))), ((gconst52)*(((((IkReal(-1.00000000000000))*(sj5)*(x3816)))+(((r20)*(x3808)*(x3813)))+(((IkReal(-1.00000000000000))*(x3810)*(x3811)))+(((IkReal(-1.00000000000000))*(x3810)*(x3812)))+(((IkReal(-1.00000000000000))*(x3813)*(x3814)))+(((IkReal(-1.00000000000000))*(x3809)*(x3818)))+(((x3809)*(x3817)))+(((x3814)*(x3815)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3812)))+(((IkReal(-1.00000000000000))*(r20)*(x3808)*(x3815)))))));
14109 sj1array[0]=IKsin(j1array[0]);
14110 cj1array[0]=IKcos(j1array[0]);
14111 if( j1array[0] > IKPI )
14112 {
14113     j1array[0]-=IK2PI;
14114 }
14115 else if( j1array[0] < -IKPI )
14116 {    j1array[0]+=IK2PI;
14117 }
14118 j1valid[0] = true;
14119 for(int ij1 = 0; ij1 < 1; ++ij1)
14120 {
14121 if( !j1valid[ij1] )
14122 {
14123     continue;
14124 }
14125 _ij1[0] = ij1; _ij1[1] = -1;
14126 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14127 {
14128 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14129 {
14130     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14131 }
14132 }
14133 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14134 {
14135 IkReal evalcond[4];
14136 IkReal x3819=IKcos(j1);
14137 IkReal x3820=IKsin(j1);
14138 IkReal x3821=((IkReal(0.707109999985348))*(cj2));
14139 IkReal x3822=((IkReal(1.00000000000000))*(cj0));
14140 IkReal x3823=((IkReal(0.707109999985348))*(sj2));
14141 IkReal x3824=((cj5)*(sj4));
14142 IkReal x3825=((sj4)*(sj5));
14143 IkReal x3826=((IkReal(1.00000000000000))*(sj0));
14144 IkReal x3827=((sj5)*(x3826));
14145 IkReal x3828=((IkReal(0.707103562373095))*(x3819));
14146 IkReal x3829=((IkReal(0.707103562373095))*(x3820));
14147 IkReal x3830=((cj2)*(x3828));
14148 IkReal x3831=((x3820)*(x3821));
14149 IkReal x3832=((sj2)*(x3829));
14150 IkReal x3833=((x3819)*(x3823));
14151 IkReal x3834=((sj2)*(x3828));
14152 IkReal x3835=((cj2)*(x3829));
14153 IkReal x3836=((x3819)*(x3821));
14154 IkReal x3837=((x3820)*(x3823));
14155 IkReal x3838=((x3834)+(x3835)+(x3836));
14156 IkReal x3839=((x3831)+(x3832)+(x3833));
14157 evalcond[0]=((((cj5)*(r21)))+(x3838)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x3837))));
14158 evalcond[1]=((((cj4)*(r22)))+(x3839)+(((IkReal(-1.00000000000000))*(x3830)))+(((IkReal(-1.00000000000000))*(r20)*(x3824)))+(((r21)*(x3825))));
14159 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3826)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3822)))+(x3830)+(((IkReal(-1.00000000000000))*(r10)*(x3827)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3822)))+(((IkReal(-1.00000000000000))*(x3839))));
14160 evalcond[3]=((((cj0)*(r00)*(x3824)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3826)))+(((r10)*(sj0)*(x3824)))+(x3838)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3822)))+(((IkReal(-1.00000000000000))*(r11)*(x3825)*(x3826)))+(((IkReal(-1.00000000000000))*(r01)*(x3822)*(x3825)))+(((IkReal(-1.00000000000000))*(x3837))));
14161 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14162 {
14163 continue;
14164 }
14165 }
14166 
14167 {
14168 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14169 vinfos[0].jointtype = 1;
14170 vinfos[0].foffset = j0;
14171 vinfos[0].indices[0] = _ij0[0];
14172 vinfos[0].indices[1] = _ij0[1];
14173 vinfos[0].maxsolutions = _nj0;
14174 vinfos[1].jointtype = 1;
14175 vinfos[1].foffset = j1;
14176 vinfos[1].indices[0] = _ij1[0];
14177 vinfos[1].indices[1] = _ij1[1];
14178 vinfos[1].maxsolutions = _nj1;
14179 vinfos[2].jointtype = 1;
14180 vinfos[2].foffset = j2;
14181 vinfos[2].indices[0] = _ij2[0];
14182 vinfos[2].indices[1] = _ij2[1];
14183 vinfos[2].maxsolutions = _nj2;
14184 vinfos[3].jointtype = 1;
14185 vinfos[3].foffset = j3;
14186 vinfos[3].indices[0] = _ij3[0];
14187 vinfos[3].indices[1] = _ij3[1];
14188 vinfos[3].maxsolutions = _nj3;
14189 vinfos[4].jointtype = 1;
14190 vinfos[4].foffset = j4;
14191 vinfos[4].indices[0] = _ij4[0];
14192 vinfos[4].indices[1] = _ij4[1];
14193 vinfos[4].maxsolutions = _nj4;
14194 vinfos[5].jointtype = 1;
14195 vinfos[5].foffset = j5;
14196 vinfos[5].indices[0] = _ij5[0];
14197 vinfos[5].indices[1] = _ij5[1];
14198 vinfos[5].maxsolutions = _nj5;
14199 std::vector<int> vfree(0);
14200 solutions.AddSolution(vinfos,vfree);
14201 }
14202 }
14203 }
14204 
14205 }
14206 
14207 }
14208 }
14209 }
14210 
14211 } else
14212 {
14213 if( 1 )
14214 {
14215 continue;
14216 
14217 } else
14218 {
14219 }
14220 }
14221 }
14222 }
14223 }
14224 }
14225 
14226 } else
14227 {
14228 {
14229 IkReal j2array[1], cj2array[1], sj2array[1];
14230 bool j2valid[1]={false};
14231 _nj2 = 1;
14232 IkReal x3840=((cj5)*(npx));
14233 IkReal x3841=((IkReal(8.66210554726807e+23))*(cj4));
14234 IkReal x3842=((npz)*(sj4));
14235 IkReal x3843=((IkReal(6.89439331452234e+23))*(cj3));
14236 IkReal x3844=((npy)*(sj5));
14237 IkReal x3845=((IkReal(6.89439331452234e+23))*(cj4));
14238 IkReal x3846=((IkReal(8.66210554726807e+23))*(cj3)*(sj4));
14239 if( IKabs(((gconst35)*(((((IkReal(5.19726332836084e+21))*(sj3)))+(((IkReal(-8.66210554726807e+23))*(x3842)))+(((x3841)*(x3844)))+(((IkReal(-1.00000000000000))*(sj4)*(x3843)*(x3844)))+(((IkReal(-1.00000000000000))*(x3840)*(x3841)))+(((sj4)*(x3840)*(x3843)))+(((IkReal(-1.00000000000000))*(cj4)*(npz)*(x3843)))+(((IkReal(1.51888207091656e+23))*(cj3))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((cj3)*(npz)*(x3841)))+(((IkReal(-2.44170809699545e+23))*(cj3)))+(((IkReal(-1.00000000000000))*(x3840)*(x3845)))+(((IkReal(-1.00000000000000))*(x3840)*(x3846)))+(((x3844)*(x3845)))+(((x3844)*(x3846)))+(((IkReal(4.13663598871341e+21))*(sj3)))+(((IkReal(-6.89439331452234e+23))*(x3842))))))) < IKFAST_ATAN2_MAGTHRESH )
14240     continue;
14241 j2array[0]=IKatan2(((gconst35)*(((((IkReal(5.19726332836084e+21))*(sj3)))+(((IkReal(-8.66210554726807e+23))*(x3842)))+(((x3841)*(x3844)))+(((IkReal(-1.00000000000000))*(sj4)*(x3843)*(x3844)))+(((IkReal(-1.00000000000000))*(x3840)*(x3841)))+(((sj4)*(x3840)*(x3843)))+(((IkReal(-1.00000000000000))*(cj4)*(npz)*(x3843)))+(((IkReal(1.51888207091656e+23))*(cj3)))))), ((gconst35)*(((((cj3)*(npz)*(x3841)))+(((IkReal(-2.44170809699545e+23))*(cj3)))+(((IkReal(-1.00000000000000))*(x3840)*(x3845)))+(((IkReal(-1.00000000000000))*(x3840)*(x3846)))+(((x3844)*(x3845)))+(((x3844)*(x3846)))+(((IkReal(4.13663598871341e+21))*(sj3)))+(((IkReal(-6.89439331452234e+23))*(x3842)))))));
14242 sj2array[0]=IKsin(j2array[0]);
14243 cj2array[0]=IKcos(j2array[0]);
14244 if( j2array[0] > IKPI )
14245 {
14246     j2array[0]-=IK2PI;
14247 }
14248 else if( j2array[0] < -IKPI )
14249 {    j2array[0]+=IK2PI;
14250 }
14251 j2valid[0] = true;
14252 for(int ij2 = 0; ij2 < 1; ++ij2)
14253 {
14254 if( !j2valid[ij2] )
14255 {
14256     continue;
14257 }
14258 _ij2[0] = ij2; _ij2[1] = -1;
14259 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
14260 {
14261 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
14262 {
14263     j2valid[iij2]=false; _ij2[1] = iij2; break; 
14264 }
14265 }
14266 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
14267 {
14268 IkReal evalcond[3];
14269 IkReal x3847=IKsin(j2);
14270 IkReal x3848=IKcos(j2);
14271 IkReal x3849=((cj5)*(npx));
14272 IkReal x3850=((npy)*(sj5));
14273 IkReal x3851=((IkReal(0.165463933124939))*(x3848));
14274 IkReal x3852=((IkReal(0.207888640466058))*(x3847));
14275 evalcond[0]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(sj4)*(x3849)))+(((IkReal(0.165463933124939))*(x3847)))+(((cj4)*(npz)))+(((sj4)*(x3850)))+(((IkReal(-0.207888640466058))*(x3848))));
14276 evalcond[1]=((IkReal(-0.00600000000000000))+(((IkReal(-0.0300035672348961))*(sj3)))+(((npx)*(sj5)))+(((IkReal(-0.00600000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x3852)))+(((IkReal(-1.00000000000000))*(sj3)*(x3851)))+(((cj5)*(npy))));
14277 evalcond[2]=((((npz)*(sj4)))+(((IkReal(-0.00600000000000000))*(sj3)))+(((cj3)*(x3852)))+(((cj3)*(x3851)))+(((IkReal(-1.00000000000000))*(cj4)*(x3850)))+(((cj4)*(x3849)))+(((IkReal(0.0300035672348961))*(cj3))));
14278 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
14279 {
14280 continue;
14281 }
14282 }
14283 
14284 {
14285 IkReal dummyeval[1];
14286 IkReal gconst36;
14287 IkReal x3853=((IkReal(1.00000000000000))*(sj3));
14288 gconst36=IKsign(((((IkReal(-1.00000000000000))*(x3853)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3853)*((sj2)*(sj2))))));
14289 IkReal x3854=((IkReal(1.00000000000000))*(sj3));
14290 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3854)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3854)*((sj2)*(sj2)))));
14291 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14292 {
14293 {
14294 IkReal dummyeval[1];
14295 IkReal gconst37;
14296 IkReal x3855=((IkReal(1.00000000000000))*(cj3));
14297 gconst37=IKsign(((((IkReal(-1.00000000000000))*(x3855)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3855)*((sj2)*(sj2))))));
14298 IkReal x3856=((IkReal(1.00000000000000))*(cj3));
14299 dummyeval[0]=((((IkReal(-1.00000000000000))*(x3856)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x3856)*((sj2)*(sj2)))));
14300 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14301 {
14302 {
14303 IkReal evalcond[9];
14304 IkReal x3857=((sj0)*(sj4));
14305 IkReal x3858=((IkReal(1.00000000000000))*(r12));
14306 IkReal x3859=((cj0)*(cj4));
14307 IkReal x3860=((r01)*(sj5));
14308 IkReal x3861=((IkReal(1.00000000000000))*(cj5));
14309 IkReal x3862=((cj4)*(cj5));
14310 IkReal x3863=((IkReal(1.00000000000000))*(cj0));
14311 IkReal x3864=((cj4)*(sj0));
14312 IkReal x3865=((r00)*(sj0));
14313 IkReal x3866=((npy)*(sj5));
14314 IkReal x3867=((IkReal(1.00000000000000))*(cj4));
14315 IkReal x3868=((cj0)*(sj4));
14316 IkReal x3869=((r11)*(sj5));
14317 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
14318 evalcond[1]=((((sj5)*(x3865)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3861)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3863))));
14319 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x3866)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3861))));
14320 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
14321 evalcond[4]=((IkReal(-0.00600000000000000))+(((IkReal(-1.00000000000000))*(x3866)*(x3867)))+(((npx)*(x3862)))+(((npz)*(sj4))));
14322 evalcond[5]=((((r02)*(x3864)))+(((IkReal(-1.00000000000000))*(x3858)*(x3859)))+(((cj5)*(r10)*(x3868)))+(((IkReal(-1.00000000000000))*(sj4)*(x3863)*(x3869)))+(((x3857)*(x3860)))+(((IkReal(-1.00000000000000))*(r00)*(x3857)*(x3861))));
14323 evalcond[6]=((IkReal(1.00000000000000))+(((r02)*(x3857)))+(((IkReal(-1.00000000000000))*(r10)*(x3859)*(x3861)))+(((IkReal(-1.00000000000000))*(x3858)*(x3868)))+(((IkReal(-1.00000000000000))*(x3860)*(x3864)))+(((x3859)*(x3869)))+(((x3862)*(x3865))));
14324 evalcond[7]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3867)))+(((r20)*(x3862))));
14325 evalcond[8]=((((x3864)*(x3869)))+(((IkReal(-1.00000000000000))*(x3857)*(x3858)))+(((IkReal(-1.00000000000000))*(r00)*(x3859)*(x3861)))+(((x3859)*(x3860)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3863)))+(((IkReal(-1.00000000000000))*(r10)*(x3861)*(x3864))));
14326 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  )
14327 {
14328 {
14329 IkReal dummyeval[1];
14330 IkReal gconst38;
14331 gconst38=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
14332 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
14333 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14334 {
14335 {
14336 IkReal dummyeval[1];
14337 IkReal gconst39;
14338 gconst39=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
14339 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
14340 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14341 {
14342 continue;
14343 
14344 } else
14345 {
14346 {
14347 IkReal j1array[1], cj1array[1], sj1array[1];
14348 bool j1valid[1]={false};
14349 _nj1 = 1;
14350 IkReal x3870=((cj5)*(r11));
14351 IkReal x3871=((r10)*(sj0));
14352 IkReal x3872=((IkReal(0.707103562373095))*(cj2));
14353 IkReal x3873=((r20)*(sj5));
14354 IkReal x3874=((IkReal(0.707103562373095))*(sj2));
14355 IkReal x3875=((IkReal(0.707109999985348))*(cj2));
14356 IkReal x3876=((cj0)*(r00));
14357 IkReal x3877=((IkReal(0.707109999985348))*(sj2));
14358 IkReal x3878=((cj5)*(r21));
14359 IkReal x3879=((sj0)*(x3874));
14360 IkReal x3880=((sj5)*(x3875));
14361 IkReal x3881=((cj0)*(cj5)*(r01));
14362 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3874)*(x3876)))+(((IkReal(-1.00000000000000))*(x3870)*(x3879)))+(((x3873)*(x3877)))+(((IkReal(-1.00000000000000))*(sj5)*(x3871)*(x3874)))+(((IkReal(-1.00000000000000))*(sj0)*(x3870)*(x3875)))+(((IkReal(-1.00000000000000))*(x3874)*(x3881)))+(((x3877)*(x3878)))+(((IkReal(-1.00000000000000))*(x3875)*(x3881)))+(((IkReal(-1.00000000000000))*(x3872)*(x3878)))+(((IkReal(-1.00000000000000))*(x3872)*(x3873)))+(((IkReal(-1.00000000000000))*(x3876)*(x3880)))+(((IkReal(-1.00000000000000))*(x3871)*(x3880))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((x3872)*(x3881)))+(((IkReal(-1.00000000000000))*(x3873)*(x3875)))+(((IkReal(-1.00000000000000))*(x3873)*(x3874)))+(((sj0)*(x3870)*(x3872)))+(((IkReal(-1.00000000000000))*(sj5)*(x3876)*(x3877)))+(((IkReal(-1.00000000000000))*(x3874)*(x3878)))+(((IkReal(-1.00000000000000))*(x3877)*(x3881)))+(((IkReal(-1.00000000000000))*(x3875)*(x3878)))+(((IkReal(-1.00000000000000))*(sj5)*(x3871)*(x3877)))+(((IkReal(-1.00000000000000))*(sj0)*(x3870)*(x3877)))+(((sj5)*(x3871)*(x3872)))+(((sj5)*(x3872)*(x3876))))))) < IKFAST_ATAN2_MAGTHRESH )
14363     continue;
14364 j1array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(sj5)*(x3874)*(x3876)))+(((IkReal(-1.00000000000000))*(x3870)*(x3879)))+(((x3873)*(x3877)))+(((IkReal(-1.00000000000000))*(sj5)*(x3871)*(x3874)))+(((IkReal(-1.00000000000000))*(sj0)*(x3870)*(x3875)))+(((IkReal(-1.00000000000000))*(x3874)*(x3881)))+(((x3877)*(x3878)))+(((IkReal(-1.00000000000000))*(x3875)*(x3881)))+(((IkReal(-1.00000000000000))*(x3872)*(x3878)))+(((IkReal(-1.00000000000000))*(x3872)*(x3873)))+(((IkReal(-1.00000000000000))*(x3876)*(x3880)))+(((IkReal(-1.00000000000000))*(x3871)*(x3880)))))), ((gconst39)*(((((x3872)*(x3881)))+(((IkReal(-1.00000000000000))*(x3873)*(x3875)))+(((IkReal(-1.00000000000000))*(x3873)*(x3874)))+(((sj0)*(x3870)*(x3872)))+(((IkReal(-1.00000000000000))*(sj5)*(x3876)*(x3877)))+(((IkReal(-1.00000000000000))*(x3874)*(x3878)))+(((IkReal(-1.00000000000000))*(x3877)*(x3881)))+(((IkReal(-1.00000000000000))*(x3875)*(x3878)))+(((IkReal(-1.00000000000000))*(sj5)*(x3871)*(x3877)))+(((IkReal(-1.00000000000000))*(sj0)*(x3870)*(x3877)))+(((sj5)*(x3871)*(x3872)))+(((sj5)*(x3872)*(x3876)))))));
14365 sj1array[0]=IKsin(j1array[0]);
14366 cj1array[0]=IKcos(j1array[0]);
14367 if( j1array[0] > IKPI )
14368 {
14369     j1array[0]-=IK2PI;
14370 }
14371 else if( j1array[0] < -IKPI )
14372 {    j1array[0]+=IK2PI;
14373 }
14374 j1valid[0] = true;
14375 for(int ij1 = 0; ij1 < 1; ++ij1)
14376 {
14377 if( !j1valid[ij1] )
14378 {
14379     continue;
14380 }
14381 _ij1[0] = ij1; _ij1[1] = -1;
14382 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14383 {
14384 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14385 {
14386     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14387 }
14388 }
14389 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14390 {
14391 IkReal evalcond[4];
14392 IkReal x3882=IKsin(j1);
14393 IkReal x3883=IKcos(j1);
14394 IkReal x3884=((IkReal(0.707109999985348))*(cj2));
14395 IkReal x3885=((IkReal(1.00000000000000))*(cj0));
14396 IkReal x3886=((IkReal(0.707109999985348))*(sj2));
14397 IkReal x3887=((cj5)*(sj4));
14398 IkReal x3888=((sj4)*(sj5));
14399 IkReal x3889=((IkReal(1.00000000000000))*(sj0));
14400 IkReal x3890=((sj5)*(x3889));
14401 IkReal x3891=((IkReal(0.707103562373095))*(x3883));
14402 IkReal x3892=((IkReal(0.707103562373095))*(x3882));
14403 IkReal x3893=((x3882)*(x3884));
14404 IkReal x3894=((sj2)*(x3892));
14405 IkReal x3895=((x3883)*(x3886));
14406 IkReal x3896=((cj2)*(x3891));
14407 IkReal x3897=((sj2)*(x3891));
14408 IkReal x3898=((cj2)*(x3892));
14409 IkReal x3899=((x3883)*(x3884));
14410 IkReal x3900=((x3882)*(x3886));
14411 IkReal x3901=((x3898)+(x3899)+(x3897));
14412 IkReal x3902=((x3893)+(x3894)+(x3895));
14413 evalcond[0]=((((IkReal(-1.00000000000000))*(x3901)))+(((cj5)*(r21)))+(x3900)+(((r20)*(sj5))));
14414 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x3887)))+(((r21)*(x3888)))+(x3902)+(((IkReal(-1.00000000000000))*(x3896))));
14415 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x3890)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3889)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3885)))+(x3902)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3885)))+(((IkReal(-1.00000000000000))*(x3896))));
14416 evalcond[3]=((((IkReal(-1.00000000000000))*(x3900)))+(((IkReal(-1.00000000000000))*(r11)*(x3888)*(x3889)))+(((cj0)*(r00)*(x3887)))+(((r10)*(sj0)*(x3887)))+(x3901)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3885)))+(((IkReal(-1.00000000000000))*(r01)*(x3885)*(x3888)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3889))));
14417 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14418 {
14419 continue;
14420 }
14421 }
14422 
14423 {
14424 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14425 vinfos[0].jointtype = 1;
14426 vinfos[0].foffset = j0;
14427 vinfos[0].indices[0] = _ij0[0];
14428 vinfos[0].indices[1] = _ij0[1];
14429 vinfos[0].maxsolutions = _nj0;
14430 vinfos[1].jointtype = 1;
14431 vinfos[1].foffset = j1;
14432 vinfos[1].indices[0] = _ij1[0];
14433 vinfos[1].indices[1] = _ij1[1];
14434 vinfos[1].maxsolutions = _nj1;
14435 vinfos[2].jointtype = 1;
14436 vinfos[2].foffset = j2;
14437 vinfos[2].indices[0] = _ij2[0];
14438 vinfos[2].indices[1] = _ij2[1];
14439 vinfos[2].maxsolutions = _nj2;
14440 vinfos[3].jointtype = 1;
14441 vinfos[3].foffset = j3;
14442 vinfos[3].indices[0] = _ij3[0];
14443 vinfos[3].indices[1] = _ij3[1];
14444 vinfos[3].maxsolutions = _nj3;
14445 vinfos[4].jointtype = 1;
14446 vinfos[4].foffset = j4;
14447 vinfos[4].indices[0] = _ij4[0];
14448 vinfos[4].indices[1] = _ij4[1];
14449 vinfos[4].maxsolutions = _nj4;
14450 vinfos[5].jointtype = 1;
14451 vinfos[5].foffset = j5;
14452 vinfos[5].indices[0] = _ij5[0];
14453 vinfos[5].indices[1] = _ij5[1];
14454 vinfos[5].maxsolutions = _nj5;
14455 std::vector<int> vfree(0);
14456 solutions.AddSolution(vinfos,vfree);
14457 }
14458 }
14459 }
14460 
14461 }
14462 
14463 }
14464 
14465 } else
14466 {
14467 {
14468 IkReal j1array[1], cj1array[1], sj1array[1];
14469 bool j1valid[1]={false};
14470 _nj1 = 1;
14471 IkReal x3903=((cj5)*(sj4));
14472 IkReal x3904=((r21)*(sj4));
14473 IkReal x3905=((cj5)*(r21));
14474 IkReal x3906=((IkReal(0.707109999985348))*(cj2));
14475 IkReal x3907=((IkReal(0.707103562373095))*(sj2));
14476 IkReal x3908=((IkReal(0.707109999985348))*(sj2));
14477 IkReal x3909=((cj4)*(r22));
14478 IkReal x3910=((IkReal(0.707103562373095))*(cj2));
14479 IkReal x3911=((r20)*(x3906));
14480 IkReal x3912=((sj5)*(x3910));
14481 IkReal x3913=((sj5)*(x3908));
14482 if( IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(x3905)*(x3910)))+(((IkReal(-1.00000000000000))*(r20)*(x3912)))+(((IkReal(-1.00000000000000))*(r20)*(x3903)*(x3907)))+(((IkReal(-1.00000000000000))*(x3903)*(x3911)))+(((x3906)*(x3909)))+(((x3905)*(x3908)))+(((x3907)*(x3909)))+(((r20)*(x3913)))+(((sj5)*(x3904)*(x3906)))+(((sj5)*(x3904)*(x3907))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(r20)*(x3903)*(x3908)))+(((IkReal(-1.00000000000000))*(x3904)*(x3912)))+(((x3904)*(x3913)))+(((IkReal(-1.00000000000000))*(x3905)*(x3906)))+(((IkReal(-1.00000000000000))*(x3905)*(x3907)))+(((IkReal(-1.00000000000000))*(x3909)*(x3910)))+(((IkReal(-1.00000000000000))*(sj5)*(x3911)))+(((x3908)*(x3909)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3907)))+(((r20)*(x3903)*(x3910))))))) < IKFAST_ATAN2_MAGTHRESH )
14483     continue;
14484 j1array[0]=IKatan2(((gconst38)*(((((IkReal(-1.00000000000000))*(x3905)*(x3910)))+(((IkReal(-1.00000000000000))*(r20)*(x3912)))+(((IkReal(-1.00000000000000))*(r20)*(x3903)*(x3907)))+(((IkReal(-1.00000000000000))*(x3903)*(x3911)))+(((x3906)*(x3909)))+(((x3905)*(x3908)))+(((x3907)*(x3909)))+(((r20)*(x3913)))+(((sj5)*(x3904)*(x3906)))+(((sj5)*(x3904)*(x3907)))))), ((gconst38)*(((((IkReal(-1.00000000000000))*(r20)*(x3903)*(x3908)))+(((IkReal(-1.00000000000000))*(x3904)*(x3912)))+(((x3904)*(x3913)))+(((IkReal(-1.00000000000000))*(x3905)*(x3906)))+(((IkReal(-1.00000000000000))*(x3905)*(x3907)))+(((IkReal(-1.00000000000000))*(x3909)*(x3910)))+(((IkReal(-1.00000000000000))*(sj5)*(x3911)))+(((x3908)*(x3909)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3907)))+(((r20)*(x3903)*(x3910)))))));
14485 sj1array[0]=IKsin(j1array[0]);
14486 cj1array[0]=IKcos(j1array[0]);
14487 if( j1array[0] > IKPI )
14488 {
14489     j1array[0]-=IK2PI;
14490 }
14491 else if( j1array[0] < -IKPI )
14492 {    j1array[0]+=IK2PI;
14493 }
14494 j1valid[0] = true;
14495 for(int ij1 = 0; ij1 < 1; ++ij1)
14496 {
14497 if( !j1valid[ij1] )
14498 {
14499     continue;
14500 }
14501 _ij1[0] = ij1; _ij1[1] = -1;
14502 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14503 {
14504 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14505 {
14506     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14507 }
14508 }
14509 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14510 {
14511 IkReal evalcond[4];
14512 IkReal x3914=IKsin(j1);
14513 IkReal x3915=IKcos(j1);
14514 IkReal x3916=((IkReal(0.707109999985348))*(cj2));
14515 IkReal x3917=((IkReal(1.00000000000000))*(cj0));
14516 IkReal x3918=((IkReal(0.707109999985348))*(sj2));
14517 IkReal x3919=((cj5)*(sj4));
14518 IkReal x3920=((sj4)*(sj5));
14519 IkReal x3921=((IkReal(1.00000000000000))*(sj0));
14520 IkReal x3922=((sj5)*(x3921));
14521 IkReal x3923=((IkReal(0.707103562373095))*(x3915));
14522 IkReal x3924=((IkReal(0.707103562373095))*(x3914));
14523 IkReal x3925=((x3914)*(x3916));
14524 IkReal x3926=((sj2)*(x3924));
14525 IkReal x3927=((x3915)*(x3918));
14526 IkReal x3928=((cj2)*(x3923));
14527 IkReal x3929=((sj2)*(x3923));
14528 IkReal x3930=((cj2)*(x3924));
14529 IkReal x3931=((x3915)*(x3916));
14530 IkReal x3932=((x3914)*(x3918));
14531 IkReal x3933=((x3929)+(x3931)+(x3930));
14532 IkReal x3934=((x3926)+(x3927)+(x3925));
14533 evalcond[0]=((((cj5)*(r21)))+(x3932)+(((IkReal(-1.00000000000000))*(x3933)))+(((r20)*(sj5))));
14534 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x3928)))+(((r21)*(x3920)))+(x3934)+(((IkReal(-1.00000000000000))*(r20)*(x3919))));
14535 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3921)))+(((IkReal(-1.00000000000000))*(r10)*(x3922)))+(((IkReal(-1.00000000000000))*(x3928)))+(x3934)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3917)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3917))));
14536 evalcond[3]=((((r10)*(sj0)*(x3919)))+(((IkReal(-1.00000000000000))*(r01)*(x3917)*(x3920)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3917)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3921)))+(x3933)+(((IkReal(-1.00000000000000))*(x3932)))+(((IkReal(-1.00000000000000))*(r11)*(x3920)*(x3921)))+(((cj0)*(r00)*(x3919))));
14537 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14538 {
14539 continue;
14540 }
14541 }
14542 
14543 {
14544 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14545 vinfos[0].jointtype = 1;
14546 vinfos[0].foffset = j0;
14547 vinfos[0].indices[0] = _ij0[0];
14548 vinfos[0].indices[1] = _ij0[1];
14549 vinfos[0].maxsolutions = _nj0;
14550 vinfos[1].jointtype = 1;
14551 vinfos[1].foffset = j1;
14552 vinfos[1].indices[0] = _ij1[0];
14553 vinfos[1].indices[1] = _ij1[1];
14554 vinfos[1].maxsolutions = _nj1;
14555 vinfos[2].jointtype = 1;
14556 vinfos[2].foffset = j2;
14557 vinfos[2].indices[0] = _ij2[0];
14558 vinfos[2].indices[1] = _ij2[1];
14559 vinfos[2].maxsolutions = _nj2;
14560 vinfos[3].jointtype = 1;
14561 vinfos[3].foffset = j3;
14562 vinfos[3].indices[0] = _ij3[0];
14563 vinfos[3].indices[1] = _ij3[1];
14564 vinfos[3].maxsolutions = _nj3;
14565 vinfos[4].jointtype = 1;
14566 vinfos[4].foffset = j4;
14567 vinfos[4].indices[0] = _ij4[0];
14568 vinfos[4].indices[1] = _ij4[1];
14569 vinfos[4].maxsolutions = _nj4;
14570 vinfos[5].jointtype = 1;
14571 vinfos[5].foffset = j5;
14572 vinfos[5].indices[0] = _ij5[0];
14573 vinfos[5].indices[1] = _ij5[1];
14574 vinfos[5].maxsolutions = _nj5;
14575 std::vector<int> vfree(0);
14576 solutions.AddSolution(vinfos,vfree);
14577 }
14578 }
14579 }
14580 
14581 }
14582 
14583 }
14584 
14585 } else
14586 {
14587 IkReal x3935=((sj0)*(sj4));
14588 IkReal x3936=((IkReal(1.00000000000000))*(r12));
14589 IkReal x3937=((cj0)*(cj4));
14590 IkReal x3938=((r01)*(sj5));
14591 IkReal x3939=((IkReal(1.00000000000000))*(cj5));
14592 IkReal x3940=((cj4)*(cj5));
14593 IkReal x3941=((IkReal(1.00000000000000))*(cj0));
14594 IkReal x3942=((cj4)*(sj0));
14595 IkReal x3943=((r00)*(sj0));
14596 IkReal x3944=((npy)*(sj5));
14597 IkReal x3945=((IkReal(1.00000000000000))*(cj4));
14598 IkReal x3946=((cj0)*(sj4));
14599 IkReal x3947=((r11)*(sj5));
14600 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
14601 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(r11)*(x3939)))+(((cj5)*(r01)*(sj0)))+(((sj5)*(x3943)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x3941))));
14602 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x3944)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x3939)))+(((IkReal(0.165463933124939))*(sj2))));
14603 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
14604 evalcond[4]=((IkReal(-0.00600000000000000))+(((npz)*(sj4)))+(((npx)*(x3940)))+(((IkReal(-1.00000000000000))*(x3944)*(x3945))));
14605 evalcond[5]=((((IkReal(-1.00000000000000))*(x3936)*(x3937)))+(((IkReal(-1.00000000000000))*(sj4)*(x3941)*(x3947)))+(((IkReal(-1.00000000000000))*(r00)*(x3935)*(x3939)))+(((x3935)*(x3938)))+(((cj5)*(r10)*(x3946)))+(((r02)*(x3942))));
14606 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x3938)*(x3942)))+(((x3940)*(x3943)))+(((x3937)*(x3947)))+(((IkReal(-1.00000000000000))*(r10)*(x3937)*(x3939)))+(((r02)*(x3935)))+(((IkReal(-1.00000000000000))*(x3936)*(x3946))));
14607 evalcond[7]=((((r22)*(sj4)))+(((r20)*(x3940)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x3945))));
14608 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x3941)))+(((x3942)*(x3947)))+(((IkReal(-1.00000000000000))*(r00)*(x3937)*(x3939)))+(((x3937)*(x3938)))+(((IkReal(-1.00000000000000))*(r10)*(x3939)*(x3942)))+(((IkReal(-1.00000000000000))*(x3935)*(x3936))));
14609 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  )
14610 {
14611 {
14612 IkReal dummyeval[1];
14613 IkReal gconst40;
14614 gconst40=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
14615 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
14616 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14617 {
14618 {
14619 IkReal dummyeval[1];
14620 IkReal gconst41;
14621 gconst41=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
14622 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
14623 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14624 {
14625 continue;
14626 
14627 } else
14628 {
14629 {
14630 IkReal j1array[1], cj1array[1], sj1array[1];
14631 bool j1valid[1]={false};
14632 _nj1 = 1;
14633 IkReal x3948=((cj5)*(r11));
14634 IkReal x3949=((r10)*(sj0));
14635 IkReal x3950=((IkReal(0.707103562373095))*(cj2));
14636 IkReal x3951=((r20)*(sj5));
14637 IkReal x3952=((IkReal(0.707103562373095))*(sj2));
14638 IkReal x3953=((IkReal(0.707109999985348))*(cj2));
14639 IkReal x3954=((cj0)*(r00));
14640 IkReal x3955=((IkReal(0.707109999985348))*(sj2));
14641 IkReal x3956=((cj5)*(r21));
14642 IkReal x3957=((sj0)*(x3952));
14643 IkReal x3958=((sj5)*(x3953));
14644 IkReal x3959=((cj0)*(cj5)*(r01));
14645 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(x3954)*(x3958)))+(((IkReal(-1.00000000000000))*(x3953)*(x3959)))+(((IkReal(-1.00000000000000))*(x3948)*(x3957)))+(((IkReal(-1.00000000000000))*(x3949)*(x3958)))+(((IkReal(-1.00000000000000))*(sj0)*(x3948)*(x3953)))+(((IkReal(-1.00000000000000))*(x3950)*(x3951)))+(((IkReal(-1.00000000000000))*(x3950)*(x3956)))+(((IkReal(-1.00000000000000))*(sj5)*(x3949)*(x3952)))+(((IkReal(-1.00000000000000))*(x3952)*(x3959)))+(((IkReal(-1.00000000000000))*(sj5)*(x3952)*(x3954)))+(((x3951)*(x3955)))+(((x3955)*(x3956))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(x3955)*(x3959)))+(((IkReal(-1.00000000000000))*(x3953)*(x3956)))+(((IkReal(-1.00000000000000))*(sj0)*(x3948)*(x3955)))+(((sj5)*(x3949)*(x3950)))+(((IkReal(-1.00000000000000))*(sj5)*(x3949)*(x3955)))+(((x3950)*(x3959)))+(((IkReal(-1.00000000000000))*(x3952)*(x3956)))+(((sj0)*(x3948)*(x3950)))+(((IkReal(-1.00000000000000))*(x3951)*(x3953)))+(((IkReal(-1.00000000000000))*(x3951)*(x3952)))+(((IkReal(-1.00000000000000))*(sj5)*(x3954)*(x3955)))+(((sj5)*(x3950)*(x3954))))))) < IKFAST_ATAN2_MAGTHRESH )
14646     continue;
14647 j1array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(x3954)*(x3958)))+(((IkReal(-1.00000000000000))*(x3953)*(x3959)))+(((IkReal(-1.00000000000000))*(x3948)*(x3957)))+(((IkReal(-1.00000000000000))*(x3949)*(x3958)))+(((IkReal(-1.00000000000000))*(sj0)*(x3948)*(x3953)))+(((IkReal(-1.00000000000000))*(x3950)*(x3951)))+(((IkReal(-1.00000000000000))*(x3950)*(x3956)))+(((IkReal(-1.00000000000000))*(sj5)*(x3949)*(x3952)))+(((IkReal(-1.00000000000000))*(x3952)*(x3959)))+(((IkReal(-1.00000000000000))*(sj5)*(x3952)*(x3954)))+(((x3951)*(x3955)))+(((x3955)*(x3956)))))), ((gconst41)*(((((IkReal(-1.00000000000000))*(x3955)*(x3959)))+(((IkReal(-1.00000000000000))*(x3953)*(x3956)))+(((IkReal(-1.00000000000000))*(sj0)*(x3948)*(x3955)))+(((sj5)*(x3949)*(x3950)))+(((IkReal(-1.00000000000000))*(sj5)*(x3949)*(x3955)))+(((x3950)*(x3959)))+(((IkReal(-1.00000000000000))*(x3952)*(x3956)))+(((sj0)*(x3948)*(x3950)))+(((IkReal(-1.00000000000000))*(x3951)*(x3953)))+(((IkReal(-1.00000000000000))*(x3951)*(x3952)))+(((IkReal(-1.00000000000000))*(sj5)*(x3954)*(x3955)))+(((sj5)*(x3950)*(x3954)))))));
14648 sj1array[0]=IKsin(j1array[0]);
14649 cj1array[0]=IKcos(j1array[0]);
14650 if( j1array[0] > IKPI )
14651 {
14652     j1array[0]-=IK2PI;
14653 }
14654 else if( j1array[0] < -IKPI )
14655 {    j1array[0]+=IK2PI;
14656 }
14657 j1valid[0] = true;
14658 for(int ij1 = 0; ij1 < 1; ++ij1)
14659 {
14660 if( !j1valid[ij1] )
14661 {
14662     continue;
14663 }
14664 _ij1[0] = ij1; _ij1[1] = -1;
14665 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14666 {
14667 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14668 {
14669     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14670 }
14671 }
14672 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14673 {
14674 IkReal evalcond[4];
14675 IkReal x3960=IKsin(j1);
14676 IkReal x3961=IKcos(j1);
14677 IkReal x3962=((IkReal(0.707109999985348))*(cj2));
14678 IkReal x3963=((IkReal(1.00000000000000))*(cj0));
14679 IkReal x3964=((IkReal(0.707109999985348))*(sj2));
14680 IkReal x3965=((cj5)*(sj4));
14681 IkReal x3966=((sj4)*(sj5));
14682 IkReal x3967=((IkReal(1.00000000000000))*(sj0));
14683 IkReal x3968=((sj5)*(x3967));
14684 IkReal x3969=((IkReal(0.707103562373095))*(x3961));
14685 IkReal x3970=((IkReal(0.707103562373095))*(x3960));
14686 IkReal x3971=((x3960)*(x3962));
14687 IkReal x3972=((sj2)*(x3970));
14688 IkReal x3973=((x3961)*(x3964));
14689 IkReal x3974=((cj2)*(x3969));
14690 IkReal x3975=((sj2)*(x3969));
14691 IkReal x3976=((cj2)*(x3970));
14692 IkReal x3977=((x3961)*(x3962));
14693 IkReal x3978=((x3960)*(x3964));
14694 IkReal x3979=((x3975)+(x3977)+(x3976));
14695 IkReal x3980=((x3971)+(x3973)+(x3972));
14696 evalcond[0]=((((IkReal(-1.00000000000000))*(x3979)))+(((cj5)*(r21)))+(x3978)+(((r20)*(sj5))));
14697 evalcond[1]=((((IkReal(-1.00000000000000))*(x3974)))+(((cj4)*(r22)))+(x3980)+(((r21)*(x3966)))+(((IkReal(-1.00000000000000))*(r20)*(x3965))));
14698 evalcond[2]=((((IkReal(-1.00000000000000))*(x3974)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3967)))+(((IkReal(-1.00000000000000))*(r10)*(x3968)))+(x3980)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3963)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3963))));
14699 evalcond[3]=((((IkReal(-1.00000000000000))*(x3978)))+(((cj0)*(r00)*(x3965)))+(((IkReal(-1.00000000000000))*(r11)*(x3966)*(x3967)))+(((r10)*(sj0)*(x3965)))+(x3979)+(((IkReal(-1.00000000000000))*(r01)*(x3963)*(x3966)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3963)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3967))));
14700 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14701 {
14702 continue;
14703 }
14704 }
14705 
14706 {
14707 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14708 vinfos[0].jointtype = 1;
14709 vinfos[0].foffset = j0;
14710 vinfos[0].indices[0] = _ij0[0];
14711 vinfos[0].indices[1] = _ij0[1];
14712 vinfos[0].maxsolutions = _nj0;
14713 vinfos[1].jointtype = 1;
14714 vinfos[1].foffset = j1;
14715 vinfos[1].indices[0] = _ij1[0];
14716 vinfos[1].indices[1] = _ij1[1];
14717 vinfos[1].maxsolutions = _nj1;
14718 vinfos[2].jointtype = 1;
14719 vinfos[2].foffset = j2;
14720 vinfos[2].indices[0] = _ij2[0];
14721 vinfos[2].indices[1] = _ij2[1];
14722 vinfos[2].maxsolutions = _nj2;
14723 vinfos[3].jointtype = 1;
14724 vinfos[3].foffset = j3;
14725 vinfos[3].indices[0] = _ij3[0];
14726 vinfos[3].indices[1] = _ij3[1];
14727 vinfos[3].maxsolutions = _nj3;
14728 vinfos[4].jointtype = 1;
14729 vinfos[4].foffset = j4;
14730 vinfos[4].indices[0] = _ij4[0];
14731 vinfos[4].indices[1] = _ij4[1];
14732 vinfos[4].maxsolutions = _nj4;
14733 vinfos[5].jointtype = 1;
14734 vinfos[5].foffset = j5;
14735 vinfos[5].indices[0] = _ij5[0];
14736 vinfos[5].indices[1] = _ij5[1];
14737 vinfos[5].maxsolutions = _nj5;
14738 std::vector<int> vfree(0);
14739 solutions.AddSolution(vinfos,vfree);
14740 }
14741 }
14742 }
14743 
14744 }
14745 
14746 }
14747 
14748 } else
14749 {
14750 {
14751 IkReal j1array[1], cj1array[1], sj1array[1];
14752 bool j1valid[1]={false};
14753 _nj1 = 1;
14754 IkReal x3981=((cj5)*(sj4));
14755 IkReal x3982=((r21)*(sj4));
14756 IkReal x3983=((cj5)*(r21));
14757 IkReal x3984=((IkReal(0.707109999985348))*(cj2));
14758 IkReal x3985=((IkReal(0.707103562373095))*(sj2));
14759 IkReal x3986=((IkReal(0.707109999985348))*(sj2));
14760 IkReal x3987=((cj4)*(r22));
14761 IkReal x3988=((IkReal(0.707103562373095))*(cj2));
14762 IkReal x3989=((r20)*(x3984));
14763 IkReal x3990=((sj5)*(x3988));
14764 IkReal x3991=((sj5)*(x3986));
14765 if( IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3981)*(x3985)))+(((sj5)*(x3982)*(x3985)))+(((sj5)*(x3982)*(x3984)))+(((x3983)*(x3986)))+(((x3984)*(x3987)))+(((x3985)*(x3987)))+(((IkReal(-1.00000000000000))*(x3981)*(x3989)))+(((IkReal(-1.00000000000000))*(x3983)*(x3988)))+(((IkReal(-1.00000000000000))*(r20)*(x3990)))+(((r20)*(x3991))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3981)*(x3986)))+(((IkReal(-1.00000000000000))*(sj5)*(x3989)))+(((x3986)*(x3987)))+(((IkReal(-1.00000000000000))*(x3987)*(x3988)))+(((IkReal(-1.00000000000000))*(x3983)*(x3984)))+(((IkReal(-1.00000000000000))*(x3983)*(x3985)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3985)))+(((r20)*(x3981)*(x3988)))+(((IkReal(-1.00000000000000))*(x3982)*(x3990)))+(((x3982)*(x3991))))))) < IKFAST_ATAN2_MAGTHRESH )
14766     continue;
14767 j1array[0]=IKatan2(((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3981)*(x3985)))+(((sj5)*(x3982)*(x3985)))+(((sj5)*(x3982)*(x3984)))+(((x3983)*(x3986)))+(((x3984)*(x3987)))+(((x3985)*(x3987)))+(((IkReal(-1.00000000000000))*(x3981)*(x3989)))+(((IkReal(-1.00000000000000))*(x3983)*(x3988)))+(((IkReal(-1.00000000000000))*(r20)*(x3990)))+(((r20)*(x3991)))))), ((gconst40)*(((((IkReal(-1.00000000000000))*(r20)*(x3981)*(x3986)))+(((IkReal(-1.00000000000000))*(sj5)*(x3989)))+(((x3986)*(x3987)))+(((IkReal(-1.00000000000000))*(x3987)*(x3988)))+(((IkReal(-1.00000000000000))*(x3983)*(x3984)))+(((IkReal(-1.00000000000000))*(x3983)*(x3985)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x3985)))+(((r20)*(x3981)*(x3988)))+(((IkReal(-1.00000000000000))*(x3982)*(x3990)))+(((x3982)*(x3991)))))));
14768 sj1array[0]=IKsin(j1array[0]);
14769 cj1array[0]=IKcos(j1array[0]);
14770 if( j1array[0] > IKPI )
14771 {
14772     j1array[0]-=IK2PI;
14773 }
14774 else if( j1array[0] < -IKPI )
14775 {    j1array[0]+=IK2PI;
14776 }
14777 j1valid[0] = true;
14778 for(int ij1 = 0; ij1 < 1; ++ij1)
14779 {
14780 if( !j1valid[ij1] )
14781 {
14782     continue;
14783 }
14784 _ij1[0] = ij1; _ij1[1] = -1;
14785 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14786 {
14787 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14788 {
14789     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14790 }
14791 }
14792 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14793 {
14794 IkReal evalcond[4];
14795 IkReal x3992=IKsin(j1);
14796 IkReal x3993=IKcos(j1);
14797 IkReal x3994=((IkReal(0.707109999985348))*(cj2));
14798 IkReal x3995=((IkReal(1.00000000000000))*(cj0));
14799 IkReal x3996=((IkReal(0.707109999985348))*(sj2));
14800 IkReal x3997=((cj5)*(sj4));
14801 IkReal x3998=((sj4)*(sj5));
14802 IkReal x3999=((IkReal(1.00000000000000))*(sj0));
14803 IkReal x4000=((sj5)*(x3999));
14804 IkReal x4001=((IkReal(0.707103562373095))*(x3993));
14805 IkReal x4002=((IkReal(0.707103562373095))*(x3992));
14806 IkReal x4003=((x3992)*(x3994));
14807 IkReal x4004=((sj2)*(x4002));
14808 IkReal x4005=((x3993)*(x3996));
14809 IkReal x4006=((cj2)*(x4001));
14810 IkReal x4007=((sj2)*(x4001));
14811 IkReal x4008=((cj2)*(x4002));
14812 IkReal x4009=((x3993)*(x3994));
14813 IkReal x4010=((x3992)*(x3996));
14814 IkReal x4011=((x4008)+(x4009)+(x4007));
14815 IkReal x4012=((x4003)+(x4004)+(x4005));
14816 evalcond[0]=((((cj5)*(r21)))+(x4010)+(((IkReal(-1.00000000000000))*(x4011)))+(((r20)*(sj5))));
14817 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x4006)))+(((IkReal(-1.00000000000000))*(r20)*(x3997)))+(((r21)*(x3998)))+(x4012));
14818 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4000)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x3999)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x3995)))+(((IkReal(-1.00000000000000))*(x4006)))+(x4012)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x3995))));
14819 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x3998)*(x3999)))+(((r10)*(sj0)*(x3997)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x3999)))+(((cj0)*(r00)*(x3997)))+(x4011)+(((IkReal(-1.00000000000000))*(x4010)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x3995)))+(((IkReal(-1.00000000000000))*(r01)*(x3995)*(x3998))));
14820 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14821 {
14822 continue;
14823 }
14824 }
14825 
14826 {
14827 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14828 vinfos[0].jointtype = 1;
14829 vinfos[0].foffset = j0;
14830 vinfos[0].indices[0] = _ij0[0];
14831 vinfos[0].indices[1] = _ij0[1];
14832 vinfos[0].maxsolutions = _nj0;
14833 vinfos[1].jointtype = 1;
14834 vinfos[1].foffset = j1;
14835 vinfos[1].indices[0] = _ij1[0];
14836 vinfos[1].indices[1] = _ij1[1];
14837 vinfos[1].maxsolutions = _nj1;
14838 vinfos[2].jointtype = 1;
14839 vinfos[2].foffset = j2;
14840 vinfos[2].indices[0] = _ij2[0];
14841 vinfos[2].indices[1] = _ij2[1];
14842 vinfos[2].maxsolutions = _nj2;
14843 vinfos[3].jointtype = 1;
14844 vinfos[3].foffset = j3;
14845 vinfos[3].indices[0] = _ij3[0];
14846 vinfos[3].indices[1] = _ij3[1];
14847 vinfos[3].maxsolutions = _nj3;
14848 vinfos[4].jointtype = 1;
14849 vinfos[4].foffset = j4;
14850 vinfos[4].indices[0] = _ij4[0];
14851 vinfos[4].indices[1] = _ij4[1];
14852 vinfos[4].maxsolutions = _nj4;
14853 vinfos[5].jointtype = 1;
14854 vinfos[5].foffset = j5;
14855 vinfos[5].indices[0] = _ij5[0];
14856 vinfos[5].indices[1] = _ij5[1];
14857 vinfos[5].maxsolutions = _nj5;
14858 std::vector<int> vfree(0);
14859 solutions.AddSolution(vinfos,vfree);
14860 }
14861 }
14862 }
14863 
14864 }
14865 
14866 }
14867 
14868 } else
14869 {
14870 IkReal x4013=((sj0)*(sj4));
14871 IkReal x4014=((IkReal(1.00000000000000))*(r12));
14872 IkReal x4015=((cj0)*(cj4));
14873 IkReal x4016=((r01)*(sj5));
14874 IkReal x4017=((IkReal(1.00000000000000))*(cj5));
14875 IkReal x4018=((cj4)*(cj5));
14876 IkReal x4019=((IkReal(1.00000000000000))*(cj0));
14877 IkReal x4020=((cj4)*(sj0));
14878 IkReal x4021=((r00)*(sj0));
14879 IkReal x4022=((npy)*(sj5));
14880 IkReal x4023=((IkReal(1.00000000000000))*(cj4));
14881 IkReal x4024=((cj0)*(sj4));
14882 IkReal x4025=((r11)*(sj5));
14883 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
14884 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4019)))+(((sj5)*(x4021)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4017))));
14885 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x4022)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4017))));
14886 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
14887 evalcond[4]=((IkReal(0.00600000000000000))+(((IkReal(-1.00000000000000))*(x4022)*(x4023)))+(((npz)*(sj4)))+(((npx)*(x4018))));
14888 evalcond[5]=((((x4013)*(x4016)))+(((IkReal(-1.00000000000000))*(x4014)*(x4015)))+(((cj5)*(r10)*(x4024)))+(((IkReal(-1.00000000000000))*(r00)*(x4013)*(x4017)))+(((IkReal(-1.00000000000000))*(sj4)*(x4019)*(x4025)))+(((r02)*(x4020))));
14889 evalcond[6]=((IkReal(-1.00000000000000))+(((r02)*(x4013)))+(((IkReal(-1.00000000000000))*(r10)*(x4015)*(x4017)))+(((x4018)*(x4021)))+(((IkReal(-1.00000000000000))*(x4014)*(x4024)))+(((IkReal(-1.00000000000000))*(x4016)*(x4020)))+(((x4015)*(x4025))));
14890 evalcond[7]=((((r22)*(sj4)))+(((r20)*(x4018)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4023))));
14891 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x4015)*(x4017)))+(((x4020)*(x4025)))+(((IkReal(-1.00000000000000))*(x4013)*(x4014)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4019)))+(((IkReal(-1.00000000000000))*(r10)*(x4017)*(x4020)))+(((x4015)*(x4016))));
14892 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  )
14893 {
14894 {
14895 IkReal dummyeval[1];
14896 IkReal gconst42;
14897 gconst42=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
14898 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
14899 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14900 {
14901 {
14902 IkReal dummyeval[1];
14903 IkReal gconst43;
14904 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
14905 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
14906 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14907 {
14908 continue;
14909 
14910 } else
14911 {
14912 {
14913 IkReal j1array[1], cj1array[1], sj1array[1];
14914 bool j1valid[1]={false};
14915 _nj1 = 1;
14916 IkReal x4026=((cj5)*(r11));
14917 IkReal x4027=((r10)*(sj0));
14918 IkReal x4028=((IkReal(0.707103562373095))*(cj2));
14919 IkReal x4029=((r20)*(sj5));
14920 IkReal x4030=((IkReal(0.707103562373095))*(sj2));
14921 IkReal x4031=((IkReal(0.707109999985348))*(cj2));
14922 IkReal x4032=((cj0)*(r00));
14923 IkReal x4033=((IkReal(0.707109999985348))*(sj2));
14924 IkReal x4034=((cj5)*(r21));
14925 IkReal x4035=((sj0)*(x4030));
14926 IkReal x4036=((sj5)*(x4031));
14927 IkReal x4037=((cj0)*(cj5)*(r01));
14928 if( IKabs(((gconst43)*(((((x4032)*(x4036)))+(((x4028)*(x4034)))+(((x4026)*(x4035)))+(((x4027)*(x4036)))+(((sj5)*(x4027)*(x4030)))+(((sj0)*(x4026)*(x4031)))+(((x4028)*(x4029)))+(((sj5)*(x4030)*(x4032)))+(((IkReal(-1.00000000000000))*(x4029)*(x4033)))+(((IkReal(-1.00000000000000))*(x4033)*(x4034)))+(((x4031)*(x4037)))+(((x4030)*(x4037))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((sj5)*(x4032)*(x4033)))+(((IkReal(-1.00000000000000))*(sj5)*(x4028)*(x4032)))+(((x4029)*(x4031)))+(((x4029)*(x4030)))+(((x4033)*(x4037)))+(((sj5)*(x4027)*(x4033)))+(((sj0)*(x4026)*(x4033)))+(((IkReal(-1.00000000000000))*(sj0)*(x4026)*(x4028)))+(((IkReal(-1.00000000000000))*(x4028)*(x4037)))+(((IkReal(-1.00000000000000))*(sj5)*(x4027)*(x4028)))+(((x4031)*(x4034)))+(((x4030)*(x4034))))))) < IKFAST_ATAN2_MAGTHRESH )
14929     continue;
14930 j1array[0]=IKatan2(((gconst43)*(((((x4032)*(x4036)))+(((x4028)*(x4034)))+(((x4026)*(x4035)))+(((x4027)*(x4036)))+(((sj5)*(x4027)*(x4030)))+(((sj0)*(x4026)*(x4031)))+(((x4028)*(x4029)))+(((sj5)*(x4030)*(x4032)))+(((IkReal(-1.00000000000000))*(x4029)*(x4033)))+(((IkReal(-1.00000000000000))*(x4033)*(x4034)))+(((x4031)*(x4037)))+(((x4030)*(x4037)))))), ((gconst43)*(((((sj5)*(x4032)*(x4033)))+(((IkReal(-1.00000000000000))*(sj5)*(x4028)*(x4032)))+(((x4029)*(x4031)))+(((x4029)*(x4030)))+(((x4033)*(x4037)))+(((sj5)*(x4027)*(x4033)))+(((sj0)*(x4026)*(x4033)))+(((IkReal(-1.00000000000000))*(sj0)*(x4026)*(x4028)))+(((IkReal(-1.00000000000000))*(x4028)*(x4037)))+(((IkReal(-1.00000000000000))*(sj5)*(x4027)*(x4028)))+(((x4031)*(x4034)))+(((x4030)*(x4034)))))));
14931 sj1array[0]=IKsin(j1array[0]);
14932 cj1array[0]=IKcos(j1array[0]);
14933 if( j1array[0] > IKPI )
14934 {
14935     j1array[0]-=IK2PI;
14936 }
14937 else if( j1array[0] < -IKPI )
14938 {    j1array[0]+=IK2PI;
14939 }
14940 j1valid[0] = true;
14941 for(int ij1 = 0; ij1 < 1; ++ij1)
14942 {
14943 if( !j1valid[ij1] )
14944 {
14945     continue;
14946 }
14947 _ij1[0] = ij1; _ij1[1] = -1;
14948 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
14949 {
14950 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
14951 {
14952     j1valid[iij1]=false; _ij1[1] = iij1; break; 
14953 }
14954 }
14955 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
14956 {
14957 IkReal evalcond[4];
14958 IkReal x4038=IKcos(j1);
14959 IkReal x4039=IKsin(j1);
14960 IkReal x4040=((IkReal(0.707109999985348))*(cj2));
14961 IkReal x4041=((IkReal(1.00000000000000))*(cj0));
14962 IkReal x4042=((IkReal(0.707109999985348))*(sj2));
14963 IkReal x4043=((cj5)*(sj4));
14964 IkReal x4044=((sj4)*(sj5));
14965 IkReal x4045=((IkReal(1.00000000000000))*(sj0));
14966 IkReal x4046=((sj5)*(x4045));
14967 IkReal x4047=((IkReal(0.707103562373095))*(x4038));
14968 IkReal x4048=((IkReal(0.707103562373095))*(x4039));
14969 IkReal x4049=((cj2)*(x4047));
14970 IkReal x4050=((x4039)*(x4040));
14971 IkReal x4051=((sj2)*(x4048));
14972 IkReal x4052=((x4038)*(x4042));
14973 IkReal x4053=((sj2)*(x4047));
14974 IkReal x4054=((cj2)*(x4048));
14975 IkReal x4055=((x4038)*(x4040));
14976 IkReal x4056=((x4039)*(x4042));
14977 IkReal x4057=((x4055)+(x4054)+(x4053));
14978 IkReal x4058=((x4052)+(x4051)+(x4050));
14979 evalcond[0]=((((cj5)*(r21)))+(x4057)+(((IkReal(-1.00000000000000))*(x4056)))+(((r20)*(sj5))));
14980 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x4044)))+(x4058)+(((IkReal(-1.00000000000000))*(x4049)))+(((IkReal(-1.00000000000000))*(r20)*(x4043))));
14981 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4045)))+(((IkReal(-1.00000000000000))*(r10)*(x4046)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4041)))+(x4049)+(((IkReal(-1.00000000000000))*(x4058)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4041))));
14982 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4041)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4045)))+(((IkReal(-1.00000000000000))*(r01)*(x4041)*(x4044)))+(((IkReal(-1.00000000000000))*(r11)*(x4044)*(x4045)))+(x4057)+(((IkReal(-1.00000000000000))*(x4056)))+(((cj0)*(r00)*(x4043)))+(((r10)*(sj0)*(x4043))));
14983 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14984 {
14985 continue;
14986 }
14987 }
14988 
14989 {
14990 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14991 vinfos[0].jointtype = 1;
14992 vinfos[0].foffset = j0;
14993 vinfos[0].indices[0] = _ij0[0];
14994 vinfos[0].indices[1] = _ij0[1];
14995 vinfos[0].maxsolutions = _nj0;
14996 vinfos[1].jointtype = 1;
14997 vinfos[1].foffset = j1;
14998 vinfos[1].indices[0] = _ij1[0];
14999 vinfos[1].indices[1] = _ij1[1];
15000 vinfos[1].maxsolutions = _nj1;
15001 vinfos[2].jointtype = 1;
15002 vinfos[2].foffset = j2;
15003 vinfos[2].indices[0] = _ij2[0];
15004 vinfos[2].indices[1] = _ij2[1];
15005 vinfos[2].maxsolutions = _nj2;
15006 vinfos[3].jointtype = 1;
15007 vinfos[3].foffset = j3;
15008 vinfos[3].indices[0] = _ij3[0];
15009 vinfos[3].indices[1] = _ij3[1];
15010 vinfos[3].maxsolutions = _nj3;
15011 vinfos[4].jointtype = 1;
15012 vinfos[4].foffset = j4;
15013 vinfos[4].indices[0] = _ij4[0];
15014 vinfos[4].indices[1] = _ij4[1];
15015 vinfos[4].maxsolutions = _nj4;
15016 vinfos[5].jointtype = 1;
15017 vinfos[5].foffset = j5;
15018 vinfos[5].indices[0] = _ij5[0];
15019 vinfos[5].indices[1] = _ij5[1];
15020 vinfos[5].maxsolutions = _nj5;
15021 std::vector<int> vfree(0);
15022 solutions.AddSolution(vinfos,vfree);
15023 }
15024 }
15025 }
15026 
15027 }
15028 
15029 }
15030 
15031 } else
15032 {
15033 {
15034 IkReal j1array[1], cj1array[1], sj1array[1];
15035 bool j1valid[1]={false};
15036 _nj1 = 1;
15037 IkReal x4059=((cj5)*(sj4));
15038 IkReal x4060=((r21)*(sj4));
15039 IkReal x4061=((cj5)*(r21));
15040 IkReal x4062=((IkReal(0.707109999985348))*(cj2));
15041 IkReal x4063=((IkReal(0.707103562373095))*(sj2));
15042 IkReal x4064=((IkReal(0.707109999985348))*(sj2));
15043 IkReal x4065=((cj4)*(r22));
15044 IkReal x4066=((IkReal(0.707103562373095))*(cj2));
15045 IkReal x4067=((r20)*(x4062));
15046 IkReal x4068=((sj5)*(x4066));
15047 IkReal x4069=((sj5)*(x4064));
15048 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(r20)*(x4068)))+(((IkReal(-1.00000000000000))*(x4061)*(x4066)))+(((x4061)*(x4064)))+(((x4059)*(x4067)))+(((IkReal(-1.00000000000000))*(x4063)*(x4065)))+(((IkReal(-1.00000000000000))*(sj5)*(x4060)*(x4063)))+(((IkReal(-1.00000000000000))*(sj5)*(x4060)*(x4062)))+(((r20)*(x4059)*(x4063)))+(((r20)*(x4069)))+(((IkReal(-1.00000000000000))*(x4062)*(x4065))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x4067)))+(((IkReal(-1.00000000000000))*(x4060)*(x4069)))+(((IkReal(-1.00000000000000))*(x4061)*(x4063)))+(((IkReal(-1.00000000000000))*(x4061)*(x4062)))+(((x4060)*(x4068)))+(((IkReal(-1.00000000000000))*(x4064)*(x4065)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4063)))+(((IkReal(-1.00000000000000))*(r20)*(x4059)*(x4066)))+(((r20)*(x4059)*(x4064)))+(((x4065)*(x4066))))))) < IKFAST_ATAN2_MAGTHRESH )
15049     continue;
15050 j1array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(r20)*(x4068)))+(((IkReal(-1.00000000000000))*(x4061)*(x4066)))+(((x4061)*(x4064)))+(((x4059)*(x4067)))+(((IkReal(-1.00000000000000))*(x4063)*(x4065)))+(((IkReal(-1.00000000000000))*(sj5)*(x4060)*(x4063)))+(((IkReal(-1.00000000000000))*(sj5)*(x4060)*(x4062)))+(((r20)*(x4059)*(x4063)))+(((r20)*(x4069)))+(((IkReal(-1.00000000000000))*(x4062)*(x4065)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x4067)))+(((IkReal(-1.00000000000000))*(x4060)*(x4069)))+(((IkReal(-1.00000000000000))*(x4061)*(x4063)))+(((IkReal(-1.00000000000000))*(x4061)*(x4062)))+(((x4060)*(x4068)))+(((IkReal(-1.00000000000000))*(x4064)*(x4065)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4063)))+(((IkReal(-1.00000000000000))*(r20)*(x4059)*(x4066)))+(((r20)*(x4059)*(x4064)))+(((x4065)*(x4066)))))));
15051 sj1array[0]=IKsin(j1array[0]);
15052 cj1array[0]=IKcos(j1array[0]);
15053 if( j1array[0] > IKPI )
15054 {
15055     j1array[0]-=IK2PI;
15056 }
15057 else if( j1array[0] < -IKPI )
15058 {    j1array[0]+=IK2PI;
15059 }
15060 j1valid[0] = true;
15061 for(int ij1 = 0; ij1 < 1; ++ij1)
15062 {
15063 if( !j1valid[ij1] )
15064 {
15065     continue;
15066 }
15067 _ij1[0] = ij1; _ij1[1] = -1;
15068 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15069 {
15070 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15071 {
15072     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15073 }
15074 }
15075 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15076 {
15077 IkReal evalcond[4];
15078 IkReal x4070=IKcos(j1);
15079 IkReal x4071=IKsin(j1);
15080 IkReal x4072=((IkReal(0.707109999985348))*(cj2));
15081 IkReal x4073=((IkReal(1.00000000000000))*(cj0));
15082 IkReal x4074=((IkReal(0.707109999985348))*(sj2));
15083 IkReal x4075=((cj5)*(sj4));
15084 IkReal x4076=((sj4)*(sj5));
15085 IkReal x4077=((IkReal(1.00000000000000))*(sj0));
15086 IkReal x4078=((sj5)*(x4077));
15087 IkReal x4079=((IkReal(0.707103562373095))*(x4070));
15088 IkReal x4080=((IkReal(0.707103562373095))*(x4071));
15089 IkReal x4081=((cj2)*(x4079));
15090 IkReal x4082=((x4071)*(x4072));
15091 IkReal x4083=((sj2)*(x4080));
15092 IkReal x4084=((x4070)*(x4074));
15093 IkReal x4085=((sj2)*(x4079));
15094 IkReal x4086=((cj2)*(x4080));
15095 IkReal x4087=((x4070)*(x4072));
15096 IkReal x4088=((x4071)*(x4074));
15097 IkReal x4089=((x4085)+(x4086)+(x4087));
15098 IkReal x4090=((x4082)+(x4083)+(x4084));
15099 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4088)))+(x4089)+(((r20)*(sj5))));
15100 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x4075)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x4081)))+(x4090)+(((r21)*(x4076))));
15101 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4078)))+(((IkReal(-1.00000000000000))*(x4090)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4073)))+(x4081)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4073)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4077))));
15102 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x4073)*(x4076)))+(((r10)*(sj0)*(x4075)))+(((cj0)*(r00)*(x4075)))+(((IkReal(-1.00000000000000))*(x4088)))+(x4089)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4077)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4073)))+(((IkReal(-1.00000000000000))*(r11)*(x4076)*(x4077))));
15103 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15104 {
15105 continue;
15106 }
15107 }
15108 
15109 {
15110 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15111 vinfos[0].jointtype = 1;
15112 vinfos[0].foffset = j0;
15113 vinfos[0].indices[0] = _ij0[0];
15114 vinfos[0].indices[1] = _ij0[1];
15115 vinfos[0].maxsolutions = _nj0;
15116 vinfos[1].jointtype = 1;
15117 vinfos[1].foffset = j1;
15118 vinfos[1].indices[0] = _ij1[0];
15119 vinfos[1].indices[1] = _ij1[1];
15120 vinfos[1].maxsolutions = _nj1;
15121 vinfos[2].jointtype = 1;
15122 vinfos[2].foffset = j2;
15123 vinfos[2].indices[0] = _ij2[0];
15124 vinfos[2].indices[1] = _ij2[1];
15125 vinfos[2].maxsolutions = _nj2;
15126 vinfos[3].jointtype = 1;
15127 vinfos[3].foffset = j3;
15128 vinfos[3].indices[0] = _ij3[0];
15129 vinfos[3].indices[1] = _ij3[1];
15130 vinfos[3].maxsolutions = _nj3;
15131 vinfos[4].jointtype = 1;
15132 vinfos[4].foffset = j4;
15133 vinfos[4].indices[0] = _ij4[0];
15134 vinfos[4].indices[1] = _ij4[1];
15135 vinfos[4].maxsolutions = _nj4;
15136 vinfos[5].jointtype = 1;
15137 vinfos[5].foffset = j5;
15138 vinfos[5].indices[0] = _ij5[0];
15139 vinfos[5].indices[1] = _ij5[1];
15140 vinfos[5].maxsolutions = _nj5;
15141 std::vector<int> vfree(0);
15142 solutions.AddSolution(vinfos,vfree);
15143 }
15144 }
15145 }
15146 
15147 }
15148 
15149 }
15150 
15151 } else
15152 {
15153 IkReal x4091=((sj0)*(sj4));
15154 IkReal x4092=((IkReal(1.00000000000000))*(r12));
15155 IkReal x4093=((cj0)*(cj4));
15156 IkReal x4094=((r01)*(sj5));
15157 IkReal x4095=((IkReal(1.00000000000000))*(cj5));
15158 IkReal x4096=((cj4)*(cj5));
15159 IkReal x4097=((IkReal(1.00000000000000))*(cj0));
15160 IkReal x4098=((cj4)*(sj0));
15161 IkReal x4099=((r00)*(sj0));
15162 IkReal x4100=((npy)*(sj5));
15163 IkReal x4101=((IkReal(1.00000000000000))*(cj4));
15164 IkReal x4102=((cj0)*(sj4));
15165 IkReal x4103=((r11)*(sj5));
15166 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
15167 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4095)))+(((sj5)*(x4099)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4097))));
15168 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4095)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2)))+(((sj4)*(x4100))));
15169 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
15170 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((npx)*(x4096)))+(((IkReal(-1.00000000000000))*(x4100)*(x4101))));
15171 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x4091)*(x4095)))+(((IkReal(-1.00000000000000))*(x4092)*(x4093)))+(((r02)*(x4098)))+(((x4091)*(x4094)))+(((IkReal(-1.00000000000000))*(sj4)*(x4097)*(x4103)))+(((cj5)*(r10)*(x4102))));
15172 evalcond[6]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x4094)*(x4098)))+(((IkReal(-1.00000000000000))*(x4092)*(x4102)))+(((x4093)*(x4103)))+(((r02)*(x4091)))+(((x4096)*(x4099)))+(((IkReal(-1.00000000000000))*(r10)*(x4093)*(x4095))));
15173 evalcond[7]=((((r20)*(x4096)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4101))));
15174 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4097)))+(((x4098)*(x4103)))+(((IkReal(-1.00000000000000))*(r00)*(x4093)*(x4095)))+(((IkReal(-1.00000000000000))*(x4091)*(x4092)))+(((x4093)*(x4094)))+(((IkReal(-1.00000000000000))*(r10)*(x4095)*(x4098))));
15175 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  )
15176 {
15177 {
15178 IkReal dummyeval[1];
15179 IkReal gconst44;
15180 gconst44=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
15181 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
15182 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15183 {
15184 {
15185 IkReal dummyeval[1];
15186 IkReal gconst45;
15187 gconst45=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
15188 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
15189 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15190 {
15191 continue;
15192 
15193 } else
15194 {
15195 {
15196 IkReal j1array[1], cj1array[1], sj1array[1];
15197 bool j1valid[1]={false};
15198 _nj1 = 1;
15199 IkReal x4104=((cj5)*(r11));
15200 IkReal x4105=((r10)*(sj0));
15201 IkReal x4106=((IkReal(0.707103562373095))*(cj2));
15202 IkReal x4107=((r20)*(sj5));
15203 IkReal x4108=((IkReal(0.707103562373095))*(sj2));
15204 IkReal x4109=((IkReal(0.707109999985348))*(cj2));
15205 IkReal x4110=((cj0)*(r00));
15206 IkReal x4111=((IkReal(0.707109999985348))*(sj2));
15207 IkReal x4112=((cj5)*(r21));
15208 IkReal x4113=((sj0)*(x4108));
15209 IkReal x4114=((sj5)*(x4109));
15210 IkReal x4115=((cj0)*(cj5)*(r01));
15211 if( IKabs(((gconst45)*(((((sj5)*(x4108)*(x4110)))+(((x4108)*(x4115)))+(((IkReal(-1.00000000000000))*(x4111)*(x4112)))+(((sj0)*(x4104)*(x4109)))+(((x4106)*(x4112)))+(((x4109)*(x4115)))+(((sj5)*(x4105)*(x4108)))+(((x4105)*(x4114)))+(((x4104)*(x4113)))+(((x4106)*(x4107)))+(((x4110)*(x4114)))+(((IkReal(-1.00000000000000))*(x4107)*(x4111))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((x4108)*(x4112)))+(((IkReal(-1.00000000000000))*(sj5)*(x4105)*(x4106)))+(((sj0)*(x4104)*(x4111)))+(((x4109)*(x4112)))+(((IkReal(-1.00000000000000))*(sj5)*(x4106)*(x4110)))+(((sj5)*(x4105)*(x4111)))+(((IkReal(-1.00000000000000))*(sj0)*(x4104)*(x4106)))+(((sj5)*(x4110)*(x4111)))+(((x4111)*(x4115)))+(((x4107)*(x4109)))+(((x4107)*(x4108)))+(((IkReal(-1.00000000000000))*(x4106)*(x4115))))))) < IKFAST_ATAN2_MAGTHRESH )
15212     continue;
15213 j1array[0]=IKatan2(((gconst45)*(((((sj5)*(x4108)*(x4110)))+(((x4108)*(x4115)))+(((IkReal(-1.00000000000000))*(x4111)*(x4112)))+(((sj0)*(x4104)*(x4109)))+(((x4106)*(x4112)))+(((x4109)*(x4115)))+(((sj5)*(x4105)*(x4108)))+(((x4105)*(x4114)))+(((x4104)*(x4113)))+(((x4106)*(x4107)))+(((x4110)*(x4114)))+(((IkReal(-1.00000000000000))*(x4107)*(x4111)))))), ((gconst45)*(((((x4108)*(x4112)))+(((IkReal(-1.00000000000000))*(sj5)*(x4105)*(x4106)))+(((sj0)*(x4104)*(x4111)))+(((x4109)*(x4112)))+(((IkReal(-1.00000000000000))*(sj5)*(x4106)*(x4110)))+(((sj5)*(x4105)*(x4111)))+(((IkReal(-1.00000000000000))*(sj0)*(x4104)*(x4106)))+(((sj5)*(x4110)*(x4111)))+(((x4111)*(x4115)))+(((x4107)*(x4109)))+(((x4107)*(x4108)))+(((IkReal(-1.00000000000000))*(x4106)*(x4115)))))));
15214 sj1array[0]=IKsin(j1array[0]);
15215 cj1array[0]=IKcos(j1array[0]);
15216 if( j1array[0] > IKPI )
15217 {
15218     j1array[0]-=IK2PI;
15219 }
15220 else if( j1array[0] < -IKPI )
15221 {    j1array[0]+=IK2PI;
15222 }
15223 j1valid[0] = true;
15224 for(int ij1 = 0; ij1 < 1; ++ij1)
15225 {
15226 if( !j1valid[ij1] )
15227 {
15228     continue;
15229 }
15230 _ij1[0] = ij1; _ij1[1] = -1;
15231 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15232 {
15233 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15234 {
15235     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15236 }
15237 }
15238 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15239 {
15240 IkReal evalcond[4];
15241 IkReal x4116=IKcos(j1);
15242 IkReal x4117=IKsin(j1);
15243 IkReal x4118=((IkReal(0.707109999985348))*(cj2));
15244 IkReal x4119=((IkReal(1.00000000000000))*(cj0));
15245 IkReal x4120=((IkReal(0.707109999985348))*(sj2));
15246 IkReal x4121=((cj5)*(sj4));
15247 IkReal x4122=((sj4)*(sj5));
15248 IkReal x4123=((IkReal(1.00000000000000))*(sj0));
15249 IkReal x4124=((sj5)*(x4123));
15250 IkReal x4125=((IkReal(0.707103562373095))*(x4116));
15251 IkReal x4126=((IkReal(0.707103562373095))*(x4117));
15252 IkReal x4127=((cj2)*(x4125));
15253 IkReal x4128=((x4117)*(x4118));
15254 IkReal x4129=((sj2)*(x4126));
15255 IkReal x4130=((x4116)*(x4120));
15256 IkReal x4131=((sj2)*(x4125));
15257 IkReal x4132=((cj2)*(x4126));
15258 IkReal x4133=((x4116)*(x4118));
15259 IkReal x4134=((x4117)*(x4120));
15260 IkReal x4135=((x4131)+(x4132)+(x4133));
15261 IkReal x4136=((x4129)+(x4128)+(x4130));
15262 evalcond[0]=((((cj5)*(r21)))+(x4135)+(((IkReal(-1.00000000000000))*(x4134)))+(((r20)*(sj5))));
15263 evalcond[1]=((((r21)*(x4122)))+(((IkReal(-1.00000000000000))*(r20)*(x4121)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x4127)))+(x4136));
15264 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4119)))+(((IkReal(-1.00000000000000))*(r10)*(x4124)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4123)))+(x4127)+(((IkReal(-1.00000000000000))*(x4136)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4119))));
15265 evalcond[3]=((((r10)*(sj0)*(x4121)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4119)))+(x4135)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4123)))+(((IkReal(-1.00000000000000))*(x4134)))+(((IkReal(-1.00000000000000))*(r11)*(x4122)*(x4123)))+(((cj0)*(r00)*(x4121)))+(((IkReal(-1.00000000000000))*(r01)*(x4119)*(x4122))));
15266 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15267 {
15268 continue;
15269 }
15270 }
15271 
15272 {
15273 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15274 vinfos[0].jointtype = 1;
15275 vinfos[0].foffset = j0;
15276 vinfos[0].indices[0] = _ij0[0];
15277 vinfos[0].indices[1] = _ij0[1];
15278 vinfos[0].maxsolutions = _nj0;
15279 vinfos[1].jointtype = 1;
15280 vinfos[1].foffset = j1;
15281 vinfos[1].indices[0] = _ij1[0];
15282 vinfos[1].indices[1] = _ij1[1];
15283 vinfos[1].maxsolutions = _nj1;
15284 vinfos[2].jointtype = 1;
15285 vinfos[2].foffset = j2;
15286 vinfos[2].indices[0] = _ij2[0];
15287 vinfos[2].indices[1] = _ij2[1];
15288 vinfos[2].maxsolutions = _nj2;
15289 vinfos[3].jointtype = 1;
15290 vinfos[3].foffset = j3;
15291 vinfos[3].indices[0] = _ij3[0];
15292 vinfos[3].indices[1] = _ij3[1];
15293 vinfos[3].maxsolutions = _nj3;
15294 vinfos[4].jointtype = 1;
15295 vinfos[4].foffset = j4;
15296 vinfos[4].indices[0] = _ij4[0];
15297 vinfos[4].indices[1] = _ij4[1];
15298 vinfos[4].maxsolutions = _nj4;
15299 vinfos[5].jointtype = 1;
15300 vinfos[5].foffset = j5;
15301 vinfos[5].indices[0] = _ij5[0];
15302 vinfos[5].indices[1] = _ij5[1];
15303 vinfos[5].maxsolutions = _nj5;
15304 std::vector<int> vfree(0);
15305 solutions.AddSolution(vinfos,vfree);
15306 }
15307 }
15308 }
15309 
15310 }
15311 
15312 }
15313 
15314 } else
15315 {
15316 {
15317 IkReal j1array[1], cj1array[1], sj1array[1];
15318 bool j1valid[1]={false};
15319 _nj1 = 1;
15320 IkReal x4137=((cj5)*(sj4));
15321 IkReal x4138=((r21)*(sj4));
15322 IkReal x4139=((cj5)*(r21));
15323 IkReal x4140=((IkReal(0.707109999985348))*(cj2));
15324 IkReal x4141=((IkReal(0.707103562373095))*(sj2));
15325 IkReal x4142=((IkReal(0.707109999985348))*(sj2));
15326 IkReal x4143=((cj4)*(r22));
15327 IkReal x4144=((IkReal(0.707103562373095))*(cj2));
15328 IkReal x4145=((r20)*(x4140));
15329 IkReal x4146=((sj5)*(x4144));
15330 IkReal x4147=((sj5)*(x4142));
15331 if( IKabs(((gconst44)*(((((x4137)*(x4145)))+(((x4139)*(x4142)))+(((IkReal(-1.00000000000000))*(x4141)*(x4143)))+(((IkReal(-1.00000000000000))*(x4140)*(x4143)))+(((IkReal(-1.00000000000000))*(sj5)*(x4138)*(x4140)))+(((IkReal(-1.00000000000000))*(sj5)*(x4138)*(x4141)))+(((IkReal(-1.00000000000000))*(x4139)*(x4144)))+(((r20)*(x4147)))+(((r20)*(x4137)*(x4141)))+(((IkReal(-1.00000000000000))*(r20)*(x4146))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((x4143)*(x4144)))+(((IkReal(-1.00000000000000))*(x4142)*(x4143)))+(((x4138)*(x4146)))+(((IkReal(-1.00000000000000))*(x4139)*(x4140)))+(((IkReal(-1.00000000000000))*(x4139)*(x4141)))+(((IkReal(-1.00000000000000))*(x4138)*(x4147)))+(((IkReal(-1.00000000000000))*(sj5)*(x4145)))+(((IkReal(-1.00000000000000))*(r20)*(x4137)*(x4144)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4141)))+(((r20)*(x4137)*(x4142))))))) < IKFAST_ATAN2_MAGTHRESH )
15332     continue;
15333 j1array[0]=IKatan2(((gconst44)*(((((x4137)*(x4145)))+(((x4139)*(x4142)))+(((IkReal(-1.00000000000000))*(x4141)*(x4143)))+(((IkReal(-1.00000000000000))*(x4140)*(x4143)))+(((IkReal(-1.00000000000000))*(sj5)*(x4138)*(x4140)))+(((IkReal(-1.00000000000000))*(sj5)*(x4138)*(x4141)))+(((IkReal(-1.00000000000000))*(x4139)*(x4144)))+(((r20)*(x4147)))+(((r20)*(x4137)*(x4141)))+(((IkReal(-1.00000000000000))*(r20)*(x4146)))))), ((gconst44)*(((((x4143)*(x4144)))+(((IkReal(-1.00000000000000))*(x4142)*(x4143)))+(((x4138)*(x4146)))+(((IkReal(-1.00000000000000))*(x4139)*(x4140)))+(((IkReal(-1.00000000000000))*(x4139)*(x4141)))+(((IkReal(-1.00000000000000))*(x4138)*(x4147)))+(((IkReal(-1.00000000000000))*(sj5)*(x4145)))+(((IkReal(-1.00000000000000))*(r20)*(x4137)*(x4144)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4141)))+(((r20)*(x4137)*(x4142)))))));
15334 sj1array[0]=IKsin(j1array[0]);
15335 cj1array[0]=IKcos(j1array[0]);
15336 if( j1array[0] > IKPI )
15337 {
15338     j1array[0]-=IK2PI;
15339 }
15340 else if( j1array[0] < -IKPI )
15341 {    j1array[0]+=IK2PI;
15342 }
15343 j1valid[0] = true;
15344 for(int ij1 = 0; ij1 < 1; ++ij1)
15345 {
15346 if( !j1valid[ij1] )
15347 {
15348     continue;
15349 }
15350 _ij1[0] = ij1; _ij1[1] = -1;
15351 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15352 {
15353 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15354 {
15355     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15356 }
15357 }
15358 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15359 {
15360 IkReal evalcond[4];
15361 IkReal x4148=IKcos(j1);
15362 IkReal x4149=IKsin(j1);
15363 IkReal x4150=((IkReal(0.707109999985348))*(cj2));
15364 IkReal x4151=((IkReal(1.00000000000000))*(cj0));
15365 IkReal x4152=((IkReal(0.707109999985348))*(sj2));
15366 IkReal x4153=((cj5)*(sj4));
15367 IkReal x4154=((sj4)*(sj5));
15368 IkReal x4155=((IkReal(1.00000000000000))*(sj0));
15369 IkReal x4156=((sj5)*(x4155));
15370 IkReal x4157=((IkReal(0.707103562373095))*(x4148));
15371 IkReal x4158=((IkReal(0.707103562373095))*(x4149));
15372 IkReal x4159=((cj2)*(x4157));
15373 IkReal x4160=((x4149)*(x4150));
15374 IkReal x4161=((sj2)*(x4158));
15375 IkReal x4162=((x4148)*(x4152));
15376 IkReal x4163=((sj2)*(x4157));
15377 IkReal x4164=((cj2)*(x4158));
15378 IkReal x4165=((x4148)*(x4150));
15379 IkReal x4166=((x4149)*(x4152));
15380 IkReal x4167=((x4165)+(x4164)+(x4163));
15381 IkReal x4168=((x4162)+(x4161)+(x4160));
15382 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4166)))+(x4167)+(((r20)*(sj5))));
15383 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x4154)))+(x4168)+(((IkReal(-1.00000000000000))*(r20)*(x4153)))+(((IkReal(-1.00000000000000))*(x4159))));
15384 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4155)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4151)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4151)))+(((IkReal(-1.00000000000000))*(x4168)))+(x4159)+(((IkReal(-1.00000000000000))*(r10)*(x4156))));
15385 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x4151)*(x4154)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4155)))+(((IkReal(-1.00000000000000))*(x4166)))+(x4167)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4151)))+(((cj0)*(r00)*(x4153)))+(((IkReal(-1.00000000000000))*(r11)*(x4154)*(x4155)))+(((r10)*(sj0)*(x4153))));
15386 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15387 {
15388 continue;
15389 }
15390 }
15391 
15392 {
15393 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15394 vinfos[0].jointtype = 1;
15395 vinfos[0].foffset = j0;
15396 vinfos[0].indices[0] = _ij0[0];
15397 vinfos[0].indices[1] = _ij0[1];
15398 vinfos[0].maxsolutions = _nj0;
15399 vinfos[1].jointtype = 1;
15400 vinfos[1].foffset = j1;
15401 vinfos[1].indices[0] = _ij1[0];
15402 vinfos[1].indices[1] = _ij1[1];
15403 vinfos[1].maxsolutions = _nj1;
15404 vinfos[2].jointtype = 1;
15405 vinfos[2].foffset = j2;
15406 vinfos[2].indices[0] = _ij2[0];
15407 vinfos[2].indices[1] = _ij2[1];
15408 vinfos[2].maxsolutions = _nj2;
15409 vinfos[3].jointtype = 1;
15410 vinfos[3].foffset = j3;
15411 vinfos[3].indices[0] = _ij3[0];
15412 vinfos[3].indices[1] = _ij3[1];
15413 vinfos[3].maxsolutions = _nj3;
15414 vinfos[4].jointtype = 1;
15415 vinfos[4].foffset = j4;
15416 vinfos[4].indices[0] = _ij4[0];
15417 vinfos[4].indices[1] = _ij4[1];
15418 vinfos[4].maxsolutions = _nj4;
15419 vinfos[5].jointtype = 1;
15420 vinfos[5].foffset = j5;
15421 vinfos[5].indices[0] = _ij5[0];
15422 vinfos[5].indices[1] = _ij5[1];
15423 vinfos[5].maxsolutions = _nj5;
15424 std::vector<int> vfree(0);
15425 solutions.AddSolution(vinfos,vfree);
15426 }
15427 }
15428 }
15429 
15430 }
15431 
15432 }
15433 
15434 } else
15435 {
15436 if( 1 )
15437 {
15438 continue;
15439 
15440 } else
15441 {
15442 }
15443 }
15444 }
15445 }
15446 }
15447 }
15448 
15449 } else
15450 {
15451 {
15452 IkReal j1array[1], cj1array[1], sj1array[1];
15453 bool j1valid[1]={false};
15454 _nj1 = 1;
15455 IkReal x4169=((IkReal(0.707109999985348))*(sj2));
15456 IkReal x4170=((r22)*(sj4));
15457 IkReal x4171=((cj5)*(r20));
15458 IkReal x4172=((r21)*(sj5));
15459 IkReal x4173=((IkReal(0.707109999985348))*(cj2));
15460 IkReal x4174=((cj3)*(r22));
15461 IkReal x4175=((cj3)*(sj4));
15462 IkReal x4176=((IkReal(0.707103562373095))*(cj4)*(sj2));
15463 IkReal x4177=((IkReal(0.707103562373095))*(x4175));
15464 IkReal x4178=((IkReal(0.707103562373095))*(cj2)*(cj4));
15465 if( IKabs(((gconst37)*(((((sj2)*(x4172)*(x4177)))+(((IkReal(-1.00000000000000))*(sj2)*(x4171)*(x4177)))+(((IkReal(0.707103562373095))*(cj2)*(x4170)))+(((IkReal(-1.00000000000000))*(x4171)*(x4173)*(x4175)))+(((IkReal(-1.00000000000000))*(x4172)*(x4178)))+(((IkReal(-1.00000000000000))*(cj4)*(x4169)*(x4171)))+(((cj4)*(x4169)*(x4172)))+(((IkReal(-1.00000000000000))*(x4169)*(x4170)))+(((x4171)*(x4178)))+(((x4172)*(x4173)*(x4175)))+(((cj4)*(x4173)*(x4174)))+(((x4174)*(x4176))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((x4169)*(x4172)*(x4175)))+(((IkReal(-1.00000000000000))*(cj4)*(x4172)*(x4173)))+(((IkReal(-1.00000000000000))*(x4169)*(x4171)*(x4175)))+(((IkReal(-1.00000000000000))*(x4172)*(x4176)))+(((IkReal(0.707103562373095))*(sj2)*(x4170)))+(((x4170)*(x4173)))+(((cj4)*(x4169)*(x4174)))+(((IkReal(-1.00000000000000))*(x4174)*(x4178)))+(((x4171)*(x4176)))+(((cj4)*(x4171)*(x4173)))+(((cj2)*(x4171)*(x4177)))+(((IkReal(-1.00000000000000))*(cj2)*(x4172)*(x4177))))))) < IKFAST_ATAN2_MAGTHRESH )
15466     continue;
15467 j1array[0]=IKatan2(((gconst37)*(((((sj2)*(x4172)*(x4177)))+(((IkReal(-1.00000000000000))*(sj2)*(x4171)*(x4177)))+(((IkReal(0.707103562373095))*(cj2)*(x4170)))+(((IkReal(-1.00000000000000))*(x4171)*(x4173)*(x4175)))+(((IkReal(-1.00000000000000))*(x4172)*(x4178)))+(((IkReal(-1.00000000000000))*(cj4)*(x4169)*(x4171)))+(((cj4)*(x4169)*(x4172)))+(((IkReal(-1.00000000000000))*(x4169)*(x4170)))+(((x4171)*(x4178)))+(((x4172)*(x4173)*(x4175)))+(((cj4)*(x4173)*(x4174)))+(((x4174)*(x4176)))))), ((gconst37)*(((((x4169)*(x4172)*(x4175)))+(((IkReal(-1.00000000000000))*(cj4)*(x4172)*(x4173)))+(((IkReal(-1.00000000000000))*(x4169)*(x4171)*(x4175)))+(((IkReal(-1.00000000000000))*(x4172)*(x4176)))+(((IkReal(0.707103562373095))*(sj2)*(x4170)))+(((x4170)*(x4173)))+(((cj4)*(x4169)*(x4174)))+(((IkReal(-1.00000000000000))*(x4174)*(x4178)))+(((x4171)*(x4176)))+(((cj4)*(x4171)*(x4173)))+(((cj2)*(x4171)*(x4177)))+(((IkReal(-1.00000000000000))*(cj2)*(x4172)*(x4177)))))));
15468 sj1array[0]=IKsin(j1array[0]);
15469 cj1array[0]=IKcos(j1array[0]);
15470 if( j1array[0] > IKPI )
15471 {
15472     j1array[0]-=IK2PI;
15473 }
15474 else if( j1array[0] < -IKPI )
15475 {    j1array[0]+=IK2PI;
15476 }
15477 j1valid[0] = true;
15478 for(int ij1 = 0; ij1 < 1; ++ij1)
15479 {
15480 if( !j1valid[ij1] )
15481 {
15482     continue;
15483 }
15484 _ij1[0] = ij1; _ij1[1] = -1;
15485 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15486 {
15487 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15488 {
15489     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15490 }
15491 }
15492 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15493 {
15494 IkReal evalcond[6];
15495 IkReal x4179=IKcos(j1);
15496 IkReal x4180=IKsin(j1);
15497 IkReal x4181=((cj0)*(cj4));
15498 IkReal x4182=((r01)*(sj5));
15499 IkReal x4183=((IkReal(1.00000000000000))*(cj4));
15500 IkReal x4184=((IkReal(1.00000000000000))*(r02));
15501 IkReal x4185=((IkReal(0.707109999985348))*(sj3));
15502 IkReal x4186=((IkReal(0.707103562373095))*(sj3));
15503 IkReal x4187=((IkReal(1.00000000000000))*(sj4));
15504 IkReal x4188=((cj5)*(r20));
15505 IkReal x4189=((cj5)*(sj0));
15506 IkReal x4190=((IkReal(1.00000000000000))*(cj0));
15507 IkReal x4191=((r12)*(sj0));
15508 IkReal x4192=((cj2)*(cj3));
15509 IkReal x4193=((IkReal(0.707103562373095))*(cj3));
15510 IkReal x4194=((r21)*(sj5));
15511 IkReal x4195=((IkReal(0.707109999985348))*(cj3));
15512 IkReal x4196=((IkReal(1.00000000000000))*(sj0)*(sj5));
15513 IkReal x4197=((sj2)*(x4179));
15514 IkReal x4198=((cj2)*(x4179));
15515 IkReal x4199=((cj0)*(cj5)*(r00));
15516 IkReal x4200=((IkReal(0.707103562373095))*(x4180));
15517 IkReal x4201=((cj2)*(x4180));
15518 IkReal x4202=((IkReal(0.707109999985348))*(sj2)*(x4180));
15519 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4186)*(x4201)))+(((IkReal(-1.00000000000000))*(x4186)*(x4197)))+(((IkReal(-1.00000000000000))*(x4185)*(x4198)))+(((r20)*(sj5)))+(((sj2)*(x4180)*(x4185))));
15520 evalcond[1]=((((cj4)*(r22)))+(((sj2)*(x4200)))+(((IkReal(-1.00000000000000))*(x4187)*(x4188)))+(((IkReal(-0.707103562373095))*(x4198)))+(((IkReal(0.707109999985348))*(x4201)))+(((sj4)*(x4194)))+(((IkReal(0.707109999985348))*(x4197))));
15521 evalcond[2]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x4180)*(x4195)))+(((x4193)*(x4197)))+(((x4192)*(x4200)))+(((cj4)*(x4188)))+(((IkReal(0.707109999985348))*(x4179)*(x4192)))+(((IkReal(-1.00000000000000))*(x4183)*(x4194))));
15522 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x4189)))+(((IkReal(-1.00000000000000))*(x4186)*(x4198)))+(((x4185)*(x4201)))+(((x4185)*(x4197)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4190)))+(((IkReal(-1.00000000000000))*(r10)*(x4196)))+(((sj2)*(x4180)*(x4186)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4190))));
15523 evalcond[4]=((((IkReal(-1.00000000000000))*(x4181)*(x4184)))+(((IkReal(-1.00000000000000))*(cj0)*(x4182)*(x4187)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x4187)))+(((IkReal(-1.00000000000000))*(x4202)))+(((IkReal(0.707103562373095))*(x4197)))+(((cj2)*(x4200)))+(((sj4)*(x4199)))+(((r10)*(sj4)*(x4189)))+(((IkReal(-1.00000000000000))*(x4183)*(x4191)))+(((IkReal(0.707109999985348))*(x4198))));
15524 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x4184)))+(((IkReal(-1.00000000000000))*(x4195)*(x4197)))+(((IkReal(-1.00000000000000))*(r10)*(x4183)*(x4189)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4181)))+(((IkReal(-1.00000000000000))*(sj2)*(x4180)*(x4193)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x4187)*(x4191)))+(((IkReal(0.707103562373095))*(x4179)*(x4192)))+(((IkReal(-0.707109999985348))*(x4180)*(x4192)))+(((x4181)*(x4182))));
15525 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  )
15526 {
15527 continue;
15528 }
15529 }
15530 
15531 {
15532 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15533 vinfos[0].jointtype = 1;
15534 vinfos[0].foffset = j0;
15535 vinfos[0].indices[0] = _ij0[0];
15536 vinfos[0].indices[1] = _ij0[1];
15537 vinfos[0].maxsolutions = _nj0;
15538 vinfos[1].jointtype = 1;
15539 vinfos[1].foffset = j1;
15540 vinfos[1].indices[0] = _ij1[0];
15541 vinfos[1].indices[1] = _ij1[1];
15542 vinfos[1].maxsolutions = _nj1;
15543 vinfos[2].jointtype = 1;
15544 vinfos[2].foffset = j2;
15545 vinfos[2].indices[0] = _ij2[0];
15546 vinfos[2].indices[1] = _ij2[1];
15547 vinfos[2].maxsolutions = _nj2;
15548 vinfos[3].jointtype = 1;
15549 vinfos[3].foffset = j3;
15550 vinfos[3].indices[0] = _ij3[0];
15551 vinfos[3].indices[1] = _ij3[1];
15552 vinfos[3].maxsolutions = _nj3;
15553 vinfos[4].jointtype = 1;
15554 vinfos[4].foffset = j4;
15555 vinfos[4].indices[0] = _ij4[0];
15556 vinfos[4].indices[1] = _ij4[1];
15557 vinfos[4].maxsolutions = _nj4;
15558 vinfos[5].jointtype = 1;
15559 vinfos[5].foffset = j5;
15560 vinfos[5].indices[0] = _ij5[0];
15561 vinfos[5].indices[1] = _ij5[1];
15562 vinfos[5].maxsolutions = _nj5;
15563 std::vector<int> vfree(0);
15564 solutions.AddSolution(vinfos,vfree);
15565 }
15566 }
15567 }
15568 
15569 }
15570 
15571 }
15572 
15573 } else
15574 {
15575 {
15576 IkReal j1array[1], cj1array[1], sj1array[1];
15577 bool j1valid[1]={false};
15578 _nj1 = 1;
15579 IkReal x4203=((sj2)*(sj3));
15580 IkReal x4204=((cj4)*(r22));
15581 IkReal x4205=((r20)*(sj5));
15582 IkReal x4206=((IkReal(0.707103562373095))*(cj2));
15583 IkReal x4207=((IkReal(0.707109999985348))*(sj2));
15584 IkReal x4208=((IkReal(0.707109999985348))*(cj2));
15585 IkReal x4209=((cj5)*(r21));
15586 IkReal x4210=((IkReal(0.707103562373095))*(sj2));
15587 IkReal x4211=((r21)*(sj4)*(sj5));
15588 IkReal x4212=((cj5)*(r20)*(sj4));
15589 if( IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(x4206)*(x4209)))+(((x4205)*(x4207)))+(((IkReal(0.707103562373095))*(x4203)*(x4204)))+(((IkReal(0.707103562373095))*(x4203)*(x4211)))+(((sj3)*(x4208)*(x4211)))+(((IkReal(-1.00000000000000))*(sj3)*(x4208)*(x4212)))+(((x4207)*(x4209)))+(((sj3)*(x4204)*(x4208)))+(((IkReal(-0.707103562373095))*(x4203)*(x4212)))+(((IkReal(-1.00000000000000))*(x4205)*(x4206))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((sj3)*(x4206)*(x4212)))+(((IkReal(-1.00000000000000))*(x4208)*(x4209)))+(((IkReal(-0.707109999985348))*(x4203)*(x4212)))+(((IkReal(-1.00000000000000))*(x4205)*(x4210)))+(((IkReal(0.707109999985348))*(x4203)*(x4204)))+(((IkReal(-1.00000000000000))*(sj3)*(x4206)*(x4211)))+(((IkReal(0.707109999985348))*(x4203)*(x4211)))+(((IkReal(-1.00000000000000))*(x4205)*(x4208)))+(((IkReal(-1.00000000000000))*(sj3)*(x4204)*(x4206)))+(((IkReal(-1.00000000000000))*(x4209)*(x4210))))))) < IKFAST_ATAN2_MAGTHRESH )
15590     continue;
15591 j1array[0]=IKatan2(((gconst36)*(((((IkReal(-1.00000000000000))*(x4206)*(x4209)))+(((x4205)*(x4207)))+(((IkReal(0.707103562373095))*(x4203)*(x4204)))+(((IkReal(0.707103562373095))*(x4203)*(x4211)))+(((sj3)*(x4208)*(x4211)))+(((IkReal(-1.00000000000000))*(sj3)*(x4208)*(x4212)))+(((x4207)*(x4209)))+(((sj3)*(x4204)*(x4208)))+(((IkReal(-0.707103562373095))*(x4203)*(x4212)))+(((IkReal(-1.00000000000000))*(x4205)*(x4206)))))), ((gconst36)*(((((sj3)*(x4206)*(x4212)))+(((IkReal(-1.00000000000000))*(x4208)*(x4209)))+(((IkReal(-0.707109999985348))*(x4203)*(x4212)))+(((IkReal(-1.00000000000000))*(x4205)*(x4210)))+(((IkReal(0.707109999985348))*(x4203)*(x4204)))+(((IkReal(-1.00000000000000))*(sj3)*(x4206)*(x4211)))+(((IkReal(0.707109999985348))*(x4203)*(x4211)))+(((IkReal(-1.00000000000000))*(x4205)*(x4208)))+(((IkReal(-1.00000000000000))*(sj3)*(x4204)*(x4206)))+(((IkReal(-1.00000000000000))*(x4209)*(x4210)))))));
15592 sj1array[0]=IKsin(j1array[0]);
15593 cj1array[0]=IKcos(j1array[0]);
15594 if( j1array[0] > IKPI )
15595 {
15596     j1array[0]-=IK2PI;
15597 }
15598 else if( j1array[0] < -IKPI )
15599 {    j1array[0]+=IK2PI;
15600 }
15601 j1valid[0] = true;
15602 for(int ij1 = 0; ij1 < 1; ++ij1)
15603 {
15604 if( !j1valid[ij1] )
15605 {
15606     continue;
15607 }
15608 _ij1[0] = ij1; _ij1[1] = -1;
15609 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15610 {
15611 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15612 {
15613     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15614 }
15615 }
15616 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15617 {
15618 IkReal evalcond[6];
15619 IkReal x4213=IKcos(j1);
15620 IkReal x4214=IKsin(j1);
15621 IkReal x4215=((cj0)*(cj4));
15622 IkReal x4216=((r01)*(sj5));
15623 IkReal x4217=((IkReal(1.00000000000000))*(cj4));
15624 IkReal x4218=((IkReal(1.00000000000000))*(r02));
15625 IkReal x4219=((IkReal(0.707109999985348))*(sj3));
15626 IkReal x4220=((IkReal(0.707103562373095))*(sj3));
15627 IkReal x4221=((IkReal(1.00000000000000))*(sj4));
15628 IkReal x4222=((cj5)*(r20));
15629 IkReal x4223=((cj5)*(sj0));
15630 IkReal x4224=((IkReal(1.00000000000000))*(cj0));
15631 IkReal x4225=((r12)*(sj0));
15632 IkReal x4226=((cj2)*(cj3));
15633 IkReal x4227=((IkReal(0.707103562373095))*(cj3));
15634 IkReal x4228=((r21)*(sj5));
15635 IkReal x4229=((IkReal(0.707109999985348))*(cj3));
15636 IkReal x4230=((IkReal(1.00000000000000))*(sj0)*(sj5));
15637 IkReal x4231=((sj2)*(x4213));
15638 IkReal x4232=((cj2)*(x4213));
15639 IkReal x4233=((cj0)*(cj5)*(r00));
15640 IkReal x4234=((IkReal(0.707103562373095))*(x4214));
15641 IkReal x4235=((cj2)*(x4214));
15642 IkReal x4236=((IkReal(0.707109999985348))*(sj2)*(x4214));
15643 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4219)*(x4232)))+(((r20)*(sj5)))+(((sj2)*(x4214)*(x4219)))+(((IkReal(-1.00000000000000))*(x4220)*(x4231)))+(((IkReal(-1.00000000000000))*(x4220)*(x4235))));
15644 evalcond[1]=((((cj4)*(r22)))+(((sj4)*(x4228)))+(((IkReal(0.707109999985348))*(x4231)))+(((IkReal(0.707109999985348))*(x4235)))+(((IkReal(-1.00000000000000))*(x4221)*(x4222)))+(((sj2)*(x4234)))+(((IkReal(-0.707103562373095))*(x4232))));
15645 evalcond[2]=((((r22)*(sj4)))+(((IkReal(0.707109999985348))*(x4213)*(x4226)))+(((x4227)*(x4231)))+(((x4226)*(x4234)))+(((IkReal(-1.00000000000000))*(x4217)*(x4228)))+(((IkReal(-1.00000000000000))*(sj2)*(x4214)*(x4229)))+(((cj4)*(x4222))));
15646 evalcond[3]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4224)))+(((IkReal(-1.00000000000000))*(r11)*(x4223)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4224)))+(((IkReal(-1.00000000000000))*(r10)*(x4230)))+(((sj2)*(x4214)*(x4220)))+(((x4219)*(x4231)))+(((x4219)*(x4235)))+(((IkReal(-1.00000000000000))*(x4220)*(x4232))));
15647 evalcond[4]=((((IkReal(-1.00000000000000))*(x4236)))+(((sj4)*(x4233)))+(((IkReal(0.707103562373095))*(x4231)))+(((IkReal(0.707109999985348))*(x4232)))+(((IkReal(-1.00000000000000))*(cj0)*(x4216)*(x4221)))+(((cj2)*(x4234)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x4221)))+(((IkReal(-1.00000000000000))*(x4217)*(x4225)))+(((IkReal(-1.00000000000000))*(x4215)*(x4218)))+(((r10)*(sj4)*(x4223))));
15648 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4215)))+(((IkReal(-0.707109999985348))*(x4214)*(x4226)))+(((IkReal(0.707103562373095))*(x4213)*(x4226)))+(((x4215)*(x4216)))+(((IkReal(-1.00000000000000))*(x4221)*(x4225)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(x4229)*(x4231)))+(((IkReal(-1.00000000000000))*(r10)*(x4217)*(x4223)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x4218)))+(((IkReal(-1.00000000000000))*(sj2)*(x4214)*(x4227))));
15649 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  )
15650 {
15651 continue;
15652 }
15653 }
15654 
15655 {
15656 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15657 vinfos[0].jointtype = 1;
15658 vinfos[0].foffset = j0;
15659 vinfos[0].indices[0] = _ij0[0];
15660 vinfos[0].indices[1] = _ij0[1];
15661 vinfos[0].maxsolutions = _nj0;
15662 vinfos[1].jointtype = 1;
15663 vinfos[1].foffset = j1;
15664 vinfos[1].indices[0] = _ij1[0];
15665 vinfos[1].indices[1] = _ij1[1];
15666 vinfos[1].maxsolutions = _nj1;
15667 vinfos[2].jointtype = 1;
15668 vinfos[2].foffset = j2;
15669 vinfos[2].indices[0] = _ij2[0];
15670 vinfos[2].indices[1] = _ij2[1];
15671 vinfos[2].maxsolutions = _nj2;
15672 vinfos[3].jointtype = 1;
15673 vinfos[3].foffset = j3;
15674 vinfos[3].indices[0] = _ij3[0];
15675 vinfos[3].indices[1] = _ij3[1];
15676 vinfos[3].maxsolutions = _nj3;
15677 vinfos[4].jointtype = 1;
15678 vinfos[4].foffset = j4;
15679 vinfos[4].indices[0] = _ij4[0];
15680 vinfos[4].indices[1] = _ij4[1];
15681 vinfos[4].maxsolutions = _nj4;
15682 vinfos[5].jointtype = 1;
15683 vinfos[5].foffset = j5;
15684 vinfos[5].indices[0] = _ij5[0];
15685 vinfos[5].indices[1] = _ij5[1];
15686 vinfos[5].maxsolutions = _nj5;
15687 std::vector<int> vfree(0);
15688 solutions.AddSolution(vinfos,vfree);
15689 }
15690 }
15691 }
15692 
15693 }
15694 
15695 }
15696 }
15697 }
15698 
15699 }
15700 
15701 }
15702 
15703 } else
15704 {
15705 {
15706 IkReal j2array[1], cj2array[1], sj2array[1];
15707 bool j2valid[1]={false};
15708 _nj2 = 1;
15709 IkReal x4237=((cj5)*(npy));
15710 IkReal x4238=((IkReal(8.66210554726807e+23))*(npx));
15711 IkReal x4239=((IkReal(6.89439331452234e+23))*(npx));
15712 IkReal x4240=((IkReal(8.66210554726807e+23))*(sj3));
15713 IkReal x4241=((cj4)*(npz));
15714 IkReal x4242=((IkReal(6.89439331452234e+23))*(sj3));
15715 IkReal x4243=((cj5)*(sj3)*(sj4));
15716 IkReal x4244=((npy)*(sj4)*(sj5));
15717 if( IKabs(((gconst34)*(((IkReal(-5.19726332836084e+21))+(((IkReal(-1.00000000000000))*(x4241)*(x4242)))+(((IkReal(8.66210554726807e+23))*(x4237)))+(((x4239)*(x4243)))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((sj5)*(x4238)))+(((IkReal(-1.00000000000000))*(x4242)*(x4244))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((IkReal(-4.13663598871341e+21))+(((x4240)*(x4244)))+(((x4240)*(x4241)))+(((IkReal(6.89439331452234e+23))*(x4237)))+(((IkReal(-1.00000000000000))*(x4238)*(x4243)))+(((sj5)*(x4239)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3))))))) < IKFAST_ATAN2_MAGTHRESH )
15718     continue;
15719 j2array[0]=IKatan2(((gconst34)*(((IkReal(-5.19726332836084e+21))+(((IkReal(-1.00000000000000))*(x4241)*(x4242)))+(((IkReal(8.66210554726807e+23))*(x4237)))+(((x4239)*(x4243)))+(((IkReal(-5.19726332836084e+21))*(cj3)))+(((IkReal(1.51888207091656e+23))*(sj3)))+(((sj5)*(x4238)))+(((IkReal(-1.00000000000000))*(x4242)*(x4244)))))), ((gconst34)*(((IkReal(-4.13663598871341e+21))+(((x4240)*(x4244)))+(((x4240)*(x4241)))+(((IkReal(6.89439331452234e+23))*(x4237)))+(((IkReal(-1.00000000000000))*(x4238)*(x4243)))+(((sj5)*(x4239)))+(((IkReal(-2.44170809699545e+23))*(sj3)))+(((IkReal(-4.13663598871341e+21))*(cj3)))))));
15720 sj2array[0]=IKsin(j2array[0]);
15721 cj2array[0]=IKcos(j2array[0]);
15722 if( j2array[0] > IKPI )
15723 {
15724     j2array[0]-=IK2PI;
15725 }
15726 else if( j2array[0] < -IKPI )
15727 {    j2array[0]+=IK2PI;
15728 }
15729 j2valid[0] = true;
15730 for(int ij2 = 0; ij2 < 1; ++ij2)
15731 {
15732 if( !j2valid[ij2] )
15733 {
15734     continue;
15735 }
15736 _ij2[0] = ij2; _ij2[1] = -1;
15737 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
15738 {
15739 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
15740 {
15741     j2valid[iij2]=false; _ij2[1] = iij2; break; 
15742 }
15743 }
15744 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
15745 {
15746 IkReal evalcond[3];
15747 IkReal x4245=IKsin(j2);
15748 IkReal x4246=IKcos(j2);
15749 IkReal x4247=((cj5)*(npx));
15750 IkReal x4248=((npy)*(sj5));
15751 IkReal x4249=((IkReal(0.165463933124939))*(x4246));
15752 IkReal x4250=((IkReal(0.207888640466058))*(x4245));
15753 evalcond[0]=((IkReal(-0.258003287011922))+(((sj4)*(x4248)))+(((IkReal(-1.00000000000000))*(sj4)*(x4247)))+(((IkReal(0.165463933124939))*(x4245)))+(((cj4)*(npz)))+(((IkReal(-0.207888640466058))*(x4246))));
15754 evalcond[1]=((IkReal(-0.00600000000000000))+(((IkReal(-0.0300035672348961))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x4250)))+(((npx)*(sj5)))+(((IkReal(-0.00600000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x4249)))+(((cj5)*(npy))));
15755 evalcond[2]=((((cj3)*(x4250)))+(((cj4)*(x4247)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(x4248)))+(((IkReal(-0.00600000000000000))*(sj3)))+(((cj3)*(x4249)))+(((IkReal(0.0300035672348961))*(cj3))));
15756 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
15757 {
15758 continue;
15759 }
15760 }
15761 
15762 {
15763 IkReal dummyeval[1];
15764 IkReal gconst36;
15765 IkReal x4251=((IkReal(1.00000000000000))*(sj3));
15766 gconst36=IKsign(((((IkReal(-1.00000000000000))*(x4251)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x4251)*((sj2)*(sj2))))));
15767 IkReal x4252=((IkReal(1.00000000000000))*(sj3));
15768 dummyeval[0]=((((IkReal(-1.00000000000000))*(x4252)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x4252)*((sj2)*(sj2)))));
15769 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15770 {
15771 {
15772 IkReal dummyeval[1];
15773 IkReal gconst37;
15774 IkReal x4253=((IkReal(1.00000000000000))*(cj3));
15775 gconst37=IKsign(((((IkReal(-1.00000000000000))*(x4253)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x4253)*((cj2)*(cj2))))));
15776 IkReal x4254=((IkReal(1.00000000000000))*(cj3));
15777 dummyeval[0]=((((IkReal(-1.00000000000000))*(x4254)*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*(x4254)*((sj2)*(sj2)))));
15778 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15779 {
15780 {
15781 IkReal evalcond[9];
15782 IkReal x4255=((sj0)*(sj4));
15783 IkReal x4256=((IkReal(1.00000000000000))*(r12));
15784 IkReal x4257=((cj0)*(cj4));
15785 IkReal x4258=((r01)*(sj5));
15786 IkReal x4259=((IkReal(1.00000000000000))*(cj5));
15787 IkReal x4260=((cj4)*(cj5));
15788 IkReal x4261=((IkReal(1.00000000000000))*(cj0));
15789 IkReal x4262=((cj4)*(sj0));
15790 IkReal x4263=((r00)*(sj0));
15791 IkReal x4264=((npy)*(sj5));
15792 IkReal x4265=((IkReal(1.00000000000000))*(cj4));
15793 IkReal x4266=((cj0)*(sj4));
15794 IkReal x4267=((r11)*(sj5));
15795 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
15796 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4259)))+(((sj5)*(x4263)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4261))));
15797 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4259)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x4264)))+(((IkReal(0.165463933124939))*(sj2))));
15798 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
15799 evalcond[4]=((IkReal(-0.00600000000000000))+(((IkReal(-1.00000000000000))*(x4264)*(x4265)))+(((npz)*(sj4)))+(((npx)*(x4260))));
15800 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x4261)*(x4267)))+(((cj5)*(r10)*(x4266)))+(((r02)*(x4262)))+(((IkReal(-1.00000000000000))*(r00)*(x4255)*(x4259)))+(((x4255)*(x4258)))+(((IkReal(-1.00000000000000))*(x4256)*(x4257))));
15801 evalcond[6]=((IkReal(1.00000000000000))+(((r02)*(x4255)))+(((IkReal(-1.00000000000000))*(x4256)*(x4266)))+(((IkReal(-1.00000000000000))*(x4258)*(x4262)))+(((x4257)*(x4267)))+(((IkReal(-1.00000000000000))*(r10)*(x4257)*(x4259)))+(((x4260)*(x4263))));
15802 evalcond[7]=((((r22)*(sj4)))+(((r20)*(x4260)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4265))));
15803 evalcond[8]=((((IkReal(-1.00000000000000))*(x4255)*(x4256)))+(((IkReal(-1.00000000000000))*(r10)*(x4259)*(x4262)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4261)))+(((x4262)*(x4267)))+(((IkReal(-1.00000000000000))*(r00)*(x4257)*(x4259)))+(((x4257)*(x4258))));
15804 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  )
15805 {
15806 {
15807 IkReal dummyeval[1];
15808 IkReal gconst38;
15809 gconst38=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
15810 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
15811 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15812 {
15813 {
15814 IkReal dummyeval[1];
15815 IkReal gconst39;
15816 gconst39=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
15817 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
15818 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15819 {
15820 continue;
15821 
15822 } else
15823 {
15824 {
15825 IkReal j1array[1], cj1array[1], sj1array[1];
15826 bool j1valid[1]={false};
15827 _nj1 = 1;
15828 IkReal x4268=((cj5)*(r11));
15829 IkReal x4269=((r10)*(sj0));
15830 IkReal x4270=((IkReal(0.707103562373095))*(cj2));
15831 IkReal x4271=((r20)*(sj5));
15832 IkReal x4272=((IkReal(0.707103562373095))*(sj2));
15833 IkReal x4273=((IkReal(0.707109999985348))*(cj2));
15834 IkReal x4274=((cj0)*(r00));
15835 IkReal x4275=((IkReal(0.707109999985348))*(sj2));
15836 IkReal x4276=((cj5)*(r21));
15837 IkReal x4277=((sj0)*(x4272));
15838 IkReal x4278=((sj5)*(x4273));
15839 IkReal x4279=((cj0)*(cj5)*(r01));
15840 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(sj0)*(x4268)*(x4273)))+(((IkReal(-1.00000000000000))*(sj5)*(x4269)*(x4272)))+(((IkReal(-1.00000000000000))*(x4273)*(x4279)))+(((IkReal(-1.00000000000000))*(sj5)*(x4272)*(x4274)))+(((IkReal(-1.00000000000000))*(x4272)*(x4279)))+(((x4275)*(x4276)))+(((IkReal(-1.00000000000000))*(x4274)*(x4278)))+(((IkReal(-1.00000000000000))*(x4268)*(x4277)))+(((IkReal(-1.00000000000000))*(x4269)*(x4278)))+(((IkReal(-1.00000000000000))*(x4270)*(x4271)))+(((IkReal(-1.00000000000000))*(x4270)*(x4276)))+(((x4271)*(x4275))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(sj0)*(x4268)*(x4275)))+(((IkReal(-1.00000000000000))*(sj5)*(x4269)*(x4275)))+(((IkReal(-1.00000000000000))*(x4273)*(x4276)))+(((x4270)*(x4279)))+(((IkReal(-1.00000000000000))*(x4275)*(x4279)))+(((sj5)*(x4269)*(x4270)))+(((IkReal(-1.00000000000000))*(sj5)*(x4274)*(x4275)))+(((IkReal(-1.00000000000000))*(x4271)*(x4273)))+(((IkReal(-1.00000000000000))*(x4271)*(x4272)))+(((sj0)*(x4268)*(x4270)))+(((IkReal(-1.00000000000000))*(x4272)*(x4276)))+(((sj5)*(x4270)*(x4274))))))) < IKFAST_ATAN2_MAGTHRESH )
15841     continue;
15842 j1array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(sj0)*(x4268)*(x4273)))+(((IkReal(-1.00000000000000))*(sj5)*(x4269)*(x4272)))+(((IkReal(-1.00000000000000))*(x4273)*(x4279)))+(((IkReal(-1.00000000000000))*(sj5)*(x4272)*(x4274)))+(((IkReal(-1.00000000000000))*(x4272)*(x4279)))+(((x4275)*(x4276)))+(((IkReal(-1.00000000000000))*(x4274)*(x4278)))+(((IkReal(-1.00000000000000))*(x4268)*(x4277)))+(((IkReal(-1.00000000000000))*(x4269)*(x4278)))+(((IkReal(-1.00000000000000))*(x4270)*(x4271)))+(((IkReal(-1.00000000000000))*(x4270)*(x4276)))+(((x4271)*(x4275)))))), ((gconst39)*(((((IkReal(-1.00000000000000))*(sj0)*(x4268)*(x4275)))+(((IkReal(-1.00000000000000))*(sj5)*(x4269)*(x4275)))+(((IkReal(-1.00000000000000))*(x4273)*(x4276)))+(((x4270)*(x4279)))+(((IkReal(-1.00000000000000))*(x4275)*(x4279)))+(((sj5)*(x4269)*(x4270)))+(((IkReal(-1.00000000000000))*(sj5)*(x4274)*(x4275)))+(((IkReal(-1.00000000000000))*(x4271)*(x4273)))+(((IkReal(-1.00000000000000))*(x4271)*(x4272)))+(((sj0)*(x4268)*(x4270)))+(((IkReal(-1.00000000000000))*(x4272)*(x4276)))+(((sj5)*(x4270)*(x4274)))))));
15843 sj1array[0]=IKsin(j1array[0]);
15844 cj1array[0]=IKcos(j1array[0]);
15845 if( j1array[0] > IKPI )
15846 {
15847     j1array[0]-=IK2PI;
15848 }
15849 else if( j1array[0] < -IKPI )
15850 {    j1array[0]+=IK2PI;
15851 }
15852 j1valid[0] = true;
15853 for(int ij1 = 0; ij1 < 1; ++ij1)
15854 {
15855 if( !j1valid[ij1] )
15856 {
15857     continue;
15858 }
15859 _ij1[0] = ij1; _ij1[1] = -1;
15860 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15861 {
15862 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15863 {
15864     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15865 }
15866 }
15867 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15868 {
15869 IkReal evalcond[4];
15870 IkReal x4280=IKsin(j1);
15871 IkReal x4281=IKcos(j1);
15872 IkReal x4282=((IkReal(0.707109999985348))*(cj2));
15873 IkReal x4283=((IkReal(1.00000000000000))*(cj0));
15874 IkReal x4284=((IkReal(0.707109999985348))*(sj2));
15875 IkReal x4285=((cj5)*(sj4));
15876 IkReal x4286=((sj4)*(sj5));
15877 IkReal x4287=((IkReal(1.00000000000000))*(sj0));
15878 IkReal x4288=((sj5)*(x4287));
15879 IkReal x4289=((IkReal(0.707103562373095))*(x4281));
15880 IkReal x4290=((IkReal(0.707103562373095))*(x4280));
15881 IkReal x4291=((x4280)*(x4282));
15882 IkReal x4292=((sj2)*(x4290));
15883 IkReal x4293=((x4281)*(x4284));
15884 IkReal x4294=((cj2)*(x4289));
15885 IkReal x4295=((sj2)*(x4289));
15886 IkReal x4296=((cj2)*(x4290));
15887 IkReal x4297=((x4281)*(x4282));
15888 IkReal x4298=((x4280)*(x4284));
15889 IkReal x4299=((x4295)+(x4297)+(x4296));
15890 IkReal x4300=((x4291)+(x4293)+(x4292));
15891 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4299)))+(x4298)+(((r20)*(sj5))));
15892 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x4285)))+(((IkReal(-1.00000000000000))*(x4294)))+(x4300)+(((r21)*(x4286))));
15893 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4288)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4287)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4283)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4283)))+(((IkReal(-1.00000000000000))*(x4294)))+(x4300));
15894 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4287)))+(((IkReal(-1.00000000000000))*(r11)*(x4286)*(x4287)))+(((IkReal(-1.00000000000000))*(r01)*(x4283)*(x4286)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4283)))+(((cj0)*(r00)*(x4285)))+(((IkReal(-1.00000000000000))*(x4298)))+(x4299)+(((r10)*(sj0)*(x4285))));
15895 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15896 {
15897 continue;
15898 }
15899 }
15900 
15901 {
15902 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15903 vinfos[0].jointtype = 1;
15904 vinfos[0].foffset = j0;
15905 vinfos[0].indices[0] = _ij0[0];
15906 vinfos[0].indices[1] = _ij0[1];
15907 vinfos[0].maxsolutions = _nj0;
15908 vinfos[1].jointtype = 1;
15909 vinfos[1].foffset = j1;
15910 vinfos[1].indices[0] = _ij1[0];
15911 vinfos[1].indices[1] = _ij1[1];
15912 vinfos[1].maxsolutions = _nj1;
15913 vinfos[2].jointtype = 1;
15914 vinfos[2].foffset = j2;
15915 vinfos[2].indices[0] = _ij2[0];
15916 vinfos[2].indices[1] = _ij2[1];
15917 vinfos[2].maxsolutions = _nj2;
15918 vinfos[3].jointtype = 1;
15919 vinfos[3].foffset = j3;
15920 vinfos[3].indices[0] = _ij3[0];
15921 vinfos[3].indices[1] = _ij3[1];
15922 vinfos[3].maxsolutions = _nj3;
15923 vinfos[4].jointtype = 1;
15924 vinfos[4].foffset = j4;
15925 vinfos[4].indices[0] = _ij4[0];
15926 vinfos[4].indices[1] = _ij4[1];
15927 vinfos[4].maxsolutions = _nj4;
15928 vinfos[5].jointtype = 1;
15929 vinfos[5].foffset = j5;
15930 vinfos[5].indices[0] = _ij5[0];
15931 vinfos[5].indices[1] = _ij5[1];
15932 vinfos[5].maxsolutions = _nj5;
15933 std::vector<int> vfree(0);
15934 solutions.AddSolution(vinfos,vfree);
15935 }
15936 }
15937 }
15938 
15939 }
15940 
15941 }
15942 
15943 } else
15944 {
15945 {
15946 IkReal j1array[1], cj1array[1], sj1array[1];
15947 bool j1valid[1]={false};
15948 _nj1 = 1;
15949 IkReal x4301=((cj5)*(sj4));
15950 IkReal x4302=((r21)*(sj4));
15951 IkReal x4303=((cj5)*(r21));
15952 IkReal x4304=((IkReal(0.707109999985348))*(cj2));
15953 IkReal x4305=((IkReal(0.707103562373095))*(sj2));
15954 IkReal x4306=((IkReal(0.707109999985348))*(sj2));
15955 IkReal x4307=((cj4)*(r22));
15956 IkReal x4308=((IkReal(0.707103562373095))*(cj2));
15957 IkReal x4309=((r20)*(x4304));
15958 IkReal x4310=((sj5)*(x4308));
15959 IkReal x4311=((sj5)*(x4306));
15960 if( IKabs(((gconst38)*(((((r20)*(x4311)))+(((IkReal(-1.00000000000000))*(x4303)*(x4308)))+(((IkReal(-1.00000000000000))*(r20)*(x4310)))+(((x4305)*(x4307)))+(((IkReal(-1.00000000000000))*(x4301)*(x4309)))+(((x4304)*(x4307)))+(((x4303)*(x4306)))+(((IkReal(-1.00000000000000))*(r20)*(x4301)*(x4305)))+(((sj5)*(x4302)*(x4305)))+(((sj5)*(x4302)*(x4304))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((IkReal(-1.00000000000000))*(x4303)*(x4305)))+(((IkReal(-1.00000000000000))*(x4303)*(x4304)))+(((IkReal(-1.00000000000000))*(sj5)*(x4309)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4305)))+(((x4302)*(x4311)))+(((x4306)*(x4307)))+(((IkReal(-1.00000000000000))*(x4307)*(x4308)))+(((r20)*(x4301)*(x4308)))+(((IkReal(-1.00000000000000))*(r20)*(x4301)*(x4306)))+(((IkReal(-1.00000000000000))*(x4302)*(x4310))))))) < IKFAST_ATAN2_MAGTHRESH )
15961     continue;
15962 j1array[0]=IKatan2(((gconst38)*(((((r20)*(x4311)))+(((IkReal(-1.00000000000000))*(x4303)*(x4308)))+(((IkReal(-1.00000000000000))*(r20)*(x4310)))+(((x4305)*(x4307)))+(((IkReal(-1.00000000000000))*(x4301)*(x4309)))+(((x4304)*(x4307)))+(((x4303)*(x4306)))+(((IkReal(-1.00000000000000))*(r20)*(x4301)*(x4305)))+(((sj5)*(x4302)*(x4305)))+(((sj5)*(x4302)*(x4304)))))), ((gconst38)*(((((IkReal(-1.00000000000000))*(x4303)*(x4305)))+(((IkReal(-1.00000000000000))*(x4303)*(x4304)))+(((IkReal(-1.00000000000000))*(sj5)*(x4309)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4305)))+(((x4302)*(x4311)))+(((x4306)*(x4307)))+(((IkReal(-1.00000000000000))*(x4307)*(x4308)))+(((r20)*(x4301)*(x4308)))+(((IkReal(-1.00000000000000))*(r20)*(x4301)*(x4306)))+(((IkReal(-1.00000000000000))*(x4302)*(x4310)))))));
15963 sj1array[0]=IKsin(j1array[0]);
15964 cj1array[0]=IKcos(j1array[0]);
15965 if( j1array[0] > IKPI )
15966 {
15967     j1array[0]-=IK2PI;
15968 }
15969 else if( j1array[0] < -IKPI )
15970 {    j1array[0]+=IK2PI;
15971 }
15972 j1valid[0] = true;
15973 for(int ij1 = 0; ij1 < 1; ++ij1)
15974 {
15975 if( !j1valid[ij1] )
15976 {
15977     continue;
15978 }
15979 _ij1[0] = ij1; _ij1[1] = -1;
15980 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
15981 {
15982 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
15983 {
15984     j1valid[iij1]=false; _ij1[1] = iij1; break; 
15985 }
15986 }
15987 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
15988 {
15989 IkReal evalcond[4];
15990 IkReal x4312=IKsin(j1);
15991 IkReal x4313=IKcos(j1);
15992 IkReal x4314=((IkReal(0.707109999985348))*(cj2));
15993 IkReal x4315=((IkReal(1.00000000000000))*(cj0));
15994 IkReal x4316=((IkReal(0.707109999985348))*(sj2));
15995 IkReal x4317=((cj5)*(sj4));
15996 IkReal x4318=((sj4)*(sj5));
15997 IkReal x4319=((IkReal(1.00000000000000))*(sj0));
15998 IkReal x4320=((sj5)*(x4319));
15999 IkReal x4321=((IkReal(0.707103562373095))*(x4313));
16000 IkReal x4322=((IkReal(0.707103562373095))*(x4312));
16001 IkReal x4323=((x4312)*(x4314));
16002 IkReal x4324=((sj2)*(x4322));
16003 IkReal x4325=((x4313)*(x4316));
16004 IkReal x4326=((cj2)*(x4321));
16005 IkReal x4327=((sj2)*(x4321));
16006 IkReal x4328=((cj2)*(x4322));
16007 IkReal x4329=((x4313)*(x4314));
16008 IkReal x4330=((x4312)*(x4316));
16009 IkReal x4331=((x4329)+(x4328)+(x4327));
16010 IkReal x4332=((x4323)+(x4325)+(x4324));
16011 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4331)))+(x4330)+(((r20)*(sj5))));
16012 evalcond[1]=((((r21)*(x4318)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x4326)))+(x4332)+(((IkReal(-1.00000000000000))*(r20)*(x4317))));
16013 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(x4320)))+(((IkReal(-1.00000000000000))*(x4326)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4319)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4315)))+(x4332)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4315))));
16014 evalcond[3]=((((r10)*(sj0)*(x4317)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4315)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4319)))+(((IkReal(-1.00000000000000))*(r01)*(x4315)*(x4318)))+(((IkReal(-1.00000000000000))*(x4330)))+(((IkReal(-1.00000000000000))*(r11)*(x4318)*(x4319)))+(x4331)+(((cj0)*(r00)*(x4317))));
16015 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16016 {
16017 continue;
16018 }
16019 }
16020 
16021 {
16022 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16023 vinfos[0].jointtype = 1;
16024 vinfos[0].foffset = j0;
16025 vinfos[0].indices[0] = _ij0[0];
16026 vinfos[0].indices[1] = _ij0[1];
16027 vinfos[0].maxsolutions = _nj0;
16028 vinfos[1].jointtype = 1;
16029 vinfos[1].foffset = j1;
16030 vinfos[1].indices[0] = _ij1[0];
16031 vinfos[1].indices[1] = _ij1[1];
16032 vinfos[1].maxsolutions = _nj1;
16033 vinfos[2].jointtype = 1;
16034 vinfos[2].foffset = j2;
16035 vinfos[2].indices[0] = _ij2[0];
16036 vinfos[2].indices[1] = _ij2[1];
16037 vinfos[2].maxsolutions = _nj2;
16038 vinfos[3].jointtype = 1;
16039 vinfos[3].foffset = j3;
16040 vinfos[3].indices[0] = _ij3[0];
16041 vinfos[3].indices[1] = _ij3[1];
16042 vinfos[3].maxsolutions = _nj3;
16043 vinfos[4].jointtype = 1;
16044 vinfos[4].foffset = j4;
16045 vinfos[4].indices[0] = _ij4[0];
16046 vinfos[4].indices[1] = _ij4[1];
16047 vinfos[4].maxsolutions = _nj4;
16048 vinfos[5].jointtype = 1;
16049 vinfos[5].foffset = j5;
16050 vinfos[5].indices[0] = _ij5[0];
16051 vinfos[5].indices[1] = _ij5[1];
16052 vinfos[5].maxsolutions = _nj5;
16053 std::vector<int> vfree(0);
16054 solutions.AddSolution(vinfos,vfree);
16055 }
16056 }
16057 }
16058 
16059 }
16060 
16061 }
16062 
16063 } else
16064 {
16065 IkReal x4333=((sj0)*(sj4));
16066 IkReal x4334=((IkReal(1.00000000000000))*(r12));
16067 IkReal x4335=((cj0)*(cj4));
16068 IkReal x4336=((r01)*(sj5));
16069 IkReal x4337=((IkReal(1.00000000000000))*(cj5));
16070 IkReal x4338=((cj4)*(cj5));
16071 IkReal x4339=((IkReal(1.00000000000000))*(cj0));
16072 IkReal x4340=((cj4)*(sj0));
16073 IkReal x4341=((r00)*(sj0));
16074 IkReal x4342=((npy)*(sj5));
16075 IkReal x4343=((IkReal(1.00000000000000))*(cj4));
16076 IkReal x4344=((cj0)*(sj4));
16077 IkReal x4345=((r11)*(sj5));
16078 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
16079 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4339)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4337)))+(((sj5)*(x4341))));
16080 evalcond[2]=((IkReal(-0.258003287011922))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4337)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x4342)))+(((IkReal(0.165463933124939))*(sj2))));
16081 evalcond[3]=((IkReal(-0.0360035672348961))+(((npx)*(sj5)))+(((IkReal(-0.165463933124939))*(cj2)))+(((cj5)*(npy)))+(((IkReal(-0.207888640466058))*(sj2))));
16082 evalcond[4]=((IkReal(-0.00600000000000000))+(((IkReal(-1.00000000000000))*(x4342)*(x4343)))+(((npz)*(sj4)))+(((npx)*(x4338))));
16083 evalcond[5]=((((IkReal(-1.00000000000000))*(x4334)*(x4335)))+(((r02)*(x4340)))+(((IkReal(-1.00000000000000))*(r00)*(x4333)*(x4337)))+(((cj5)*(r10)*(x4344)))+(((x4333)*(x4336)))+(((IkReal(-1.00000000000000))*(sj4)*(x4339)*(x4345))));
16084 evalcond[6]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x4336)*(x4340)))+(((x4335)*(x4345)))+(((x4338)*(x4341)))+(((IkReal(-1.00000000000000))*(r10)*(x4335)*(x4337)))+(((r02)*(x4333)))+(((IkReal(-1.00000000000000))*(x4334)*(x4344))));
16085 evalcond[7]=((((r20)*(x4338)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4343))));
16086 evalcond[8]=((((IkReal(-1.00000000000000))*(x4333)*(x4334)))+(((IkReal(-1.00000000000000))*(r00)*(x4335)*(x4337)))+(((x4335)*(x4336)))+(((IkReal(-1.00000000000000))*(r10)*(x4337)*(x4340)))+(((x4340)*(x4345)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4339))));
16087 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  )
16088 {
16089 {
16090 IkReal dummyeval[1];
16091 IkReal gconst40;
16092 gconst40=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
16093 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
16094 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16095 {
16096 {
16097 IkReal dummyeval[1];
16098 IkReal gconst41;
16099 gconst41=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
16100 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
16101 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16102 {
16103 continue;
16104 
16105 } else
16106 {
16107 {
16108 IkReal j1array[1], cj1array[1], sj1array[1];
16109 bool j1valid[1]={false};
16110 _nj1 = 1;
16111 IkReal x4346=((cj5)*(r11));
16112 IkReal x4347=((r10)*(sj0));
16113 IkReal x4348=((IkReal(0.707103562373095))*(cj2));
16114 IkReal x4349=((r20)*(sj5));
16115 IkReal x4350=((IkReal(0.707103562373095))*(sj2));
16116 IkReal x4351=((IkReal(0.707109999985348))*(cj2));
16117 IkReal x4352=((cj0)*(r00));
16118 IkReal x4353=((IkReal(0.707109999985348))*(sj2));
16119 IkReal x4354=((cj5)*(r21));
16120 IkReal x4355=((sj0)*(x4350));
16121 IkReal x4356=((sj5)*(x4351));
16122 IkReal x4357=((cj0)*(cj5)*(r01));
16123 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x4350)*(x4352)))+(((x4353)*(x4354)))+(((IkReal(-1.00000000000000))*(x4350)*(x4357)))+(((IkReal(-1.00000000000000))*(x4351)*(x4357)))+(((IkReal(-1.00000000000000))*(x4352)*(x4356)))+(((x4349)*(x4353)))+(((IkReal(-1.00000000000000))*(x4348)*(x4354)))+(((IkReal(-1.00000000000000))*(x4347)*(x4356)))+(((IkReal(-1.00000000000000))*(x4348)*(x4349)))+(((IkReal(-1.00000000000000))*(sj5)*(x4347)*(x4350)))+(((IkReal(-1.00000000000000))*(x4346)*(x4355)))+(((IkReal(-1.00000000000000))*(sj0)*(x4346)*(x4351))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(x4353)*(x4357)))+(((IkReal(-1.00000000000000))*(sj5)*(x4352)*(x4353)))+(((x4348)*(x4357)))+(((IkReal(-1.00000000000000))*(x4349)*(x4350)))+(((IkReal(-1.00000000000000))*(x4349)*(x4351)))+(((IkReal(-1.00000000000000))*(x4350)*(x4354)))+(((sj5)*(x4347)*(x4348)))+(((IkReal(-1.00000000000000))*(x4351)*(x4354)))+(((sj5)*(x4348)*(x4352)))+(((IkReal(-1.00000000000000))*(sj5)*(x4347)*(x4353)))+(((sj0)*(x4346)*(x4348)))+(((IkReal(-1.00000000000000))*(sj0)*(x4346)*(x4353))))))) < IKFAST_ATAN2_MAGTHRESH )
16124     continue;
16125 j1array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(sj5)*(x4350)*(x4352)))+(((x4353)*(x4354)))+(((IkReal(-1.00000000000000))*(x4350)*(x4357)))+(((IkReal(-1.00000000000000))*(x4351)*(x4357)))+(((IkReal(-1.00000000000000))*(x4352)*(x4356)))+(((x4349)*(x4353)))+(((IkReal(-1.00000000000000))*(x4348)*(x4354)))+(((IkReal(-1.00000000000000))*(x4347)*(x4356)))+(((IkReal(-1.00000000000000))*(x4348)*(x4349)))+(((IkReal(-1.00000000000000))*(sj5)*(x4347)*(x4350)))+(((IkReal(-1.00000000000000))*(x4346)*(x4355)))+(((IkReal(-1.00000000000000))*(sj0)*(x4346)*(x4351)))))), ((gconst41)*(((((IkReal(-1.00000000000000))*(x4353)*(x4357)))+(((IkReal(-1.00000000000000))*(sj5)*(x4352)*(x4353)))+(((x4348)*(x4357)))+(((IkReal(-1.00000000000000))*(x4349)*(x4350)))+(((IkReal(-1.00000000000000))*(x4349)*(x4351)))+(((IkReal(-1.00000000000000))*(x4350)*(x4354)))+(((sj5)*(x4347)*(x4348)))+(((IkReal(-1.00000000000000))*(x4351)*(x4354)))+(((sj5)*(x4348)*(x4352)))+(((IkReal(-1.00000000000000))*(sj5)*(x4347)*(x4353)))+(((sj0)*(x4346)*(x4348)))+(((IkReal(-1.00000000000000))*(sj0)*(x4346)*(x4353)))))));
16126 sj1array[0]=IKsin(j1array[0]);
16127 cj1array[0]=IKcos(j1array[0]);
16128 if( j1array[0] > IKPI )
16129 {
16130     j1array[0]-=IK2PI;
16131 }
16132 else if( j1array[0] < -IKPI )
16133 {    j1array[0]+=IK2PI;
16134 }
16135 j1valid[0] = true;
16136 for(int ij1 = 0; ij1 < 1; ++ij1)
16137 {
16138 if( !j1valid[ij1] )
16139 {
16140     continue;
16141 }
16142 _ij1[0] = ij1; _ij1[1] = -1;
16143 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16144 {
16145 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16146 {
16147     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16148 }
16149 }
16150 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16151 {
16152 IkReal evalcond[4];
16153 IkReal x4358=IKsin(j1);
16154 IkReal x4359=IKcos(j1);
16155 IkReal x4360=((IkReal(0.707109999985348))*(cj2));
16156 IkReal x4361=((IkReal(1.00000000000000))*(cj0));
16157 IkReal x4362=((IkReal(0.707109999985348))*(sj2));
16158 IkReal x4363=((cj5)*(sj4));
16159 IkReal x4364=((sj4)*(sj5));
16160 IkReal x4365=((IkReal(1.00000000000000))*(sj0));
16161 IkReal x4366=((sj5)*(x4365));
16162 IkReal x4367=((IkReal(0.707103562373095))*(x4359));
16163 IkReal x4368=((IkReal(0.707103562373095))*(x4358));
16164 IkReal x4369=((x4358)*(x4360));
16165 IkReal x4370=((sj2)*(x4368));
16166 IkReal x4371=((x4359)*(x4362));
16167 IkReal x4372=((cj2)*(x4367));
16168 IkReal x4373=((sj2)*(x4367));
16169 IkReal x4374=((cj2)*(x4368));
16170 IkReal x4375=((x4359)*(x4360));
16171 IkReal x4376=((x4358)*(x4362));
16172 IkReal x4377=((x4373)+(x4374)+(x4375));
16173 IkReal x4378=((x4370)+(x4371)+(x4369));
16174 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4377)))+(x4376)+(((r20)*(sj5))));
16175 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x4364)))+(((IkReal(-1.00000000000000))*(x4372)))+(((IkReal(-1.00000000000000))*(r20)*(x4363)))+(x4378));
16176 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4361)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4365)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4361)))+(((IkReal(-1.00000000000000))*(x4372)))+(x4378)+(((IkReal(-1.00000000000000))*(r10)*(x4366))));
16177 evalcond[3]=((((cj0)*(r00)*(x4363)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4361)))+(((r10)*(sj0)*(x4363)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4365)))+(((IkReal(-1.00000000000000))*(x4376)))+(((IkReal(-1.00000000000000))*(r11)*(x4364)*(x4365)))+(((IkReal(-1.00000000000000))*(r01)*(x4361)*(x4364)))+(x4377));
16178 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16179 {
16180 continue;
16181 }
16182 }
16183 
16184 {
16185 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16186 vinfos[0].jointtype = 1;
16187 vinfos[0].foffset = j0;
16188 vinfos[0].indices[0] = _ij0[0];
16189 vinfos[0].indices[1] = _ij0[1];
16190 vinfos[0].maxsolutions = _nj0;
16191 vinfos[1].jointtype = 1;
16192 vinfos[1].foffset = j1;
16193 vinfos[1].indices[0] = _ij1[0];
16194 vinfos[1].indices[1] = _ij1[1];
16195 vinfos[1].maxsolutions = _nj1;
16196 vinfos[2].jointtype = 1;
16197 vinfos[2].foffset = j2;
16198 vinfos[2].indices[0] = _ij2[0];
16199 vinfos[2].indices[1] = _ij2[1];
16200 vinfos[2].maxsolutions = _nj2;
16201 vinfos[3].jointtype = 1;
16202 vinfos[3].foffset = j3;
16203 vinfos[3].indices[0] = _ij3[0];
16204 vinfos[3].indices[1] = _ij3[1];
16205 vinfos[3].maxsolutions = _nj3;
16206 vinfos[4].jointtype = 1;
16207 vinfos[4].foffset = j4;
16208 vinfos[4].indices[0] = _ij4[0];
16209 vinfos[4].indices[1] = _ij4[1];
16210 vinfos[4].maxsolutions = _nj4;
16211 vinfos[5].jointtype = 1;
16212 vinfos[5].foffset = j5;
16213 vinfos[5].indices[0] = _ij5[0];
16214 vinfos[5].indices[1] = _ij5[1];
16215 vinfos[5].maxsolutions = _nj5;
16216 std::vector<int> vfree(0);
16217 solutions.AddSolution(vinfos,vfree);
16218 }
16219 }
16220 }
16221 
16222 }
16223 
16224 }
16225 
16226 } else
16227 {
16228 {
16229 IkReal j1array[1], cj1array[1], sj1array[1];
16230 bool j1valid[1]={false};
16231 _nj1 = 1;
16232 IkReal x4379=((cj5)*(sj4));
16233 IkReal x4380=((r21)*(sj4));
16234 IkReal x4381=((cj5)*(r21));
16235 IkReal x4382=((IkReal(0.707109999985348))*(cj2));
16236 IkReal x4383=((IkReal(0.707103562373095))*(sj2));
16237 IkReal x4384=((IkReal(0.707109999985348))*(sj2));
16238 IkReal x4385=((cj4)*(r22));
16239 IkReal x4386=((IkReal(0.707103562373095))*(cj2));
16240 IkReal x4387=((r20)*(x4382));
16241 IkReal x4388=((sj5)*(x4386));
16242 IkReal x4389=((sj5)*(x4384));
16243 if( IKabs(((gconst40)*(((((IkReal(-1.00000000000000))*(x4379)*(x4387)))+(((IkReal(-1.00000000000000))*(x4381)*(x4386)))+(((x4383)*(x4385)))+(((IkReal(-1.00000000000000))*(r20)*(x4379)*(x4383)))+(((x4381)*(x4384)))+(((x4382)*(x4385)))+(((r20)*(x4389)))+(((sj5)*(x4380)*(x4382)))+(((sj5)*(x4380)*(x4383)))+(((IkReal(-1.00000000000000))*(r20)*(x4388))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((r20)*(x4379)*(x4386)))+(((IkReal(-1.00000000000000))*(sj5)*(x4387)))+(((IkReal(-1.00000000000000))*(x4380)*(x4388)))+(((IkReal(-1.00000000000000))*(x4381)*(x4383)))+(((IkReal(-1.00000000000000))*(x4381)*(x4382)))+(((IkReal(-1.00000000000000))*(r20)*(x4379)*(x4384)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4383)))+(((x4380)*(x4389)))+(((x4384)*(x4385)))+(((IkReal(-1.00000000000000))*(x4385)*(x4386))))))) < IKFAST_ATAN2_MAGTHRESH )
16244     continue;
16245 j1array[0]=IKatan2(((gconst40)*(((((IkReal(-1.00000000000000))*(x4379)*(x4387)))+(((IkReal(-1.00000000000000))*(x4381)*(x4386)))+(((x4383)*(x4385)))+(((IkReal(-1.00000000000000))*(r20)*(x4379)*(x4383)))+(((x4381)*(x4384)))+(((x4382)*(x4385)))+(((r20)*(x4389)))+(((sj5)*(x4380)*(x4382)))+(((sj5)*(x4380)*(x4383)))+(((IkReal(-1.00000000000000))*(r20)*(x4388)))))), ((gconst40)*(((((r20)*(x4379)*(x4386)))+(((IkReal(-1.00000000000000))*(sj5)*(x4387)))+(((IkReal(-1.00000000000000))*(x4380)*(x4388)))+(((IkReal(-1.00000000000000))*(x4381)*(x4383)))+(((IkReal(-1.00000000000000))*(x4381)*(x4382)))+(((IkReal(-1.00000000000000))*(r20)*(x4379)*(x4384)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4383)))+(((x4380)*(x4389)))+(((x4384)*(x4385)))+(((IkReal(-1.00000000000000))*(x4385)*(x4386)))))));
16246 sj1array[0]=IKsin(j1array[0]);
16247 cj1array[0]=IKcos(j1array[0]);
16248 if( j1array[0] > IKPI )
16249 {
16250     j1array[0]-=IK2PI;
16251 }
16252 else if( j1array[0] < -IKPI )
16253 {    j1array[0]+=IK2PI;
16254 }
16255 j1valid[0] = true;
16256 for(int ij1 = 0; ij1 < 1; ++ij1)
16257 {
16258 if( !j1valid[ij1] )
16259 {
16260     continue;
16261 }
16262 _ij1[0] = ij1; _ij1[1] = -1;
16263 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16264 {
16265 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16266 {
16267     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16268 }
16269 }
16270 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16271 {
16272 IkReal evalcond[4];
16273 IkReal x4390=IKsin(j1);
16274 IkReal x4391=IKcos(j1);
16275 IkReal x4392=((IkReal(0.707109999985348))*(cj2));
16276 IkReal x4393=((IkReal(1.00000000000000))*(cj0));
16277 IkReal x4394=((IkReal(0.707109999985348))*(sj2));
16278 IkReal x4395=((cj5)*(sj4));
16279 IkReal x4396=((sj4)*(sj5));
16280 IkReal x4397=((IkReal(1.00000000000000))*(sj0));
16281 IkReal x4398=((sj5)*(x4397));
16282 IkReal x4399=((IkReal(0.707103562373095))*(x4391));
16283 IkReal x4400=((IkReal(0.707103562373095))*(x4390));
16284 IkReal x4401=((x4390)*(x4392));
16285 IkReal x4402=((sj2)*(x4400));
16286 IkReal x4403=((x4391)*(x4394));
16287 IkReal x4404=((cj2)*(x4399));
16288 IkReal x4405=((sj2)*(x4399));
16289 IkReal x4406=((cj2)*(x4400));
16290 IkReal x4407=((x4391)*(x4392));
16291 IkReal x4408=((x4390)*(x4394));
16292 IkReal x4409=((x4405)+(x4406)+(x4407));
16293 IkReal x4410=((x4401)+(x4402)+(x4403));
16294 evalcond[0]=((((cj5)*(r21)))+(x4408)+(((IkReal(-1.00000000000000))*(x4409)))+(((r20)*(sj5))));
16295 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x4395)))+(((cj4)*(r22)))+(x4410)+(((IkReal(-1.00000000000000))*(x4404)))+(((r21)*(x4396))));
16296 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4393)))+(x4410)+(((IkReal(-1.00000000000000))*(r10)*(x4398)))+(((IkReal(-1.00000000000000))*(x4404)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4393)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4397))));
16297 evalcond[3]=((x4409)+(((IkReal(-1.00000000000000))*(r01)*(x4393)*(x4396)))+(((IkReal(-1.00000000000000))*(r11)*(x4396)*(x4397)))+(((cj0)*(r00)*(x4395)))+(((r10)*(sj0)*(x4395)))+(((IkReal(-1.00000000000000))*(x4408)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4393)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4397))));
16298 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16299 {
16300 continue;
16301 }
16302 }
16303 
16304 {
16305 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16306 vinfos[0].jointtype = 1;
16307 vinfos[0].foffset = j0;
16308 vinfos[0].indices[0] = _ij0[0];
16309 vinfos[0].indices[1] = _ij0[1];
16310 vinfos[0].maxsolutions = _nj0;
16311 vinfos[1].jointtype = 1;
16312 vinfos[1].foffset = j1;
16313 vinfos[1].indices[0] = _ij1[0];
16314 vinfos[1].indices[1] = _ij1[1];
16315 vinfos[1].maxsolutions = _nj1;
16316 vinfos[2].jointtype = 1;
16317 vinfos[2].foffset = j2;
16318 vinfos[2].indices[0] = _ij2[0];
16319 vinfos[2].indices[1] = _ij2[1];
16320 vinfos[2].maxsolutions = _nj2;
16321 vinfos[3].jointtype = 1;
16322 vinfos[3].foffset = j3;
16323 vinfos[3].indices[0] = _ij3[0];
16324 vinfos[3].indices[1] = _ij3[1];
16325 vinfos[3].maxsolutions = _nj3;
16326 vinfos[4].jointtype = 1;
16327 vinfos[4].foffset = j4;
16328 vinfos[4].indices[0] = _ij4[0];
16329 vinfos[4].indices[1] = _ij4[1];
16330 vinfos[4].maxsolutions = _nj4;
16331 vinfos[5].jointtype = 1;
16332 vinfos[5].foffset = j5;
16333 vinfos[5].indices[0] = _ij5[0];
16334 vinfos[5].indices[1] = _ij5[1];
16335 vinfos[5].maxsolutions = _nj5;
16336 std::vector<int> vfree(0);
16337 solutions.AddSolution(vinfos,vfree);
16338 }
16339 }
16340 }
16341 
16342 }
16343 
16344 }
16345 
16346 } else
16347 {
16348 IkReal x4411=((sj0)*(sj4));
16349 IkReal x4412=((IkReal(1.00000000000000))*(r12));
16350 IkReal x4413=((cj0)*(cj4));
16351 IkReal x4414=((r01)*(sj5));
16352 IkReal x4415=((IkReal(1.00000000000000))*(cj5));
16353 IkReal x4416=((cj4)*(cj5));
16354 IkReal x4417=((IkReal(1.00000000000000))*(cj0));
16355 IkReal x4418=((cj4)*(sj0));
16356 IkReal x4419=((r00)*(sj0));
16357 IkReal x4420=((npy)*(sj5));
16358 IkReal x4421=((IkReal(1.00000000000000))*(cj4));
16359 IkReal x4422=((cj0)*(sj4));
16360 IkReal x4423=((r11)*(sj5));
16361 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959)))))));
16362 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x4419)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4415)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4417))));
16363 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x4420)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4415)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2))));
16364 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
16365 evalcond[4]=((IkReal(0.00600000000000000))+(((npx)*(x4416)))+(((IkReal(-1.00000000000000))*(x4420)*(x4421)))+(((npz)*(sj4))));
16366 evalcond[5]=((((IkReal(-1.00000000000000))*(r00)*(x4411)*(x4415)))+(((cj5)*(r10)*(x4422)))+(((IkReal(-1.00000000000000))*(x4412)*(x4413)))+(((IkReal(-1.00000000000000))*(sj4)*(x4417)*(x4423)))+(((r02)*(x4418)))+(((x4411)*(x4414))));
16367 evalcond[6]=((IkReal(-1.00000000000000))+(((x4413)*(x4423)))+(((IkReal(-1.00000000000000))*(x4412)*(x4422)))+(((x4416)*(x4419)))+(((IkReal(-1.00000000000000))*(r10)*(x4413)*(x4415)))+(((r02)*(x4411)))+(((IkReal(-1.00000000000000))*(x4414)*(x4418))));
16368 evalcond[7]=((((r22)*(sj4)))+(((r20)*(x4416)))+(((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4421))));
16369 evalcond[8]=((((IkReal(-1.00000000000000))*(r10)*(x4415)*(x4418)))+(((IkReal(-1.00000000000000))*(r00)*(x4413)*(x4415)))+(((x4418)*(x4423)))+(((IkReal(-1.00000000000000))*(x4411)*(x4412)))+(((x4413)*(x4414)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4417))));
16370 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  )
16371 {
16372 {
16373 IkReal dummyeval[1];
16374 IkReal gconst42;
16375 gconst42=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
16376 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
16377 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16378 {
16379 {
16380 IkReal dummyeval[1];
16381 IkReal gconst43;
16382 gconst43=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
16383 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
16384 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16385 {
16386 continue;
16387 
16388 } else
16389 {
16390 {
16391 IkReal j1array[1], cj1array[1], sj1array[1];
16392 bool j1valid[1]={false};
16393 _nj1 = 1;
16394 IkReal x4424=((cj5)*(r11));
16395 IkReal x4425=((r10)*(sj0));
16396 IkReal x4426=((IkReal(0.707103562373095))*(cj2));
16397 IkReal x4427=((r20)*(sj5));
16398 IkReal x4428=((IkReal(0.707103562373095))*(sj2));
16399 IkReal x4429=((IkReal(0.707109999985348))*(cj2));
16400 IkReal x4430=((cj0)*(r00));
16401 IkReal x4431=((IkReal(0.707109999985348))*(sj2));
16402 IkReal x4432=((cj5)*(r21));
16403 IkReal x4433=((sj0)*(x4428));
16404 IkReal x4434=((sj5)*(x4429));
16405 IkReal x4435=((cj0)*(cj5)*(r01));
16406 if( IKabs(((gconst43)*(((((IkReal(-1.00000000000000))*(x4427)*(x4431)))+(((x4429)*(x4435)))+(((x4428)*(x4435)))+(((sj5)*(x4425)*(x4428)))+(((x4430)*(x4434)))+(((x4426)*(x4427)))+(((x4425)*(x4434)))+(((IkReal(-1.00000000000000))*(x4431)*(x4432)))+(((x4426)*(x4432)))+(((x4424)*(x4433)))+(((sj5)*(x4428)*(x4430)))+(((sj0)*(x4424)*(x4429))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((x4429)*(x4432)))+(((sj5)*(x4430)*(x4431)))+(((x4428)*(x4432)))+(((IkReal(-1.00000000000000))*(sj0)*(x4424)*(x4426)))+(((sj5)*(x4425)*(x4431)))+(((x4427)*(x4428)))+(((x4427)*(x4429)))+(((sj0)*(x4424)*(x4431)))+(((x4431)*(x4435)))+(((IkReal(-1.00000000000000))*(sj5)*(x4426)*(x4430)))+(((IkReal(-1.00000000000000))*(sj5)*(x4425)*(x4426)))+(((IkReal(-1.00000000000000))*(x4426)*(x4435))))))) < IKFAST_ATAN2_MAGTHRESH )
16407     continue;
16408 j1array[0]=IKatan2(((gconst43)*(((((IkReal(-1.00000000000000))*(x4427)*(x4431)))+(((x4429)*(x4435)))+(((x4428)*(x4435)))+(((sj5)*(x4425)*(x4428)))+(((x4430)*(x4434)))+(((x4426)*(x4427)))+(((x4425)*(x4434)))+(((IkReal(-1.00000000000000))*(x4431)*(x4432)))+(((x4426)*(x4432)))+(((x4424)*(x4433)))+(((sj5)*(x4428)*(x4430)))+(((sj0)*(x4424)*(x4429)))))), ((gconst43)*(((((x4429)*(x4432)))+(((sj5)*(x4430)*(x4431)))+(((x4428)*(x4432)))+(((IkReal(-1.00000000000000))*(sj0)*(x4424)*(x4426)))+(((sj5)*(x4425)*(x4431)))+(((x4427)*(x4428)))+(((x4427)*(x4429)))+(((sj0)*(x4424)*(x4431)))+(((x4431)*(x4435)))+(((IkReal(-1.00000000000000))*(sj5)*(x4426)*(x4430)))+(((IkReal(-1.00000000000000))*(sj5)*(x4425)*(x4426)))+(((IkReal(-1.00000000000000))*(x4426)*(x4435)))))));
16409 sj1array[0]=IKsin(j1array[0]);
16410 cj1array[0]=IKcos(j1array[0]);
16411 if( j1array[0] > IKPI )
16412 {
16413     j1array[0]-=IK2PI;
16414 }
16415 else if( j1array[0] < -IKPI )
16416 {    j1array[0]+=IK2PI;
16417 }
16418 j1valid[0] = true;
16419 for(int ij1 = 0; ij1 < 1; ++ij1)
16420 {
16421 if( !j1valid[ij1] )
16422 {
16423     continue;
16424 }
16425 _ij1[0] = ij1; _ij1[1] = -1;
16426 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16427 {
16428 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16429 {
16430     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16431 }
16432 }
16433 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16434 {
16435 IkReal evalcond[4];
16436 IkReal x4436=IKcos(j1);
16437 IkReal x4437=IKsin(j1);
16438 IkReal x4438=((IkReal(0.707109999985348))*(cj2));
16439 IkReal x4439=((IkReal(1.00000000000000))*(cj0));
16440 IkReal x4440=((IkReal(0.707109999985348))*(sj2));
16441 IkReal x4441=((cj5)*(sj4));
16442 IkReal x4442=((sj4)*(sj5));
16443 IkReal x4443=((IkReal(1.00000000000000))*(sj0));
16444 IkReal x4444=((sj5)*(x4443));
16445 IkReal x4445=((IkReal(0.707103562373095))*(x4436));
16446 IkReal x4446=((IkReal(0.707103562373095))*(x4437));
16447 IkReal x4447=((cj2)*(x4445));
16448 IkReal x4448=((x4437)*(x4438));
16449 IkReal x4449=((sj2)*(x4446));
16450 IkReal x4450=((x4436)*(x4440));
16451 IkReal x4451=((sj2)*(x4445));
16452 IkReal x4452=((cj2)*(x4446));
16453 IkReal x4453=((x4436)*(x4438));
16454 IkReal x4454=((x4437)*(x4440));
16455 IkReal x4455=((x4453)+(x4452)+(x4451));
16456 IkReal x4456=((x4448)+(x4449)+(x4450));
16457 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4454)))+(x4455)+(((r20)*(sj5))));
16458 evalcond[1]=((((cj4)*(r22)))+(((r21)*(x4442)))+(x4456)+(((IkReal(-1.00000000000000))*(x4447)))+(((IkReal(-1.00000000000000))*(r20)*(x4441))));
16459 evalcond[2]=((((IkReal(-1.00000000000000))*(x4456)))+(x4447)+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4439)))+(((IkReal(-1.00000000000000))*(r10)*(x4444)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4439)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4443))));
16460 evalcond[3]=((((IkReal(-1.00000000000000))*(x4454)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4439)))+(x4455)+(((IkReal(-1.00000000000000))*(r01)*(x4439)*(x4442)))+(((cj0)*(r00)*(x4441)))+(((r10)*(sj0)*(x4441)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4443)))+(((IkReal(-1.00000000000000))*(r11)*(x4442)*(x4443))));
16461 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16462 {
16463 continue;
16464 }
16465 }
16466 
16467 {
16468 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16469 vinfos[0].jointtype = 1;
16470 vinfos[0].foffset = j0;
16471 vinfos[0].indices[0] = _ij0[0];
16472 vinfos[0].indices[1] = _ij0[1];
16473 vinfos[0].maxsolutions = _nj0;
16474 vinfos[1].jointtype = 1;
16475 vinfos[1].foffset = j1;
16476 vinfos[1].indices[0] = _ij1[0];
16477 vinfos[1].indices[1] = _ij1[1];
16478 vinfos[1].maxsolutions = _nj1;
16479 vinfos[2].jointtype = 1;
16480 vinfos[2].foffset = j2;
16481 vinfos[2].indices[0] = _ij2[0];
16482 vinfos[2].indices[1] = _ij2[1];
16483 vinfos[2].maxsolutions = _nj2;
16484 vinfos[3].jointtype = 1;
16485 vinfos[3].foffset = j3;
16486 vinfos[3].indices[0] = _ij3[0];
16487 vinfos[3].indices[1] = _ij3[1];
16488 vinfos[3].maxsolutions = _nj3;
16489 vinfos[4].jointtype = 1;
16490 vinfos[4].foffset = j4;
16491 vinfos[4].indices[0] = _ij4[0];
16492 vinfos[4].indices[1] = _ij4[1];
16493 vinfos[4].maxsolutions = _nj4;
16494 vinfos[5].jointtype = 1;
16495 vinfos[5].foffset = j5;
16496 vinfos[5].indices[0] = _ij5[0];
16497 vinfos[5].indices[1] = _ij5[1];
16498 vinfos[5].maxsolutions = _nj5;
16499 std::vector<int> vfree(0);
16500 solutions.AddSolution(vinfos,vfree);
16501 }
16502 }
16503 }
16504 
16505 }
16506 
16507 }
16508 
16509 } else
16510 {
16511 {
16512 IkReal j1array[1], cj1array[1], sj1array[1];
16513 bool j1valid[1]={false};
16514 _nj1 = 1;
16515 IkReal x4457=((cj5)*(sj4));
16516 IkReal x4458=((r21)*(sj4));
16517 IkReal x4459=((cj5)*(r21));
16518 IkReal x4460=((IkReal(0.707109999985348))*(cj2));
16519 IkReal x4461=((IkReal(0.707103562373095))*(sj2));
16520 IkReal x4462=((IkReal(0.707109999985348))*(sj2));
16521 IkReal x4463=((cj4)*(r22));
16522 IkReal x4464=((IkReal(0.707103562373095))*(cj2));
16523 IkReal x4465=((r20)*(x4460));
16524 IkReal x4466=((sj5)*(x4464));
16525 IkReal x4467=((sj5)*(x4462));
16526 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x4458)*(x4461)))+(((IkReal(-1.00000000000000))*(sj5)*(x4458)*(x4460)))+(((IkReal(-1.00000000000000))*(x4459)*(x4464)))+(((x4459)*(x4462)))+(((r20)*(x4457)*(x4461)))+(((r20)*(x4467)))+(((x4457)*(x4465)))+(((IkReal(-1.00000000000000))*(x4460)*(x4463)))+(((IkReal(-1.00000000000000))*(x4461)*(x4463)))+(((IkReal(-1.00000000000000))*(r20)*(x4466))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((x4458)*(x4466)))+(((IkReal(-1.00000000000000))*(r20)*(x4457)*(x4464)))+(((IkReal(-1.00000000000000))*(x4462)*(x4463)))+(((IkReal(-1.00000000000000))*(x4458)*(x4467)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4461)))+(((IkReal(-1.00000000000000))*(sj5)*(x4465)))+(((IkReal(-1.00000000000000))*(x4459)*(x4461)))+(((IkReal(-1.00000000000000))*(x4459)*(x4460)))+(((r20)*(x4457)*(x4462)))+(((x4463)*(x4464))))))) < IKFAST_ATAN2_MAGTHRESH )
16527     continue;
16528 j1array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(sj5)*(x4458)*(x4461)))+(((IkReal(-1.00000000000000))*(sj5)*(x4458)*(x4460)))+(((IkReal(-1.00000000000000))*(x4459)*(x4464)))+(((x4459)*(x4462)))+(((r20)*(x4457)*(x4461)))+(((r20)*(x4467)))+(((x4457)*(x4465)))+(((IkReal(-1.00000000000000))*(x4460)*(x4463)))+(((IkReal(-1.00000000000000))*(x4461)*(x4463)))+(((IkReal(-1.00000000000000))*(r20)*(x4466)))))), ((gconst42)*(((((x4458)*(x4466)))+(((IkReal(-1.00000000000000))*(r20)*(x4457)*(x4464)))+(((IkReal(-1.00000000000000))*(x4462)*(x4463)))+(((IkReal(-1.00000000000000))*(x4458)*(x4467)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4461)))+(((IkReal(-1.00000000000000))*(sj5)*(x4465)))+(((IkReal(-1.00000000000000))*(x4459)*(x4461)))+(((IkReal(-1.00000000000000))*(x4459)*(x4460)))+(((r20)*(x4457)*(x4462)))+(((x4463)*(x4464)))))));
16529 sj1array[0]=IKsin(j1array[0]);
16530 cj1array[0]=IKcos(j1array[0]);
16531 if( j1array[0] > IKPI )
16532 {
16533     j1array[0]-=IK2PI;
16534 }
16535 else if( j1array[0] < -IKPI )
16536 {    j1array[0]+=IK2PI;
16537 }
16538 j1valid[0] = true;
16539 for(int ij1 = 0; ij1 < 1; ++ij1)
16540 {
16541 if( !j1valid[ij1] )
16542 {
16543     continue;
16544 }
16545 _ij1[0] = ij1; _ij1[1] = -1;
16546 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16547 {
16548 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16549 {
16550     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16551 }
16552 }
16553 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16554 {
16555 IkReal evalcond[4];
16556 IkReal x4468=IKcos(j1);
16557 IkReal x4469=IKsin(j1);
16558 IkReal x4470=((IkReal(0.707109999985348))*(cj2));
16559 IkReal x4471=((IkReal(1.00000000000000))*(cj0));
16560 IkReal x4472=((IkReal(0.707109999985348))*(sj2));
16561 IkReal x4473=((cj5)*(sj4));
16562 IkReal x4474=((sj4)*(sj5));
16563 IkReal x4475=((IkReal(1.00000000000000))*(sj0));
16564 IkReal x4476=((sj5)*(x4475));
16565 IkReal x4477=((IkReal(0.707103562373095))*(x4468));
16566 IkReal x4478=((IkReal(0.707103562373095))*(x4469));
16567 IkReal x4479=((cj2)*(x4477));
16568 IkReal x4480=((x4469)*(x4470));
16569 IkReal x4481=((sj2)*(x4478));
16570 IkReal x4482=((x4468)*(x4472));
16571 IkReal x4483=((sj2)*(x4477));
16572 IkReal x4484=((cj2)*(x4478));
16573 IkReal x4485=((x4468)*(x4470));
16574 IkReal x4486=((x4469)*(x4472));
16575 IkReal x4487=((x4484)+(x4485)+(x4483));
16576 IkReal x4488=((x4480)+(x4481)+(x4482));
16577 evalcond[0]=((((cj5)*(r21)))+(x4487)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x4486))));
16578 evalcond[1]=((((IkReal(-1.00000000000000))*(x4479)))+(((cj4)*(r22)))+(x4488)+(((r21)*(x4474)))+(((IkReal(-1.00000000000000))*(r20)*(x4473))));
16579 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4475)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4471)))+(x4479)+(((IkReal(-1.00000000000000))*(r10)*(x4476)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4471)))+(((IkReal(-1.00000000000000))*(x4488))));
16580 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x4474)*(x4475)))+(x4487)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4475)))+(((cj0)*(r00)*(x4473)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4471)))+(((r10)*(sj0)*(x4473)))+(((IkReal(-1.00000000000000))*(r01)*(x4471)*(x4474)))+(((IkReal(-1.00000000000000))*(x4486))));
16581 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16582 {
16583 continue;
16584 }
16585 }
16586 
16587 {
16588 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16589 vinfos[0].jointtype = 1;
16590 vinfos[0].foffset = j0;
16591 vinfos[0].indices[0] = _ij0[0];
16592 vinfos[0].indices[1] = _ij0[1];
16593 vinfos[0].maxsolutions = _nj0;
16594 vinfos[1].jointtype = 1;
16595 vinfos[1].foffset = j1;
16596 vinfos[1].indices[0] = _ij1[0];
16597 vinfos[1].indices[1] = _ij1[1];
16598 vinfos[1].maxsolutions = _nj1;
16599 vinfos[2].jointtype = 1;
16600 vinfos[2].foffset = j2;
16601 vinfos[2].indices[0] = _ij2[0];
16602 vinfos[2].indices[1] = _ij2[1];
16603 vinfos[2].maxsolutions = _nj2;
16604 vinfos[3].jointtype = 1;
16605 vinfos[3].foffset = j3;
16606 vinfos[3].indices[0] = _ij3[0];
16607 vinfos[3].indices[1] = _ij3[1];
16608 vinfos[3].maxsolutions = _nj3;
16609 vinfos[4].jointtype = 1;
16610 vinfos[4].foffset = j4;
16611 vinfos[4].indices[0] = _ij4[0];
16612 vinfos[4].indices[1] = _ij4[1];
16613 vinfos[4].maxsolutions = _nj4;
16614 vinfos[5].jointtype = 1;
16615 vinfos[5].foffset = j5;
16616 vinfos[5].indices[0] = _ij5[0];
16617 vinfos[5].indices[1] = _ij5[1];
16618 vinfos[5].maxsolutions = _nj5;
16619 std::vector<int> vfree(0);
16620 solutions.AddSolution(vinfos,vfree);
16621 }
16622 }
16623 }
16624 
16625 }
16626 
16627 }
16628 
16629 } else
16630 {
16631 IkReal x4489=((sj0)*(sj4));
16632 IkReal x4490=((IkReal(1.00000000000000))*(r12));
16633 IkReal x4491=((cj0)*(cj4));
16634 IkReal x4492=((r01)*(sj5));
16635 IkReal x4493=((IkReal(1.00000000000000))*(cj5));
16636 IkReal x4494=((cj4)*(cj5));
16637 IkReal x4495=((IkReal(1.00000000000000))*(cj0));
16638 IkReal x4496=((cj4)*(sj0));
16639 IkReal x4497=((r00)*(sj0));
16640 IkReal x4498=((npy)*(sj5));
16641 IkReal x4499=((IkReal(1.00000000000000))*(cj4));
16642 IkReal x4500=((cj0)*(sj4));
16643 IkReal x4501=((r11)*(sj5));
16644 evalcond[0]=((IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))))))+(IKabs(((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.11022302462516e-16))+(j3)), IkReal(6.28318530717959)))))));
16645 evalcond[1]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(r11)*(x4493)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x4495)))+(((sj5)*(x4497))));
16646 evalcond[2]=((IkReal(-0.258003287011922))+(((sj4)*(x4498)))+(((IkReal(-0.207888640466058))*(cj2)))+(((cj4)*(npz)))+(((IkReal(0.165463933124939))*(sj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x4493))));
16647 evalcond[3]=((IkReal(0.0240035672348961))+(((npx)*(sj5)))+(((IkReal(0.207888640466058))*(sj2)))+(((cj5)*(npy)))+(((IkReal(0.165463933124939))*(cj2))));
16648 evalcond[4]=((IkReal(0.00600000000000000))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x4498)*(x4499)))+(((npx)*(x4494))));
16649 evalcond[5]=((((IkReal(-1.00000000000000))*(sj4)*(x4495)*(x4501)))+(((r02)*(x4496)))+(((IkReal(-1.00000000000000))*(x4490)*(x4491)))+(((cj5)*(r10)*(x4500)))+(((IkReal(-1.00000000000000))*(r00)*(x4489)*(x4493)))+(((x4489)*(x4492))));
16650 evalcond[6]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x4490)*(x4500)))+(((IkReal(-1.00000000000000))*(r10)*(x4491)*(x4493)))+(((IkReal(-1.00000000000000))*(x4492)*(x4496)))+(((x4491)*(x4501)))+(((r02)*(x4489)))+(((x4494)*(x4497))));
16651 evalcond[7]=((((IkReal(-1.00000000000000))*(r21)*(sj5)*(x4499)))+(((r22)*(sj4)))+(((r20)*(x4494))));
16652 evalcond[8]=((((IkReal(-1.00000000000000))*(x4489)*(x4490)))+(((x4496)*(x4501)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x4495)))+(((IkReal(-1.00000000000000))*(r10)*(x4493)*(x4496)))+(((IkReal(-1.00000000000000))*(r00)*(x4491)*(x4493)))+(((x4491)*(x4492))));
16653 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  )
16654 {
16655 {
16656 IkReal dummyeval[1];
16657 IkReal gconst44;
16658 gconst44=IKsign((((sj2)*(sj2))+((cj2)*(cj2))));
16659 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
16660 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16661 {
16662 {
16663 IkReal dummyeval[1];
16664 IkReal gconst45;
16665 gconst45=IKsign(((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2))))));
16666 dummyeval[0]=((((IkReal(-1.00000000000000))*((cj2)*(cj2))))+(((IkReal(-1.00000000000000))*((sj2)*(sj2)))));
16667 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16668 {
16669 continue;
16670 
16671 } else
16672 {
16673 {
16674 IkReal j1array[1], cj1array[1], sj1array[1];
16675 bool j1valid[1]={false};
16676 _nj1 = 1;
16677 IkReal x4502=((cj5)*(r11));
16678 IkReal x4503=((r10)*(sj0));
16679 IkReal x4504=((IkReal(0.707103562373095))*(cj2));
16680 IkReal x4505=((r20)*(sj5));
16681 IkReal x4506=((IkReal(0.707103562373095))*(sj2));
16682 IkReal x4507=((IkReal(0.707109999985348))*(cj2));
16683 IkReal x4508=((cj0)*(r00));
16684 IkReal x4509=((IkReal(0.707109999985348))*(sj2));
16685 IkReal x4510=((cj5)*(r21));
16686 IkReal x4511=((sj0)*(x4506));
16687 IkReal x4512=((sj5)*(x4507));
16688 IkReal x4513=((cj0)*(cj5)*(r01));
16689 if( IKabs(((gconst45)*(((((sj5)*(x4503)*(x4506)))+(((x4502)*(x4511)))+(((x4504)*(x4510)))+(((x4503)*(x4512)))+(((sj0)*(x4502)*(x4507)))+(((x4506)*(x4513)))+(((sj5)*(x4506)*(x4508)))+(((x4504)*(x4505)))+(((x4507)*(x4513)))+(((IkReal(-1.00000000000000))*(x4505)*(x4509)))+(((x4508)*(x4512)))+(((IkReal(-1.00000000000000))*(x4509)*(x4510))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((sj5)*(x4503)*(x4509)))+(((IkReal(-1.00000000000000))*(sj0)*(x4502)*(x4504)))+(((IkReal(-1.00000000000000))*(x4504)*(x4513)))+(((sj0)*(x4502)*(x4509)))+(((IkReal(-1.00000000000000))*(sj5)*(x4503)*(x4504)))+(((x4506)*(x4510)))+(((x4505)*(x4506)))+(((x4505)*(x4507)))+(((x4507)*(x4510)))+(((sj5)*(x4508)*(x4509)))+(((IkReal(-1.00000000000000))*(sj5)*(x4504)*(x4508)))+(((x4509)*(x4513))))))) < IKFAST_ATAN2_MAGTHRESH )
16690     continue;
16691 j1array[0]=IKatan2(((gconst45)*(((((sj5)*(x4503)*(x4506)))+(((x4502)*(x4511)))+(((x4504)*(x4510)))+(((x4503)*(x4512)))+(((sj0)*(x4502)*(x4507)))+(((x4506)*(x4513)))+(((sj5)*(x4506)*(x4508)))+(((x4504)*(x4505)))+(((x4507)*(x4513)))+(((IkReal(-1.00000000000000))*(x4505)*(x4509)))+(((x4508)*(x4512)))+(((IkReal(-1.00000000000000))*(x4509)*(x4510)))))), ((gconst45)*(((((sj5)*(x4503)*(x4509)))+(((IkReal(-1.00000000000000))*(sj0)*(x4502)*(x4504)))+(((IkReal(-1.00000000000000))*(x4504)*(x4513)))+(((sj0)*(x4502)*(x4509)))+(((IkReal(-1.00000000000000))*(sj5)*(x4503)*(x4504)))+(((x4506)*(x4510)))+(((x4505)*(x4506)))+(((x4505)*(x4507)))+(((x4507)*(x4510)))+(((sj5)*(x4508)*(x4509)))+(((IkReal(-1.00000000000000))*(sj5)*(x4504)*(x4508)))+(((x4509)*(x4513)))))));
16692 sj1array[0]=IKsin(j1array[0]);
16693 cj1array[0]=IKcos(j1array[0]);
16694 if( j1array[0] > IKPI )
16695 {
16696     j1array[0]-=IK2PI;
16697 }
16698 else if( j1array[0] < -IKPI )
16699 {    j1array[0]+=IK2PI;
16700 }
16701 j1valid[0] = true;
16702 for(int ij1 = 0; ij1 < 1; ++ij1)
16703 {
16704 if( !j1valid[ij1] )
16705 {
16706     continue;
16707 }
16708 _ij1[0] = ij1; _ij1[1] = -1;
16709 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16710 {
16711 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16712 {
16713     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16714 }
16715 }
16716 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16717 {
16718 IkReal evalcond[4];
16719 IkReal x4514=IKcos(j1);
16720 IkReal x4515=IKsin(j1);
16721 IkReal x4516=((IkReal(0.707109999985348))*(cj2));
16722 IkReal x4517=((IkReal(1.00000000000000))*(cj0));
16723 IkReal x4518=((IkReal(0.707109999985348))*(sj2));
16724 IkReal x4519=((cj5)*(sj4));
16725 IkReal x4520=((sj4)*(sj5));
16726 IkReal x4521=((IkReal(1.00000000000000))*(sj0));
16727 IkReal x4522=((sj5)*(x4521));
16728 IkReal x4523=((IkReal(0.707103562373095))*(x4514));
16729 IkReal x4524=((IkReal(0.707103562373095))*(x4515));
16730 IkReal x4525=((cj2)*(x4523));
16731 IkReal x4526=((x4515)*(x4516));
16732 IkReal x4527=((sj2)*(x4524));
16733 IkReal x4528=((x4514)*(x4518));
16734 IkReal x4529=((sj2)*(x4523));
16735 IkReal x4530=((cj2)*(x4524));
16736 IkReal x4531=((x4514)*(x4516));
16737 IkReal x4532=((x4515)*(x4518));
16738 IkReal x4533=((x4530)+(x4531)+(x4529));
16739 IkReal x4534=((x4528)+(x4527)+(x4526));
16740 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4532)))+(x4533)+(((r20)*(sj5))));
16741 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x4525)))+(((r21)*(x4520)))+(x4534)+(((IkReal(-1.00000000000000))*(r20)*(x4519))));
16742 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4517)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4517)))+(((IkReal(-1.00000000000000))*(x4534)))+(x4525)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4521)))+(((IkReal(-1.00000000000000))*(r10)*(x4522))));
16743 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x4520)*(x4521)))+(((IkReal(-1.00000000000000))*(x4532)))+(x4533)+(((r10)*(sj0)*(x4519)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4521)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4517)))+(((cj0)*(r00)*(x4519)))+(((IkReal(-1.00000000000000))*(r01)*(x4517)*(x4520))));
16744 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16745 {
16746 continue;
16747 }
16748 }
16749 
16750 {
16751 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16752 vinfos[0].jointtype = 1;
16753 vinfos[0].foffset = j0;
16754 vinfos[0].indices[0] = _ij0[0];
16755 vinfos[0].indices[1] = _ij0[1];
16756 vinfos[0].maxsolutions = _nj0;
16757 vinfos[1].jointtype = 1;
16758 vinfos[1].foffset = j1;
16759 vinfos[1].indices[0] = _ij1[0];
16760 vinfos[1].indices[1] = _ij1[1];
16761 vinfos[1].maxsolutions = _nj1;
16762 vinfos[2].jointtype = 1;
16763 vinfos[2].foffset = j2;
16764 vinfos[2].indices[0] = _ij2[0];
16765 vinfos[2].indices[1] = _ij2[1];
16766 vinfos[2].maxsolutions = _nj2;
16767 vinfos[3].jointtype = 1;
16768 vinfos[3].foffset = j3;
16769 vinfos[3].indices[0] = _ij3[0];
16770 vinfos[3].indices[1] = _ij3[1];
16771 vinfos[3].maxsolutions = _nj3;
16772 vinfos[4].jointtype = 1;
16773 vinfos[4].foffset = j4;
16774 vinfos[4].indices[0] = _ij4[0];
16775 vinfos[4].indices[1] = _ij4[1];
16776 vinfos[4].maxsolutions = _nj4;
16777 vinfos[5].jointtype = 1;
16778 vinfos[5].foffset = j5;
16779 vinfos[5].indices[0] = _ij5[0];
16780 vinfos[5].indices[1] = _ij5[1];
16781 vinfos[5].maxsolutions = _nj5;
16782 std::vector<int> vfree(0);
16783 solutions.AddSolution(vinfos,vfree);
16784 }
16785 }
16786 }
16787 
16788 }
16789 
16790 }
16791 
16792 } else
16793 {
16794 {
16795 IkReal j1array[1], cj1array[1], sj1array[1];
16796 bool j1valid[1]={false};
16797 _nj1 = 1;
16798 IkReal x4535=((cj5)*(sj4));
16799 IkReal x4536=((r21)*(sj4));
16800 IkReal x4537=((cj5)*(r21));
16801 IkReal x4538=((IkReal(0.707109999985348))*(cj2));
16802 IkReal x4539=((IkReal(0.707103562373095))*(sj2));
16803 IkReal x4540=((IkReal(0.707109999985348))*(sj2));
16804 IkReal x4541=((cj4)*(r22));
16805 IkReal x4542=((IkReal(0.707103562373095))*(cj2));
16806 IkReal x4543=((r20)*(x4538));
16807 IkReal x4544=((sj5)*(x4542));
16808 IkReal x4545=((sj5)*(x4540));
16809 if( IKabs(((gconst44)*(((((r20)*(x4535)*(x4539)))+(((x4537)*(x4540)))+(((IkReal(-1.00000000000000))*(x4537)*(x4542)))+(((r20)*(x4545)))+(((IkReal(-1.00000000000000))*(r20)*(x4544)))+(((IkReal(-1.00000000000000))*(x4538)*(x4541)))+(((x4535)*(x4543)))+(((IkReal(-1.00000000000000))*(x4539)*(x4541)))+(((IkReal(-1.00000000000000))*(sj5)*(x4536)*(x4538)))+(((IkReal(-1.00000000000000))*(sj5)*(x4536)*(x4539))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4539)))+(((r20)*(x4535)*(x4540)))+(((IkReal(-1.00000000000000))*(x4537)*(x4538)))+(((IkReal(-1.00000000000000))*(x4537)*(x4539)))+(((IkReal(-1.00000000000000))*(x4536)*(x4545)))+(((IkReal(-1.00000000000000))*(x4540)*(x4541)))+(((IkReal(-1.00000000000000))*(r20)*(x4535)*(x4542)))+(((x4536)*(x4544)))+(((x4541)*(x4542)))+(((IkReal(-1.00000000000000))*(sj5)*(x4543))))))) < IKFAST_ATAN2_MAGTHRESH )
16810     continue;
16811 j1array[0]=IKatan2(((gconst44)*(((((r20)*(x4535)*(x4539)))+(((x4537)*(x4540)))+(((IkReal(-1.00000000000000))*(x4537)*(x4542)))+(((r20)*(x4545)))+(((IkReal(-1.00000000000000))*(r20)*(x4544)))+(((IkReal(-1.00000000000000))*(x4538)*(x4541)))+(((x4535)*(x4543)))+(((IkReal(-1.00000000000000))*(x4539)*(x4541)))+(((IkReal(-1.00000000000000))*(sj5)*(x4536)*(x4538)))+(((IkReal(-1.00000000000000))*(sj5)*(x4536)*(x4539)))))), ((gconst44)*(((((IkReal(-1.00000000000000))*(r20)*(sj5)*(x4539)))+(((r20)*(x4535)*(x4540)))+(((IkReal(-1.00000000000000))*(x4537)*(x4538)))+(((IkReal(-1.00000000000000))*(x4537)*(x4539)))+(((IkReal(-1.00000000000000))*(x4536)*(x4545)))+(((IkReal(-1.00000000000000))*(x4540)*(x4541)))+(((IkReal(-1.00000000000000))*(r20)*(x4535)*(x4542)))+(((x4536)*(x4544)))+(((x4541)*(x4542)))+(((IkReal(-1.00000000000000))*(sj5)*(x4543)))))));
16812 sj1array[0]=IKsin(j1array[0]);
16813 cj1array[0]=IKcos(j1array[0]);
16814 if( j1array[0] > IKPI )
16815 {
16816     j1array[0]-=IK2PI;
16817 }
16818 else if( j1array[0] < -IKPI )
16819 {    j1array[0]+=IK2PI;
16820 }
16821 j1valid[0] = true;
16822 for(int ij1 = 0; ij1 < 1; ++ij1)
16823 {
16824 if( !j1valid[ij1] )
16825 {
16826     continue;
16827 }
16828 _ij1[0] = ij1; _ij1[1] = -1;
16829 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16830 {
16831 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16832 {
16833     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16834 }
16835 }
16836 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16837 {
16838 IkReal evalcond[4];
16839 IkReal x4546=IKcos(j1);
16840 IkReal x4547=IKsin(j1);
16841 IkReal x4548=((IkReal(0.707109999985348))*(cj2));
16842 IkReal x4549=((IkReal(1.00000000000000))*(cj0));
16843 IkReal x4550=((IkReal(0.707109999985348))*(sj2));
16844 IkReal x4551=((cj5)*(sj4));
16845 IkReal x4552=((sj4)*(sj5));
16846 IkReal x4553=((IkReal(1.00000000000000))*(sj0));
16847 IkReal x4554=((sj5)*(x4553));
16848 IkReal x4555=((IkReal(0.707103562373095))*(x4546));
16849 IkReal x4556=((IkReal(0.707103562373095))*(x4547));
16850 IkReal x4557=((cj2)*(x4555));
16851 IkReal x4558=((x4547)*(x4548));
16852 IkReal x4559=((sj2)*(x4556));
16853 IkReal x4560=((x4546)*(x4550));
16854 IkReal x4561=((sj2)*(x4555));
16855 IkReal x4562=((cj2)*(x4556));
16856 IkReal x4563=((x4546)*(x4548));
16857 IkReal x4564=((x4547)*(x4550));
16858 IkReal x4565=((x4563)+(x4562)+(x4561));
16859 IkReal x4566=((x4558)+(x4559)+(x4560));
16860 evalcond[0]=((((cj5)*(r21)))+(x4565)+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x4564))));
16861 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x4551)))+(x4566)+(((IkReal(-1.00000000000000))*(x4557)))+(((r21)*(x4552))));
16862 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4549)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x4553)))+(x4557)+(((IkReal(-1.00000000000000))*(r10)*(x4554)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4549)))+(((IkReal(-1.00000000000000))*(x4566))));
16863 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x4553)))+(x4565)+(((IkReal(-1.00000000000000))*(r11)*(x4552)*(x4553)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x4549)))+(((IkReal(-1.00000000000000))*(r01)*(x4549)*(x4552)))+(((r10)*(sj0)*(x4551)))+(((cj0)*(r00)*(x4551)))+(((IkReal(-1.00000000000000))*(x4564))));
16864 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16865 {
16866 continue;
16867 }
16868 }
16869 
16870 {
16871 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16872 vinfos[0].jointtype = 1;
16873 vinfos[0].foffset = j0;
16874 vinfos[0].indices[0] = _ij0[0];
16875 vinfos[0].indices[1] = _ij0[1];
16876 vinfos[0].maxsolutions = _nj0;
16877 vinfos[1].jointtype = 1;
16878 vinfos[1].foffset = j1;
16879 vinfos[1].indices[0] = _ij1[0];
16880 vinfos[1].indices[1] = _ij1[1];
16881 vinfos[1].maxsolutions = _nj1;
16882 vinfos[2].jointtype = 1;
16883 vinfos[2].foffset = j2;
16884 vinfos[2].indices[0] = _ij2[0];
16885 vinfos[2].indices[1] = _ij2[1];
16886 vinfos[2].maxsolutions = _nj2;
16887 vinfos[3].jointtype = 1;
16888 vinfos[3].foffset = j3;
16889 vinfos[3].indices[0] = _ij3[0];
16890 vinfos[3].indices[1] = _ij3[1];
16891 vinfos[3].maxsolutions = _nj3;
16892 vinfos[4].jointtype = 1;
16893 vinfos[4].foffset = j4;
16894 vinfos[4].indices[0] = _ij4[0];
16895 vinfos[4].indices[1] = _ij4[1];
16896 vinfos[4].maxsolutions = _nj4;
16897 vinfos[5].jointtype = 1;
16898 vinfos[5].foffset = j5;
16899 vinfos[5].indices[0] = _ij5[0];
16900 vinfos[5].indices[1] = _ij5[1];
16901 vinfos[5].maxsolutions = _nj5;
16902 std::vector<int> vfree(0);
16903 solutions.AddSolution(vinfos,vfree);
16904 }
16905 }
16906 }
16907 
16908 }
16909 
16910 }
16911 
16912 } else
16913 {
16914 if( 1 )
16915 {
16916 continue;
16917 
16918 } else
16919 {
16920 }
16921 }
16922 }
16923 }
16924 }
16925 }
16926 
16927 } else
16928 {
16929 {
16930 IkReal j1array[1], cj1array[1], sj1array[1];
16931 bool j1valid[1]={false};
16932 _nj1 = 1;
16933 IkReal x4567=((IkReal(0.707109999985348))*(sj2));
16934 IkReal x4568=((r22)*(sj4));
16935 IkReal x4569=((cj5)*(r20));
16936 IkReal x4570=((r21)*(sj5));
16937 IkReal x4571=((IkReal(0.707109999985348))*(cj2));
16938 IkReal x4572=((cj3)*(r22));
16939 IkReal x4573=((cj3)*(sj4));
16940 IkReal x4574=((IkReal(0.707103562373095))*(cj4)*(sj2));
16941 IkReal x4575=((IkReal(0.707103562373095))*(x4573));
16942 IkReal x4576=((IkReal(0.707103562373095))*(cj2)*(cj4));
16943 if( IKabs(((gconst37)*(((((x4570)*(x4571)*(x4573)))+(((IkReal(-1.00000000000000))*(cj4)*(x4567)*(x4569)))+(((cj4)*(x4567)*(x4570)))+(((sj2)*(x4570)*(x4575)))+(((IkReal(-1.00000000000000))*(x4567)*(x4568)))+(((IkReal(-1.00000000000000))*(x4570)*(x4576)))+(((x4569)*(x4576)))+(((IkReal(-1.00000000000000))*(sj2)*(x4569)*(x4575)))+(((IkReal(0.707103562373095))*(cj2)*(x4568)))+(((IkReal(-1.00000000000000))*(x4569)*(x4571)*(x4573)))+(((x4572)*(x4574)))+(((cj4)*(x4571)*(x4572))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((IkReal(-1.00000000000000))*(cj2)*(x4570)*(x4575)))+(((cj4)*(x4567)*(x4572)))+(((IkReal(-1.00000000000000))*(cj4)*(x4570)*(x4571)))+(((IkReal(-1.00000000000000))*(x4570)*(x4574)))+(((cj4)*(x4569)*(x4571)))+(((cj2)*(x4569)*(x4575)))+(((x4569)*(x4574)))+(((x4568)*(x4571)))+(((IkReal(-1.00000000000000))*(x4572)*(x4576)))+(((IkReal(-1.00000000000000))*(x4567)*(x4569)*(x4573)))+(((x4567)*(x4570)*(x4573)))+(((IkReal(0.707103562373095))*(sj2)*(x4568))))))) < IKFAST_ATAN2_MAGTHRESH )
16944     continue;
16945 j1array[0]=IKatan2(((gconst37)*(((((x4570)*(x4571)*(x4573)))+(((IkReal(-1.00000000000000))*(cj4)*(x4567)*(x4569)))+(((cj4)*(x4567)*(x4570)))+(((sj2)*(x4570)*(x4575)))+(((IkReal(-1.00000000000000))*(x4567)*(x4568)))+(((IkReal(-1.00000000000000))*(x4570)*(x4576)))+(((x4569)*(x4576)))+(((IkReal(-1.00000000000000))*(sj2)*(x4569)*(x4575)))+(((IkReal(0.707103562373095))*(cj2)*(x4568)))+(((IkReal(-1.00000000000000))*(x4569)*(x4571)*(x4573)))+(((x4572)*(x4574)))+(((cj4)*(x4571)*(x4572)))))), ((gconst37)*(((((IkReal(-1.00000000000000))*(cj2)*(x4570)*(x4575)))+(((cj4)*(x4567)*(x4572)))+(((IkReal(-1.00000000000000))*(cj4)*(x4570)*(x4571)))+(((IkReal(-1.00000000000000))*(x4570)*(x4574)))+(((cj4)*(x4569)*(x4571)))+(((cj2)*(x4569)*(x4575)))+(((x4569)*(x4574)))+(((x4568)*(x4571)))+(((IkReal(-1.00000000000000))*(x4572)*(x4576)))+(((IkReal(-1.00000000000000))*(x4567)*(x4569)*(x4573)))+(((x4567)*(x4570)*(x4573)))+(((IkReal(0.707103562373095))*(sj2)*(x4568)))))));
16946 sj1array[0]=IKsin(j1array[0]);
16947 cj1array[0]=IKcos(j1array[0]);
16948 if( j1array[0] > IKPI )
16949 {
16950     j1array[0]-=IK2PI;
16951 }
16952 else if( j1array[0] < -IKPI )
16953 {    j1array[0]+=IK2PI;
16954 }
16955 j1valid[0] = true;
16956 for(int ij1 = 0; ij1 < 1; ++ij1)
16957 {
16958 if( !j1valid[ij1] )
16959 {
16960     continue;
16961 }
16962 _ij1[0] = ij1; _ij1[1] = -1;
16963 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
16964 {
16965 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
16966 {
16967     j1valid[iij1]=false; _ij1[1] = iij1; break; 
16968 }
16969 }
16970 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
16971 {
16972 IkReal evalcond[6];
16973 IkReal x4577=IKcos(j1);
16974 IkReal x4578=IKsin(j1);
16975 IkReal x4579=((cj0)*(cj4));
16976 IkReal x4580=((r01)*(sj5));
16977 IkReal x4581=((IkReal(1.00000000000000))*(cj4));
16978 IkReal x4582=((IkReal(1.00000000000000))*(r02));
16979 IkReal x4583=((IkReal(0.707109999985348))*(sj3));
16980 IkReal x4584=((IkReal(0.707103562373095))*(sj3));
16981 IkReal x4585=((IkReal(1.00000000000000))*(sj4));
16982 IkReal x4586=((cj5)*(r20));
16983 IkReal x4587=((cj5)*(sj0));
16984 IkReal x4588=((IkReal(1.00000000000000))*(cj0));
16985 IkReal x4589=((r12)*(sj0));
16986 IkReal x4590=((cj2)*(cj3));
16987 IkReal x4591=((IkReal(0.707103562373095))*(cj3));
16988 IkReal x4592=((r21)*(sj5));
16989 IkReal x4593=((IkReal(0.707109999985348))*(cj3));
16990 IkReal x4594=((IkReal(1.00000000000000))*(sj0)*(sj5));
16991 IkReal x4595=((sj2)*(x4577));
16992 IkReal x4596=((cj2)*(x4577));
16993 IkReal x4597=((cj0)*(cj5)*(r00));
16994 IkReal x4598=((IkReal(0.707103562373095))*(x4578));
16995 IkReal x4599=((cj2)*(x4578));
16996 IkReal x4600=((IkReal(0.707109999985348))*(sj2)*(x4578));
16997 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4583)*(x4596)))+(((sj2)*(x4578)*(x4583)))+(((IkReal(-1.00000000000000))*(x4584)*(x4599)))+(((IkReal(-1.00000000000000))*(x4584)*(x4595)))+(((r20)*(sj5))));
16998 evalcond[1]=((((cj4)*(r22)))+(((sj4)*(x4592)))+(((IkReal(0.707109999985348))*(x4599)))+(((IkReal(0.707109999985348))*(x4595)))+(((sj2)*(x4598)))+(((IkReal(-1.00000000000000))*(x4585)*(x4586)))+(((IkReal(-0.707103562373095))*(x4596))));
16999 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x4578)*(x4593)))+(((IkReal(0.707109999985348))*(x4577)*(x4590)))+(((x4590)*(x4598)))+(((cj4)*(x4586)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x4581)*(x4592)))+(((x4591)*(x4595))));
17000 evalcond[3]=((((sj2)*(x4578)*(x4584)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4588)))+(((x4583)*(x4595)))+(((x4583)*(x4599)))+(((IkReal(-1.00000000000000))*(r10)*(x4594)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4588)))+(((IkReal(-1.00000000000000))*(x4584)*(x4596)))+(((IkReal(-1.00000000000000))*(r11)*(x4587))));
17001 evalcond[4]=((((r10)*(sj4)*(x4587)))+(((IkReal(-1.00000000000000))*(x4579)*(x4582)))+(((IkReal(-1.00000000000000))*(x4600)))+(((IkReal(-1.00000000000000))*(cj0)*(x4580)*(x4585)))+(((sj4)*(x4597)))+(((IkReal(-1.00000000000000))*(x4581)*(x4589)))+(((IkReal(0.707109999985348))*(x4596)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x4585)))+(((IkReal(0.707103562373095))*(x4595)))+(((cj2)*(x4598))));
17002 evalcond[5]=((((IkReal(-1.00000000000000))*(sj2)*(x4578)*(x4591)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4579)))+(((x4579)*(x4580)))+(((IkReal(-1.00000000000000))*(x4593)*(x4595)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(0.707103562373095))*(x4577)*(x4590)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x4582)))+(((IkReal(-1.00000000000000))*(r10)*(x4581)*(x4587)))+(((IkReal(-1.00000000000000))*(x4585)*(x4589)))+(((IkReal(-0.707109999985348))*(x4578)*(x4590))));
17003 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  )
17004 {
17005 continue;
17006 }
17007 }
17008 
17009 {
17010 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17011 vinfos[0].jointtype = 1;
17012 vinfos[0].foffset = j0;
17013 vinfos[0].indices[0] = _ij0[0];
17014 vinfos[0].indices[1] = _ij0[1];
17015 vinfos[0].maxsolutions = _nj0;
17016 vinfos[1].jointtype = 1;
17017 vinfos[1].foffset = j1;
17018 vinfos[1].indices[0] = _ij1[0];
17019 vinfos[1].indices[1] = _ij1[1];
17020 vinfos[1].maxsolutions = _nj1;
17021 vinfos[2].jointtype = 1;
17022 vinfos[2].foffset = j2;
17023 vinfos[2].indices[0] = _ij2[0];
17024 vinfos[2].indices[1] = _ij2[1];
17025 vinfos[2].maxsolutions = _nj2;
17026 vinfos[3].jointtype = 1;
17027 vinfos[3].foffset = j3;
17028 vinfos[3].indices[0] = _ij3[0];
17029 vinfos[3].indices[1] = _ij3[1];
17030 vinfos[3].maxsolutions = _nj3;
17031 vinfos[4].jointtype = 1;
17032 vinfos[4].foffset = j4;
17033 vinfos[4].indices[0] = _ij4[0];
17034 vinfos[4].indices[1] = _ij4[1];
17035 vinfos[4].maxsolutions = _nj4;
17036 vinfos[5].jointtype = 1;
17037 vinfos[5].foffset = j5;
17038 vinfos[5].indices[0] = _ij5[0];
17039 vinfos[5].indices[1] = _ij5[1];
17040 vinfos[5].maxsolutions = _nj5;
17041 std::vector<int> vfree(0);
17042 solutions.AddSolution(vinfos,vfree);
17043 }
17044 }
17045 }
17046 
17047 }
17048 
17049 }
17050 
17051 } else
17052 {
17053 {
17054 IkReal j1array[1], cj1array[1], sj1array[1];
17055 bool j1valid[1]={false};
17056 _nj1 = 1;
17057 IkReal x4601=((sj2)*(sj3));
17058 IkReal x4602=((cj4)*(r22));
17059 IkReal x4603=((r20)*(sj5));
17060 IkReal x4604=((IkReal(0.707103562373095))*(cj2));
17061 IkReal x4605=((IkReal(0.707109999985348))*(sj2));
17062 IkReal x4606=((IkReal(0.707109999985348))*(cj2));
17063 IkReal x4607=((cj5)*(r21));
17064 IkReal x4608=((IkReal(0.707103562373095))*(sj2));
17065 IkReal x4609=((r21)*(sj4)*(sj5));
17066 IkReal x4610=((cj5)*(r20)*(sj4));
17067 if( IKabs(((gconst36)*(((((x4605)*(x4607)))+(((IkReal(-1.00000000000000))*(x4603)*(x4604)))+(((IkReal(-0.707103562373095))*(x4601)*(x4610)))+(((x4603)*(x4605)))+(((sj3)*(x4606)*(x4609)))+(((IkReal(0.707103562373095))*(x4601)*(x4609)))+(((IkReal(0.707103562373095))*(x4601)*(x4602)))+(((IkReal(-1.00000000000000))*(x4604)*(x4607)))+(((sj3)*(x4602)*(x4606)))+(((IkReal(-1.00000000000000))*(sj3)*(x4606)*(x4610))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((sj3)*(x4604)*(x4610)))+(((IkReal(-1.00000000000000))*(x4603)*(x4608)))+(((IkReal(-1.00000000000000))*(x4603)*(x4606)))+(((IkReal(-1.00000000000000))*(x4606)*(x4607)))+(((IkReal(-1.00000000000000))*(sj3)*(x4604)*(x4609)))+(((IkReal(0.707109999985348))*(x4601)*(x4609)))+(((IkReal(0.707109999985348))*(x4601)*(x4602)))+(((IkReal(-0.707109999985348))*(x4601)*(x4610)))+(((IkReal(-1.00000000000000))*(sj3)*(x4602)*(x4604)))+(((IkReal(-1.00000000000000))*(x4607)*(x4608))))))) < IKFAST_ATAN2_MAGTHRESH )
17068     continue;
17069 j1array[0]=IKatan2(((gconst36)*(((((x4605)*(x4607)))+(((IkReal(-1.00000000000000))*(x4603)*(x4604)))+(((IkReal(-0.707103562373095))*(x4601)*(x4610)))+(((x4603)*(x4605)))+(((sj3)*(x4606)*(x4609)))+(((IkReal(0.707103562373095))*(x4601)*(x4609)))+(((IkReal(0.707103562373095))*(x4601)*(x4602)))+(((IkReal(-1.00000000000000))*(x4604)*(x4607)))+(((sj3)*(x4602)*(x4606)))+(((IkReal(-1.00000000000000))*(sj3)*(x4606)*(x4610)))))), ((gconst36)*(((((sj3)*(x4604)*(x4610)))+(((IkReal(-1.00000000000000))*(x4603)*(x4608)))+(((IkReal(-1.00000000000000))*(x4603)*(x4606)))+(((IkReal(-1.00000000000000))*(x4606)*(x4607)))+(((IkReal(-1.00000000000000))*(sj3)*(x4604)*(x4609)))+(((IkReal(0.707109999985348))*(x4601)*(x4609)))+(((IkReal(0.707109999985348))*(x4601)*(x4602)))+(((IkReal(-0.707109999985348))*(x4601)*(x4610)))+(((IkReal(-1.00000000000000))*(sj3)*(x4602)*(x4604)))+(((IkReal(-1.00000000000000))*(x4607)*(x4608)))))));
17070 sj1array[0]=IKsin(j1array[0]);
17071 cj1array[0]=IKcos(j1array[0]);
17072 if( j1array[0] > IKPI )
17073 {
17074     j1array[0]-=IK2PI;
17075 }
17076 else if( j1array[0] < -IKPI )
17077 {    j1array[0]+=IK2PI;
17078 }
17079 j1valid[0] = true;
17080 for(int ij1 = 0; ij1 < 1; ++ij1)
17081 {
17082 if( !j1valid[ij1] )
17083 {
17084     continue;
17085 }
17086 _ij1[0] = ij1; _ij1[1] = -1;
17087 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
17088 {
17089 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
17090 {
17091     j1valid[iij1]=false; _ij1[1] = iij1; break; 
17092 }
17093 }
17094 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
17095 {
17096 IkReal evalcond[6];
17097 IkReal x4611=IKcos(j1);
17098 IkReal x4612=IKsin(j1);
17099 IkReal x4613=((cj0)*(cj4));
17100 IkReal x4614=((r01)*(sj5));
17101 IkReal x4615=((IkReal(1.00000000000000))*(cj4));
17102 IkReal x4616=((IkReal(1.00000000000000))*(r02));
17103 IkReal x4617=((IkReal(0.707109999985348))*(sj3));
17104 IkReal x4618=((IkReal(0.707103562373095))*(sj3));
17105 IkReal x4619=((IkReal(1.00000000000000))*(sj4));
17106 IkReal x4620=((cj5)*(r20));
17107 IkReal x4621=((cj5)*(sj0));
17108 IkReal x4622=((IkReal(1.00000000000000))*(cj0));
17109 IkReal x4623=((r12)*(sj0));
17110 IkReal x4624=((cj2)*(cj3));
17111 IkReal x4625=((IkReal(0.707103562373095))*(cj3));
17112 IkReal x4626=((r21)*(sj5));
17113 IkReal x4627=((IkReal(0.707109999985348))*(cj3));
17114 IkReal x4628=((IkReal(1.00000000000000))*(sj0)*(sj5));
17115 IkReal x4629=((sj2)*(x4611));
17116 IkReal x4630=((cj2)*(x4611));
17117 IkReal x4631=((cj0)*(cj5)*(r00));
17118 IkReal x4632=((IkReal(0.707103562373095))*(x4612));
17119 IkReal x4633=((cj2)*(x4612));
17120 IkReal x4634=((IkReal(0.707109999985348))*(sj2)*(x4612));
17121 evalcond[0]=((((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(x4617)*(x4630)))+(((IkReal(-1.00000000000000))*(x4618)*(x4629)))+(((sj2)*(x4612)*(x4617)))+(((IkReal(-1.00000000000000))*(x4618)*(x4633)))+(((r20)*(sj5))));
17122 evalcond[1]=((((cj4)*(r22)))+(((IkReal(0.707109999985348))*(x4633)))+(((IkReal(0.707109999985348))*(x4629)))+(((IkReal(-1.00000000000000))*(x4619)*(x4620)))+(((sj2)*(x4632)))+(((IkReal(-0.707103562373095))*(x4630)))+(((sj4)*(x4626))));
17123 evalcond[2]=((((IkReal(-1.00000000000000))*(sj2)*(x4612)*(x4627)))+(((r22)*(sj4)))+(((x4624)*(x4632)))+(((cj4)*(x4620)))+(((IkReal(0.707109999985348))*(x4611)*(x4624)))+(((x4625)*(x4629)))+(((IkReal(-1.00000000000000))*(x4615)*(x4626))));
17124 evalcond[3]=((((sj2)*(x4612)*(x4618)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x4622)))+(((x4617)*(x4633)))+(((IkReal(-1.00000000000000))*(x4618)*(x4630)))+(((IkReal(-1.00000000000000))*(r11)*(x4621)))+(((x4617)*(x4629)))+(((IkReal(-1.00000000000000))*(r10)*(x4628)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x4622))));
17125 evalcond[4]=((((sj4)*(x4631)))+(((IkReal(0.707103562373095))*(x4629)))+(((IkReal(-1.00000000000000))*(x4634)))+(((IkReal(-1.00000000000000))*(cj0)*(x4614)*(x4619)))+(((IkReal(0.707109999985348))*(x4630)))+(((r10)*(sj4)*(x4621)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x4619)))+(((cj2)*(x4632)))+(((IkReal(-1.00000000000000))*(x4615)*(x4623)))+(((IkReal(-1.00000000000000))*(x4613)*(x4616))));
17126 evalcond[5]=((((IkReal(-1.00000000000000))*(sj2)*(x4612)*(x4625)))+(((IkReal(-1.00000000000000))*(x4627)*(x4629)))+(((IkReal(0.707103562373095))*(x4611)*(x4624)))+(((cj4)*(r11)*(sj0)*(sj5)))+(((IkReal(-1.00000000000000))*(cj0)*(sj4)*(x4616)))+(((IkReal(-1.00000000000000))*(r10)*(x4615)*(x4621)))+(((IkReal(-1.00000000000000))*(x4619)*(x4623)))+(((IkReal(-0.707109999985348))*(x4612)*(x4624)))+(((IkReal(-1.00000000000000))*(cj5)*(r00)*(x4613)))+(((x4613)*(x4614))));
17127 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  )
17128 {
17129 continue;
17130 }
17131 }
17132 
17133 {
17134 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
17135 vinfos[0].jointtype = 1;
17136 vinfos[0].foffset = j0;
17137 vinfos[0].indices[0] = _ij0[0];
17138 vinfos[0].indices[1] = _ij0[1];
17139 vinfos[0].maxsolutions = _nj0;
17140 vinfos[1].jointtype = 1;
17141 vinfos[1].foffset = j1;
17142 vinfos[1].indices[0] = _ij1[0];
17143 vinfos[1].indices[1] = _ij1[1];
17144 vinfos[1].maxsolutions = _nj1;
17145 vinfos[2].jointtype = 1;
17146 vinfos[2].foffset = j2;
17147 vinfos[2].indices[0] = _ij2[0];
17148 vinfos[2].indices[1] = _ij2[1];
17149 vinfos[2].maxsolutions = _nj2;
17150 vinfos[3].jointtype = 1;
17151 vinfos[3].foffset = j3;
17152 vinfos[3].indices[0] = _ij3[0];
17153 vinfos[3].indices[1] = _ij3[1];
17154 vinfos[3].maxsolutions = _nj3;
17155 vinfos[4].jointtype = 1;
17156 vinfos[4].foffset = j4;
17157 vinfos[4].indices[0] = _ij4[0];
17158 vinfos[4].indices[1] = _ij4[1];
17159 vinfos[4].maxsolutions = _nj4;
17160 vinfos[5].jointtype = 1;
17161 vinfos[5].foffset = j5;
17162 vinfos[5].indices[0] = _ij5[0];
17163 vinfos[5].indices[1] = _ij5[1];
17164 vinfos[5].maxsolutions = _nj5;
17165 std::vector<int> vfree(0);
17166 solutions.AddSolution(vinfos,vfree);
17167 }
17168 }
17169 }
17170 
17171 }
17172 
17173 }
17174 }
17175 }
17176 
17177 }
17178 
17179 }
17180 }
17181 }
17182 
17183 }
17184 
17185 }
17186     }
17187 }
17188 return solutions.GetNumSolutions()>0;
17189 }
17190 
17191 static inline bool checkconsistency8(const IkReal* Breal)
17192 {
17193     IkReal norm = 0.1;
17194     for(int i = 0; i < 7; ++i) {
17195         norm += IKabs(Breal[i]);
17196     }
17197     IkReal tol = 1e-5*norm; // have to increase the threshold since many computations are involved
17198     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;
17199 }
17203 static inline void solvedialyticpoly8qep(const IkReal* matcoeffs, IkReal* rawroots, int& numroots)
17204 {
17205     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
17206     IkReal IKFAST_ALIGNED16(M[16*16]) = {0};
17207     IkReal IKFAST_ALIGNED16(A[8*8]);
17208     IkReal IKFAST_ALIGNED16(work[16*16*15]);
17209     int ipiv[8];
17210     int info, coeffindex;
17211     const int worksize=16*16*15;
17212     const int matrixdim = 8;
17213     const int matrixdim2 = 16;
17214     numroots = 0;
17215     // first setup M = [0 I; -C -B] and A
17216     coeffindex = 0;
17217     for(int j = 0; j < 4; ++j) {
17218         for(int k = 0; k < 6; ++k) {
17219             M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -matcoeffs[coeffindex++];
17220         }
17221     }
17222     for(int j = 0; j < 4; ++j) {
17223         for(int k = 0; k < 6; ++k) {
17224             M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -matcoeffs[coeffindex++];
17225         }
17226     }
17227     for(int j = 0; j < 4; ++j) {
17228         for(int k = 0; k < 6; ++k) {
17229             A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = matcoeffs[coeffindex++];
17230         }
17231         for(int k = 0; k < 2; ++k) {
17232             A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
17233         }
17234     }
17235     const IkReal lfpossibilities[4][4] = {{1,-1,1,1},{1,0,-2,1},{1,1,2,0},{1,-1,4,1}};
17236     int lfindex = -1;
17237     bool bsingular = true;
17238     do {
17239         dgetrf_(&matrixdim,&matrixdim,A,&matrixdim,&ipiv[0],&info);
17240         if( info == 0 ) {
17241             bsingular = false;
17242             for(int j = 0; j < matrixdim; ++j) {
17243                 if( IKabs(A[j*matrixdim+j]) < 100*tol ) {
17244                     bsingular = true;
17245                     break;
17246                 }
17247             }
17248             if( !bsingular ) {
17249                 break;
17250             }
17251         }
17252         if( lfindex == 3 ) {
17253             break;
17254         }
17255         // transform by the linear functional
17256         lfindex++;
17257         const IkReal* lf = lfpossibilities[lfindex];
17258         // have to reinitialize A
17259         coeffindex = 0;
17260         for(int j = 0; j < 4; ++j) {
17261             for(int k = 0; k < 6; ++k) {
17262                 IkReal a = matcoeffs[coeffindex+48], b = matcoeffs[coeffindex+24], c = matcoeffs[coeffindex];
17263                 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;
17264                 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);
17265                 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);
17266                 coeffindex++;
17267             }
17268             for(int k = 0; k < 2; ++k) {
17269                 A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
17270             }
17271         }
17272     } while(lfindex<4);
17273 
17274     if( bsingular ) {
17275         return;
17276     }
17277     dgetrs_("No transpose", &matrixdim, &matrixdim2, A, &matrixdim, &ipiv[0], &M[matrixdim], &matrixdim2, &info);
17278     if( info != 0 ) {
17279         return;
17280     }
17281 
17282     // set identity in upper corner
17283     for(int j = 0; j < matrixdim; ++j) {
17284         M[matrixdim*2*matrixdim+j+matrixdim*2*j] = 1;
17285     }
17286     IkReal IKFAST_ALIGNED16(wr[16]);
17287     IkReal IKFAST_ALIGNED16(wi[16]);
17288     IkReal IKFAST_ALIGNED16(vr[16*16]);
17289     int one=1;
17290     dgeev_("N", "V", &matrixdim2, M, &matrixdim2, wr, wi,NULL, &one, vr, &matrixdim2, work, &worksize, &info);
17291     if( info != 0 ) {
17292         return;
17293     }
17294     IkReal Breal[matrixdim-1];
17295     for(int i = 0; i < matrixdim2; ++i) {
17296         if( IKabs(wi[i]) < tol*100 ) {
17297             IkReal* ev = vr+matrixdim2*i;
17298             if( IKabs(wr[i]) > 1 ) {
17299                 ev += matrixdim;
17300             }
17301             // consistency has to be checked!!
17302             if( IKabs(ev[0]) < tol ) {
17303                 continue;
17304             }
17305             IkReal iconst = 1/ev[0];
17306             for(int j = 1; j < matrixdim; ++j) {
17307                 Breal[j-1] = ev[j]*iconst;
17308             }
17309             if( checkconsistency8(Breal) ) {
17310                 if( lfindex >= 0 ) {
17311                     const IkReal* lf = lfpossibilities[lfindex];
17312                     rawroots[numroots++] = (wr[i]*lf[0]+lf[1])/(wr[i]*lf[2]+lf[3]);
17313                 }
17314                 else {
17315                     rawroots[numroots++] = wr[i];
17316                 }
17317                 bool bsmall0=IKabs(ev[0]) > IKabs(ev[2]);
17318                 bool bsmall1=IKabs(ev[0]) > IKabs(ev[1]);
17319                 if( bsmall0 && bsmall1 ) {
17320                     rawroots[numroots++] = ev[2]/ev[0];
17321                     rawroots[numroots++] = ev[1]/ev[0];
17322                 }
17323                 else if( bsmall0 && !bsmall1 ) {
17324                     rawroots[numroots++] = ev[3]/ev[1];
17325                     rawroots[numroots++] = ev[1]/ev[0];
17326                 }
17327                 else if( !bsmall0 && bsmall1 ) {
17328                     rawroots[numroots++] = ev[6]/ev[4];
17329                     rawroots[numroots++] = ev[7]/ev[6];
17330                 }
17331                 else if( !bsmall0 && !bsmall1 ) {
17332                     rawroots[numroots++] = ev[7]/ev[5];
17333                     rawroots[numroots++] = ev[7]/ev[6];
17334                 }
17335             }
17336         }
17337     }
17338 }};
17339 
17340 
17343 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
17344 IKSolver solver;
17345 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
17346 }
17347 
17348 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - armadillo_arm_urdf (0441215a9dbfd0cdd2b1453a38e101c8)>"; }
17349 
17350 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
17351 
17352 #ifdef IKFAST_NAMESPACE
17353 } // end namespace
17354 #endif
17355 
17356 #ifndef IKFAST_NO_MAIN
17357 #include <stdio.h>
17358 #include <stdlib.h>
17359 #ifdef IKFAST_NAMESPACE
17360 using namespace IKFAST_NAMESPACE;
17361 #endif
17362 int main(int argc, char** argv)
17363 {
17364     if( argc != 12+GetNumFreeParameters()+1 ) {
17365         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
17366                "Returns the ik solutions given the transformation of the end effector specified by\n"
17367                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
17368                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
17369         return 1;
17370     }
17371 
17372     IkSolutionList<IkReal> solutions;
17373     std::vector<IkReal> vfree(GetNumFreeParameters());
17374     IkReal eerot[9],eetrans[3];
17375     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
17376     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
17377     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
17378     for(std::size_t i = 0; i < vfree.size(); ++i)
17379         vfree[i] = atof(argv[13+i]);
17380     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
17381 
17382     if( !bSuccess ) {
17383         fprintf(stderr,"Failed to get ik solution\n");
17384         return -1;
17385     }
17386 
17387     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
17388     std::vector<IkReal> solvalues(GetNumJoints());
17389     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
17390         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
17391         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
17392         std::vector<IkReal> vsolfree(sol.GetFree().size());
17393         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
17394         for( std::size_t j = 0; j < solvalues.size(); ++j)
17395             printf("%.15f, ", solvalues[j]);
17396         printf("\n");
17397     }
17398     return 0;
17399 }
17400 
17401 #endif


robotican_manipulator_h
Author(s):
autogenerated on Fri Oct 27 2017 03:03:10