fanuc_m430ia2p_manipulator_ikfast_solver.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 #define IKFAST_HAS_LIBRARY
00021 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
00022 using namespace ikfast;
00023 
00024 // check if the included ikfast version matches what this file was compiled with
00025 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
00026 IKFAST_COMPILE_ASSERT(IKFAST_VERSION==61);
00027 
00028 #include <cmath>
00029 #include <vector>
00030 #include <limits>
00031 #include <algorithm>
00032 #include <complex>
00033 
00034 #define IKFAST_STRINGIZE2(s) #s
00035 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
00036 
00037 #ifndef IKFAST_ASSERT
00038 #include <stdexcept>
00039 #include <sstream>
00040 #include <iostream>
00041 
00042 #ifdef _MSC_VER
00043 #ifndef __PRETTY_FUNCTION__
00044 #define __PRETTY_FUNCTION__ __FUNCDNAME__
00045 #endif
00046 #endif
00047 
00048 #ifndef __PRETTY_FUNCTION__
00049 #define __PRETTY_FUNCTION__ __func__
00050 #endif
00051 
00052 #define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } }
00053 
00054 #endif
00055 
00056 #if defined(_MSC_VER)
00057 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
00058 #else
00059 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
00060 #endif
00061 
00062 #define IK2PI  ((IkReal)6.28318530717959)
00063 #define IKPI  ((IkReal)3.14159265358979)
00064 #define IKPI_2  ((IkReal)1.57079632679490)
00065 
00066 #ifdef _MSC_VER
00067 #ifndef isnan
00068 #define isnan _isnan
00069 #endif
00070 #endif // _MSC_VER
00071 
00072 // lapack routines
00073 extern "C" {
00074   void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
00075   void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
00076   void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
00077   void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
00078   void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info);
00079   void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info);
00080 }
00081 
00082 using namespace std; // necessary to get std math routines
00083 
00084 #ifdef IKFAST_NAMESPACE
00085 namespace IKFAST_NAMESPACE {
00086 #endif
00087 
00088 inline float IKabs(float f) { return fabsf(f); }
00089 inline double IKabs(double f) { return fabs(f); }
00090 
00091 inline float IKsqr(float f) { return f*f; }
00092 inline double IKsqr(double f) { return f*f; }
00093 
00094 inline float IKlog(float f) { return logf(f); }
00095 inline double IKlog(double f) { return log(f); }
00096 
00097 // allows asin and acos to exceed 1
00098 #ifndef IKFAST_SINCOS_THRESH
00099 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
00100 #endif
00101 
00102 // used to check input to atan2 for degenerate cases
00103 #ifndef IKFAST_ATAN2_MAGTHRESH
00104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
00105 #endif
00106 
00107 // minimum distance of separate solutions
00108 #ifndef IKFAST_SOLUTION_THRESH
00109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
00110 #endif
00111 
00112 inline float IKasin(float f)
00113 {
00114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00115 if( f <= -1 ) return float(-IKPI_2);
00116 else if( f >= 1 ) return float(IKPI_2);
00117 return asinf(f);
00118 }
00119 inline double IKasin(double f)
00120 {
00121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00122 if( f <= -1 ) return -IKPI_2;
00123 else if( f >= 1 ) return IKPI_2;
00124 return asin(f);
00125 }
00126 
00127 // return positive value in [0,y)
00128 inline float IKfmod(float x, float y)
00129 {
00130     while(x < 0) {
00131         x += y;
00132     }
00133     return fmodf(x,y);
00134 }
00135 
00136 // return positive value in [0,y)
00137 inline double IKfmod(double x, double y)
00138 {
00139     while(x < 0) {
00140         x += y;
00141     }
00142     return fmod(x,y);
00143 }
00144 
00145 inline float IKacos(float f)
00146 {
00147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00148 if( f <= -1 ) return float(IKPI);
00149 else if( f >= 1 ) return float(0);
00150 return acosf(f);
00151 }
00152 inline double IKacos(double f)
00153 {
00154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00155 if( f <= -1 ) return IKPI;
00156 else if( f >= 1 ) return 0;
00157 return acos(f);
00158 }
00159 inline float IKsin(float f) { return sinf(f); }
00160 inline double IKsin(double f) { return sin(f); }
00161 inline float IKcos(float f) { return cosf(f); }
00162 inline double IKcos(double f) { return cos(f); }
00163 inline float IKtan(float f) { return tanf(f); }
00164 inline double IKtan(double f) { return tan(f); }
00165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
00166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
00167 inline float IKatan2(float fy, float fx) {
00168     if( isnan(fy) ) {
00169         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00170         return float(IKPI_2);
00171     }
00172     else if( isnan(fx) ) {
00173         return 0;
00174     }
00175     return atan2f(fy,fx);
00176 }
00177 inline double IKatan2(double fy, double fx) {
00178     if( isnan(fy) ) {
00179         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00180         return IKPI_2;
00181     }
00182     else if( isnan(fx) ) {
00183         return 0;
00184     }
00185     return atan2(fy,fx);
00186 }
00187 
00188 inline float IKsign(float f) {
00189     if( f > 0 ) {
00190         return float(1);
00191     }
00192     else if( f < 0 ) {
00193         return float(-1);
00194     }
00195     return 0;
00196 }
00197 
00198 inline double IKsign(double f) {
00199     if( f > 0 ) {
00200         return 1.0;
00201     }
00202     else if( f < 0 ) {
00203         return -1.0;
00204     }
00205     return 0;
00206 }
00207 
00210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
00211 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42,x43,x44,x45,x46,x47,x48,x49,x50,x51,x52,x53,x54,x55;
00212 x0=IKcos(j[0]);
00213 x1=IKcos(j[1]);
00214 x2=IKcos(j[2]);
00215 x3=IKsin(j[1]);
00216 x4=IKsin(j[2]);
00217 x5=IKsin(j[3]);
00218 x6=IKcos(j[3]);
00219 x7=IKsin(j[0]);
00220 x8=IKcos(j[5]);
00221 x9=IKsin(j[5]);
00222 x10=IKcos(j[4]);
00223 x11=IKsin(j[4]);
00224 x12=((IkReal(0.0650000000000000))*(x2));
00225 x13=((IkReal(0.0950000000000000))*(x6));
00226 x14=((IkReal(1.00000000000000))*(x10));
00227 x15=((IkReal(1.00000000000000))*(x11));
00228 x16=((IkReal(1.00000000000000))*(x7));
00229 x17=((IkReal(0.0950000000000000))*(x4));
00230 x18=((IkReal(1.00000000000000))*(x2));
00231 x19=((IkReal(0.350000000000000))*(x1));
00232 x20=((IkReal(0.0650000000000000))*(x0));
00233 x21=((IkReal(0.350000000000000))*(x2));
00234 x22=((IkReal(0.0650000000000000))*(x7));
00235 x23=((IkReal(0.0650000000000000))*(x6));
00236 x24=((IkReal(0.0950000000000000))*(x2));
00237 x25=((IkReal(1.00000000000000))*(x4));
00238 x26=((x3)*(x7));
00239 x27=((x0)*(x3));
00240 x28=((x3)*(x4));
00241 x29=((x11)*(x6));
00242 x30=((x1)*(x4));
00243 x31=((x1)*(x7));
00244 x32=((x1)*(x18));
00245 x33=((x0)*(x1)*(x2));
00246 x34=((x25)*(x27));
00247 x35=((x16)*(x28));
00248 x36=((x28)+(((IkReal(-1.00000000000000))*(x32))));
00249 x37=((((x1)*(x25)))+(((x18)*(x3))));
00250 x38=((IkReal(-1.00000000000000))*(x37));
00251 x39=((x33)+(((IkReal(-1.00000000000000))*(x34))));
00252 x40=((((x2)*(x31)))+(((IkReal(-1.00000000000000))*(x35))));
00253 x41=((x37)*(x5));
00254 x42=((x38)*(x6));
00255 x43=((((IkReal(-1.00000000000000))*(x0)*(x1)*(x25)))+(((IkReal(-1.00000000000000))*(x18)*(x27))));
00256 x44=((((x18)*(x27)))+(((x0)*(x1)*(x25))));
00257 IkReal x56=((IkReal(1.00000000000000))*(x16));
00258 x45=((((IkReal(-1.00000000000000))*(x2)*(x3)*(x56)))+(((IkReal(-1.00000000000000))*(x30)*(x56))));
00259 x46=((((x16)*(x30)))+(((x16)*(x2)*(x3))));
00260 x47=((x39)*(x6));
00261 x48=((x40)*(x6));
00262 x49=((x11)*(x43));
00263 x50=((x11)*(x45));
00264 x51=((x47)+(((IkReal(-1.00000000000000))*(x16)*(x5))));
00265 x52=((x48)+(((x0)*(x5))));
00266 x53=((((IkReal(-1.00000000000000))*(x16)*(x6)))+(((x5)*(((x34)+(((IkReal(-1.00000000000000))*(x0)*(x32))))))));
00267 x54=((((x5)*(((((IkReal(-1.00000000000000))*(x1)*(x16)*(x2)))+(x35)))))+(((x0)*(x6))));
00268 x55=((x10)*(x51));
00269 eerot[0]=((((x8)*(((x55)+(x49)))))+(((x53)*(x9))));
00270 eerot[1]=((((x9)*(((((IkReal(-1.00000000000000))*(x15)*(x43)))+(((IkReal(-1.00000000000000))*(x14)*(x51)))))))+(((x53)*(x8))));
00271 eerot[2]=((((x10)*(x44)))+(((x11)*(x51))));
00272 eetrans[0]=((((x10)*(((((x12)*(x27)))+(((x20)*(x30)))))))+(((x13)*(x7)))+(((IkReal(0.350000000000000))*(x27)))+(((x0)*(x19)*(x4)))+(((x5)*(((((x0)*(x1)*(x24)))+(((IkReal(-1.00000000000000))*(x17)*(x27)))))))+(((x11)*(((((x23)*(x39)))+(((IkReal(-1.00000000000000))*(x22)*(x5)))))))+(((x21)*(x27))));
00273 eerot[3]=((((x54)*(x9)))+(((x8)*(((x50)+(((x10)*(x52))))))));
00274 eerot[4]=((((x54)*(x8)))+(((x9)*(((((IkReal(-1.00000000000000))*(x15)*(x45)))+(((IkReal(-1.00000000000000))*(x14)*(x52))))))));
00275 eerot[5]=((((x11)*(x52)))+(((x10)*(x46))));
00276 eetrans[1]=((((x21)*(x26)))+(((IkReal(-1.00000000000000))*(x0)*(x13)))+(((x19)*(x4)*(x7)))+(((IkReal(0.350000000000000))*(x26)))+(((x10)*(((((x22)*(x30)))+(((x12)*(x26)))))))+(((x11)*(((((x23)*(x40)))+(((x20)*(x5)))))))+(((x5)*(((((x24)*(x31)))+(((IkReal(-1.00000000000000))*(x17)*(x26))))))));
00277 eerot[6]=((((x41)*(x9)))+(((x8)*(((((x11)*(x36)))+(((x10)*(x42))))))));
00278 eerot[7]=((((x41)*(x8)))+(((x9)*(((((IkReal(-1.00000000000000))*(x14)*(x42)))+(((IkReal(-1.00000000000000))*(x15)*(x36))))))));
00279 eerot[8]=((((x10)*(((x32)+(((IkReal(-1.00000000000000))*(x25)*(x3)))))))+(((x29)*(x38))));
00280 IkReal x57=((IkReal(1.00000000000000))*(x3));
00281 eetrans[2]=((IkReal(0.410000000000000))+(((x5)*(((((IkReal(-1.00000000000000))*(x1)*(x17)))+(((IkReal(-1.00000000000000))*(x24)*(x57)))))))+(((x10)*(((((x1)*(x12)))+(((IkReal(-0.0650000000000000))*(x28)))))))+(x19)+(((IkReal(-0.350000000000000))*(x28)))+(((x19)*(x2)))+(((x29)*(((((IkReal(-0.0650000000000000))*(x30)))+(((IkReal(-1.00000000000000))*(x12)*(x57))))))));
00282 }
00283 
00284 IKFAST_API int GetNumFreeParameters() { return 0; }
00285 IKFAST_API int* GetFreeParameters() { return NULL; }
00286 IKFAST_API int GetNumJoints() { return 6; }
00287 
00288 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00289 
00290 IKFAST_API int GetIkType() { return 0x67000001; }
00291 
00292 class IKSolver {
00293 public:
00294 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;
00295 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5;
00296 
00297 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00298 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; 
00299 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00300     solutions.Clear();
00301 r00 = eerot[0*3+0];
00302 r01 = eerot[0*3+1];
00303 r02 = eerot[0*3+2];
00304 r10 = eerot[1*3+0];
00305 r11 = eerot[1*3+1];
00306 r12 = eerot[1*3+2];
00307 r20 = eerot[2*3+0];
00308 r21 = eerot[2*3+1];
00309 r22 = eerot[2*3+2];
00310 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00311 
00312 new_r00=r00;
00313 new_r01=r01;
00314 new_r02=r02;
00315 new_px=((px)+(((IkReal(-0.0650000000000000))*(r02))));
00316 new_r10=r10;
00317 new_r11=r11;
00318 new_r12=r12;
00319 new_py=((((IkReal(-0.0650000000000000))*(r12)))+(py));
00320 new_r20=r20;
00321 new_r21=r21;
00322 new_r22=r22;
00323 new_pz=((IkReal(-0.410000000000000))+(((IkReal(-0.0650000000000000))*(r22)))+(pz));
00324 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;
00325 pp=(((px)*(px))+((pz)*(pz))+((py)*(py)));
00326 npx=((((py)*(r10)))+(((pz)*(r20)))+(((px)*(r00))));
00327 npy=((((px)*(r01)))+(((pz)*(r21)))+(((py)*(r11))));
00328 npz=((((py)*(r12)))+(((pz)*(r22)))+(((px)*(r02))));
00329 rxp0_0=((((IkReal(-1.00000000000000))*(py)*(r20)))+(((pz)*(r10))));
00330 rxp0_1=((((px)*(r20)))+(((IkReal(-1.00000000000000))*(pz)*(r00))));
00331 rxp0_2=((((py)*(r00)))+(((IkReal(-1.00000000000000))*(px)*(r10))));
00332 rxp1_0=((((pz)*(r11)))+(((IkReal(-1.00000000000000))*(py)*(r21))));
00333 rxp1_1=((((IkReal(-1.00000000000000))*(pz)*(r01)))+(((px)*(r21))));
00334 rxp1_2=((((py)*(r01)))+(((IkReal(-1.00000000000000))*(px)*(r11))));
00335 rxp2_0=((((IkReal(-1.00000000000000))*(py)*(r22)))+(((pz)*(r12))));
00336 rxp2_1=((((px)*(r22)))+(((IkReal(-1.00000000000000))*(pz)*(r02))));
00337 rxp2_2=((((py)*(r02)))+(((IkReal(-1.00000000000000))*(px)*(r12))));
00338 IkReal op[8+1], zeror[8];
00339 int numroots;
00340 IkReal gconst0;
00341 gconst0=((((IkReal(-1.00000000000000))*(rxp2_2)))+(((IkReal(0.0950000000000000))*(r20))));
00342 IkReal gconst1;
00343 gconst1=((IkReal(-0.190000000000000))*(r21));
00344 IkReal gconst2;
00345 gconst2=((((IkReal(-1.00000000000000))*(rxp2_2)))+(((IkReal(-0.0950000000000000))*(r20))));
00346 IkReal gconst3;
00347 gconst3=((IkReal(-0.00902500000000000))+(((IkReal(-0.190000000000000))*(npy)))+(((IkReal(0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp))));
00348 IkReal gconst4;
00349 gconst4=((IkReal(-0.380000000000000))*(npx));
00350 IkReal gconst5;
00351 gconst5=((IkReal(-0.00902500000000000))+(((IkReal(0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.190000000000000))*(npy))));
00352 IkReal gconst6;
00353 gconst6=((((IkReal(-1.00000000000000))*(rxp2_2)))+(((IkReal(0.0950000000000000))*(r20))));
00354 IkReal gconst7;
00355 gconst7=((IkReal(-0.190000000000000))*(r21));
00356 IkReal gconst8;
00357 gconst8=((((IkReal(-1.00000000000000))*(rxp2_2)))+(((IkReal(-0.0950000000000000))*(r20))));
00358 IkReal gconst9;
00359 gconst9=((IkReal(-0.00902500000000000))+(((IkReal(-0.190000000000000))*(npy)))+(((IkReal(0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp))));
00360 IkReal gconst10;
00361 gconst10=((IkReal(-0.380000000000000))*(npx));
00362 IkReal gconst11;
00363 gconst11=((IkReal(-0.00902500000000000))+(((IkReal(0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.190000000000000))*(npy))));
00364 IkReal gconst12;
00365 gconst12=((((IkReal(0.190000000000000))*(r22)))+(((IkReal(2.00000000000000))*(rxp0_2))));
00366 IkReal gconst13;
00367 gconst13=((IkReal(-4.00000000000000))*(rxp1_2));
00368 IkReal gconst14;
00369 gconst14=((((IkReal(-2.00000000000000))*(rxp0_2)))+(((IkReal(0.190000000000000))*(r22))));
00370 IkReal gconst15;
00371 gconst15=((IkReal(-1.40000000000000))*(npx));
00372 IkReal gconst16;
00373 gconst16=((IkReal(2.80000000000000))*(npy));
00374 IkReal gconst17;
00375 gconst17=((IkReal(1.40000000000000))*(npx));
00376 IkReal gconst18;
00377 gconst18=((((IkReal(0.190000000000000))*(r22)))+(((IkReal(2.00000000000000))*(rxp0_2))));
00378 IkReal gconst19;
00379 gconst19=((IkReal(-4.00000000000000))*(rxp1_2));
00380 IkReal gconst20;
00381 gconst20=((((IkReal(-2.00000000000000))*(rxp0_2)))+(((IkReal(0.190000000000000))*(r22))));
00382 IkReal gconst21;
00383 gconst21=((IkReal(-1.40000000000000))*(npx));
00384 IkReal gconst22;
00385 gconst22=((IkReal(2.80000000000000))*(npy));
00386 IkReal gconst23;
00387 gconst23=((IkReal(1.40000000000000))*(npx));
00388 IkReal gconst24;
00389 gconst24=((rxp2_2)+(((IkReal(-0.0950000000000000))*(r20))));
00390 IkReal gconst25;
00391 gconst25=((IkReal(0.190000000000000))*(r21));
00392 IkReal gconst26;
00393 gconst26=((rxp2_2)+(((IkReal(0.0950000000000000))*(r20))));
00394 IkReal gconst27;
00395 gconst27=((IkReal(-0.00902500000000000))+(((IkReal(-0.700000000000000))*(npz)))+(((IkReal(-0.190000000000000))*(npy)))+(((IkReal(-1.00000000000000))*(pp))));
00396 IkReal gconst28;
00397 gconst28=((IkReal(-0.380000000000000))*(npx));
00398 IkReal gconst29;
00399 gconst29=((IkReal(-0.00902500000000000))+(((IkReal(-0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.190000000000000))*(npy))));
00400 IkReal gconst30;
00401 gconst30=((rxp2_2)+(((IkReal(-0.0950000000000000))*(r20))));
00402 IkReal gconst31;
00403 gconst31=((IkReal(0.190000000000000))*(r21));
00404 IkReal gconst32;
00405 gconst32=((rxp2_2)+(((IkReal(0.0950000000000000))*(r20))));
00406 IkReal gconst33;
00407 gconst33=((IkReal(-0.00902500000000000))+(((IkReal(-0.700000000000000))*(npz)))+(((IkReal(-0.190000000000000))*(npy)))+(((IkReal(-1.00000000000000))*(pp))));
00408 IkReal gconst34;
00409 gconst34=((IkReal(-0.380000000000000))*(npx));
00410 IkReal gconst35;
00411 gconst35=((IkReal(-0.00902500000000000))+(((IkReal(-0.700000000000000))*(npz)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.190000000000000))*(npy))));
00412 IkReal x58=((IkReal(1.00000000000000))*(gconst26));
00413 IkReal x59=((gconst30)*(gconst34));
00414 IkReal x60=((gconst31)*(gconst33));
00415 IkReal x61=((IkReal(1.00000000000000))*(gconst17));
00416 IkReal x62=((gconst2)*(gconst6));
00417 IkReal x63=((gconst11)*(gconst3));
00418 IkReal x64=((gconst25)*(gconst29));
00419 IkReal x65=((gconst14)*(gconst28));
00420 IkReal x66=((gconst0)*(gconst5));
00421 IkReal x67=((IkReal(1.00000000000000))*(gconst6));
00422 IkReal x68=((IkReal(1.00000000000000))*(gconst14));
00423 IkReal x69=((gconst21)*(gconst32));
00424 IkReal x70=((gconst10)*(gconst6));
00425 IkReal x71=((gconst21)*(gconst8));
00426 IkReal x72=((gconst13)*(gconst5));
00427 IkReal x73=((gconst7)*(gconst9));
00428 IkReal x74=((gconst30)*(gconst35));
00429 IkReal x75=((gconst26)*(gconst27));
00430 IkReal x76=((gconst22)*(gconst30));
00431 IkReal x77=((IkReal(1.00000000000000))*(gconst29));
00432 IkReal x78=((gconst19)*(gconst33));
00433 IkReal x79=((gconst26)*(gconst28));
00434 IkReal x80=((gconst2)*(gconst4));
00435 IkReal x81=((gconst18)*(gconst35));
00436 IkReal x82=((gconst1)*(gconst5));
00437 IkReal x83=((gconst21)*(gconst7));
00438 IkReal x84=((gconst12)*(gconst5));
00439 IkReal x85=((gconst18)*(gconst34));
00440 IkReal x86=((gconst23)*(gconst30));
00441 IkReal x87=((gconst3)*(gconst8));
00442 IkReal x88=((gconst29)*(gconst33));
00443 IkReal x89=((gconst32)*(gconst33));
00444 IkReal x90=((gconst8)*(gconst9));
00445 IkReal x91=((gconst21)*(gconst31));
00446 IkReal x92=((gconst18)*(gconst2));
00447 IkReal x93=((gconst14)*(gconst6));
00448 IkReal x94=((gconst19)*(gconst9));
00449 IkReal x95=((IkReal(1.00000000000000))*(gconst10)*(gconst4));
00450 IkReal x96=((gconst27)*(x89));
00451 IkReal x97=((IkReal(1.00000000000000))*(gconst2)*(gconst9));
00452 op[0]=((((IkReal(-1.00000000000000))*(x58)*(x96)))+(((x60)*(x79)))+(((IkReal(-1.00000000000000))*(x60)*(x64)))+(((x59)*(x64)))+(((IkReal(-1.00000000000000))*(gconst28)*(x58)*(x59)))+(((x74)*(x75)))+(((IkReal(-1.00000000000000))*(gconst24)*(x74)*(x77)))+(((gconst24)*(gconst32)*(x88))));
00453 op[1]=((((IkReal(-1.00000000000000))*(gconst24)*(x77)*(x86)))+(((gconst17)*(gconst25)*(x59)))+(((gconst16)*(gconst26)*(x60)))+(((x75)*(x81)))+(((IkReal(-1.00000000000000))*(gconst15)*(x58)*(x89)))+(((IkReal(-1.00000000000000))*(gconst16)*(x58)*(x59)))+(((IkReal(-1.00000000000000))*(gconst24)*(x61)*(x74)))+(((IkReal(-1.00000000000000))*(gconst28)*(x58)*(x85)))+(((x60)*(x65)))+(((gconst12)*(gconst32)*(x88)))+(((IkReal(-1.00000000000000))*(gconst28)*(x58)*(x76)))+(((IkReal(-1.00000000000000))*(gconst24)*(x77)*(x81)))+(((x78)*(x79)))+(((IkReal(-1.00000000000000))*(gconst27)*(x58)*(x69)))+(((IkReal(-1.00000000000000))*(x64)*(x91)))+(((IkReal(-1.00000000000000))*(gconst25)*(x60)*(x61)))+(((x64)*(x85)))+(((x75)*(x86)))+(((x64)*(x76)))+(((x79)*(x91)))+(((IkReal(-1.00000000000000))*(x64)*(x78)))+(((gconst14)*(gconst27)*(x74)))+(((gconst15)*(gconst26)*(x74)))+(((gconst13)*(gconst29)*(x59)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst27)*(gconst33)*(x58)))+(((gconst24)*(gconst29)*(x69)))+(((gconst17)*(gconst24)*(x89)))+(((IkReal(-1.00000000000000))*(gconst13)*(x60)*(x77)))+(((IkReal(-1.00000000000000))*(x68)*(x96)))+(((IkReal(-1.00000000000000))*(gconst12)*(x74)*(x77)))+(((IkReal(-1.00000000000000))*(x59)*(x65)))+(((gconst20)*(gconst24)*(x88))));
00454 op[2]=((((gconst17)*(gconst21)*(gconst24)*(gconst32)))+(((gconst15)*(gconst23)*(gconst26)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst24)*(gconst29)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst3)*(gconst32)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst21)*(gconst29)*(gconst31)))+(((gconst13)*(gconst22)*(gconst29)*(gconst30)))+(((gconst24)*(gconst32)*(gconst33)*(gconst5)))+(((gconst14)*(gconst23)*(gconst27)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst18)*(gconst29)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst22)*(gconst26)*(gconst30)))+(((gconst16)*(gconst19)*(gconst26)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst29)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst30)*(gconst34)))+(((gconst14)*(gconst16)*(gconst31)*(gconst33)))+(((gconst0)*(gconst29)*(gconst32)*(gconst33)))+(((gconst2)*(gconst28)*(gconst31)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst29)*(gconst30)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst21)*(gconst26)*(gconst27)))+(((gconst13)*(gconst18)*(gconst29)*(gconst34)))+(((gconst10)*(gconst25)*(gconst29)*(gconst30)))+(((gconst14)*(gconst21)*(gconst28)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst27)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst28)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst23)*(gconst24)*(gconst29)))+(((gconst25)*(gconst30)*(gconst34)*(gconst5)))+(((gconst14)*(gconst19)*(gconst28)*(gconst33)))+(((gconst26)*(gconst3)*(gconst30)*(gconst35)))+(((gconst20)*(gconst21)*(gconst24)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst23)*(gconst24)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst22)*(gconst26)*(gconst28)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst18)*(gconst26)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst19)*(gconst21)*(gconst25)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst21)*(gconst27)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst18)*(gconst28)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst23)*(gconst29)*(gconst30)))+(((gconst11)*(gconst26)*(gconst27)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst18)*(gconst24)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst32)*(gconst33)))+(((gconst13)*(gconst17)*(gconst30)*(gconst34)))+(((gconst17)*(gconst18)*(gconst25)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst27)*(gconst32)*(gconst33)))+(((gconst25)*(gconst29)*(gconst34)*(gconst6)))+(((gconst24)*(gconst29)*(gconst33)*(gconst8)))+(((gconst16)*(gconst21)*(gconst26)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst19)*(gconst25)*(gconst33)))+(((gconst18)*(gconst22)*(gconst25)*(gconst29)))+(((gconst1)*(gconst29)*(gconst30)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst30)*(gconst34)*(gconst4)))+(((gconst15)*(gconst18)*(gconst26)*(gconst35)))+(((gconst12)*(gconst17)*(gconst32)*(gconst33)))+(((gconst26)*(gconst28)*(gconst33)*(gconst7)))+(((gconst26)*(gconst28)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst24)*(gconst30)*(gconst35)*(gconst5)))+(((gconst19)*(gconst21)*(gconst26)*(gconst28)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst26)*(gconst28)*(gconst30)))+(((gconst2)*(gconst27)*(gconst30)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst30)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst22)*(gconst28)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst27)*(gconst32)*(gconst9)))+(((gconst14)*(gconst15)*(gconst30)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst24)*(gconst29)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst31)*(gconst33)*(gconst5)))+(((gconst26)*(gconst31)*(gconst33)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst31)*(gconst33)))+(((gconst12)*(gconst20)*(gconst29)*(gconst33)))+(((gconst18)*(gconst23)*(gconst26)*(gconst27)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst21)*(gconst26)*(gconst32)))+(((gconst24)*(gconst29)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst28)*(gconst30)*(gconst34)))+(((gconst17)*(gconst22)*(gconst25)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst29)*(gconst31)*(gconst33)))+(((gconst26)*(gconst27)*(gconst35)*(gconst6)))+(((gconst12)*(gconst21)*(gconst29)*(gconst32)))+(((gconst14)*(gconst18)*(gconst27)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst21)*(gconst25)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst27)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst29)*(gconst33)))+(((gconst17)*(gconst20)*(gconst24)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst29)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst20)*(gconst26)*(gconst33))));
00455 op[3]=((((IkReal(-1.00000000000000))*(gconst14)*(gconst27)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst26)*(gconst32)*(gconst9)))+(((gconst14)*(gconst16)*(gconst19)*(gconst33)))+(((gconst12)*(gconst29)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst25)*(gconst31)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst20)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst21)*(gconst27)))+(((gconst10)*(gconst18)*(gconst25)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst27)*(gconst32)*(gconst9)))+(((gconst13)*(gconst30)*(gconst34)*(gconst5)))+(((gconst21)*(gconst26)*(gconst28)*(gconst7)))+(((gconst17)*(gconst24)*(gconst33)*(gconst8)))+(((gconst15)*(gconst18)*(gconst23)*(gconst26)))+(((gconst13)*(gconst17)*(gconst22)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst24)*(gconst35)*(gconst5)))+(((gconst17)*(gconst24)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst28)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst21)*(gconst27)*(gconst32)))+(((gconst14)*(gconst27)*(gconst35)*(gconst6)))+(((gconst20)*(gconst24)*(gconst29)*(gconst9)))+(((gconst18)*(gconst26)*(gconst3)*(gconst35)))+(((gconst2)*(gconst23)*(gconst27)*(gconst30)))+(((gconst14)*(gconst16)*(gconst21)*(gconst31)))+(((gconst22)*(gconst25)*(gconst29)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst19)*(gconst25)*(gconst29)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst22)*(gconst28)*(gconst30)))+(((gconst0)*(gconst21)*(gconst29)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst25)*(gconst33)*(gconst7)))+(((gconst15)*(gconst2)*(gconst30)*(gconst35)))+(((gconst1)*(gconst18)*(gconst29)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst25)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst29)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst26)*(gconst34)*(gconst6)))+(((gconst11)*(gconst18)*(gconst26)*(gconst27)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst18)*(gconst23)*(gconst24)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst18)*(gconst35)))+(((gconst14)*(gconst19)*(gconst21)*(gconst28)))+(((gconst12)*(gconst17)*(gconst21)*(gconst32)))+(((gconst23)*(gconst26)*(gconst3)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst22)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(gconst26)*(gconst30)))+(((gconst12)*(gconst32)*(gconst33)*(gconst5)))+(((gconst14)*(gconst28)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst21)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst26)*(gconst27)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst24)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst19)*(gconst21)*(gconst25)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst19)*(gconst29)*(gconst33)))+(((gconst2)*(gconst21)*(gconst28)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst18)*(gconst23)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst26)*(gconst27)*(gconst8)))+(((gconst10)*(gconst13)*(gconst29)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst17)*(gconst24)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst31)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst30)*(gconst34)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst26)*(gconst34)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst23)*(gconst24)*(gconst30)*(gconst5)))+(((gconst16)*(gconst19)*(gconst21)*(gconst26)))+(((gconst14)*(gconst18)*(gconst23)*(gconst27)))+(((IkReal(-1.00000000000000))*(gconst19)*(gconst25)*(gconst33)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst18)*(gconst34)))+(((gconst17)*(gconst25)*(gconst34)*(gconst6)))+(((gconst14)*(gconst31)*(gconst33)*(gconst4)))+(((gconst17)*(gconst20)*(gconst21)*(gconst24)))+(((gconst21)*(gconst26)*(gconst31)*(gconst4)))+(((gconst13)*(gconst17)*(gconst18)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst18)*(gconst22)*(gconst28)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst26)*(gconst3)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst30)*(gconst35)))+(((gconst1)*(gconst22)*(gconst29)*(gconst30)))+(((gconst21)*(gconst24)*(gconst29)*(gconst8)))+(((gconst14)*(gconst28)*(gconst33)*(gconst7)))+(((gconst0)*(gconst17)*(gconst32)*(gconst33)))+(((gconst11)*(gconst15)*(gconst26)*(gconst30)))+(((gconst14)*(gconst15)*(gconst18)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst22)*(gconst26)*(gconst28)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst29)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst23)*(gconst29)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst22)*(gconst26)*(gconst30)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst18)*(gconst26)*(gconst28)))+(((gconst14)*(gconst15)*(gconst23)*(gconst30)))+(((gconst12)*(gconst17)*(gconst20)*(gconst33)))+(((gconst12)*(gconst29)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst21)*(gconst29)))+(((gconst19)*(gconst26)*(gconst28)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst32)*(gconst33)))+(((gconst20)*(gconst24)*(gconst33)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst2)*(gconst30)*(gconst34)))+(((gconst18)*(gconst25)*(gconst34)*(gconst5)))+(((gconst19)*(gconst26)*(gconst33)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst23)*(gconst24)*(gconst29)*(gconst6)))+(((gconst13)*(gconst18)*(gconst22)*(gconst29)))+(((gconst16)*(gconst26)*(gconst31)*(gconst9)))+(((gconst16)*(gconst2)*(gconst31)*(gconst33)))+(((gconst11)*(gconst14)*(gconst27)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst29)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst31)*(gconst33)*(gconst5)))+(((gconst23)*(gconst26)*(gconst27)*(gconst6)))+(((gconst16)*(gconst26)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst23)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst26)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst25)*(gconst29)*(gconst7)))+(((gconst22)*(gconst25)*(gconst30)*(gconst5)))+(((gconst18)*(gconst2)*(gconst27)*(gconst35)))+(((gconst21)*(gconst24)*(gconst32)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst19)*(gconst33)))+(((gconst19)*(gconst2)*(gconst28)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst26)*(gconst3)*(gconst33)))+(((gconst12)*(gconst20)*(gconst21)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst20)*(gconst21)*(gconst26)))+(((gconst15)*(gconst26)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst29)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst21)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst28)*(gconst34)*(gconst6)))+(((gconst14)*(gconst3)*(gconst30)*(gconst35)))+(((gconst1)*(gconst17)*(gconst30)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst30)*(gconst35)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst18)*(gconst24)*(gconst29)))+(((gconst0)*(gconst20)*(gconst29)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst21)*(gconst29)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst2)*(gconst28)*(gconst34)))+(((gconst17)*(gconst18)*(gconst22)*(gconst25)))+(((gconst10)*(gconst17)*(gconst25)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst18)*(gconst22)*(gconst26)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst20)*(gconst27)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst18)*(gconst29)*(gconst35)))+(((gconst13)*(gconst29)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst3)*(gconst32)*(gconst33))));
00456 op[4]=((((gconst0)*(gconst32)*(gconst33)*(gconst5)))+(((gconst12)*(gconst20)*(gconst33)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst3)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst18)*(gconst34)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst29)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(gconst18)*(gconst26)))+(((gconst24)*(gconst33)*(gconst5)*(gconst8)))+(((gconst0)*(gconst20)*(gconst21)*(gconst29)))+(((gconst11)*(gconst26)*(gconst27)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst20)*(gconst21)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst2)*(gconst28)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst34)*(gconst4)*(gconst6)))+(((gconst26)*(gconst28)*(gconst7)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst18)*(gconst23)))+(((gconst2)*(gconst3)*(gconst30)*(gconst35)))+(((gconst12)*(gconst20)*(gconst29)*(gconst9)))+(((gconst12)*(gconst17)*(gconst32)*(gconst9)))+(((gconst13)*(gconst17)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst28)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst2)*(gconst22)*(gconst28)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst27)*(gconst33)*(gconst8)))+(((gconst14)*(gconst16)*(gconst19)*(gconst21)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst21)*(gconst27)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst31)*(gconst5)*(gconst9)))+(((gconst14)*(gconst21)*(gconst31)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst31)*(gconst33)*(gconst5)))+(((gconst24)*(gconst32)*(gconst5)*(gconst9)))+(((gconst12)*(gconst21)*(gconst32)*(gconst5)))+(((gconst12)*(gconst17)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst18)*(gconst35)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst22)*(gconst28)*(gconst6)))+(((gconst10)*(gconst25)*(gconst30)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst30)*(gconst34)*(gconst4)))+(((gconst19)*(gconst2)*(gconst21)*(gconst28)))+(((gconst14)*(gconst19)*(gconst28)*(gconst9)))+(((gconst1)*(gconst17)*(gconst22)*(gconst30)))+(((gconst14)*(gconst15)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst27)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst26)*(gconst28)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst27)*(gconst9)))+(((gconst2)*(gconst28)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst23)*(gconst24)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst3)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst29)*(gconst7)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst21)*(gconst3)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst21)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst21)*(gconst25)*(gconst7)))+(((gconst0)*(gconst17)*(gconst21)*(gconst32)))+(((gconst20)*(gconst21)*(gconst24)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst19)*(gconst25)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst2)*(gconst22)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst31)*(gconst9)))+(((gconst1)*(gconst30)*(gconst34)*(gconst5)))+(((gconst18)*(gconst22)*(gconst25)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst19)*(gconst21)*(gconst25)*(gconst5)))+(((gconst14)*(gconst21)*(gconst28)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst24)*(gconst29)*(gconst6)))+(((gconst12)*(gconst17)*(gconst20)*(gconst21)))+(((gconst14)*(gconst23)*(gconst27)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst23)*(gconst29)*(gconst6)))+(((gconst17)*(gconst22)*(gconst25)*(gconst6)))+(((gconst16)*(gconst21)*(gconst26)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst20)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst23)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst3)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst18)*(gconst2)*(gconst34)))+(((gconst13)*(gconst17)*(gconst18)*(gconst22)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst21)*(gconst26)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst18)*(gconst22)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst29)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst18)*(gconst28)))+(((gconst14)*(gconst23)*(gconst3)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst17)*(gconst18)*(gconst24)))+(((gconst14)*(gconst19)*(gconst33)*(gconst4)))+(((gconst13)*(gconst22)*(gconst30)*(gconst5)))+(((gconst10)*(gconst13)*(gconst17)*(gconst30)))+(((gconst1)*(gconst29)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst18)*(gconst23)*(gconst29)))+(((gconst17)*(gconst20)*(gconst24)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst18)*(gconst35)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst20)*(gconst21)*(gconst27)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst22)*(gconst26)*(gconst6)))+(((gconst15)*(gconst2)*(gconst23)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst18)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst33)*(gconst8)))+(((gconst25)*(gconst34)*(gconst5)*(gconst6)))+(((gconst15)*(gconst18)*(gconst2)*(gconst35)))+(((gconst26)*(gconst3)*(gconst35)*(gconst6)))+(((gconst14)*(gconst16)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst23)*(gconst24)*(gconst5)))+(((gconst10)*(gconst13)*(gconst18)*(gconst29)))+(((gconst10)*(gconst17)*(gconst18)*(gconst25)))+(((gconst0)*(gconst17)*(gconst20)*(gconst33)))+(((gconst16)*(gconst19)*(gconst2)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst24)*(gconst30)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst26)*(gconst30)*(gconst4)))+(((gconst14)*(gconst16)*(gconst31)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst19)*(gconst33)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst20)*(gconst26)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst22)*(gconst26)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst16)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst33)*(gconst5)*(gconst7)))+(((gconst2)*(gconst31)*(gconst33)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst19)*(gconst21)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst27)*(gconst32)*(gconst9)))+(((gconst1)*(gconst10)*(gconst29)*(gconst30)))+(((gconst14)*(gconst15)*(gconst18)*(gconst23)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst19)*(gconst21)))+(((gconst0)*(gconst29)*(gconst32)*(gconst9)))+(((gconst14)*(gconst18)*(gconst3)*(gconst35)))+(((gconst12)*(gconst21)*(gconst29)*(gconst8)))+(((gconst13)*(gconst22)*(gconst29)*(gconst6)))+(((gconst2)*(gconst27)*(gconst35)*(gconst6)))+(((gconst1)*(gconst17)*(gconst18)*(gconst34)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst21)*(gconst31)*(gconst5)))+(((gconst11)*(gconst2)*(gconst27)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst29)*(gconst33)*(gconst7)))+(((gconst11)*(gconst14)*(gconst15)*(gconst30)))+(((gconst11)*(gconst26)*(gconst3)*(gconst30)))+(((gconst18)*(gconst2)*(gconst23)*(gconst27)))+(((gconst1)*(gconst18)*(gconst22)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst21)*(gconst29)*(gconst7)))+(((gconst24)*(gconst29)*(gconst8)*(gconst9)))+(((gconst2)*(gconst28)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst30)*(gconst35)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst33)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst21)*(gconst32)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst29)*(gconst35)*(gconst6)))+(((gconst13)*(gconst18)*(gconst34)*(gconst5)))+(((gconst16)*(gconst19)*(gconst26)*(gconst9)))+(((gconst10)*(gconst25)*(gconst29)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst17)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst3)*(gconst32)*(gconst33)))+(((gconst26)*(gconst31)*(gconst4)*(gconst9)))+(((gconst11)*(gconst14)*(gconst18)*(gconst27)))+(((gconst19)*(gconst21)*(gconst26)*(gconst4)))+(((gconst17)*(gconst21)*(gconst24)*(gconst8)))+(((gconst15)*(gconst23)*(gconst26)*(gconst6)))+(((gconst26)*(gconst33)*(gconst4)*(gconst7)))+(((gconst18)*(gconst23)*(gconst26)*(gconst3)))+(((gconst11)*(gconst15)*(gconst18)*(gconst26)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst23)*(gconst30)*(gconst5)))+(((gconst16)*(gconst2)*(gconst21)*(gconst31)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst29)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst24)*(gconst35)*(gconst5)*(gconst6)))+(((gconst0)*(gconst29)*(gconst33)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst22)*(gconst30)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst21)*(gconst26)*(gconst3))));
00457 op[5]=((((IkReal(-1.00000000000000))*(gconst1)*(gconst19)*(gconst29)*(gconst9)))+(((gconst2)*(gconst23)*(gconst27)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst18)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst29)*(gconst6)))+(((gconst23)*(gconst26)*(gconst3)*(gconst6)))+(((gconst0)*(gconst17)*(gconst33)*(gconst8)))+(((gconst1)*(gconst17)*(gconst34)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst33)*(gconst8)))+(((gconst14)*(gconst31)*(gconst4)*(gconst9)))+(((gconst16)*(gconst2)*(gconst31)*(gconst9)))+(((gconst11)*(gconst18)*(gconst2)*(gconst27)))+(((gconst1)*(gconst18)*(gconst34)*(gconst5)))+(((gconst14)*(gconst28)*(gconst7)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst20)*(gconst9)))+(((gconst12)*(gconst17)*(gconst20)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst16)*(gconst22)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(gconst26)*(gconst6)))+(((gconst13)*(gconst18)*(gconst22)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst21)*(gconst3)*(gconst32)))+(((gconst15)*(gconst18)*(gconst2)*(gconst23)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst35)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst26)*(gconst8)*(gconst9)))+(((gconst12)*(gconst32)*(gconst5)*(gconst9)))+(((gconst11)*(gconst18)*(gconst26)*(gconst3)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst21)*(gconst5)))+(((gconst11)*(gconst14)*(gconst27)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst31)*(gconst9)))+(((gconst2)*(gconst23)*(gconst3)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst18)*(gconst24)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst2)*(gconst34)*(gconst4)))+(((gconst0)*(gconst17)*(gconst20)*(gconst21)))+(((gconst22)*(gconst25)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst33)*(gconst5)*(gconst7)))+(((gconst0)*(gconst17)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst25)*(gconst5)*(gconst7)))+(((gconst0)*(gconst20)*(gconst29)*(gconst9)))+(((gconst0)*(gconst20)*(gconst33)*(gconst5)))+(((gconst0)*(gconst21)*(gconst32)*(gconst5)))+(((gconst18)*(gconst2)*(gconst3)*(gconst35)))+(((gconst12)*(gconst17)*(gconst21)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst3)*(gconst33)*(gconst8)))+(((gconst10)*(gconst17)*(gconst25)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst3)*(gconst32)*(gconst9)))+(((gconst14)*(gconst33)*(gconst4)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst19)*(gconst25)*(gconst5)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst20)*(gconst3)*(gconst33)))+(((gconst15)*(gconst2)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst22)*(gconst28)*(gconst6)))+(((gconst14)*(gconst15)*(gconst23)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst21)*(gconst31)*(gconst5)))+(((gconst2)*(gconst21)*(gconst28)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst30)*(gconst5)))+(((gconst19)*(gconst26)*(gconst4)*(gconst9)))+(((gconst11)*(gconst14)*(gconst3)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(gconst2)*(gconst30)))+(((gconst19)*(gconst2)*(gconst33)*(gconst4)))+(((gconst1)*(gconst10)*(gconst18)*(gconst29)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst18)*(gconst2)*(gconst28)))+(((gconst11)*(gconst15)*(gconst26)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst27)*(gconst8)*(gconst9)))+(((gconst11)*(gconst14)*(gconst15)*(gconst18)))+(((IkReal(-1.00000000000000))*(gconst17)*(gconst25)*(gconst7)*(gconst9)))+(((gconst13)*(gconst34)*(gconst5)*(gconst6)))+(((gconst16)*(gconst2)*(gconst33)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst18)*(gconst23)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst28)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst19)*(gconst33)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst18)*(gconst2)*(gconst22)))+(((gconst10)*(gconst13)*(gconst29)*(gconst6)))+(((gconst19)*(gconst2)*(gconst28)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst21)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst26)*(gconst3)*(gconst9)))+(((gconst1)*(gconst10)*(gconst17)*(gconst30)))+(((gconst14)*(gconst18)*(gconst23)*(gconst3)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst22)*(gconst30)*(gconst4)))+(((gconst16)*(gconst26)*(gconst7)*(gconst9)))+(((gconst21)*(gconst24)*(gconst5)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst18)*(gconst35)*(gconst5)))+(((gconst14)*(gconst16)*(gconst19)*(gconst9)))+(((gconst16)*(gconst19)*(gconst2)*(gconst21)))+(((gconst1)*(gconst17)*(gconst18)*(gconst22)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst16)*(gconst18)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst23)*(gconst29)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst21)*(gconst3)))+(((gconst13)*(gconst17)*(gconst22)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst21)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst21)*(gconst26)*(gconst3)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst32)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst23)*(gconst24)*(gconst5)*(gconst6)))+(((gconst1)*(gconst22)*(gconst29)*(gconst6)))+(((gconst2)*(gconst21)*(gconst31)*(gconst4)))+(((gconst10)*(gconst13)*(gconst30)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst18)*(gconst26)*(gconst4)))+(((gconst14)*(gconst3)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst23)*(gconst30)*(gconst5)))+(((gconst12)*(gconst29)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst19)*(gconst21)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst19)*(gconst9)))+(((gconst10)*(gconst18)*(gconst25)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst29)*(gconst7)*(gconst9)))+(((gconst0)*(gconst21)*(gconst29)*(gconst8)))+(((gconst20)*(gconst24)*(gconst5)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst18)*(gconst22)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst21)*(gconst29)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst31)*(gconst5)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst17)*(gconst24)*(gconst6)))+(((gconst14)*(gconst16)*(gconst21)*(gconst7)))+(((gconst21)*(gconst26)*(gconst4)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst20)*(gconst21)))+(((gconst12)*(gconst33)*(gconst5)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst17)*(gconst23)*(gconst6)))+(((gconst11)*(gconst15)*(gconst2)*(gconst30)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst20)*(gconst27)*(gconst9)))+(((gconst1)*(gconst22)*(gconst30)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst18)*(gconst23)))+(((gconst10)*(gconst13)*(gconst17)*(gconst18)))+(((gconst12)*(gconst20)*(gconst21)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst34)*(gconst4)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst17)*(gconst30)))+(((gconst17)*(gconst24)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst21)*(gconst27)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst30)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst17)*(gconst18)))+(((IkReal(-1.00000000000000))*(gconst22)*(gconst26)*(gconst4)*(gconst6)))+(((gconst14)*(gconst19)*(gconst21)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst2)*(gconst34)*(gconst6))));
00458 op[6]=((((gconst12)*(gconst20)*(gconst5)*(gconst9)))+(((gconst11)*(gconst2)*(gconst3)*(gconst30)))+(((gconst14)*(gconst21)*(gconst4)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst21)*(gconst5)*(gconst7)))+(((gconst0)*(gconst20)*(gconst21)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst20)*(gconst21)*(gconst3)))+(((gconst1)*(gconst18)*(gconst22)*(gconst5)))+(((gconst11)*(gconst15)*(gconst18)*(gconst2)))+(((gconst1)*(gconst10)*(gconst30)*(gconst5)))+(((gconst14)*(gconst23)*(gconst3)*(gconst6)))+(((gconst0)*(gconst17)*(gconst21)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst19)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst19)*(gconst5)*(gconst9)))+(((gconst15)*(gconst2)*(gconst23)*(gconst6)))+(((gconst11)*(gconst26)*(gconst3)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst35)*(gconst5)*(gconst6)))+(((gconst14)*(gconst16)*(gconst7)*(gconst9)))+(((gconst12)*(gconst21)*(gconst5)*(gconst8)))+(((gconst0)*(gconst17)*(gconst20)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst21)*(gconst8)))+(((gconst2)*(gconst31)*(gconst4)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst26)*(gconst3)*(gconst8)*(gconst9)))+(((gconst24)*(gconst5)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(gconst18)*(gconst2)))+(((gconst2)*(gconst3)*(gconst35)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst29)*(gconst7)*(gconst9)))+(((gconst1)*(gconst10)*(gconst17)*(gconst18)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst22)*(gconst4)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst16)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst16)*(gconst2)*(gconst22)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst20)*(gconst3)*(gconst9)))+(((gconst18)*(gconst2)*(gconst23)*(gconst3)))+(((gconst2)*(gconst28)*(gconst7)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst17)*(gconst6)))+(((gconst13)*(gconst22)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst2)*(gconst28)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst2)*(gconst30)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst17)*(gconst21)*(gconst7)))+(((gconst10)*(gconst13)*(gconst17)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst26)*(gconst4)*(gconst6)))+(((gconst14)*(gconst19)*(gconst4)*(gconst9)))+(((gconst1)*(gconst34)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst12)*(gconst18)*(gconst5)))+(((gconst19)*(gconst2)*(gconst21)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst17)*(gconst23)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst30)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst18)*(gconst4)))+(((IkReal(-1.00000000000000))*(gconst13)*(gconst17)*(gconst7)*(gconst9)))+(((gconst26)*(gconst4)*(gconst7)*(gconst9)))+(((gconst0)*(gconst29)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst17)*(gconst18)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst27)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst3)*(gconst33)*(gconst8)))+(((gconst16)*(gconst19)*(gconst2)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst34)*(gconst4)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst12)*(gconst23)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst31)*(gconst5)*(gconst9)))+(((gconst11)*(gconst14)*(gconst18)*(gconst3)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst33)*(gconst5)*(gconst7)))+(((gconst2)*(gconst33)*(gconst4)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst21)*(gconst3)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(gconst20)*(gconst9)))+(((gconst16)*(gconst2)*(gconst21)*(gconst7)))+(((IkReal(-1.00000000000000))*(gconst25)*(gconst5)*(gconst7)*(gconst9)))+(((gconst10)*(gconst25)*(gconst5)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst18)*(gconst23)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst1)*(gconst19)*(gconst21)*(gconst5)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst3)*(gconst32)*(gconst9)))+(((gconst0)*(gconst33)*(gconst5)*(gconst8)))+(((IkReal(-1.00000000000000))*(gconst14)*(gconst15)*(gconst8)*(gconst9)))+(((gconst11)*(gconst2)*(gconst27)*(gconst6)))+(((gconst11)*(gconst14)*(gconst15)*(gconst6)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst24)*(gconst5)*(gconst6)))+(((gconst10)*(gconst13)*(gconst18)*(gconst5)))+(((gconst0)*(gconst32)*(gconst5)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst18)*(gconst2)*(gconst22)*(gconst4)))+(((gconst1)*(gconst17)*(gconst22)*(gconst6)))+(((gconst12)*(gconst17)*(gconst8)*(gconst9)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst29)*(gconst6)))+(((gconst1)*(gconst10)*(gconst29)*(gconst6))));
00459 op[7]=((((x70)*(x72)))+(((gconst11)*(gconst15)*(x62)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst14)*(gconst4)*(x67)))+(((IkReal(-1.00000000000000))*(gconst11)*(gconst18)*(x66)))+(((x63)*(x93)))+(((IkReal(-1.00000000000000))*(gconst15)*(gconst2)*(x90)))+(((gconst23)*(gconst3)*(x62)))+(((IkReal(-1.00000000000000))*(x82)*(x94)))+(((IkReal(-1.00000000000000))*(gconst22)*(gconst4)*(x62)))+(((x84)*(x90)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst16)*(x62)))+(((gconst22)*(gconst6)*(x82)))+(((gconst20)*(gconst9)*(x66)))+(((x80)*(x83)))+(((gconst0)*(gconst17)*(x90)))+(((IkReal(-1.00000000000000))*(x72)*(x73)))+(((IkReal(-1.00000000000000))*(gconst10)*(gconst18)*(x80)))+(((IkReal(-1.00000000000000))*(gconst2)*(gconst3)*(x71)))+(((IkReal(-1.00000000000000))*(gconst11)*(x67)*(x84)))+(((IkReal(-1.00000000000000))*(gconst1)*(x61)*(x73)))+(((gconst10)*(gconst18)*(x82)))+(((x63)*(x92)))+(((IkReal(-1.00000000000000))*(x82)*(x83)))+(((x66)*(x71)))+(((gconst16)*(gconst2)*(x73)))+(((IkReal(-1.00000000000000))*(gconst0)*(gconst11)*(gconst6)*(x61)))+(((IkReal(-1.00000000000000))*(gconst23)*(x66)*(x67)))+(((gconst14)*(gconst4)*(x73)))+(((x80)*(x94)))+(((gconst1)*(gconst17)*(x70)))+(((IkReal(-1.00000000000000))*(gconst9)*(x68)*(x87)))+(((IkReal(-1.00000000000000))*(gconst20)*(gconst3)*(x97))));
00460 op[8]=((((IkReal(-1.00000000000000))*(gconst11)*(x66)*(x67)))+(((x66)*(x90)))+(((IkReal(-1.00000000000000))*(x73)*(x82)))+(((x62)*(x63)))+(((x73)*(x80)))+(((x70)*(x82)))+(((IkReal(-1.00000000000000))*(x87)*(x97)))+(((IkReal(-1.00000000000000))*(x62)*(x95))));
00461 polyroots8(op,zeror,numroots);
00462 IkReal j4array[8], cj4array[8], sj4array[8], tempj4array[1];
00463 int numsolutions = 0;
00464 for(int ij4 = 0; ij4 < numroots; ++ij4)
00465 {
00466 IkReal htj4 = zeror[ij4];
00467 tempj4array[0]=((IkReal(2.00000000000000))*(atan(htj4)));
00468 for(int kj4 = 0; kj4 < 1; ++kj4)
00469 {
00470 j4array[numsolutions] = tempj4array[kj4];
00471 if( j4array[numsolutions] > IKPI )
00472 {
00473     j4array[numsolutions]-=IK2PI;
00474 }
00475 else if( j4array[numsolutions] < -IKPI )
00476 {
00477     j4array[numsolutions]+=IK2PI;
00478 }
00479 sj4array[numsolutions] = IKsin(j4array[numsolutions]);
00480 cj4array[numsolutions] = IKcos(j4array[numsolutions]);
00481 numsolutions++;
00482 }
00483 }
00484 bool j4valid[8]={true,true,true,true,true,true,true,true};
00485 _nj4 = 8;
00486 for(int ij4 = 0; ij4 < numsolutions; ++ij4)
00487     {
00488 if( !j4valid[ij4] )
00489 {
00490     continue;
00491 }
00492     j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
00493 htj4 = IKtan(j4/2);
00494 
00495 _ij4[0] = ij4; _ij4[1] = -1;
00496 for(int iij4 = ij4+1; iij4 < numsolutions; ++iij4)
00497 {
00498 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
00499 {
00500     j4valid[iij4]=false; _ij4[1] = iij4; break; 
00501 }
00502 }
00503 {
00504 IkReal dummyeval[1];
00505 IkReal gconst52;
00506 IkReal x98=(sj4)*(sj4);
00507 IkReal x99=((IkReal(0.0180500000000000))*(cj4));
00508 IkReal x100=((IkReal(0.190000000000000))*(sj4));
00509 IkReal x101=((IkReal(0.0665000000000000))*(cj4)*(sj4));
00510 IkReal x102=((IkReal(0.700000000000000))*(x98));
00511 gconst52=IKsign(((((IkReal(-1.00000000000000))*(npy)*(r21)*(x99)))+(((npy)*(r20)*(x101)))+(((IkReal(-1.00000000000000))*(npx)*(rxp0_2)*(x100)))+(((npy)*(rxp0_2)*(x102)))+(((IkReal(-1.00000000000000))*(npx)*(rxp1_2)*(x102)))+(((IkReal(-1.00000000000000))*(npx)*(r21)*(x101)))+(((IkReal(-1.00000000000000))*(npy)*(rxp1_2)*(x100)))+(((IkReal(-1.00000000000000))*(npx)*(r20)*(x99)))));
00512 IkReal x103=(sj4)*(sj4);
00513 IkReal x104=((cj4)*(r20));
00514 IkReal x105=((npy)*(sj4));
00515 IkReal x106=((cj4)*(r21));
00516 IkReal x107=((npx)*(sj4));
00517 IkReal x108=((IkReal(38.7811634349030))*(x103));
00518 dummyeval[0]=((((IkReal(-1.00000000000000))*(npx)*(rxp1_2)*(x108)))+(((IkReal(-10.5263157894737))*(rxp0_2)*(x107)))+(((npy)*(rxp0_2)*(x108)))+(((IkReal(-1.00000000000000))*(npy)*(x106)))+(((IkReal(3.68421052631579))*(x104)*(x105)))+(((IkReal(-3.68421052631579))*(x106)*(x107)))+(((IkReal(-1.00000000000000))*(npx)*(x104)))+(((IkReal(-10.5263157894737))*(rxp1_2)*(x105))));
00519 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00520 {
00521 continue;
00522 
00523 } else
00524 {
00525 {
00526 IkReal j5array[1], cj5array[1], sj5array[1];
00527 bool j5valid[1]={false};
00528 _nj5 = 1;
00529 IkReal x109=(cj4)*(cj4);
00530 IkReal x110=(sj4)*(sj4);
00531 IkReal x111=((rxp0_2)*(sj4));
00532 IkReal x112=((IkReal(0.700000000000000))*(cj4));
00533 IkReal x113=((npx)*(rxp2_2));
00534 IkReal x114=((IkReal(0.190000000000000))*(cj4));
00535 IkReal x115=((rxp1_2)*(sj4));
00536 IkReal x116=((IkReal(0.000857375000000000))*(cj4));
00537 IkReal x117=((npy)*(rxp2_2));
00538 IkReal x118=((IkReal(0.0950000000000000))*(cj4)*(pp));
00539 IkReal x119=((IkReal(0.0180500000000000))*(r22)*(sj4));
00540 IkReal x120=((IkReal(0.0665000000000000))*(npz)*(x109));
00541 IkReal x121=((IkReal(0.0665000000000000))*(r22)*(x110));
00542 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(npy)*(x119)))+(((r20)*(x118)))+(((pp)*(x111)))+(((IkReal(-1.00000000000000))*(r20)*(x120)))+(((IkReal(-1.00000000000000))*(npx)*(x121)))+(((sj4)*(x112)*(x113)))+(((r20)*(x116)))+(((IkReal(-1.00000000000000))*(npz)*(x111)*(x112)))+(((IkReal(0.00902500000000000))*(x111)))+(((x114)*(x117))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((IkReal(0.00902500000000000))*(x115)))+(((IkReal(-1.00000000000000))*(npy)*(x121)))+(((IkReal(-1.00000000000000))*(x113)*(x114)))+(((IkReal(-1.00000000000000))*(r21)*(x120)))+(((r21)*(x118)))+(((sj4)*(x112)*(x117)))+(((IkReal(-1.00000000000000))*(npz)*(x112)*(x115)))+(((npx)*(x119)))+(((r21)*(x116)))+(((pp)*(x115))))))) < IKFAST_ATAN2_MAGTHRESH )
00543     continue;
00544 j5array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(npy)*(x119)))+(((r20)*(x118)))+(((pp)*(x111)))+(((IkReal(-1.00000000000000))*(r20)*(x120)))+(((IkReal(-1.00000000000000))*(npx)*(x121)))+(((sj4)*(x112)*(x113)))+(((r20)*(x116)))+(((IkReal(-1.00000000000000))*(npz)*(x111)*(x112)))+(((IkReal(0.00902500000000000))*(x111)))+(((x114)*(x117)))))), ((gconst52)*(((((IkReal(0.00902500000000000))*(x115)))+(((IkReal(-1.00000000000000))*(npy)*(x121)))+(((IkReal(-1.00000000000000))*(x113)*(x114)))+(((IkReal(-1.00000000000000))*(r21)*(x120)))+(((r21)*(x118)))+(((sj4)*(x112)*(x117)))+(((IkReal(-1.00000000000000))*(npz)*(x112)*(x115)))+(((npx)*(x119)))+(((r21)*(x116)))+(((pp)*(x115)))))));
00545 sj5array[0]=IKsin(j5array[0]);
00546 cj5array[0]=IKcos(j5array[0]);
00547 if( j5array[0] > IKPI )
00548 {
00549     j5array[0]-=IK2PI;
00550 }
00551 else if( j5array[0] < -IKPI )
00552 {    j5array[0]+=IK2PI;
00553 }
00554 j5valid[0] = true;
00555 for(int ij5 = 0; ij5 < 1; ++ij5)
00556 {
00557 if( !j5valid[ij5] )
00558 {
00559     continue;
00560 }
00561 _ij5[0] = ij5; _ij5[1] = -1;
00562 for(int iij5 = ij5+1; iij5 < 1; ++iij5)
00563 {
00564 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
00565 {
00566     j5valid[iij5]=false; _ij5[1] = iij5; break; 
00567 }
00568 }
00569 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
00570 {
00571 IkReal evalcond[2];
00572 IkReal x122=IKcos(j5);
00573 IkReal x123=IKsin(j5);
00574 IkReal x124=((IkReal(0.0950000000000000))*(cj4));
00575 IkReal x125=((sj4)*(x122));
00576 IkReal x126=((sj4)*(x123));
00577 evalcond[0]=((((IkReal(-1.00000000000000))*(rxp1_2)*(x126)))+(((rxp0_2)*(x125)))+(((IkReal(-1.00000000000000))*(r21)*(x123)*(x124)))+(((IkReal(-1.00000000000000))*(cj4)*(rxp2_2)))+(((r20)*(x122)*(x124)))+(((IkReal(0.0950000000000000))*(r22)*(sj4))));
00578 evalcond[1]=((IkReal(-0.00902500000000000))+(((IkReal(-0.190000000000000))*(npx)*(x123)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.700000000000000))*(npy)*(x126)))+(((IkReal(0.700000000000000))*(cj4)*(npz)))+(((IkReal(-0.190000000000000))*(npy)*(x122)))+(((IkReal(-0.700000000000000))*(npx)*(x125))));
00579 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00580 {
00581 continue;
00582 }
00583 }
00584 
00585 {
00586 IkReal j2array[2], cj2array[2], sj2array[2];
00587 bool j2valid[2]={false};
00588 _nj2 = 2;
00589 IkReal x127=((IkReal(2.85714285714286))*(sj4));
00590 cj2array[0]=((IkReal(-1.00000000000000))+(((IkReal(2.85714285714286))*(cj4)*(npz)))+(((npy)*(sj5)*(x127)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(x127))));
00591 if( cj2array[0] >= -1-IKFAST_SINCOS_THRESH && cj2array[0] <= 1+IKFAST_SINCOS_THRESH )
00592 {
00593     j2valid[0] = j2valid[1] = true;
00594     j2array[0] = IKacos(cj2array[0]);
00595     sj2array[0] = IKsin(j2array[0]);
00596     cj2array[1] = cj2array[0];
00597     j2array[1] = -j2array[0];
00598     sj2array[1] = -sj2array[0];
00599 }
00600 else if( isnan(cj2array[0]) )
00601 {
00602     // probably any value will work
00603     j2valid[0] = true;
00604     cj2array[0] = 1; sj2array[0] = 0; j2array[0] = 0;
00605 }
00606 for(int ij2 = 0; ij2 < 2; ++ij2)
00607 {
00608 if( !j2valid[ij2] )
00609 {
00610     continue;
00611 }
00612 _ij2[0] = ij2; _ij2[1] = -1;
00613 for(int iij2 = ij2+1; iij2 < 2; ++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 {
00623 IkReal dummyeval[1];
00624 IkReal gconst53;
00625 gconst53=IKsign(sj2);
00626 dummyeval[0]=sj2;
00627 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00628 {
00629 {
00630 IkReal j0array[2], cj0array[2], sj0array[2];
00631 bool j0valid[2]={false};
00632 _nj0 = 2;
00633 IkReal x128=((cj5)*(sj4));
00634 IkReal x129=((sj4)*(sj5));
00635 if( IKabs(((((IkReal(-1.00000000000000))*(cj4)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x129)))+(((r10)*(x128))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(r00)*(x128)))+(((cj4)*(r02)))+(((r01)*(x129))))) < IKFAST_ATAN2_MAGTHRESH )
00636     continue;
00637 IkReal x130=IKatan2(((((IkReal(-1.00000000000000))*(cj4)*(r12)))+(((IkReal(-1.00000000000000))*(r11)*(x129)))+(((r10)*(x128)))), ((((IkReal(-1.00000000000000))*(r00)*(x128)))+(((cj4)*(r02)))+(((r01)*(x129)))));
00638 j0array[0]=((IkReal(-1.00000000000000))*(x130));
00639 sj0array[0]=IKsin(j0array[0]);
00640 cj0array[0]=IKcos(j0array[0]);
00641 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x130))));
00642 sj0array[1]=IKsin(j0array[1]);
00643 cj0array[1]=IKcos(j0array[1]);
00644 if( j0array[0] > IKPI )
00645 {
00646     j0array[0]-=IK2PI;
00647 }
00648 else if( j0array[0] < -IKPI )
00649 {    j0array[0]+=IK2PI;
00650 }
00651 j0valid[0] = true;
00652 if( j0array[1] > IKPI )
00653 {
00654     j0array[1]-=IK2PI;
00655 }
00656 else if( j0array[1] < -IKPI )
00657 {    j0array[1]+=IK2PI;
00658 }
00659 j0valid[1] = true;
00660 for(int ij0 = 0; ij0 < 2; ++ij0)
00661 {
00662 if( !j0valid[ij0] )
00663 {
00664     continue;
00665 }
00666 _ij0[0] = ij0; _ij0[1] = -1;
00667 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
00668 {
00669 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00670 {
00671     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00672 }
00673 }
00674 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00675 
00676 {
00677 IkReal j3array[1], cj3array[1], sj3array[1];
00678 bool j3valid[1]={false};
00679 _nj3 = 1;
00680 IkReal x131=((cj4)*(cj5));
00681 IkReal x132=((IkReal(1.00000000000000))*(sj0));
00682 IkReal x133=((cj0)*(r10));
00683 IkReal x134=((cj0)*(r11));
00684 IkReal x135=((cj4)*(sj5));
00685 if( IKabs(((((x131)*(x133)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(x131)*(x132)))+(((IkReal(-1.00000000000000))*(x134)*(x135)))+(((cj0)*(r12)*(sj4)))+(((r01)*(sj0)*(x135))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((cj5)*(x134)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x132)))+(((sj5)*(x133))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((x131)*(x133)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(x131)*(x132)))+(((IkReal(-1.00000000000000))*(x134)*(x135)))+(((cj0)*(r12)*(sj4)))+(((r01)*(sj0)*(x135)))))+IKsqr(((((cj5)*(x134)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x132)))+(((sj5)*(x133)))))-1) <= IKFAST_SINCOS_THRESH )
00686     continue;
00687 j3array[0]=IKatan2(((((x131)*(x133)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(x131)*(x132)))+(((IkReal(-1.00000000000000))*(x134)*(x135)))+(((cj0)*(r12)*(sj4)))+(((r01)*(sj0)*(x135)))), ((((cj5)*(x134)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x132)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x132)))+(((sj5)*(x133)))));
00688 sj3array[0]=IKsin(j3array[0]);
00689 cj3array[0]=IKcos(j3array[0]);
00690 if( j3array[0] > IKPI )
00691 {
00692     j3array[0]-=IK2PI;
00693 }
00694 else if( j3array[0] < -IKPI )
00695 {    j3array[0]+=IK2PI;
00696 }
00697 j3valid[0] = true;
00698 for(int ij3 = 0; ij3 < 1; ++ij3)
00699 {
00700 if( !j3valid[ij3] )
00701 {
00702     continue;
00703 }
00704 _ij3[0] = ij3; _ij3[1] = -1;
00705 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00706 {
00707 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00708 {
00709     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00710 }
00711 }
00712 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00713 {
00714 IkReal evalcond[4];
00715 IkReal x136=IKcos(j3);
00716 IkReal x137=IKsin(j3);
00717 IkReal x138=((r00)*(sj0));
00718 IkReal x139=((cj4)*(cj5));
00719 IkReal x140=((IkReal(1.00000000000000))*(cj0));
00720 IkReal x141=((IkReal(0.350000000000000))*(sj2));
00721 IkReal x142=((cj4)*(sj5));
00722 IkReal x143=((r01)*(sj0));
00723 evalcond[0]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(-1.00000000000000))*(x137)*(x141)))+(((npx)*(sj5))));
00724 evalcond[1]=((((x136)*(x141)))+(((npx)*(x139)))+(((IkReal(-1.00000000000000))*(npy)*(x142)))+(((npz)*(sj4))));
00725 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(sj5)*(x140)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x140)))+(((sj5)*(x138)))+(((cj5)*(x143)))+(x136));
00726 evalcond[3]=((((IkReal(-1.00000000000000))*(r10)*(x139)*(x140)))+(((cj0)*(r11)*(x142)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x140)))+(((r02)*(sj0)*(sj4)))+(((x138)*(x139)))+(x137)+(((IkReal(-1.00000000000000))*(x142)*(x143))));
00727 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00728 {
00729 continue;
00730 }
00731 }
00732 
00733 {
00734 IkReal dummyeval[1];
00735 IkReal gconst74;
00736 gconst74=IKsign(((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2))))));
00737 dummyeval[0]=((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2)))));
00738 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00739 {
00740 {
00741 IkReal dummyeval[1];
00742 IkReal gconst75;
00743 gconst75=IKsign(((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2))))));
00744 dummyeval[0]=((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2)))));
00745 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00746 {
00747 {
00748 IkReal evalcond[9];
00749 IkReal x144=((sj0)*(sj4));
00750 IkReal x145=((IkReal(1.00000000000000))*(r12));
00751 IkReal x146=((cj4)*(cj5));
00752 IkReal x147=((IkReal(1.00000000000000))*(cj0));
00753 IkReal x148=((cj4)*(sj0));
00754 IkReal x149=((IkReal(1.00000000000000))*(sj5));
00755 IkReal x150=((cj0)*(cj4));
00756 IkReal x151=((r00)*(sj0));
00757 IkReal x152=((sj4)*(sj5));
00758 IkReal x153=((IkReal(1.00000000000000))*(cj5));
00759 IkReal x154=((r01)*(sj5));
00760 IkReal x155=((cj0)*(sj4));
00761 IkReal x156=((r11)*(sj5));
00762 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))));
00763 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(-0.350000000000000))*(sj2)))+(((npx)*(sj5))));
00764 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((npy)*(x152)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x153))));
00765 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(npy)*(x149)))+(((npz)*(sj4)))+(((npx)*(x146))));
00766 evalcond[4]=((((sj5)*(x151)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x147)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x147))));
00767 evalcond[5]=((((r20)*(x146)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x149))));
00768 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x144)*(x153)))+(((IkReal(-1.00000000000000))*(r11)*(x147)*(x152)))+(((IkReal(-1.00000000000000))*(x145)*(x150)))+(((r02)*(x148)))+(((cj5)*(r10)*(x155)))+(((x144)*(x154))));
00769 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x148)*(x149)))+(((r02)*(x144)))+(((x146)*(x151)))+(((x150)*(x156)))+(((IkReal(-1.00000000000000))*(x145)*(x155)))+(((IkReal(-1.00000000000000))*(r10)*(x146)*(x147))));
00770 evalcond[8]=((((IkReal(-1.00000000000000))*(x144)*(x145)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x147)))+(((x148)*(x156)))+(((x150)*(x154)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x146)))+(((IkReal(-1.00000000000000))*(r00)*(x146)*(x147))));
00771 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  )
00772 {
00773 {
00774 IkReal dummyeval[1];
00775 IkReal gconst76;
00776 gconst76=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
00777 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
00778 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00779 {
00780 {
00781 IkReal dummyeval[1];
00782 IkReal gconst77;
00783 gconst77=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
00784 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
00785 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00786 {
00787 continue;
00788 
00789 } else
00790 {
00791 {
00792 IkReal j1array[1], cj1array[1], sj1array[1];
00793 bool j1valid[1]={false};
00794 _nj1 = 1;
00795 IkReal x157=((cj2)*(sj5));
00796 IkReal x158=((r10)*(sj0));
00797 IkReal x159=((cj2)*(cj5));
00798 IkReal x160=((cj0)*(r00));
00799 IkReal x161=((sj2)*(sj5));
00800 IkReal x162=((r11)*(sj0));
00801 IkReal x163=((cj5)*(sj2));
00802 IkReal x164=((cj0)*(r01));
00803 if( IKabs(((gconst77)*(((((x160)*(x161)))+(((r21)*(x159)))+(((x162)*(x163)))+(((x163)*(x164)))+(((x158)*(x161)))+(((r20)*(x157))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst77)*(((((IkReal(-1.00000000000000))*(x159)*(x162)))+(((IkReal(-1.00000000000000))*(x159)*(x164)))+(((IkReal(-1.00000000000000))*(x157)*(x158)))+(((IkReal(-1.00000000000000))*(x157)*(x160)))+(((r20)*(x161)))+(((r21)*(x163))))))) < IKFAST_ATAN2_MAGTHRESH )
00804     continue;
00805 j1array[0]=IKatan2(((gconst77)*(((((x160)*(x161)))+(((r21)*(x159)))+(((x162)*(x163)))+(((x163)*(x164)))+(((x158)*(x161)))+(((r20)*(x157)))))), ((gconst77)*(((((IkReal(-1.00000000000000))*(x159)*(x162)))+(((IkReal(-1.00000000000000))*(x159)*(x164)))+(((IkReal(-1.00000000000000))*(x157)*(x158)))+(((IkReal(-1.00000000000000))*(x157)*(x160)))+(((r20)*(x161)))+(((r21)*(x163)))))));
00806 sj1array[0]=IKsin(j1array[0]);
00807 cj1array[0]=IKcos(j1array[0]);
00808 if( j1array[0] > IKPI )
00809 {
00810     j1array[0]-=IK2PI;
00811 }
00812 else if( j1array[0] < -IKPI )
00813 {    j1array[0]+=IK2PI;
00814 }
00815 j1valid[0] = true;
00816 for(int ij1 = 0; ij1 < 1; ++ij1)
00817 {
00818 if( !j1valid[ij1] )
00819 {
00820     continue;
00821 }
00822 _ij1[0] = ij1; _ij1[1] = -1;
00823 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
00824 {
00825 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00826 {
00827     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00828 }
00829 }
00830 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00831 {
00832 IkReal evalcond[4];
00833 IkReal x165=IKsin(j1);
00834 IkReal x166=IKcos(j1);
00835 IkReal x167=((cj0)*(sj4));
00836 IkReal x168=((IkReal(1.00000000000000))*(sj5));
00837 IkReal x169=((cj5)*(sj0));
00838 IkReal x170=((IkReal(1.00000000000000))*(cj4));
00839 IkReal x171=((IkReal(1.00000000000000))*(cj5));
00840 IkReal x172=((sj2)*(x165));
00841 IkReal x173=((IkReal(1.00000000000000))*(x166));
00842 IkReal x174=((cj2)*(x165));
00843 IkReal x175=((cj2)*(x173));
00844 evalcond[0]=((((IkReal(-1.00000000000000))*(x174)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(sj2)*(x173)))+(((cj5)*(r21))));
00845 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(sj4)*(x171)))+(((IkReal(-1.00000000000000))*(x175)))+(x172)+(((cj4)*(r22)))+(((r21)*(sj4)*(sj5))));
00846 evalcond[2]=((((IkReal(-1.00000000000000))*(x175)))+(x172)+(((IkReal(-1.00000000000000))*(r11)*(x169)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x168)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x168)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x171))));
00847 evalcond[3]=((((r10)*(sj4)*(x169)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x170)))+(x174)+(((cj5)*(r00)*(x167)))+(((sj2)*(x166)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x170)))+(((IkReal(-1.00000000000000))*(r01)*(x167)*(x168)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x168))));
00848 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00849 {
00850 continue;
00851 }
00852 }
00853 
00854 {
00855 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00856 vinfos[0].jointtype = 1;
00857 vinfos[0].foffset = j0;
00858 vinfos[0].indices[0] = _ij0[0];
00859 vinfos[0].indices[1] = _ij0[1];
00860 vinfos[0].maxsolutions = _nj0;
00861 vinfos[1].jointtype = 1;
00862 vinfos[1].foffset = j1;
00863 vinfos[1].indices[0] = _ij1[0];
00864 vinfos[1].indices[1] = _ij1[1];
00865 vinfos[1].maxsolutions = _nj1;
00866 vinfos[2].jointtype = 1;
00867 vinfos[2].foffset = j2;
00868 vinfos[2].indices[0] = _ij2[0];
00869 vinfos[2].indices[1] = _ij2[1];
00870 vinfos[2].maxsolutions = _nj2;
00871 vinfos[3].jointtype = 1;
00872 vinfos[3].foffset = j3;
00873 vinfos[3].indices[0] = _ij3[0];
00874 vinfos[3].indices[1] = _ij3[1];
00875 vinfos[3].maxsolutions = _nj3;
00876 vinfos[4].jointtype = 1;
00877 vinfos[4].foffset = j4;
00878 vinfos[4].indices[0] = _ij4[0];
00879 vinfos[4].indices[1] = _ij4[1];
00880 vinfos[4].maxsolutions = _nj4;
00881 vinfos[5].jointtype = 1;
00882 vinfos[5].foffset = j5;
00883 vinfos[5].indices[0] = _ij5[0];
00884 vinfos[5].indices[1] = _ij5[1];
00885 vinfos[5].maxsolutions = _nj5;
00886 std::vector<int> vfree(0);
00887 solutions.AddSolution(vinfos,vfree);
00888 }
00889 }
00890 }
00891 
00892 }
00893 
00894 }
00895 
00896 } else
00897 {
00898 {
00899 IkReal j1array[1], cj1array[1], sj1array[1];
00900 bool j1valid[1]={false};
00901 _nj1 = 1;
00902 IkReal x176=((r20)*(sj5));
00903 IkReal x177=((sj2)*(sj4));
00904 IkReal x178=((cj5)*(r20));
00905 IkReal x179=((cj5)*(r21));
00906 IkReal x180=((cj4)*(r22));
00907 IkReal x181=((r21)*(sj5));
00908 IkReal x182=((cj2)*(sj4));
00909 if( IKabs(((gconst76)*(((((IkReal(-1.00000000000000))*(x177)*(x181)))+(((x177)*(x178)))+(((IkReal(-1.00000000000000))*(sj2)*(x180)))+(((cj2)*(x179)))+(((cj2)*(x176))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst76)*(((((IkReal(-1.00000000000000))*(x178)*(x182)))+(((sj2)*(x179)))+(((cj2)*(x180)))+(((x181)*(x182)))+(((sj2)*(x176))))))) < IKFAST_ATAN2_MAGTHRESH )
00910     continue;
00911 j1array[0]=IKatan2(((gconst76)*(((((IkReal(-1.00000000000000))*(x177)*(x181)))+(((x177)*(x178)))+(((IkReal(-1.00000000000000))*(sj2)*(x180)))+(((cj2)*(x179)))+(((cj2)*(x176)))))), ((gconst76)*(((((IkReal(-1.00000000000000))*(x178)*(x182)))+(((sj2)*(x179)))+(((cj2)*(x180)))+(((x181)*(x182)))+(((sj2)*(x176)))))));
00912 sj1array[0]=IKsin(j1array[0]);
00913 cj1array[0]=IKcos(j1array[0]);
00914 if( j1array[0] > IKPI )
00915 {
00916     j1array[0]-=IK2PI;
00917 }
00918 else if( j1array[0] < -IKPI )
00919 {    j1array[0]+=IK2PI;
00920 }
00921 j1valid[0] = true;
00922 for(int ij1 = 0; ij1 < 1; ++ij1)
00923 {
00924 if( !j1valid[ij1] )
00925 {
00926     continue;
00927 }
00928 _ij1[0] = ij1; _ij1[1] = -1;
00929 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
00930 {
00931 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00932 {
00933     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00934 }
00935 }
00936 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00937 {
00938 IkReal evalcond[4];
00939 IkReal x183=IKsin(j1);
00940 IkReal x184=IKcos(j1);
00941 IkReal x185=((cj0)*(sj4));
00942 IkReal x186=((IkReal(1.00000000000000))*(sj5));
00943 IkReal x187=((cj5)*(sj0));
00944 IkReal x188=((IkReal(1.00000000000000))*(cj4));
00945 IkReal x189=((IkReal(1.00000000000000))*(cj5));
00946 IkReal x190=((sj2)*(x183));
00947 IkReal x191=((IkReal(1.00000000000000))*(x184));
00948 IkReal x192=((cj2)*(x183));
00949 IkReal x193=((cj2)*(x191));
00950 evalcond[0]=((((IkReal(-1.00000000000000))*(x192)))+(((IkReal(-1.00000000000000))*(sj2)*(x191)))+(((r20)*(sj5)))+(((cj5)*(r21))));
00951 evalcond[1]=((((IkReal(-1.00000000000000))*(x193)))+(x190)+(((cj4)*(r22)))+(((r21)*(sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x189))));
00952 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(sj0)*(x186)))+(((IkReal(-1.00000000000000))*(x193)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x189)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x186)))+(x190)+(((IkReal(-1.00000000000000))*(r11)*(x187))));
00953 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x188)))+(((sj2)*(x184)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x188)))+(x192)+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x186)))+(((cj5)*(r00)*(x185)))+(((IkReal(-1.00000000000000))*(r01)*(x185)*(x186)))+(((r10)*(sj4)*(x187))));
00954 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00955 {
00956 continue;
00957 }
00958 }
00959 
00960 {
00961 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00962 vinfos[0].jointtype = 1;
00963 vinfos[0].foffset = j0;
00964 vinfos[0].indices[0] = _ij0[0];
00965 vinfos[0].indices[1] = _ij0[1];
00966 vinfos[0].maxsolutions = _nj0;
00967 vinfos[1].jointtype = 1;
00968 vinfos[1].foffset = j1;
00969 vinfos[1].indices[0] = _ij1[0];
00970 vinfos[1].indices[1] = _ij1[1];
00971 vinfos[1].maxsolutions = _nj1;
00972 vinfos[2].jointtype = 1;
00973 vinfos[2].foffset = j2;
00974 vinfos[2].indices[0] = _ij2[0];
00975 vinfos[2].indices[1] = _ij2[1];
00976 vinfos[2].maxsolutions = _nj2;
00977 vinfos[3].jointtype = 1;
00978 vinfos[3].foffset = j3;
00979 vinfos[3].indices[0] = _ij3[0];
00980 vinfos[3].indices[1] = _ij3[1];
00981 vinfos[3].maxsolutions = _nj3;
00982 vinfos[4].jointtype = 1;
00983 vinfos[4].foffset = j4;
00984 vinfos[4].indices[0] = _ij4[0];
00985 vinfos[4].indices[1] = _ij4[1];
00986 vinfos[4].maxsolutions = _nj4;
00987 vinfos[5].jointtype = 1;
00988 vinfos[5].foffset = j5;
00989 vinfos[5].indices[0] = _ij5[0];
00990 vinfos[5].indices[1] = _ij5[1];
00991 vinfos[5].maxsolutions = _nj5;
00992 std::vector<int> vfree(0);
00993 solutions.AddSolution(vinfos,vfree);
00994 }
00995 }
00996 }
00997 
00998 }
00999 
01000 }
01001 
01002 } else
01003 {
01004 IkReal x194=((sj0)*(sj4));
01005 IkReal x195=((IkReal(1.00000000000000))*(r12));
01006 IkReal x196=((cj4)*(cj5));
01007 IkReal x197=((IkReal(1.00000000000000))*(cj0));
01008 IkReal x198=((cj4)*(sj0));
01009 IkReal x199=((IkReal(1.00000000000000))*(sj5));
01010 IkReal x200=((cj0)*(cj4));
01011 IkReal x201=((r00)*(sj0));
01012 IkReal x202=((sj4)*(sj5));
01013 IkReal x203=((IkReal(1.00000000000000))*(cj5));
01014 IkReal x204=((r01)*(sj5));
01015 IkReal x205=((cj0)*(sj4));
01016 IkReal x206=((r11)*(sj5));
01017 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))));
01018 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(0.350000000000000))*(sj2)))+(((npx)*(sj5))));
01019 evalcond[2]=((IkReal(-0.350000000000000))+(((npy)*(x202)))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x203))));
01020 evalcond[3]=((((npx)*(x196)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x199)))+(((npz)*(sj4))));
01021 evalcond[4]=((((sj5)*(x201)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x197)))+(((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x197))));
01022 evalcond[5]=((((r22)*(sj4)))+(((r20)*(x196)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x199))));
01023 evalcond[6]=((((x194)*(x204)))+(((IkReal(-1.00000000000000))*(x195)*(x200)))+(((cj5)*(r10)*(x205)))+(((IkReal(-1.00000000000000))*(r11)*(x197)*(x202)))+(((IkReal(-1.00000000000000))*(r00)*(x194)*(x203)))+(((r02)*(x198))));
01024 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r01)*(x198)*(x199)))+(((IkReal(-1.00000000000000))*(x195)*(x205)))+(((r02)*(x194)))+(((x196)*(x201)))+(((x200)*(x206)))+(((IkReal(-1.00000000000000))*(r10)*(x196)*(x197))));
01025 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(x196)*(x197)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x197)))+(((IkReal(-1.00000000000000))*(x194)*(x195)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x196)))+(((x198)*(x206)))+(((x200)*(x204))));
01026 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  )
01027 {
01028 {
01029 IkReal dummyeval[1];
01030 IkReal gconst78;
01031 gconst78=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
01032 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
01033 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01034 {
01035 {
01036 IkReal dummyeval[1];
01037 IkReal gconst79;
01038 gconst79=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
01039 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
01040 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01041 {
01042 continue;
01043 
01044 } else
01045 {
01046 {
01047 IkReal j1array[1], cj1array[1], sj1array[1];
01048 bool j1valid[1]={false};
01049 _nj1 = 1;
01050 IkReal x207=((IkReal(1.00000000000000))*(sj2));
01051 IkReal x208=((cj2)*(sj5));
01052 IkReal x209=((cj0)*(r00));
01053 IkReal x210=((cj5)*(r21));
01054 IkReal x211=((cj5)*(r11)*(sj0));
01055 IkReal x212=((r10)*(sj0)*(sj5));
01056 IkReal x213=((cj0)*(cj5)*(r01));
01057 if( IKabs(((gconst79)*(((((IkReal(-1.00000000000000))*(sj5)*(x207)*(x209)))+(((IkReal(-1.00000000000000))*(x207)*(x212)))+(((IkReal(-1.00000000000000))*(x207)*(x211)))+(((IkReal(-1.00000000000000))*(cj2)*(x210)))+(((IkReal(-1.00000000000000))*(x207)*(x213)))+(((IkReal(-1.00000000000000))*(r20)*(x208))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((r10)*(sj0)*(x208)))+(((x208)*(x209)))+(((IkReal(-1.00000000000000))*(x207)*(x210)))+(((cj2)*(x213)))+(((cj2)*(x211)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x207))))))) < IKFAST_ATAN2_MAGTHRESH )
01058     continue;
01059 j1array[0]=IKatan2(((gconst79)*(((((IkReal(-1.00000000000000))*(sj5)*(x207)*(x209)))+(((IkReal(-1.00000000000000))*(x207)*(x212)))+(((IkReal(-1.00000000000000))*(x207)*(x211)))+(((IkReal(-1.00000000000000))*(cj2)*(x210)))+(((IkReal(-1.00000000000000))*(x207)*(x213)))+(((IkReal(-1.00000000000000))*(r20)*(x208)))))), ((gconst79)*(((((r10)*(sj0)*(x208)))+(((x208)*(x209)))+(((IkReal(-1.00000000000000))*(x207)*(x210)))+(((cj2)*(x213)))+(((cj2)*(x211)))+(((IkReal(-1.00000000000000))*(r20)*(sj5)*(x207)))))));
01060 sj1array[0]=IKsin(j1array[0]);
01061 cj1array[0]=IKcos(j1array[0]);
01062 if( j1array[0] > IKPI )
01063 {
01064     j1array[0]-=IK2PI;
01065 }
01066 else if( j1array[0] < -IKPI )
01067 {    j1array[0]+=IK2PI;
01068 }
01069 j1valid[0] = true;
01070 for(int ij1 = 0; ij1 < 1; ++ij1)
01071 {
01072 if( !j1valid[ij1] )
01073 {
01074     continue;
01075 }
01076 _ij1[0] = ij1; _ij1[1] = -1;
01077 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01078 {
01079 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01080 {
01081     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01082 }
01083 }
01084 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01085 {
01086 IkReal evalcond[4];
01087 IkReal x214=IKsin(j1);
01088 IkReal x215=IKcos(j1);
01089 IkReal x216=((cj5)*(sj0));
01090 IkReal x217=((IkReal(1.00000000000000))*(r11));
01091 IkReal x218=((cj5)*(sj4));
01092 IkReal x219=((cj0)*(r00));
01093 IkReal x220=((IkReal(1.00000000000000))*(sj0));
01094 IkReal x221=((sj4)*(sj5));
01095 IkReal x222=((IkReal(1.00000000000000))*(cj0));
01096 IkReal x223=((sj2)*(x215));
01097 IkReal x224=((cj2)*(x214));
01098 IkReal x225=((cj2)*(x215));
01099 IkReal x226=((sj2)*(x214));
01100 IkReal x227=((x223)+(x224));
01101 evalcond[0]=((((r20)*(sj5)))+(x227)+(((cj5)*(r21))));
01102 evalcond[1]=((((r21)*(x221)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x225)))+(x226)+(((IkReal(-1.00000000000000))*(r20)*(x218))));
01103 evalcond[2]=((((IkReal(-1.00000000000000))*(sj5)*(x219)))+(((IkReal(-1.00000000000000))*(x216)*(x217)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x220)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x222)))+(x225)+(((IkReal(-1.00000000000000))*(x226))));
01104 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x221)*(x222)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x222)))+(((x218)*(x219)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x220)))+(((IkReal(-1.00000000000000))*(sj0)*(x217)*(x221)))+(x227)+(((r10)*(sj4)*(x216))));
01105 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01106 {
01107 continue;
01108 }
01109 }
01110 
01111 {
01112 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01113 vinfos[0].jointtype = 1;
01114 vinfos[0].foffset = j0;
01115 vinfos[0].indices[0] = _ij0[0];
01116 vinfos[0].indices[1] = _ij0[1];
01117 vinfos[0].maxsolutions = _nj0;
01118 vinfos[1].jointtype = 1;
01119 vinfos[1].foffset = j1;
01120 vinfos[1].indices[0] = _ij1[0];
01121 vinfos[1].indices[1] = _ij1[1];
01122 vinfos[1].maxsolutions = _nj1;
01123 vinfos[2].jointtype = 1;
01124 vinfos[2].foffset = j2;
01125 vinfos[2].indices[0] = _ij2[0];
01126 vinfos[2].indices[1] = _ij2[1];
01127 vinfos[2].maxsolutions = _nj2;
01128 vinfos[3].jointtype = 1;
01129 vinfos[3].foffset = j3;
01130 vinfos[3].indices[0] = _ij3[0];
01131 vinfos[3].indices[1] = _ij3[1];
01132 vinfos[3].maxsolutions = _nj3;
01133 vinfos[4].jointtype = 1;
01134 vinfos[4].foffset = j4;
01135 vinfos[4].indices[0] = _ij4[0];
01136 vinfos[4].indices[1] = _ij4[1];
01137 vinfos[4].maxsolutions = _nj4;
01138 vinfos[5].jointtype = 1;
01139 vinfos[5].foffset = j5;
01140 vinfos[5].indices[0] = _ij5[0];
01141 vinfos[5].indices[1] = _ij5[1];
01142 vinfos[5].maxsolutions = _nj5;
01143 std::vector<int> vfree(0);
01144 solutions.AddSolution(vinfos,vfree);
01145 }
01146 }
01147 }
01148 
01149 }
01150 
01151 }
01152 
01153 } else
01154 {
01155 {
01156 IkReal j1array[1], cj1array[1], sj1array[1];
01157 bool j1valid[1]={false};
01158 _nj1 = 1;
01159 IkReal x228=((cj4)*(r22));
01160 IkReal x229=((cj2)*(r20));
01161 IkReal x230=((cj5)*(r21));
01162 IkReal x231=((sj2)*(sj5));
01163 IkReal x232=((r21)*(sj4));
01164 IkReal x233=((IkReal(1.00000000000000))*(cj2));
01165 IkReal x234=((cj5)*(sj4));
01166 if( IKabs(((gconst78)*(((((sj2)*(x228)))+(((x231)*(x232)))+(((cj2)*(x230)))+(((IkReal(-1.00000000000000))*(r20)*(sj2)*(x234)))+(((sj5)*(x229))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((r20)*(x231)))+(((IkReal(-1.00000000000000))*(x228)*(x233)))+(((sj2)*(x230)))+(((x229)*(x234)))+(((IkReal(-1.00000000000000))*(sj5)*(x232)*(x233))))))) < IKFAST_ATAN2_MAGTHRESH )
01167     continue;
01168 j1array[0]=IKatan2(((gconst78)*(((((sj2)*(x228)))+(((x231)*(x232)))+(((cj2)*(x230)))+(((IkReal(-1.00000000000000))*(r20)*(sj2)*(x234)))+(((sj5)*(x229)))))), ((gconst78)*(((((r20)*(x231)))+(((IkReal(-1.00000000000000))*(x228)*(x233)))+(((sj2)*(x230)))+(((x229)*(x234)))+(((IkReal(-1.00000000000000))*(sj5)*(x232)*(x233)))))));
01169 sj1array[0]=IKsin(j1array[0]);
01170 cj1array[0]=IKcos(j1array[0]);
01171 if( j1array[0] > IKPI )
01172 {
01173     j1array[0]-=IK2PI;
01174 }
01175 else if( j1array[0] < -IKPI )
01176 {    j1array[0]+=IK2PI;
01177 }
01178 j1valid[0] = true;
01179 for(int ij1 = 0; ij1 < 1; ++ij1)
01180 {
01181 if( !j1valid[ij1] )
01182 {
01183     continue;
01184 }
01185 _ij1[0] = ij1; _ij1[1] = -1;
01186 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01187 {
01188 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01189 {
01190     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01191 }
01192 }
01193 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01194 {
01195 IkReal evalcond[4];
01196 IkReal x235=IKsin(j1);
01197 IkReal x236=IKcos(j1);
01198 IkReal x237=((cj5)*(sj0));
01199 IkReal x238=((IkReal(1.00000000000000))*(r11));
01200 IkReal x239=((cj5)*(sj4));
01201 IkReal x240=((cj0)*(r00));
01202 IkReal x241=((IkReal(1.00000000000000))*(sj0));
01203 IkReal x242=((sj4)*(sj5));
01204 IkReal x243=((IkReal(1.00000000000000))*(cj0));
01205 IkReal x244=((sj2)*(x236));
01206 IkReal x245=((cj2)*(x235));
01207 IkReal x246=((cj2)*(x236));
01208 IkReal x247=((sj2)*(x235));
01209 IkReal x248=((x245)+(x244));
01210 evalcond[0]=((((r20)*(sj5)))+(x248)+(((cj5)*(r21))));
01211 evalcond[1]=((((IkReal(-1.00000000000000))*(x246)))+(((cj4)*(r22)))+(((r21)*(x242)))+(x247)+(((IkReal(-1.00000000000000))*(r20)*(x239))));
01212 evalcond[2]=((((IkReal(-1.00000000000000))*(x247)))+(((IkReal(-1.00000000000000))*(sj5)*(x240)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x241)))+(x246)+(((IkReal(-1.00000000000000))*(x237)*(x238)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x243))));
01213 evalcond[3]=((((x239)*(x240)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x241)))+(((IkReal(-1.00000000000000))*(r01)*(x242)*(x243)))+(((r10)*(sj4)*(x237)))+(x248)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x243)))+(((IkReal(-1.00000000000000))*(sj0)*(x238)*(x242))));
01214 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01215 {
01216 continue;
01217 }
01218 }
01219 
01220 {
01221 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01222 vinfos[0].jointtype = 1;
01223 vinfos[0].foffset = j0;
01224 vinfos[0].indices[0] = _ij0[0];
01225 vinfos[0].indices[1] = _ij0[1];
01226 vinfos[0].maxsolutions = _nj0;
01227 vinfos[1].jointtype = 1;
01228 vinfos[1].foffset = j1;
01229 vinfos[1].indices[0] = _ij1[0];
01230 vinfos[1].indices[1] = _ij1[1];
01231 vinfos[1].maxsolutions = _nj1;
01232 vinfos[2].jointtype = 1;
01233 vinfos[2].foffset = j2;
01234 vinfos[2].indices[0] = _ij2[0];
01235 vinfos[2].indices[1] = _ij2[1];
01236 vinfos[2].maxsolutions = _nj2;
01237 vinfos[3].jointtype = 1;
01238 vinfos[3].foffset = j3;
01239 vinfos[3].indices[0] = _ij3[0];
01240 vinfos[3].indices[1] = _ij3[1];
01241 vinfos[3].maxsolutions = _nj3;
01242 vinfos[4].jointtype = 1;
01243 vinfos[4].foffset = j4;
01244 vinfos[4].indices[0] = _ij4[0];
01245 vinfos[4].indices[1] = _ij4[1];
01246 vinfos[4].maxsolutions = _nj4;
01247 vinfos[5].jointtype = 1;
01248 vinfos[5].foffset = j5;
01249 vinfos[5].indices[0] = _ij5[0];
01250 vinfos[5].indices[1] = _ij5[1];
01251 vinfos[5].maxsolutions = _nj5;
01252 std::vector<int> vfree(0);
01253 solutions.AddSolution(vinfos,vfree);
01254 }
01255 }
01256 }
01257 
01258 }
01259 
01260 }
01261 
01262 } else
01263 {
01264 IkReal x249=((IkReal(1.00000000000000))*(r10));
01265 IkReal x250=((sj0)*(sj5));
01266 IkReal x251=((r02)*(sj0));
01267 IkReal x252=((cj4)*(cj5));
01268 IkReal x253=((IkReal(1.00000000000000))*(cj4));
01269 IkReal x254=((cj0)*(r12));
01270 IkReal x255=((IkReal(1.00000000000000))*(cj0));
01271 IkReal x256=((cj5)*(r11));
01272 IkReal x257=((cj5)*(r01));
01273 IkReal x258=((r00)*(sj0));
01274 IkReal x259=((npy)*(sj5));
01275 IkReal x260=((IkReal(1.00000000000000))*(sj4));
01276 IkReal x261=((cj0)*(sj5));
01277 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959))));
01278 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
01279 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(x260)))+(((cj4)*(npz)))+(((sj4)*(x259))));
01280 evalcond[3]=((((npx)*(x252)))+(((IkReal(-1.00000000000000))*(x253)*(x259)))+(((IkReal(0.350000000000000))*(sj2)))+(((npz)*(sj4))));
01281 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
01282 evalcond[5]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x255)*(x256)))+(((sj0)*(x257)))+(((IkReal(-1.00000000000000))*(x249)*(x261)))+(((r00)*(x250))));
01283 evalcond[6]=((((IkReal(-1.00000000000000))*(x255)*(x257)))+(((IkReal(-1.00000000000000))*(sj0)*(x256)))+(((IkReal(-1.00000000000000))*(x249)*(x250)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x255))));
01284 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(sj4)*(sj5)*(x255)))+(((cj4)*(x251)))+(((r01)*(sj4)*(x250)))+(((IkReal(-1.00000000000000))*(x253)*(x254)))+(((cj0)*(cj5)*(r10)*(sj4)))+(((IkReal(-1.00000000000000))*(cj5)*(x258)*(x260))));
01285 evalcond[8]=((((IkReal(-1.00000000000000))*(cj0)*(x249)*(x252)))+(((IkReal(-1.00000000000000))*(x254)*(x260)))+(((x252)*(x258)))+(((sj4)*(x251)))+(((cj4)*(r11)*(x261)))+(((IkReal(-1.00000000000000))*(r01)*(x250)*(x253))));
01286 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  )
01287 {
01288 {
01289 IkReal dummyeval[1];
01290 IkReal gconst80;
01291 gconst80=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
01292 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
01293 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01294 {
01295 {
01296 IkReal dummyeval[1];
01297 IkReal gconst81;
01298 gconst81=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
01299 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
01300 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01301 {
01302 continue;
01303 
01304 } else
01305 {
01306 {
01307 IkReal j1array[1], cj1array[1], sj1array[1];
01308 bool j1valid[1]={false};
01309 _nj1 = 1;
01310 IkReal x262=((cj4)*(r22));
01311 IkReal x263=((IkReal(1.00000000000000))*(sj0));
01312 IkReal x264=((IkReal(1.00000000000000))*(cj2));
01313 IkReal x265=((cj4)*(r12));
01314 IkReal x266=((cj5)*(sj4));
01315 IkReal x267=((IkReal(1.00000000000000))*(sj2));
01316 IkReal x268=((r10)*(sj0));
01317 IkReal x269=((cj0)*(r00));
01318 IkReal x270=((cj0)*(r01));
01319 IkReal x271=((sj4)*(sj5));
01320 IkReal x272=((sj2)*(x271));
01321 IkReal x273=((cj0)*(cj4)*(r02));
01322 if( IKabs(((gconst81)*(((((IkReal(-1.00000000000000))*(cj2)*(r11)*(x263)*(x271)))+(((IkReal(-1.00000000000000))*(x264)*(x270)*(x271)))+(((cj2)*(x266)*(x269)))+(((cj2)*(x266)*(x268)))+(((IkReal(-1.00000000000000))*(cj2)*(x263)*(x265)))+(((IkReal(-1.00000000000000))*(r20)*(x266)*(x267)))+(((IkReal(-1.00000000000000))*(x264)*(x273)))+(((r21)*(x272)))+(((sj2)*(x262))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst81)*(((((IkReal(-1.00000000000000))*(r11)*(x263)*(x272)))+(((IkReal(-1.00000000000000))*(sj2)*(x263)*(x265)))+(((sj2)*(x266)*(x269)))+(((cj2)*(r20)*(x266)))+(((sj2)*(x266)*(x268)))+(((IkReal(-1.00000000000000))*(x267)*(x270)*(x271)))+(((IkReal(-1.00000000000000))*(r21)*(x264)*(x271)))+(((IkReal(-1.00000000000000))*(x262)*(x264)))+(((IkReal(-1.00000000000000))*(x267)*(x273))))))) < IKFAST_ATAN2_MAGTHRESH )
01323     continue;
01324 j1array[0]=IKatan2(((gconst81)*(((((IkReal(-1.00000000000000))*(cj2)*(r11)*(x263)*(x271)))+(((IkReal(-1.00000000000000))*(x264)*(x270)*(x271)))+(((cj2)*(x266)*(x269)))+(((cj2)*(x266)*(x268)))+(((IkReal(-1.00000000000000))*(cj2)*(x263)*(x265)))+(((IkReal(-1.00000000000000))*(r20)*(x266)*(x267)))+(((IkReal(-1.00000000000000))*(x264)*(x273)))+(((r21)*(x272)))+(((sj2)*(x262)))))), ((gconst81)*(((((IkReal(-1.00000000000000))*(r11)*(x263)*(x272)))+(((IkReal(-1.00000000000000))*(sj2)*(x263)*(x265)))+(((sj2)*(x266)*(x269)))+(((cj2)*(r20)*(x266)))+(((sj2)*(x266)*(x268)))+(((IkReal(-1.00000000000000))*(x267)*(x270)*(x271)))+(((IkReal(-1.00000000000000))*(r21)*(x264)*(x271)))+(((IkReal(-1.00000000000000))*(x262)*(x264)))+(((IkReal(-1.00000000000000))*(x267)*(x273)))))));
01325 sj1array[0]=IKsin(j1array[0]);
01326 cj1array[0]=IKcos(j1array[0]);
01327 if( j1array[0] > IKPI )
01328 {
01329     j1array[0]-=IK2PI;
01330 }
01331 else if( j1array[0] < -IKPI )
01332 {    j1array[0]+=IK2PI;
01333 }
01334 j1valid[0] = true;
01335 for(int ij1 = 0; ij1 < 1; ++ij1)
01336 {
01337 if( !j1valid[ij1] )
01338 {
01339     continue;
01340 }
01341 _ij1[0] = ij1; _ij1[1] = -1;
01342 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01343 {
01344 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01345 {
01346     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01347 }
01348 }
01349 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01350 {
01351 IkReal evalcond[4];
01352 IkReal x274=IKcos(j1);
01353 IkReal x275=IKsin(j1);
01354 IkReal x276=((IkReal(1.00000000000000))*(sj4));
01355 IkReal x277=((cj5)*(r00));
01356 IkReal x278=((cj5)*(r20));
01357 IkReal x279=((r12)*(sj0));
01358 IkReal x280=((r21)*(sj5));
01359 IkReal x281=((IkReal(1.00000000000000))*(cj4));
01360 IkReal x282=((sj2)*(x274));
01361 IkReal x283=((cj2)*(x275));
01362 IkReal x284=((cj2)*(x274));
01363 IkReal x285=((r11)*(sj0)*(sj5));
01364 IkReal x286=((cj0)*(x281));
01365 IkReal x287=((cj0)*(r01)*(sj5));
01366 IkReal x288=((cj5)*(r10)*(sj0));
01367 IkReal x289=((sj2)*(x275));
01368 IkReal x290=((x283)+(x282));
01369 evalcond[0]=((((sj4)*(x280)))+(x289)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x284)))+(((IkReal(-1.00000000000000))*(x276)*(x278))));
01370 evalcond[1]=((((IkReal(-1.00000000000000))*(x280)*(x281)))+(((cj4)*(x278)))+(((r22)*(sj4)))+(x290));
01371 evalcond[2]=((((IkReal(-1.00000000000000))*(x279)*(x281)))+(((cj0)*(sj4)*(x277)))+(x290)+(((IkReal(-1.00000000000000))*(x276)*(x285)))+(((sj4)*(x288)))+(((IkReal(-1.00000000000000))*(x276)*(x287)))+(((IkReal(-1.00000000000000))*(r02)*(x286))));
01372 evalcond[3]=((((IkReal(-1.00000000000000))*(x281)*(x288)))+(x284)+(((IkReal(-1.00000000000000))*(x276)*(x279)))+(((cj4)*(x285)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x276)))+(((cj4)*(x287)))+(((IkReal(-1.00000000000000))*(x289)))+(((IkReal(-1.00000000000000))*(x277)*(x286))));
01373 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01374 {
01375 continue;
01376 }
01377 }
01378 
01379 {
01380 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01381 vinfos[0].jointtype = 1;
01382 vinfos[0].foffset = j0;
01383 vinfos[0].indices[0] = _ij0[0];
01384 vinfos[0].indices[1] = _ij0[1];
01385 vinfos[0].maxsolutions = _nj0;
01386 vinfos[1].jointtype = 1;
01387 vinfos[1].foffset = j1;
01388 vinfos[1].indices[0] = _ij1[0];
01389 vinfos[1].indices[1] = _ij1[1];
01390 vinfos[1].maxsolutions = _nj1;
01391 vinfos[2].jointtype = 1;
01392 vinfos[2].foffset = j2;
01393 vinfos[2].indices[0] = _ij2[0];
01394 vinfos[2].indices[1] = _ij2[1];
01395 vinfos[2].maxsolutions = _nj2;
01396 vinfos[3].jointtype = 1;
01397 vinfos[3].foffset = j3;
01398 vinfos[3].indices[0] = _ij3[0];
01399 vinfos[3].indices[1] = _ij3[1];
01400 vinfos[3].maxsolutions = _nj3;
01401 vinfos[4].jointtype = 1;
01402 vinfos[4].foffset = j4;
01403 vinfos[4].indices[0] = _ij4[0];
01404 vinfos[4].indices[1] = _ij4[1];
01405 vinfos[4].maxsolutions = _nj4;
01406 vinfos[5].jointtype = 1;
01407 vinfos[5].foffset = j5;
01408 vinfos[5].indices[0] = _ij5[0];
01409 vinfos[5].indices[1] = _ij5[1];
01410 vinfos[5].maxsolutions = _nj5;
01411 std::vector<int> vfree(0);
01412 solutions.AddSolution(vinfos,vfree);
01413 }
01414 }
01415 }
01416 
01417 }
01418 
01419 }
01420 
01421 } else
01422 {
01423 {
01424 IkReal j1array[1], cj1array[1], sj1array[1];
01425 bool j1valid[1]={false};
01426 _nj1 = 1;
01427 IkReal x291=((cj4)*(r22));
01428 IkReal x292=((r21)*(sj5));
01429 IkReal x293=((cj2)*(cj4));
01430 IkReal x294=((cj2)*(sj4));
01431 IkReal x295=((sj2)*(sj4));
01432 IkReal x296=((cj5)*(r20));
01433 IkReal x297=((cj4)*(sj2));
01434 if( IKabs(((gconst80)*(((((IkReal(-1.00000000000000))*(x295)*(x296)))+(((x292)*(x295)))+(((r22)*(x294)))+(((sj2)*(x291)))+(((IkReal(-1.00000000000000))*(x292)*(x293)))+(((x293)*(x296))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst80)*(((((x294)*(x296)))+(((x296)*(x297)))+(((IkReal(-1.00000000000000))*(cj2)*(x291)))+(((IkReal(-1.00000000000000))*(x292)*(x297)))+(((IkReal(-1.00000000000000))*(x292)*(x294)))+(((r22)*(x295))))))) < IKFAST_ATAN2_MAGTHRESH )
01435     continue;
01436 j1array[0]=IKatan2(((gconst80)*(((((IkReal(-1.00000000000000))*(x295)*(x296)))+(((x292)*(x295)))+(((r22)*(x294)))+(((sj2)*(x291)))+(((IkReal(-1.00000000000000))*(x292)*(x293)))+(((x293)*(x296)))))), ((gconst80)*(((((x294)*(x296)))+(((x296)*(x297)))+(((IkReal(-1.00000000000000))*(cj2)*(x291)))+(((IkReal(-1.00000000000000))*(x292)*(x297)))+(((IkReal(-1.00000000000000))*(x292)*(x294)))+(((r22)*(x295)))))));
01437 sj1array[0]=IKsin(j1array[0]);
01438 cj1array[0]=IKcos(j1array[0]);
01439 if( j1array[0] > IKPI )
01440 {
01441     j1array[0]-=IK2PI;
01442 }
01443 else if( j1array[0] < -IKPI )
01444 {    j1array[0]+=IK2PI;
01445 }
01446 j1valid[0] = true;
01447 for(int ij1 = 0; ij1 < 1; ++ij1)
01448 {
01449 if( !j1valid[ij1] )
01450 {
01451     continue;
01452 }
01453 _ij1[0] = ij1; _ij1[1] = -1;
01454 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01455 {
01456 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01457 {
01458     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01459 }
01460 }
01461 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01462 {
01463 IkReal evalcond[4];
01464 IkReal x298=IKcos(j1);
01465 IkReal x299=IKsin(j1);
01466 IkReal x300=((IkReal(1.00000000000000))*(sj4));
01467 IkReal x301=((cj5)*(r00));
01468 IkReal x302=((cj5)*(r20));
01469 IkReal x303=((r12)*(sj0));
01470 IkReal x304=((r21)*(sj5));
01471 IkReal x305=((IkReal(1.00000000000000))*(cj4));
01472 IkReal x306=((sj2)*(x298));
01473 IkReal x307=((cj2)*(x299));
01474 IkReal x308=((cj2)*(x298));
01475 IkReal x309=((r11)*(sj0)*(sj5));
01476 IkReal x310=((cj0)*(x305));
01477 IkReal x311=((cj0)*(r01)*(sj5));
01478 IkReal x312=((cj5)*(r10)*(sj0));
01479 IkReal x313=((sj2)*(x299));
01480 IkReal x314=((x306)+(x307));
01481 evalcond[0]=((((cj4)*(r22)))+(x313)+(((IkReal(-1.00000000000000))*(x308)))+(((IkReal(-1.00000000000000))*(x300)*(x302)))+(((sj4)*(x304))));
01482 evalcond[1]=((((r22)*(sj4)))+(((cj4)*(x302)))+(x314)+(((IkReal(-1.00000000000000))*(x304)*(x305))));
01483 evalcond[2]=((((sj4)*(x312)))+(((IkReal(-1.00000000000000))*(x303)*(x305)))+(((IkReal(-1.00000000000000))*(x300)*(x309)))+(((cj0)*(sj4)*(x301)))+(x314)+(((IkReal(-1.00000000000000))*(r02)*(x310)))+(((IkReal(-1.00000000000000))*(x300)*(x311))));
01484 evalcond[3]=((((cj4)*(x309)))+(((IkReal(-1.00000000000000))*(x301)*(x310)))+(((IkReal(-1.00000000000000))*(x300)*(x303)))+(x308)+(((cj4)*(x311)))+(((IkReal(-1.00000000000000))*(x305)*(x312)))+(((IkReal(-1.00000000000000))*(x313)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x300))));
01485 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01486 {
01487 continue;
01488 }
01489 }
01490 
01491 {
01492 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01493 vinfos[0].jointtype = 1;
01494 vinfos[0].foffset = j0;
01495 vinfos[0].indices[0] = _ij0[0];
01496 vinfos[0].indices[1] = _ij0[1];
01497 vinfos[0].maxsolutions = _nj0;
01498 vinfos[1].jointtype = 1;
01499 vinfos[1].foffset = j1;
01500 vinfos[1].indices[0] = _ij1[0];
01501 vinfos[1].indices[1] = _ij1[1];
01502 vinfos[1].maxsolutions = _nj1;
01503 vinfos[2].jointtype = 1;
01504 vinfos[2].foffset = j2;
01505 vinfos[2].indices[0] = _ij2[0];
01506 vinfos[2].indices[1] = _ij2[1];
01507 vinfos[2].maxsolutions = _nj2;
01508 vinfos[3].jointtype = 1;
01509 vinfos[3].foffset = j3;
01510 vinfos[3].indices[0] = _ij3[0];
01511 vinfos[3].indices[1] = _ij3[1];
01512 vinfos[3].maxsolutions = _nj3;
01513 vinfos[4].jointtype = 1;
01514 vinfos[4].foffset = j4;
01515 vinfos[4].indices[0] = _ij4[0];
01516 vinfos[4].indices[1] = _ij4[1];
01517 vinfos[4].maxsolutions = _nj4;
01518 vinfos[5].jointtype = 1;
01519 vinfos[5].foffset = j5;
01520 vinfos[5].indices[0] = _ij5[0];
01521 vinfos[5].indices[1] = _ij5[1];
01522 vinfos[5].maxsolutions = _nj5;
01523 std::vector<int> vfree(0);
01524 solutions.AddSolution(vinfos,vfree);
01525 }
01526 }
01527 }
01528 
01529 }
01530 
01531 }
01532 
01533 } else
01534 {
01535 IkReal x315=((IkReal(1.00000000000000))*(r10));
01536 IkReal x316=((sj0)*(sj5));
01537 IkReal x317=((r02)*(sj0));
01538 IkReal x318=((cj4)*(cj5));
01539 IkReal x319=((IkReal(1.00000000000000))*(cj4));
01540 IkReal x320=((cj0)*(r12));
01541 IkReal x321=((IkReal(1.00000000000000))*(cj0));
01542 IkReal x322=((cj5)*(r11));
01543 IkReal x323=((cj5)*(r01));
01544 IkReal x324=((r00)*(sj0));
01545 IkReal x325=((npy)*(sj5));
01546 IkReal x326=((IkReal(1.00000000000000))*(sj4));
01547 IkReal x327=((cj0)*(sj5));
01548 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j3, IkReal(6.28318530717959))));
01549 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
01550 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x325)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(x326))));
01551 evalcond[3]=((((npx)*(x318)))+(((IkReal(-1.00000000000000))*(x319)*(x325)))+(((IkReal(-0.350000000000000))*(sj2)))+(((npz)*(sj4))));
01552 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
01553 evalcond[5]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x321)*(x322)))+(((sj0)*(x323)))+(((IkReal(-1.00000000000000))*(x315)*(x327)))+(((r00)*(x316))));
01554 evalcond[6]=((((IkReal(-1.00000000000000))*(sj0)*(x322)))+(((IkReal(-1.00000000000000))*(x321)*(x323)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x321)))+(((IkReal(-1.00000000000000))*(x315)*(x316))));
01555 evalcond[7]=((((IkReal(-1.00000000000000))*(x319)*(x320)))+(((cj4)*(x317)))+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(sj5)*(x321)))+(((IkReal(-1.00000000000000))*(cj5)*(x324)*(x326)))+(((cj0)*(cj5)*(r10)*(sj4)))+(((r01)*(sj4)*(x316))));
01556 evalcond[8]=((((IkReal(-1.00000000000000))*(x320)*(x326)))+(((x318)*(x324)))+(((IkReal(-1.00000000000000))*(r01)*(x316)*(x319)))+(((sj4)*(x317)))+(((IkReal(-1.00000000000000))*(cj0)*(x315)*(x318)))+(((cj4)*(r11)*(x327))));
01557 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  )
01558 {
01559 {
01560 IkReal dummyeval[1];
01561 IkReal gconst82;
01562 gconst82=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
01563 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
01564 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01565 {
01566 {
01567 IkReal dummyeval[1];
01568 IkReal gconst83;
01569 gconst83=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
01570 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
01571 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01572 {
01573 continue;
01574 
01575 } else
01576 {
01577 {
01578 IkReal j1array[1], cj1array[1], sj1array[1];
01579 bool j1valid[1]={false};
01580 _nj1 = 1;
01581 IkReal x328=((cj4)*(r22));
01582 IkReal x329=((r11)*(sj0));
01583 IkReal x330=((IkReal(1.00000000000000))*(cj2));
01584 IkReal x331=((sj2)*(sj4));
01585 IkReal x332=((IkReal(1.00000000000000))*(sj2));
01586 IkReal x333=((cj2)*(sj4));
01587 IkReal x334=((cj0)*(r01));
01588 IkReal x335=((cj5)*(r20));
01589 IkReal x336=((IkReal(1.00000000000000))*(sj4)*(sj5));
01590 IkReal x337=((cj0)*(cj4)*(r02));
01591 IkReal x338=((cj4)*(r12)*(sj0));
01592 IkReal x339=((cj5)*(r10)*(sj0));
01593 IkReal x340=((cj0)*(cj5)*(r00));
01594 if( IKabs(((gconst83)*(((((x333)*(x339)))+(((x333)*(x340)))+(((IkReal(-1.00000000000000))*(x330)*(x337)))+(((IkReal(-1.00000000000000))*(x331)*(x335)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x330)*(x334)))+(((sj2)*(x328)))+(((IkReal(-1.00000000000000))*(x330)*(x338)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x329)*(x330)))+(((r21)*(sj5)*(x331))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst83)*(((((x333)*(x335)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x330)))+(((IkReal(-1.00000000000000))*(x332)*(x338)))+(((x331)*(x339)))+(((x331)*(x340)))+(((IkReal(-1.00000000000000))*(x332)*(x337)))+(((IkReal(-1.00000000000000))*(x328)*(x330)))+(((IkReal(-1.00000000000000))*(sj5)*(x329)*(x331)))+(((IkReal(-1.00000000000000))*(sj5)*(x331)*(x334))))))) < IKFAST_ATAN2_MAGTHRESH )
01595     continue;
01596 j1array[0]=IKatan2(((gconst83)*(((((x333)*(x339)))+(((x333)*(x340)))+(((IkReal(-1.00000000000000))*(x330)*(x337)))+(((IkReal(-1.00000000000000))*(x331)*(x335)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x330)*(x334)))+(((sj2)*(x328)))+(((IkReal(-1.00000000000000))*(x330)*(x338)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x329)*(x330)))+(((r21)*(sj5)*(x331)))))), ((gconst83)*(((((x333)*(x335)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x330)))+(((IkReal(-1.00000000000000))*(x332)*(x338)))+(((x331)*(x339)))+(((x331)*(x340)))+(((IkReal(-1.00000000000000))*(x332)*(x337)))+(((IkReal(-1.00000000000000))*(x328)*(x330)))+(((IkReal(-1.00000000000000))*(sj5)*(x329)*(x331)))+(((IkReal(-1.00000000000000))*(sj5)*(x331)*(x334)))))));
01597 sj1array[0]=IKsin(j1array[0]);
01598 cj1array[0]=IKcos(j1array[0]);
01599 if( j1array[0] > IKPI )
01600 {
01601     j1array[0]-=IK2PI;
01602 }
01603 else if( j1array[0] < -IKPI )
01604 {    j1array[0]+=IK2PI;
01605 }
01606 j1valid[0] = true;
01607 for(int ij1 = 0; ij1 < 1; ++ij1)
01608 {
01609 if( !j1valid[ij1] )
01610 {
01611     continue;
01612 }
01613 _ij1[0] = ij1; _ij1[1] = -1;
01614 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01615 {
01616 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01617 {
01618     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01619 }
01620 }
01621 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01622 {
01623 IkReal evalcond[4];
01624 IkReal x341=IKcos(j1);
01625 IkReal x342=IKsin(j1);
01626 IkReal x343=((IkReal(1.00000000000000))*(sj4));
01627 IkReal x344=((cj5)*(r00));
01628 IkReal x345=((cj5)*(r20));
01629 IkReal x346=((r12)*(sj0));
01630 IkReal x347=((r21)*(sj5));
01631 IkReal x348=((IkReal(1.00000000000000))*(cj4));
01632 IkReal x349=((sj2)*(x342));
01633 IkReal x350=((IkReal(1.00000000000000))*(x341));
01634 IkReal x351=((r11)*(sj0)*(sj5));
01635 IkReal x352=((cj0)*(x348));
01636 IkReal x353=((cj0)*(r01)*(sj5));
01637 IkReal x354=((cj2)*(x342));
01638 IkReal x355=((cj5)*(r10)*(sj0));
01639 IkReal x356=((cj2)*(x350));
01640 evalcond[0]=((((sj4)*(x347)))+(((IkReal(-1.00000000000000))*(x343)*(x345)))+(((cj4)*(r22)))+(x349)+(((IkReal(-1.00000000000000))*(x356))));
01641 evalcond[1]=((((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x347)*(x348)))+(((IkReal(-1.00000000000000))*(sj2)*(x350)))+(((IkReal(-1.00000000000000))*(x354)))+(((cj4)*(x345))));
01642 evalcond[2]=((((IkReal(-1.00000000000000))*(x343)*(x351)))+(((sj2)*(x341)))+(((IkReal(-1.00000000000000))*(x346)*(x348)))+(((IkReal(-1.00000000000000))*(x343)*(x353)))+(((IkReal(-1.00000000000000))*(r02)*(x352)))+(x354)+(((sj4)*(x355)))+(((cj0)*(sj4)*(x344))));
01643 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x343)))+(((IkReal(-1.00000000000000))*(x348)*(x355)))+(((IkReal(-1.00000000000000))*(x344)*(x352)))+(((IkReal(-1.00000000000000))*(x343)*(x346)))+(x349)+(((cj4)*(x353)))+(((IkReal(-1.00000000000000))*(x356)))+(((cj4)*(x351))));
01644 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01645 {
01646 continue;
01647 }
01648 }
01649 
01650 {
01651 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01652 vinfos[0].jointtype = 1;
01653 vinfos[0].foffset = j0;
01654 vinfos[0].indices[0] = _ij0[0];
01655 vinfos[0].indices[1] = _ij0[1];
01656 vinfos[0].maxsolutions = _nj0;
01657 vinfos[1].jointtype = 1;
01658 vinfos[1].foffset = j1;
01659 vinfos[1].indices[0] = _ij1[0];
01660 vinfos[1].indices[1] = _ij1[1];
01661 vinfos[1].maxsolutions = _nj1;
01662 vinfos[2].jointtype = 1;
01663 vinfos[2].foffset = j2;
01664 vinfos[2].indices[0] = _ij2[0];
01665 vinfos[2].indices[1] = _ij2[1];
01666 vinfos[2].maxsolutions = _nj2;
01667 vinfos[3].jointtype = 1;
01668 vinfos[3].foffset = j3;
01669 vinfos[3].indices[0] = _ij3[0];
01670 vinfos[3].indices[1] = _ij3[1];
01671 vinfos[3].maxsolutions = _nj3;
01672 vinfos[4].jointtype = 1;
01673 vinfos[4].foffset = j4;
01674 vinfos[4].indices[0] = _ij4[0];
01675 vinfos[4].indices[1] = _ij4[1];
01676 vinfos[4].maxsolutions = _nj4;
01677 vinfos[5].jointtype = 1;
01678 vinfos[5].foffset = j5;
01679 vinfos[5].indices[0] = _ij5[0];
01680 vinfos[5].indices[1] = _ij5[1];
01681 vinfos[5].maxsolutions = _nj5;
01682 std::vector<int> vfree(0);
01683 solutions.AddSolution(vinfos,vfree);
01684 }
01685 }
01686 }
01687 
01688 }
01689 
01690 }
01691 
01692 } else
01693 {
01694 {
01695 IkReal j1array[1], cj1array[1], sj1array[1];
01696 bool j1valid[1]={false};
01697 _nj1 = 1;
01698 IkReal x357=((IkReal(1.00000000000000))*(cj2));
01699 IkReal x358=((cj4)*(r22));
01700 IkReal x359=((r21)*(sj5));
01701 IkReal x360=((r22)*(sj4));
01702 IkReal x361=((cj5)*(r20)*(sj4));
01703 IkReal x362=((cj4)*(cj5)*(r20));
01704 IkReal x363=((IkReal(1.00000000000000))*(sj2)*(x359));
01705 if( IKabs(((gconst82)*(((((cj2)*(x360)))+(((IkReal(-1.00000000000000))*(sj2)*(x358)))+(((IkReal(-1.00000000000000))*(cj4)*(x357)*(x359)))+(((sj2)*(x361)))+(((cj2)*(x362)))+(((IkReal(-1.00000000000000))*(sj4)*(x363))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst82)*(((((IkReal(-1.00000000000000))*(cj4)*(x363)))+(((cj2)*(sj4)*(x359)))+(((sj2)*(x360)))+(((sj2)*(x362)))+(((IkReal(-1.00000000000000))*(x357)*(x361)))+(((cj2)*(x358))))))) < IKFAST_ATAN2_MAGTHRESH )
01706     continue;
01707 j1array[0]=IKatan2(((gconst82)*(((((cj2)*(x360)))+(((IkReal(-1.00000000000000))*(sj2)*(x358)))+(((IkReal(-1.00000000000000))*(cj4)*(x357)*(x359)))+(((sj2)*(x361)))+(((cj2)*(x362)))+(((IkReal(-1.00000000000000))*(sj4)*(x363)))))), ((gconst82)*(((((IkReal(-1.00000000000000))*(cj4)*(x363)))+(((cj2)*(sj4)*(x359)))+(((sj2)*(x360)))+(((sj2)*(x362)))+(((IkReal(-1.00000000000000))*(x357)*(x361)))+(((cj2)*(x358)))))));
01708 sj1array[0]=IKsin(j1array[0]);
01709 cj1array[0]=IKcos(j1array[0]);
01710 if( j1array[0] > IKPI )
01711 {
01712     j1array[0]-=IK2PI;
01713 }
01714 else if( j1array[0] < -IKPI )
01715 {    j1array[0]+=IK2PI;
01716 }
01717 j1valid[0] = true;
01718 for(int ij1 = 0; ij1 < 1; ++ij1)
01719 {
01720 if( !j1valid[ij1] )
01721 {
01722     continue;
01723 }
01724 _ij1[0] = ij1; _ij1[1] = -1;
01725 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01726 {
01727 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01728 {
01729     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01730 }
01731 }
01732 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01733 {
01734 IkReal evalcond[4];
01735 IkReal x364=IKcos(j1);
01736 IkReal x365=IKsin(j1);
01737 IkReal x366=((IkReal(1.00000000000000))*(sj4));
01738 IkReal x367=((cj5)*(r00));
01739 IkReal x368=((cj5)*(r20));
01740 IkReal x369=((r12)*(sj0));
01741 IkReal x370=((r21)*(sj5));
01742 IkReal x371=((IkReal(1.00000000000000))*(cj4));
01743 IkReal x372=((sj2)*(x365));
01744 IkReal x373=((IkReal(1.00000000000000))*(x364));
01745 IkReal x374=((r11)*(sj0)*(sj5));
01746 IkReal x375=((cj0)*(x371));
01747 IkReal x376=((cj0)*(r01)*(sj5));
01748 IkReal x377=((cj2)*(x365));
01749 IkReal x378=((cj5)*(r10)*(sj0));
01750 IkReal x379=((cj2)*(x373));
01751 evalcond[0]=((((sj4)*(x370)))+(x372)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x379)))+(((IkReal(-1.00000000000000))*(x366)*(x368))));
01752 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)*(x373)))+(((cj4)*(x368)))+(((IkReal(-1.00000000000000))*(x370)*(x371)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x377))));
01753 evalcond[2]=((((sj2)*(x364)))+(((cj0)*(sj4)*(x367)))+(x377)+(((IkReal(-1.00000000000000))*(x366)*(x374)))+(((sj4)*(x378)))+(((IkReal(-1.00000000000000))*(x366)*(x376)))+(((IkReal(-1.00000000000000))*(x369)*(x371)))+(((IkReal(-1.00000000000000))*(r02)*(x375))));
01754 evalcond[3]=((((IkReal(-1.00000000000000))*(x371)*(x378)))+(x372)+(((cj4)*(x376)))+(((cj4)*(x374)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x366)))+(((IkReal(-1.00000000000000))*(x379)))+(((IkReal(-1.00000000000000))*(x367)*(x375)))+(((IkReal(-1.00000000000000))*(x366)*(x369))));
01755 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01756 {
01757 continue;
01758 }
01759 }
01760 
01761 {
01762 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01763 vinfos[0].jointtype = 1;
01764 vinfos[0].foffset = j0;
01765 vinfos[0].indices[0] = _ij0[0];
01766 vinfos[0].indices[1] = _ij0[1];
01767 vinfos[0].maxsolutions = _nj0;
01768 vinfos[1].jointtype = 1;
01769 vinfos[1].foffset = j1;
01770 vinfos[1].indices[0] = _ij1[0];
01771 vinfos[1].indices[1] = _ij1[1];
01772 vinfos[1].maxsolutions = _nj1;
01773 vinfos[2].jointtype = 1;
01774 vinfos[2].foffset = j2;
01775 vinfos[2].indices[0] = _ij2[0];
01776 vinfos[2].indices[1] = _ij2[1];
01777 vinfos[2].maxsolutions = _nj2;
01778 vinfos[3].jointtype = 1;
01779 vinfos[3].foffset = j3;
01780 vinfos[3].indices[0] = _ij3[0];
01781 vinfos[3].indices[1] = _ij3[1];
01782 vinfos[3].maxsolutions = _nj3;
01783 vinfos[4].jointtype = 1;
01784 vinfos[4].foffset = j4;
01785 vinfos[4].indices[0] = _ij4[0];
01786 vinfos[4].indices[1] = _ij4[1];
01787 vinfos[4].maxsolutions = _nj4;
01788 vinfos[5].jointtype = 1;
01789 vinfos[5].foffset = j5;
01790 vinfos[5].indices[0] = _ij5[0];
01791 vinfos[5].indices[1] = _ij5[1];
01792 vinfos[5].maxsolutions = _nj5;
01793 std::vector<int> vfree(0);
01794 solutions.AddSolution(vinfos,vfree);
01795 }
01796 }
01797 }
01798 
01799 }
01800 
01801 }
01802 
01803 } else
01804 {
01805 if( 1 )
01806 {
01807 continue;
01808 
01809 } else
01810 {
01811 }
01812 }
01813 }
01814 }
01815 }
01816 }
01817 
01818 } else
01819 {
01820 {
01821 IkReal j1array[1], cj1array[1], sj1array[1];
01822 bool j1valid[1]={false};
01823 _nj1 = 1;
01824 IkReal x380=((IkReal(1.00000000000000))*(sj4));
01825 IkReal x381=((r22)*(sj2));
01826 IkReal x382=((cj2)*(cj4));
01827 IkReal x383=((cj3)*(cj5)*(r20));
01828 IkReal x384=((cj2)*(r21)*(sj5));
01829 IkReal x385=((r21)*(sj2)*(sj5));
01830 IkReal x386=((IkReal(1.00000000000000))*(cj5)*(r20));
01831 if( IKabs(((gconst75)*(((((IkReal(-1.00000000000000))*(x382)*(x386)))+(((r21)*(sj5)*(x382)))+(((IkReal(-1.00000000000000))*(cj3)*(x380)*(x385)))+(((sj2)*(sj4)*(x383)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x381)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(x380))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst75)*(((((cj3)*(r22)*(x382)))+(((cj4)*(x385)))+(((IkReal(-1.00000000000000))*(x380)*(x381)))+(((IkReal(-1.00000000000000))*(cj2)*(x380)*(x383)))+(((cj3)*(sj4)*(x384)))+(((IkReal(-1.00000000000000))*(cj4)*(sj2)*(x386))))))) < IKFAST_ATAN2_MAGTHRESH )
01832     continue;
01833 j1array[0]=IKatan2(((gconst75)*(((((IkReal(-1.00000000000000))*(x382)*(x386)))+(((r21)*(sj5)*(x382)))+(((IkReal(-1.00000000000000))*(cj3)*(x380)*(x385)))+(((sj2)*(sj4)*(x383)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x381)))+(((IkReal(-1.00000000000000))*(cj2)*(r22)*(x380)))))), ((gconst75)*(((((cj3)*(r22)*(x382)))+(((cj4)*(x385)))+(((IkReal(-1.00000000000000))*(x380)*(x381)))+(((IkReal(-1.00000000000000))*(cj2)*(x380)*(x383)))+(((cj3)*(sj4)*(x384)))+(((IkReal(-1.00000000000000))*(cj4)*(sj2)*(x386)))))));
01834 sj1array[0]=IKsin(j1array[0]);
01835 cj1array[0]=IKcos(j1array[0]);
01836 if( j1array[0] > IKPI )
01837 {
01838     j1array[0]-=IK2PI;
01839 }
01840 else if( j1array[0] < -IKPI )
01841 {    j1array[0]+=IK2PI;
01842 }
01843 j1valid[0] = true;
01844 for(int ij1 = 0; ij1 < 1; ++ij1)
01845 {
01846 if( !j1valid[ij1] )
01847 {
01848     continue;
01849 }
01850 _ij1[0] = ij1; _ij1[1] = -1;
01851 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01852 {
01853 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01854 {
01855     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01856 }
01857 }
01858 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01859 {
01860 IkReal evalcond[6];
01861 IkReal x387=IKsin(j1);
01862 IkReal x388=IKcos(j1);
01863 IkReal x389=((IkReal(1.00000000000000))*(sj2));
01864 IkReal x390=((cj5)*(r00));
01865 IkReal x391=((cj0)*(sj4));
01866 IkReal x392=((cj5)*(sj4));
01867 IkReal x393=((IkReal(1.00000000000000))*(sj5));
01868 IkReal x394=((r10)*(sj0));
01869 IkReal x395=((IkReal(1.00000000000000))*(sj0));
01870 IkReal x396=((cj0)*(r01));
01871 IkReal x397=((cj4)*(sj5));
01872 IkReal x398=((IkReal(1.00000000000000))*(cj5));
01873 IkReal x399=((cj2)*(x388));
01874 IkReal x400=((sj0)*(x393));
01875 IkReal x401=((cj3)*(x387));
01876 IkReal x402=((IkReal(1.00000000000000))*(cj0)*(cj4));
01877 IkReal x403=((sj3)*(x387));
01878 IkReal x404=((sj2)*(x388));
01879 evalcond[0]=((((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x403)))+(((IkReal(-1.00000000000000))*(sj3)*(x388)*(x389)))+(((cj5)*(r21))));
01880 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x392)))+(((cj4)*(r22)))+(((sj2)*(x387)))+(((IkReal(-1.00000000000000))*(x399)))+(((r21)*(sj4)*(sj5))));
01881 evalcond[2]=((((cj2)*(x401)))+(((cj3)*(x404)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x393)))+(((cj4)*(cj5)*(r20)))+(((r22)*(sj4))));
01882 evalcond[3]=((((sj2)*(x403)))+(((IkReal(-1.00000000000000))*(x393)*(x394)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x395)))+(((IkReal(-1.00000000000000))*(sj3)*(x399)))+(((IkReal(-1.00000000000000))*(x396)*(x398)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x393))));
01883 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r12)*(x395)))+(((cj2)*(x387)))+(((IkReal(-1.00000000000000))*(r02)*(x402)))+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(x400)))+(((x390)*(x391)))+(((x392)*(x394)))+(x404)+(((IkReal(-1.00000000000000))*(r01)*(x391)*(x393))));
01884 evalcond[5]=((((IkReal(-1.00000000000000))*(x390)*(x402)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x395)))+(((IkReal(-1.00000000000000))*(r02)*(x391)))+(((cj3)*(x399)))+(((IkReal(-1.00000000000000))*(x389)*(x401)))+(((r11)*(sj0)*(x397)))+(((x396)*(x397)))+(((IkReal(-1.00000000000000))*(cj4)*(x394)*(x398))));
01885 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  )
01886 {
01887 continue;
01888 }
01889 }
01890 
01891 {
01892 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01893 vinfos[0].jointtype = 1;
01894 vinfos[0].foffset = j0;
01895 vinfos[0].indices[0] = _ij0[0];
01896 vinfos[0].indices[1] = _ij0[1];
01897 vinfos[0].maxsolutions = _nj0;
01898 vinfos[1].jointtype = 1;
01899 vinfos[1].foffset = j1;
01900 vinfos[1].indices[0] = _ij1[0];
01901 vinfos[1].indices[1] = _ij1[1];
01902 vinfos[1].maxsolutions = _nj1;
01903 vinfos[2].jointtype = 1;
01904 vinfos[2].foffset = j2;
01905 vinfos[2].indices[0] = _ij2[0];
01906 vinfos[2].indices[1] = _ij2[1];
01907 vinfos[2].maxsolutions = _nj2;
01908 vinfos[3].jointtype = 1;
01909 vinfos[3].foffset = j3;
01910 vinfos[3].indices[0] = _ij3[0];
01911 vinfos[3].indices[1] = _ij3[1];
01912 vinfos[3].maxsolutions = _nj3;
01913 vinfos[4].jointtype = 1;
01914 vinfos[4].foffset = j4;
01915 vinfos[4].indices[0] = _ij4[0];
01916 vinfos[4].indices[1] = _ij4[1];
01917 vinfos[4].maxsolutions = _nj4;
01918 vinfos[5].jointtype = 1;
01919 vinfos[5].foffset = j5;
01920 vinfos[5].indices[0] = _ij5[0];
01921 vinfos[5].indices[1] = _ij5[1];
01922 vinfos[5].maxsolutions = _nj5;
01923 std::vector<int> vfree(0);
01924 solutions.AddSolution(vinfos,vfree);
01925 }
01926 }
01927 }
01928 
01929 }
01930 
01931 }
01932 
01933 } else
01934 {
01935 {
01936 IkReal j1array[1], cj1array[1], sj1array[1];
01937 bool j1valid[1]={false};
01938 _nj1 = 1;
01939 IkReal x405=((cj2)*(r20));
01940 IkReal x406=((sj3)*(sj4));
01941 IkReal x407=((cj2)*(r21));
01942 IkReal x408=((sj2)*(sj5));
01943 IkReal x409=((cj5)*(sj2));
01944 IkReal x410=((cj4)*(r22)*(sj3));
01945 if( IKabs(((gconst74)*(((((cj5)*(x407)))+(((r20)*(x406)*(x409)))+(((IkReal(-1.00000000000000))*(r21)*(x406)*(x408)))+(((IkReal(-1.00000000000000))*(sj2)*(x410)))+(((sj5)*(x405))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst74)*(((((sj5)*(x406)*(x407)))+(((r20)*(x408)))+(((r21)*(x409)))+(((cj2)*(x410)))+(((IkReal(-1.00000000000000))*(cj5)*(x405)*(x406))))))) < IKFAST_ATAN2_MAGTHRESH )
01946     continue;
01947 j1array[0]=IKatan2(((gconst74)*(((((cj5)*(x407)))+(((r20)*(x406)*(x409)))+(((IkReal(-1.00000000000000))*(r21)*(x406)*(x408)))+(((IkReal(-1.00000000000000))*(sj2)*(x410)))+(((sj5)*(x405)))))), ((gconst74)*(((((sj5)*(x406)*(x407)))+(((r20)*(x408)))+(((r21)*(x409)))+(((cj2)*(x410)))+(((IkReal(-1.00000000000000))*(cj5)*(x405)*(x406)))))));
01948 sj1array[0]=IKsin(j1array[0]);
01949 cj1array[0]=IKcos(j1array[0]);
01950 if( j1array[0] > IKPI )
01951 {
01952     j1array[0]-=IK2PI;
01953 }
01954 else if( j1array[0] < -IKPI )
01955 {    j1array[0]+=IK2PI;
01956 }
01957 j1valid[0] = true;
01958 for(int ij1 = 0; ij1 < 1; ++ij1)
01959 {
01960 if( !j1valid[ij1] )
01961 {
01962     continue;
01963 }
01964 _ij1[0] = ij1; _ij1[1] = -1;
01965 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
01966 {
01967 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
01968 {
01969     j1valid[iij1]=false; _ij1[1] = iij1; break; 
01970 }
01971 }
01972 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
01973 {
01974 IkReal evalcond[6];
01975 IkReal x411=IKsin(j1);
01976 IkReal x412=IKcos(j1);
01977 IkReal x413=((IkReal(1.00000000000000))*(sj2));
01978 IkReal x414=((cj5)*(r00));
01979 IkReal x415=((cj0)*(sj4));
01980 IkReal x416=((cj5)*(sj4));
01981 IkReal x417=((IkReal(1.00000000000000))*(sj5));
01982 IkReal x418=((r10)*(sj0));
01983 IkReal x419=((IkReal(1.00000000000000))*(sj0));
01984 IkReal x420=((cj0)*(r01));
01985 IkReal x421=((cj4)*(sj5));
01986 IkReal x422=((IkReal(1.00000000000000))*(cj5));
01987 IkReal x423=((cj2)*(x412));
01988 IkReal x424=((sj0)*(x417));
01989 IkReal x425=((cj3)*(x411));
01990 IkReal x426=((IkReal(1.00000000000000))*(cj0)*(cj4));
01991 IkReal x427=((sj3)*(x411));
01992 IkReal x428=((sj2)*(x412));
01993 evalcond[0]=((((IkReal(-1.00000000000000))*(sj3)*(x412)*(x413)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(cj2)*(x427)))+(((cj5)*(r21))));
01994 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x423)))+(((IkReal(-1.00000000000000))*(r20)*(x416)))+(((sj2)*(x411)))+(((r21)*(sj4)*(sj5))));
01995 evalcond[2]=((((cj3)*(x428)))+(((cj4)*(cj5)*(r20)))+(((r22)*(sj4)))+(((cj2)*(x425)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x417))));
01996 evalcond[3]=((((IkReal(-1.00000000000000))*(sj3)*(x423)))+(((IkReal(-1.00000000000000))*(x420)*(x422)))+(((sj2)*(x427)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x419)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x417)))+(((IkReal(-1.00000000000000))*(x417)*(x418))));
01997 evalcond[4]=((((x414)*(x415)))+(((IkReal(-1.00000000000000))*(r01)*(x415)*(x417)))+(x428)+(((x416)*(x418)))+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(x424)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x419)))+(((IkReal(-1.00000000000000))*(r02)*(x426)))+(((cj2)*(x411))));
01998 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(x418)*(x422)))+(((cj3)*(x423)))+(((IkReal(-1.00000000000000))*(x414)*(x426)))+(((x420)*(x421)))+(((r11)*(sj0)*(x421)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x419)))+(((IkReal(-1.00000000000000))*(r02)*(x415)))+(((IkReal(-1.00000000000000))*(x413)*(x425))));
01999 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  )
02000 {
02001 continue;
02002 }
02003 }
02004 
02005 {
02006 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02007 vinfos[0].jointtype = 1;
02008 vinfos[0].foffset = j0;
02009 vinfos[0].indices[0] = _ij0[0];
02010 vinfos[0].indices[1] = _ij0[1];
02011 vinfos[0].maxsolutions = _nj0;
02012 vinfos[1].jointtype = 1;
02013 vinfos[1].foffset = j1;
02014 vinfos[1].indices[0] = _ij1[0];
02015 vinfos[1].indices[1] = _ij1[1];
02016 vinfos[1].maxsolutions = _nj1;
02017 vinfos[2].jointtype = 1;
02018 vinfos[2].foffset = j2;
02019 vinfos[2].indices[0] = _ij2[0];
02020 vinfos[2].indices[1] = _ij2[1];
02021 vinfos[2].maxsolutions = _nj2;
02022 vinfos[3].jointtype = 1;
02023 vinfos[3].foffset = j3;
02024 vinfos[3].indices[0] = _ij3[0];
02025 vinfos[3].indices[1] = _ij3[1];
02026 vinfos[3].maxsolutions = _nj3;
02027 vinfos[4].jointtype = 1;
02028 vinfos[4].foffset = j4;
02029 vinfos[4].indices[0] = _ij4[0];
02030 vinfos[4].indices[1] = _ij4[1];
02031 vinfos[4].maxsolutions = _nj4;
02032 vinfos[5].jointtype = 1;
02033 vinfos[5].foffset = j5;
02034 vinfos[5].indices[0] = _ij5[0];
02035 vinfos[5].indices[1] = _ij5[1];
02036 vinfos[5].maxsolutions = _nj5;
02037 std::vector<int> vfree(0);
02038 solutions.AddSolution(vinfos,vfree);
02039 }
02040 }
02041 }
02042 
02043 }
02044 
02045 }
02046 }
02047 }
02048 }
02049 }
02050 
02051 } else
02052 {
02053 {
02054 IkReal j3array[1], cj3array[1], sj3array[1];
02055 bool j3valid[1]={false};
02056 _nj3 = 1;
02057 IkReal x429=((IkReal(20.0000000000000))*(sj5));
02058 IkReal x430=((IkReal(20.0000000000000))*(cj5));
02059 if( IKabs(((gconst53)*(((IkReal(1.90000000000000))+(((npy)*(x430)))+(((npx)*(x429))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((cj4)*(npy)*(x429)))+(((IkReal(-1.00000000000000))*(cj4)*(npx)*(x430)))+(((IkReal(-20.0000000000000))*(npz)*(sj4))))))) < IKFAST_ATAN2_MAGTHRESH )
02060     continue;
02061 j3array[0]=IKatan2(((gconst53)*(((IkReal(1.90000000000000))+(((npy)*(x430)))+(((npx)*(x429)))))), ((gconst53)*(((((cj4)*(npy)*(x429)))+(((IkReal(-1.00000000000000))*(cj4)*(npx)*(x430)))+(((IkReal(-20.0000000000000))*(npz)*(sj4)))))));
02062 sj3array[0]=IKsin(j3array[0]);
02063 cj3array[0]=IKcos(j3array[0]);
02064 if( j3array[0] > IKPI )
02065 {
02066     j3array[0]-=IK2PI;
02067 }
02068 else if( j3array[0] < -IKPI )
02069 {    j3array[0]+=IK2PI;
02070 }
02071 j3valid[0] = true;
02072 for(int ij3 = 0; ij3 < 1; ++ij3)
02073 {
02074 if( !j3valid[ij3] )
02075 {
02076     continue;
02077 }
02078 _ij3[0] = ij3; _ij3[1] = -1;
02079 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02080 {
02081 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02082 {
02083     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02084 }
02085 }
02086 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02087 {
02088 IkReal evalcond[2];
02089 IkReal x431=((IkReal(0.350000000000000))*(sj2));
02090 evalcond[0]=((IkReal(0.0950000000000000))+(((IkReal(-1.00000000000000))*(x431)*(IKsin(j3))))+(((cj5)*(npy)))+(((npx)*(sj5))));
02091 evalcond[1]=((((IkReal(-1.00000000000000))*(cj4)*(npy)*(sj5)))+(((cj4)*(cj5)*(npx)))+(((x431)*(IKcos(j3))))+(((npz)*(sj4))));
02092 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
02093 {
02094 continue;
02095 }
02096 }
02097 
02098 {
02099 IkReal dummyeval[1];
02100 IkReal gconst86;
02101 gconst86=IKsign(((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2))))));
02102 dummyeval[0]=((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2)))));
02103 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02104 {
02105 {
02106 IkReal dummyeval[1];
02107 IkReal gconst87;
02108 gconst87=IKsign(((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2))))));
02109 dummyeval[0]=((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2)))));
02110 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02111 {
02112 {
02113 IkReal dummyeval[1];
02114 IkReal gconst84;
02115 IkReal x432=(cj5)*(cj5);
02116 IkReal x433=(sj5)*(sj5);
02117 IkReal x434=((IkReal(1.00000000000000))*(r10));
02118 IkReal x435=((cj4)*(sj5));
02119 IkReal x436=((r00)*(r11));
02120 IkReal x437=((cj4)*(cj5));
02121 IkReal x438=((sj4)*(x432));
02122 IkReal x439=((sj4)*(x433));
02123 gconst84=IKsign(((((x436)*(x439)))+(((x436)*(x438)))+(((r00)*(r12)*(x435)))+(((r01)*(r12)*(x437)))+(((IkReal(-1.00000000000000))*(r02)*(x434)*(x435)))+(((IkReal(-1.00000000000000))*(r01)*(x434)*(x439)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x437)))+(((IkReal(-1.00000000000000))*(r01)*(x434)*(x438)))));
02124 IkReal x440=(cj5)*(cj5);
02125 IkReal x441=(sj5)*(sj5);
02126 IkReal x442=((IkReal(1.00000000000000))*(r10));
02127 IkReal x443=((cj4)*(sj5));
02128 IkReal x444=((r00)*(r11));
02129 IkReal x445=((cj4)*(cj5));
02130 IkReal x446=((sj4)*(x440));
02131 IkReal x447=((sj4)*(x441));
02132 dummyeval[0]=((((r00)*(r12)*(x443)))+(((IkReal(-1.00000000000000))*(r01)*(x442)*(x447)))+(((IkReal(-1.00000000000000))*(r01)*(x442)*(x446)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x445)))+(((x444)*(x447)))+(((x444)*(x446)))+(((IkReal(-1.00000000000000))*(r02)*(x442)*(x443)))+(((r01)*(r12)*(x445))));
02133 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02134 {
02135 {
02136 IkReal evalcond[5];
02137 IkReal x448=((cj5)*(npx));
02138 IkReal x449=((IkReal(1.00000000000000))*(cj4)*(sj5));
02139 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))));
02140 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(-0.350000000000000))*(sj2)))+(((npx)*(sj5))));
02141 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((npy)*(sj4)*(sj5)))+(((IkReal(-1.00000000000000))*(sj4)*(x448))));
02142 evalcond[3]=((((cj4)*(x448)))+(((IkReal(-1.00000000000000))*(npy)*(x449)))+(((npz)*(sj4))));
02143 evalcond[4]=((((cj4)*(cj5)*(r20)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(x449))));
02144 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  )
02145 {
02146 {
02147 IkReal dummyeval[1];
02148 IkReal gconst102;
02149 gconst102=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
02150 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
02151 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02152 {
02153 {
02154 IkReal dummyeval[1];
02155 IkReal gconst100;
02156 IkReal x450=(cj5)*(cj5);
02157 IkReal x451=(sj5)*(sj5);
02158 IkReal x452=((sj4)*(sj5));
02159 IkReal x453=((IkReal(1.00000000000000))*(r12));
02160 IkReal x454=((cj5)*(sj4));
02161 IkReal x455=((cj4)*(r00)*(r11));
02162 IkReal x456=((IkReal(1.00000000000000))*(cj4)*(r01)*(r10));
02163 gconst100=IKsign(((((IkReal(-1.00000000000000))*(r00)*(x452)*(x453)))+(((IkReal(-1.00000000000000))*(x450)*(x456)))+(((x450)*(x455)))+(((x451)*(x455)))+(((IkReal(-1.00000000000000))*(x451)*(x456)))+(((r02)*(r11)*(x454)))+(((r02)*(r10)*(x452)))+(((IkReal(-1.00000000000000))*(r01)*(x453)*(x454)))));
02164 IkReal x457=(cj5)*(cj5);
02165 IkReal x458=(sj5)*(sj5);
02166 IkReal x459=((sj4)*(sj5));
02167 IkReal x460=((IkReal(1.00000000000000))*(r12));
02168 IkReal x461=((cj5)*(sj4));
02169 IkReal x462=((cj4)*(r00)*(r11));
02170 IkReal x463=x456;
02171 dummyeval[0]=((((IkReal(-1.00000000000000))*(x458)*(x463)))+(((x457)*(x462)))+(((r02)*(r10)*(x459)))+(((IkReal(-1.00000000000000))*(r01)*(x460)*(x461)))+(((IkReal(-1.00000000000000))*(x457)*(x463)))+(((IkReal(-1.00000000000000))*(r00)*(x459)*(x460)))+(((x458)*(x462)))+(((r02)*(r11)*(x461))));
02172 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02173 {
02174 {
02175 IkReal dummyeval[1];
02176 IkReal gconst101;
02177 IkReal x464=(cj4)*(cj4);
02178 IkReal x465=(sj4)*(sj4);
02179 IkReal x466=((r00)*(r12));
02180 IkReal x467=((r02)*(r11));
02181 IkReal x468=((cj5)*(x464));
02182 IkReal x469=((sj5)*(x465));
02183 IkReal x470=((IkReal(1.00000000000000))*(r02)*(r10));
02184 IkReal x471=((IkReal(1.00000000000000))*(r01)*(r12));
02185 IkReal x472=((cj5)*(x465));
02186 IkReal x473=((sj5)*(x464));
02187 gconst101=IKsign(((((IkReal(-1.00000000000000))*(x468)*(x470)))+(((x467)*(x473)))+(((IkReal(-1.00000000000000))*(x471)*(x473)))+(((x466)*(x468)))+(((x466)*(x472)))+(((IkReal(-1.00000000000000))*(x470)*(x472)))+(((x467)*(x469)))+(((IkReal(-1.00000000000000))*(x469)*(x471)))));
02188 IkReal x474=(cj4)*(cj4);
02189 IkReal x475=(sj4)*(sj4);
02190 IkReal x476=((r00)*(r12));
02191 IkReal x477=((r02)*(r11));
02192 IkReal x478=((cj5)*(x474));
02193 IkReal x479=((sj5)*(x475));
02194 IkReal x480=((IkReal(1.00000000000000))*(r02)*(r10));
02195 IkReal x481=((IkReal(1.00000000000000))*(r01)*(r12));
02196 IkReal x482=((cj5)*(x475));
02197 IkReal x483=((sj5)*(x474));
02198 dummyeval[0]=((((x476)*(x482)))+(((IkReal(-1.00000000000000))*(x478)*(x480)))+(((x476)*(x478)))+(((IkReal(-1.00000000000000))*(x481)*(x483)))+(((x477)*(x483)))+(((x477)*(x479)))+(((IkReal(-1.00000000000000))*(x480)*(x482)))+(((IkReal(-1.00000000000000))*(x479)*(x481))));
02199 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02200 {
02201 continue;
02202 
02203 } else
02204 {
02205 {
02206 IkReal j0array[1], cj0array[1], sj0array[1];
02207 bool j0valid[1]={false};
02208 _nj0 = 1;
02209 IkReal x484=((cj5)*(sj4));
02210 IkReal x485=((IkReal(1.00000000000000))*(cj4));
02211 IkReal x486=((IkReal(1.00000000000000))*(sj4)*(sj5));
02212 if( IKabs(((gconst101)*(((((r10)*(x484)))+(((IkReal(-1.00000000000000))*(r11)*(x486)))+(((IkReal(-1.00000000000000))*(r12)*(x485))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst101)*(((((IkReal(-1.00000000000000))*(r01)*(x486)))+(((r00)*(x484)))+(((IkReal(-1.00000000000000))*(r02)*(x485))))))) < IKFAST_ATAN2_MAGTHRESH )
02213     continue;
02214 j0array[0]=IKatan2(((gconst101)*(((((r10)*(x484)))+(((IkReal(-1.00000000000000))*(r11)*(x486)))+(((IkReal(-1.00000000000000))*(r12)*(x485)))))), ((gconst101)*(((((IkReal(-1.00000000000000))*(r01)*(x486)))+(((r00)*(x484)))+(((IkReal(-1.00000000000000))*(r02)*(x485)))))));
02215 sj0array[0]=IKsin(j0array[0]);
02216 cj0array[0]=IKcos(j0array[0]);
02217 if( j0array[0] > IKPI )
02218 {
02219     j0array[0]-=IK2PI;
02220 }
02221 else if( j0array[0] < -IKPI )
02222 {    j0array[0]+=IK2PI;
02223 }
02224 j0valid[0] = true;
02225 for(int ij0 = 0; ij0 < 1; ++ij0)
02226 {
02227 if( !j0valid[ij0] )
02228 {
02229     continue;
02230 }
02231 _ij0[0] = ij0; _ij0[1] = -1;
02232 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02233 {
02234 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02235 {
02236     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02237 }
02238 }
02239 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02240 {
02241 IkReal evalcond[4];
02242 IkReal x487=IKsin(j0);
02243 IkReal x488=IKcos(j0);
02244 IkReal x489=((IkReal(1.00000000000000))*(sj5));
02245 IkReal x490=((cj5)*(r10));
02246 IkReal x491=((IkReal(1.00000000000000))*(r12));
02247 IkReal x492=((cj4)*(cj5));
02248 IkReal x493=((r11)*(sj5));
02249 IkReal x494=((IkReal(1.00000000000000))*(cj5));
02250 IkReal x495=((r00)*(x487));
02251 IkReal x496=((sj4)*(x488));
02252 IkReal x497=((r01)*(x487));
02253 IkReal x498=((sj4)*(x487));
02254 IkReal x499=((cj4)*(x487));
02255 IkReal x500=((cj4)*(x488));
02256 evalcond[0]=((((cj5)*(x497)))+(((IkReal(-1.00000000000000))*(r10)*(x488)*(x489)))+(((sj5)*(x495)))+(((IkReal(-1.00000000000000))*(r11)*(x488)*(x494))));
02257 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x489)*(x496)))+(((x490)*(x496)))+(((r02)*(x499)))+(((IkReal(-1.00000000000000))*(x491)*(x500)))+(((IkReal(-1.00000000000000))*(sj4)*(x494)*(x495)))+(((sj4)*(sj5)*(x497))));
02258 evalcond[2]=((IkReal(1.00000000000000))+(((x493)*(x500)))+(((IkReal(-1.00000000000000))*(x491)*(x496)))+(((r02)*(x498)))+(((IkReal(-1.00000000000000))*(cj4)*(x489)*(x497)))+(((IkReal(-1.00000000000000))*(x490)*(x500)))+(((x492)*(x495))));
02259 evalcond[3]=((((IkReal(-1.00000000000000))*(x491)*(x498)))+(((IkReal(-1.00000000000000))*(x490)*(x499)))+(((IkReal(-1.00000000000000))*(r02)*(x496)))+(((IkReal(-1.00000000000000))*(r00)*(x488)*(x492)))+(((r01)*(sj5)*(x500)))+(((x493)*(x499))));
02260 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02261 {
02262 continue;
02263 }
02264 }
02265 
02266 {
02267 IkReal dummyeval[1];
02268 IkReal gconst103;
02269 gconst103=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
02270 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
02271 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02272 {
02273 {
02274 IkReal dummyeval[1];
02275 IkReal gconst104;
02276 gconst104=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
02277 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
02278 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02279 {
02280 continue;
02281 
02282 } else
02283 {
02284 {
02285 IkReal j1array[1], cj1array[1], sj1array[1];
02286 bool j1valid[1]={false};
02287 _nj1 = 1;
02288 IkReal x501=((cj2)*(sj5));
02289 IkReal x502=((r10)*(sj0));
02290 IkReal x503=((cj2)*(cj5));
02291 IkReal x504=((cj0)*(r00));
02292 IkReal x505=((sj2)*(sj5));
02293 IkReal x506=((r11)*(sj0));
02294 IkReal x507=((cj5)*(sj2));
02295 IkReal x508=((cj0)*(r01));
02296 if( IKabs(((gconst104)*(((((r20)*(x501)))+(((x504)*(x505)))+(((x507)*(x508)))+(((x506)*(x507)))+(((x502)*(x505)))+(((r21)*(x503))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst104)*(((((r20)*(x505)))+(((IkReal(-1.00000000000000))*(x501)*(x504)))+(((IkReal(-1.00000000000000))*(x501)*(x502)))+(((r21)*(x507)))+(((IkReal(-1.00000000000000))*(x503)*(x506)))+(((IkReal(-1.00000000000000))*(x503)*(x508))))))) < IKFAST_ATAN2_MAGTHRESH )
02297     continue;
02298 j1array[0]=IKatan2(((gconst104)*(((((r20)*(x501)))+(((x504)*(x505)))+(((x507)*(x508)))+(((x506)*(x507)))+(((x502)*(x505)))+(((r21)*(x503)))))), ((gconst104)*(((((r20)*(x505)))+(((IkReal(-1.00000000000000))*(x501)*(x504)))+(((IkReal(-1.00000000000000))*(x501)*(x502)))+(((r21)*(x507)))+(((IkReal(-1.00000000000000))*(x503)*(x506)))+(((IkReal(-1.00000000000000))*(x503)*(x508)))))));
02299 sj1array[0]=IKsin(j1array[0]);
02300 cj1array[0]=IKcos(j1array[0]);
02301 if( j1array[0] > IKPI )
02302 {
02303     j1array[0]-=IK2PI;
02304 }
02305 else if( j1array[0] < -IKPI )
02306 {    j1array[0]+=IK2PI;
02307 }
02308 j1valid[0] = true;
02309 for(int ij1 = 0; ij1 < 1; ++ij1)
02310 {
02311 if( !j1valid[ij1] )
02312 {
02313     continue;
02314 }
02315 _ij1[0] = ij1; _ij1[1] = -1;
02316 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02317 {
02318 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02319 {
02320     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02321 }
02322 }
02323 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02324 {
02325 IkReal evalcond[4];
02326 IkReal x509=IKsin(j1);
02327 IkReal x510=IKcos(j1);
02328 IkReal x511=((cj0)*(sj4));
02329 IkReal x512=((IkReal(1.00000000000000))*(sj5));
02330 IkReal x513=((cj5)*(sj0));
02331 IkReal x514=((IkReal(1.00000000000000))*(cj4));
02332 IkReal x515=((IkReal(1.00000000000000))*(cj5));
02333 IkReal x516=((sj2)*(x509));
02334 IkReal x517=((IkReal(1.00000000000000))*(x510));
02335 IkReal x518=((cj2)*(x509));
02336 IkReal x519=((cj2)*(x517));
02337 evalcond[0]=((((IkReal(-1.00000000000000))*(sj2)*(x517)))+(((IkReal(-1.00000000000000))*(x518)))+(((r20)*(sj5)))+(((cj5)*(r21))));
02338 evalcond[1]=((x516)+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x515)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x519)))+(((r21)*(sj4)*(sj5))));
02339 evalcond[2]=((x516)+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x512)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x515)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x512)))+(((IkReal(-1.00000000000000))*(x519)))+(((IkReal(-1.00000000000000))*(r11)*(x513))));
02340 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x512)))+(((sj2)*(x510)))+(x518)+(((r10)*(sj4)*(x513)))+(((IkReal(-1.00000000000000))*(r01)*(x511)*(x512)))+(((cj5)*(r00)*(x511)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x514)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x514))));
02341 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02342 {
02343 continue;
02344 }
02345 }
02346 
02347 {
02348 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02349 vinfos[0].jointtype = 1;
02350 vinfos[0].foffset = j0;
02351 vinfos[0].indices[0] = _ij0[0];
02352 vinfos[0].indices[1] = _ij0[1];
02353 vinfos[0].maxsolutions = _nj0;
02354 vinfos[1].jointtype = 1;
02355 vinfos[1].foffset = j1;
02356 vinfos[1].indices[0] = _ij1[0];
02357 vinfos[1].indices[1] = _ij1[1];
02358 vinfos[1].maxsolutions = _nj1;
02359 vinfos[2].jointtype = 1;
02360 vinfos[2].foffset = j2;
02361 vinfos[2].indices[0] = _ij2[0];
02362 vinfos[2].indices[1] = _ij2[1];
02363 vinfos[2].maxsolutions = _nj2;
02364 vinfos[3].jointtype = 1;
02365 vinfos[3].foffset = j3;
02366 vinfos[3].indices[0] = _ij3[0];
02367 vinfos[3].indices[1] = _ij3[1];
02368 vinfos[3].maxsolutions = _nj3;
02369 vinfos[4].jointtype = 1;
02370 vinfos[4].foffset = j4;
02371 vinfos[4].indices[0] = _ij4[0];
02372 vinfos[4].indices[1] = _ij4[1];
02373 vinfos[4].maxsolutions = _nj4;
02374 vinfos[5].jointtype = 1;
02375 vinfos[5].foffset = j5;
02376 vinfos[5].indices[0] = _ij5[0];
02377 vinfos[5].indices[1] = _ij5[1];
02378 vinfos[5].maxsolutions = _nj5;
02379 std::vector<int> vfree(0);
02380 solutions.AddSolution(vinfos,vfree);
02381 }
02382 }
02383 }
02384 
02385 }
02386 
02387 }
02388 
02389 } else
02390 {
02391 {
02392 IkReal j1array[1], cj1array[1], sj1array[1];
02393 bool j1valid[1]={false};
02394 _nj1 = 1;
02395 IkReal x520=((r20)*(sj5));
02396 IkReal x521=((cj4)*(r22));
02397 IkReal x522=((sj2)*(sj4));
02398 IkReal x523=((cj5)*(r20));
02399 IkReal x524=((cj5)*(r21));
02400 IkReal x525=((r21)*(sj5));
02401 IkReal x526=((cj2)*(sj4));
02402 if( IKabs(((gconst103)*(((((x522)*(x523)))+(((IkReal(-1.00000000000000))*(sj2)*(x521)))+(((cj2)*(x520)))+(((IkReal(-1.00000000000000))*(x522)*(x525)))+(((cj2)*(x524))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst103)*(((((cj2)*(x521)))+(((sj2)*(x524)))+(((sj2)*(x520)))+(((IkReal(-1.00000000000000))*(x523)*(x526)))+(((x525)*(x526))))))) < IKFAST_ATAN2_MAGTHRESH )
02403     continue;
02404 j1array[0]=IKatan2(((gconst103)*(((((x522)*(x523)))+(((IkReal(-1.00000000000000))*(sj2)*(x521)))+(((cj2)*(x520)))+(((IkReal(-1.00000000000000))*(x522)*(x525)))+(((cj2)*(x524)))))), ((gconst103)*(((((cj2)*(x521)))+(((sj2)*(x524)))+(((sj2)*(x520)))+(((IkReal(-1.00000000000000))*(x523)*(x526)))+(((x525)*(x526)))))));
02405 sj1array[0]=IKsin(j1array[0]);
02406 cj1array[0]=IKcos(j1array[0]);
02407 if( j1array[0] > IKPI )
02408 {
02409     j1array[0]-=IK2PI;
02410 }
02411 else if( j1array[0] < -IKPI )
02412 {    j1array[0]+=IK2PI;
02413 }
02414 j1valid[0] = true;
02415 for(int ij1 = 0; ij1 < 1; ++ij1)
02416 {
02417 if( !j1valid[ij1] )
02418 {
02419     continue;
02420 }
02421 _ij1[0] = ij1; _ij1[1] = -1;
02422 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02423 {
02424 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02425 {
02426     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02427 }
02428 }
02429 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02430 {
02431 IkReal evalcond[4];
02432 IkReal x527=IKsin(j1);
02433 IkReal x528=IKcos(j1);
02434 IkReal x529=((cj0)*(sj4));
02435 IkReal x530=((IkReal(1.00000000000000))*(sj5));
02436 IkReal x531=((cj5)*(sj0));
02437 IkReal x532=((IkReal(1.00000000000000))*(cj4));
02438 IkReal x533=((IkReal(1.00000000000000))*(cj5));
02439 IkReal x534=((sj2)*(x527));
02440 IkReal x535=((IkReal(1.00000000000000))*(x528));
02441 IkReal x536=((cj2)*(x527));
02442 IkReal x537=((cj2)*(x535));
02443 evalcond[0]=((((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x536)))+(((IkReal(-1.00000000000000))*(sj2)*(x535)))+(((cj5)*(r21))));
02444 evalcond[1]=((((IkReal(-1.00000000000000))*(x537)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x533)))+(((r21)*(sj4)*(sj5)))+(x534));
02445 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(r01)*(x533)))+(((IkReal(-1.00000000000000))*(x537)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x530)))+(((IkReal(-1.00000000000000))*(r11)*(x531)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x530)))+(x534));
02446 evalcond[3]=((((sj2)*(x528)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x532)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x530)))+(((IkReal(-1.00000000000000))*(r01)*(x529)*(x530)))+(((cj5)*(r00)*(x529)))+(((r10)*(sj4)*(x531)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x532)))+(x536));
02447 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02448 {
02449 continue;
02450 }
02451 }
02452 
02453 {
02454 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02455 vinfos[0].jointtype = 1;
02456 vinfos[0].foffset = j0;
02457 vinfos[0].indices[0] = _ij0[0];
02458 vinfos[0].indices[1] = _ij0[1];
02459 vinfos[0].maxsolutions = _nj0;
02460 vinfos[1].jointtype = 1;
02461 vinfos[1].foffset = j1;
02462 vinfos[1].indices[0] = _ij1[0];
02463 vinfos[1].indices[1] = _ij1[1];
02464 vinfos[1].maxsolutions = _nj1;
02465 vinfos[2].jointtype = 1;
02466 vinfos[2].foffset = j2;
02467 vinfos[2].indices[0] = _ij2[0];
02468 vinfos[2].indices[1] = _ij2[1];
02469 vinfos[2].maxsolutions = _nj2;
02470 vinfos[3].jointtype = 1;
02471 vinfos[3].foffset = j3;
02472 vinfos[3].indices[0] = _ij3[0];
02473 vinfos[3].indices[1] = _ij3[1];
02474 vinfos[3].maxsolutions = _nj3;
02475 vinfos[4].jointtype = 1;
02476 vinfos[4].foffset = j4;
02477 vinfos[4].indices[0] = _ij4[0];
02478 vinfos[4].indices[1] = _ij4[1];
02479 vinfos[4].maxsolutions = _nj4;
02480 vinfos[5].jointtype = 1;
02481 vinfos[5].foffset = j5;
02482 vinfos[5].indices[0] = _ij5[0];
02483 vinfos[5].indices[1] = _ij5[1];
02484 vinfos[5].maxsolutions = _nj5;
02485 std::vector<int> vfree(0);
02486 solutions.AddSolution(vinfos,vfree);
02487 }
02488 }
02489 }
02490 
02491 }
02492 
02493 }
02494 }
02495 }
02496 
02497 }
02498 
02499 }
02500 
02501 } else
02502 {
02503 {
02504 IkReal j0array[1], cj0array[1], sj0array[1];
02505 bool j0valid[1]={false};
02506 _nj0 = 1;
02507 IkReal x538=((IkReal(1.00000000000000))*(sj5));
02508 IkReal x539=((IkReal(1.00000000000000))*(cj5));
02509 if( IKabs(((gconst100)*(((((IkReal(-1.00000000000000))*(r10)*(x538)))+(((IkReal(-1.00000000000000))*(r11)*(x539))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst100)*(((((IkReal(-1.00000000000000))*(r01)*(x539)))+(((IkReal(-1.00000000000000))*(r00)*(x538))))))) < IKFAST_ATAN2_MAGTHRESH )
02510     continue;
02511 j0array[0]=IKatan2(((gconst100)*(((((IkReal(-1.00000000000000))*(r10)*(x538)))+(((IkReal(-1.00000000000000))*(r11)*(x539)))))), ((gconst100)*(((((IkReal(-1.00000000000000))*(r01)*(x539)))+(((IkReal(-1.00000000000000))*(r00)*(x538)))))));
02512 sj0array[0]=IKsin(j0array[0]);
02513 cj0array[0]=IKcos(j0array[0]);
02514 if( j0array[0] > IKPI )
02515 {
02516     j0array[0]-=IK2PI;
02517 }
02518 else if( j0array[0] < -IKPI )
02519 {    j0array[0]+=IK2PI;
02520 }
02521 j0valid[0] = true;
02522 for(int ij0 = 0; ij0 < 1; ++ij0)
02523 {
02524 if( !j0valid[ij0] )
02525 {
02526     continue;
02527 }
02528 _ij0[0] = ij0; _ij0[1] = -1;
02529 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02530 {
02531 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02532 {
02533     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02534 }
02535 }
02536 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02537 {
02538 IkReal evalcond[4];
02539 IkReal x540=IKsin(j0);
02540 IkReal x541=IKcos(j0);
02541 IkReal x542=((IkReal(1.00000000000000))*(sj5));
02542 IkReal x543=((cj5)*(r10));
02543 IkReal x544=((IkReal(1.00000000000000))*(r12));
02544 IkReal x545=((cj4)*(cj5));
02545 IkReal x546=((r11)*(sj5));
02546 IkReal x547=((IkReal(1.00000000000000))*(cj5));
02547 IkReal x548=((r00)*(x540));
02548 IkReal x549=((sj4)*(x541));
02549 IkReal x550=((r01)*(x540));
02550 IkReal x551=((sj4)*(x540));
02551 IkReal x552=((cj4)*(x540));
02552 IkReal x553=((cj4)*(x541));
02553 evalcond[0]=((((cj5)*(x550)))+(((IkReal(-1.00000000000000))*(r11)*(x541)*(x547)))+(((sj5)*(x548)))+(((IkReal(-1.00000000000000))*(r10)*(x541)*(x542))));
02554 evalcond[1]=((((IkReal(-1.00000000000000))*(x544)*(x553)))+(((IkReal(-1.00000000000000))*(sj4)*(x547)*(x548)))+(((sj4)*(sj5)*(x550)))+(((r02)*(x552)))+(((IkReal(-1.00000000000000))*(r11)*(x542)*(x549)))+(((x543)*(x549))));
02555 evalcond[2]=((IkReal(1.00000000000000))+(((x545)*(x548)))+(((IkReal(-1.00000000000000))*(x543)*(x553)))+(((IkReal(-1.00000000000000))*(cj4)*(x542)*(x550)))+(((x546)*(x553)))+(((r02)*(x551)))+(((IkReal(-1.00000000000000))*(x544)*(x549))));
02556 evalcond[3]=((((x546)*(x552)))+(((r01)*(sj5)*(x553)))+(((IkReal(-1.00000000000000))*(r02)*(x549)))+(((IkReal(-1.00000000000000))*(x543)*(x552)))+(((IkReal(-1.00000000000000))*(r00)*(x541)*(x545)))+(((IkReal(-1.00000000000000))*(x544)*(x551))));
02557 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02558 {
02559 continue;
02560 }
02561 }
02562 
02563 {
02564 IkReal dummyeval[1];
02565 IkReal gconst103;
02566 gconst103=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
02567 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
02568 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02569 {
02570 {
02571 IkReal dummyeval[1];
02572 IkReal gconst104;
02573 gconst104=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
02574 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
02575 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02576 {
02577 continue;
02578 
02579 } else
02580 {
02581 {
02582 IkReal j1array[1], cj1array[1], sj1array[1];
02583 bool j1valid[1]={false};
02584 _nj1 = 1;
02585 IkReal x554=((cj2)*(sj5));
02586 IkReal x555=((r10)*(sj0));
02587 IkReal x556=((cj2)*(cj5));
02588 IkReal x557=((cj0)*(r00));
02589 IkReal x558=((sj2)*(sj5));
02590 IkReal x559=((r11)*(sj0));
02591 IkReal x560=((cj5)*(sj2));
02592 IkReal x561=((cj0)*(r01));
02593 if( IKabs(((gconst104)*(((((x560)*(x561)))+(((r21)*(x556)))+(((r20)*(x554)))+(((x555)*(x558)))+(((x559)*(x560)))+(((x557)*(x558))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst104)*(((((IkReal(-1.00000000000000))*(x554)*(x557)))+(((r20)*(x558)))+(((IkReal(-1.00000000000000))*(x554)*(x555)))+(((IkReal(-1.00000000000000))*(x556)*(x559)))+(((IkReal(-1.00000000000000))*(x556)*(x561)))+(((r21)*(x560))))))) < IKFAST_ATAN2_MAGTHRESH )
02594     continue;
02595 j1array[0]=IKatan2(((gconst104)*(((((x560)*(x561)))+(((r21)*(x556)))+(((r20)*(x554)))+(((x555)*(x558)))+(((x559)*(x560)))+(((x557)*(x558)))))), ((gconst104)*(((((IkReal(-1.00000000000000))*(x554)*(x557)))+(((r20)*(x558)))+(((IkReal(-1.00000000000000))*(x554)*(x555)))+(((IkReal(-1.00000000000000))*(x556)*(x559)))+(((IkReal(-1.00000000000000))*(x556)*(x561)))+(((r21)*(x560)))))));
02596 sj1array[0]=IKsin(j1array[0]);
02597 cj1array[0]=IKcos(j1array[0]);
02598 if( j1array[0] > IKPI )
02599 {
02600     j1array[0]-=IK2PI;
02601 }
02602 else if( j1array[0] < -IKPI )
02603 {    j1array[0]+=IK2PI;
02604 }
02605 j1valid[0] = true;
02606 for(int ij1 = 0; ij1 < 1; ++ij1)
02607 {
02608 if( !j1valid[ij1] )
02609 {
02610     continue;
02611 }
02612 _ij1[0] = ij1; _ij1[1] = -1;
02613 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02614 {
02615 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02616 {
02617     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02618 }
02619 }
02620 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02621 {
02622 IkReal evalcond[4];
02623 IkReal x562=IKsin(j1);
02624 IkReal x563=IKcos(j1);
02625 IkReal x564=((cj0)*(sj4));
02626 IkReal x565=((IkReal(1.00000000000000))*(sj5));
02627 IkReal x566=((cj5)*(sj0));
02628 IkReal x567=((IkReal(1.00000000000000))*(cj4));
02629 IkReal x568=((IkReal(1.00000000000000))*(cj5));
02630 IkReal x569=((sj2)*(x562));
02631 IkReal x570=((IkReal(1.00000000000000))*(x563));
02632 IkReal x571=((cj2)*(x562));
02633 IkReal x572=((cj2)*(x570));
02634 evalcond[0]=((((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(sj2)*(x570)))+(((IkReal(-1.00000000000000))*(x571)))+(((cj5)*(r21))));
02635 evalcond[1]=((x569)+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x568)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x572)))+(((r21)*(sj4)*(sj5))));
02636 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(r01)*(x568)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x565)))+(x569)+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x565)))+(((IkReal(-1.00000000000000))*(x572)))+(((IkReal(-1.00000000000000))*(r11)*(x566))));
02637 evalcond[3]=((x571)+(((r10)*(sj4)*(x566)))+(((cj5)*(r00)*(x564)))+(((IkReal(-1.00000000000000))*(r01)*(x564)*(x565)))+(((sj2)*(x563)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x565)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x567)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x567))));
02638 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02639 {
02640 continue;
02641 }
02642 }
02643 
02644 {
02645 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02646 vinfos[0].jointtype = 1;
02647 vinfos[0].foffset = j0;
02648 vinfos[0].indices[0] = _ij0[0];
02649 vinfos[0].indices[1] = _ij0[1];
02650 vinfos[0].maxsolutions = _nj0;
02651 vinfos[1].jointtype = 1;
02652 vinfos[1].foffset = j1;
02653 vinfos[1].indices[0] = _ij1[0];
02654 vinfos[1].indices[1] = _ij1[1];
02655 vinfos[1].maxsolutions = _nj1;
02656 vinfos[2].jointtype = 1;
02657 vinfos[2].foffset = j2;
02658 vinfos[2].indices[0] = _ij2[0];
02659 vinfos[2].indices[1] = _ij2[1];
02660 vinfos[2].maxsolutions = _nj2;
02661 vinfos[3].jointtype = 1;
02662 vinfos[3].foffset = j3;
02663 vinfos[3].indices[0] = _ij3[0];
02664 vinfos[3].indices[1] = _ij3[1];
02665 vinfos[3].maxsolutions = _nj3;
02666 vinfos[4].jointtype = 1;
02667 vinfos[4].foffset = j4;
02668 vinfos[4].indices[0] = _ij4[0];
02669 vinfos[4].indices[1] = _ij4[1];
02670 vinfos[4].maxsolutions = _nj4;
02671 vinfos[5].jointtype = 1;
02672 vinfos[5].foffset = j5;
02673 vinfos[5].indices[0] = _ij5[0];
02674 vinfos[5].indices[1] = _ij5[1];
02675 vinfos[5].maxsolutions = _nj5;
02676 std::vector<int> vfree(0);
02677 solutions.AddSolution(vinfos,vfree);
02678 }
02679 }
02680 }
02681 
02682 }
02683 
02684 }
02685 
02686 } else
02687 {
02688 {
02689 IkReal j1array[1], cj1array[1], sj1array[1];
02690 bool j1valid[1]={false};
02691 _nj1 = 1;
02692 IkReal x573=((r20)*(sj5));
02693 IkReal x574=((cj4)*(r22));
02694 IkReal x575=((sj2)*(sj4));
02695 IkReal x576=((cj5)*(r20));
02696 IkReal x577=((cj5)*(r21));
02697 IkReal x578=((r21)*(sj5));
02698 IkReal x579=((cj2)*(sj4));
02699 if( IKabs(((gconst103)*(((((cj2)*(x573)))+(((x575)*(x576)))+(((IkReal(-1.00000000000000))*(sj2)*(x574)))+(((cj2)*(x577)))+(((IkReal(-1.00000000000000))*(x575)*(x578))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst103)*(((((IkReal(-1.00000000000000))*(x576)*(x579)))+(((cj2)*(x574)))+(((sj2)*(x573)))+(((sj2)*(x577)))+(((x578)*(x579))))))) < IKFAST_ATAN2_MAGTHRESH )
02700     continue;
02701 j1array[0]=IKatan2(((gconst103)*(((((cj2)*(x573)))+(((x575)*(x576)))+(((IkReal(-1.00000000000000))*(sj2)*(x574)))+(((cj2)*(x577)))+(((IkReal(-1.00000000000000))*(x575)*(x578)))))), ((gconst103)*(((((IkReal(-1.00000000000000))*(x576)*(x579)))+(((cj2)*(x574)))+(((sj2)*(x573)))+(((sj2)*(x577)))+(((x578)*(x579)))))));
02702 sj1array[0]=IKsin(j1array[0]);
02703 cj1array[0]=IKcos(j1array[0]);
02704 if( j1array[0] > IKPI )
02705 {
02706     j1array[0]-=IK2PI;
02707 }
02708 else if( j1array[0] < -IKPI )
02709 {    j1array[0]+=IK2PI;
02710 }
02711 j1valid[0] = true;
02712 for(int ij1 = 0; ij1 < 1; ++ij1)
02713 {
02714 if( !j1valid[ij1] )
02715 {
02716     continue;
02717 }
02718 _ij1[0] = ij1; _ij1[1] = -1;
02719 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02720 {
02721 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02722 {
02723     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02724 }
02725 }
02726 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02727 {
02728 IkReal evalcond[4];
02729 IkReal x580=IKsin(j1);
02730 IkReal x581=IKcos(j1);
02731 IkReal x582=((cj0)*(sj4));
02732 IkReal x583=((IkReal(1.00000000000000))*(sj5));
02733 IkReal x584=((cj5)*(sj0));
02734 IkReal x585=((IkReal(1.00000000000000))*(cj4));
02735 IkReal x586=((IkReal(1.00000000000000))*(cj5));
02736 IkReal x587=((sj2)*(x580));
02737 IkReal x588=((IkReal(1.00000000000000))*(x581));
02738 IkReal x589=((cj2)*(x580));
02739 IkReal x590=((cj2)*(x588));
02740 evalcond[0]=((((IkReal(-1.00000000000000))*(sj2)*(x588)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x589)))+(((cj5)*(r21))));
02741 evalcond[1]=((((IkReal(-1.00000000000000))*(x590)))+(((cj4)*(r22)))+(x587)+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x586)))+(((r21)*(sj4)*(sj5))));
02742 evalcond[2]=((((IkReal(-1.00000000000000))*(x590)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x583)))+(((IkReal(-1.00000000000000))*(r11)*(x584)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x583)))+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x586)))+(x587));
02743 evalcond[3]=((((r10)*(sj4)*(x584)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x585)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x585)))+(((IkReal(-1.00000000000000))*(r01)*(x582)*(x583)))+(((sj2)*(x581)))+(x589)+(((cj5)*(r00)*(x582)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x583))));
02744 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02745 {
02746 continue;
02747 }
02748 }
02749 
02750 {
02751 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02752 vinfos[0].jointtype = 1;
02753 vinfos[0].foffset = j0;
02754 vinfos[0].indices[0] = _ij0[0];
02755 vinfos[0].indices[1] = _ij0[1];
02756 vinfos[0].maxsolutions = _nj0;
02757 vinfos[1].jointtype = 1;
02758 vinfos[1].foffset = j1;
02759 vinfos[1].indices[0] = _ij1[0];
02760 vinfos[1].indices[1] = _ij1[1];
02761 vinfos[1].maxsolutions = _nj1;
02762 vinfos[2].jointtype = 1;
02763 vinfos[2].foffset = j2;
02764 vinfos[2].indices[0] = _ij2[0];
02765 vinfos[2].indices[1] = _ij2[1];
02766 vinfos[2].maxsolutions = _nj2;
02767 vinfos[3].jointtype = 1;
02768 vinfos[3].foffset = j3;
02769 vinfos[3].indices[0] = _ij3[0];
02770 vinfos[3].indices[1] = _ij3[1];
02771 vinfos[3].maxsolutions = _nj3;
02772 vinfos[4].jointtype = 1;
02773 vinfos[4].foffset = j4;
02774 vinfos[4].indices[0] = _ij4[0];
02775 vinfos[4].indices[1] = _ij4[1];
02776 vinfos[4].maxsolutions = _nj4;
02777 vinfos[5].jointtype = 1;
02778 vinfos[5].foffset = j5;
02779 vinfos[5].indices[0] = _ij5[0];
02780 vinfos[5].indices[1] = _ij5[1];
02781 vinfos[5].maxsolutions = _nj5;
02782 std::vector<int> vfree(0);
02783 solutions.AddSolution(vinfos,vfree);
02784 }
02785 }
02786 }
02787 
02788 }
02789 
02790 }
02791 }
02792 }
02793 
02794 }
02795 
02796 }
02797 
02798 } else
02799 {
02800 {
02801 IkReal j1array[1], cj1array[1], sj1array[1];
02802 bool j1valid[1]={false};
02803 _nj1 = 1;
02804 IkReal x591=((cj2)*(sj5));
02805 IkReal x592=((r21)*(sj4));
02806 IkReal x593=((r20)*(sj2));
02807 IkReal x594=((cj5)*(sj4));
02808 IkReal x595=((cj5)*(r21));
02809 IkReal x596=((IkReal(1.00000000000000))*(sj2));
02810 IkReal x597=((cj4)*(r22));
02811 if( IKabs(((gconst102)*(((((x593)*(x594)))+(((cj2)*(x595)))+(((IkReal(-1.00000000000000))*(x596)*(x597)))+(((r20)*(x591)))+(((IkReal(-1.00000000000000))*(sj5)*(x592)*(x596))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst102)*(((((cj2)*(x597)))+(((sj2)*(x595)))+(((IkReal(-1.00000000000000))*(cj2)*(r20)*(x594)))+(((x591)*(x592)))+(((sj5)*(x593))))))) < IKFAST_ATAN2_MAGTHRESH )
02812     continue;
02813 j1array[0]=IKatan2(((gconst102)*(((((x593)*(x594)))+(((cj2)*(x595)))+(((IkReal(-1.00000000000000))*(x596)*(x597)))+(((r20)*(x591)))+(((IkReal(-1.00000000000000))*(sj5)*(x592)*(x596)))))), ((gconst102)*(((((cj2)*(x597)))+(((sj2)*(x595)))+(((IkReal(-1.00000000000000))*(cj2)*(r20)*(x594)))+(((x591)*(x592)))+(((sj5)*(x593)))))));
02814 sj1array[0]=IKsin(j1array[0]);
02815 cj1array[0]=IKcos(j1array[0]);
02816 if( j1array[0] > IKPI )
02817 {
02818     j1array[0]-=IK2PI;
02819 }
02820 else if( j1array[0] < -IKPI )
02821 {    j1array[0]+=IK2PI;
02822 }
02823 j1valid[0] = true;
02824 for(int ij1 = 0; ij1 < 1; ++ij1)
02825 {
02826 if( !j1valid[ij1] )
02827 {
02828     continue;
02829 }
02830 _ij1[0] = ij1; _ij1[1] = -1;
02831 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
02832 {
02833 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
02834 {
02835     j1valid[iij1]=false; _ij1[1] = iij1; break; 
02836 }
02837 }
02838 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
02839 {
02840 IkReal evalcond[2];
02841 IkReal x598=IKsin(j1);
02842 IkReal x599=IKcos(j1);
02843 IkReal x600=((IkReal(1.00000000000000))*(x599));
02844 evalcond[0]=((((IkReal(-1.00000000000000))*(sj2)*(x600)))+(((IkReal(-1.00000000000000))*(cj2)*(x598)))+(((r20)*(sj5)))+(((cj5)*(r21))));
02845 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj4)))+(((IkReal(-1.00000000000000))*(cj2)*(x600)))+(((cj4)*(r22)))+(((r21)*(sj4)*(sj5)))+(((sj2)*(x598))));
02846 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
02847 {
02848 continue;
02849 }
02850 }
02851 
02852 {
02853 IkReal dummyeval[1];
02854 IkReal gconst106;
02855 IkReal x601=(cj5)*(cj5);
02856 IkReal x602=(sj5)*(sj5);
02857 IkReal x603=((sj4)*(sj5));
02858 IkReal x604=((IkReal(1.00000000000000))*(r12));
02859 IkReal x605=((cj5)*(sj4));
02860 IkReal x606=((cj4)*(r00)*(r11));
02861 IkReal x607=((IkReal(1.00000000000000))*(cj4)*(r01)*(r10));
02862 gconst106=IKsign(((((x602)*(x606)))+(((r02)*(r10)*(x603)))+(((r02)*(r11)*(x605)))+(((IkReal(-1.00000000000000))*(x601)*(x607)))+(((x601)*(x606)))+(((IkReal(-1.00000000000000))*(x602)*(x607)))+(((IkReal(-1.00000000000000))*(r00)*(x603)*(x604)))+(((IkReal(-1.00000000000000))*(r01)*(x604)*(x605)))));
02863 IkReal x608=(cj5)*(cj5);
02864 IkReal x609=(sj5)*(sj5);
02865 IkReal x610=((sj4)*(sj5));
02866 IkReal x611=((IkReal(1.00000000000000))*(r12));
02867 IkReal x612=((cj5)*(sj4));
02868 IkReal x613=((cj4)*(r00)*(r11));
02869 IkReal x614=x607;
02870 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(x610)*(x611)))+(((x609)*(x613)))+(((r02)*(r10)*(x610)))+(((x608)*(x613)))+(((IkReal(-1.00000000000000))*(r01)*(x611)*(x612)))+(((r02)*(r11)*(x612)))+(((IkReal(-1.00000000000000))*(x608)*(x614)))+(((IkReal(-1.00000000000000))*(x609)*(x614))));
02871 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02872 {
02873 {
02874 IkReal dummyeval[1];
02875 IkReal gconst105;
02876 IkReal x615=(cj5)*(cj5);
02877 IkReal x616=(sj5)*(sj5);
02878 IkReal x617=((IkReal(1.00000000000000))*(x616));
02879 IkReal x618=((IkReal(2.00000000000000))*(cj5)*(sj5));
02880 IkReal x619=((IkReal(1.00000000000000))*(x615));
02881 gconst105=IKsign(((((IkReal(-1.00000000000000))*(x617)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x618)))+(((IkReal(-1.00000000000000))*(x617)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x618)))+(((IkReal(-1.00000000000000))*(x619)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x619)*((r01)*(r01))))));
02882 IkReal x620=(cj5)*(cj5);
02883 IkReal x621=(sj5)*(sj5);
02884 IkReal x622=((IkReal(1.00000000000000))*(x621));
02885 IkReal x623=((IkReal(2.00000000000000))*(cj5)*(sj5));
02886 IkReal x624=((IkReal(1.00000000000000))*(x620));
02887 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(r01)*(x623)))+(((IkReal(-1.00000000000000))*(x624)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x622)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x622)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x623)))+(((IkReal(-1.00000000000000))*(x624)*((r01)*(r01)))));
02888 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02889 {
02890 continue;
02891 
02892 } else
02893 {
02894 {
02895 IkReal j0array[1], cj0array[1], sj0array[1];
02896 bool j0valid[1]={false};
02897 _nj0 = 1;
02898 IkReal x625=((cj1)*(cj2));
02899 IkReal x626=((r00)*(sj5));
02900 IkReal x627=((cj5)*(r01));
02901 IkReal x628=((r10)*(sj5));
02902 IkReal x629=((cj5)*(r11));
02903 IkReal x630=((IkReal(1.00000000000000))*(sj1)*(sj2));
02904 if( IKabs(((gconst105)*(((((IkReal(-1.00000000000000))*(x629)*(x630)))+(((x625)*(x628)))+(((x625)*(x629)))+(((IkReal(-1.00000000000000))*(x628)*(x630))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst105)*(((((IkReal(-1.00000000000000))*(x626)*(x630)))+(((IkReal(-1.00000000000000))*(x627)*(x630)))+(((x625)*(x626)))+(((x625)*(x627))))))) < IKFAST_ATAN2_MAGTHRESH )
02905     continue;
02906 j0array[0]=IKatan2(((gconst105)*(((((IkReal(-1.00000000000000))*(x629)*(x630)))+(((x625)*(x628)))+(((x625)*(x629)))+(((IkReal(-1.00000000000000))*(x628)*(x630)))))), ((gconst105)*(((((IkReal(-1.00000000000000))*(x626)*(x630)))+(((IkReal(-1.00000000000000))*(x627)*(x630)))+(((x625)*(x626)))+(((x625)*(x627)))))));
02907 sj0array[0]=IKsin(j0array[0]);
02908 cj0array[0]=IKcos(j0array[0]);
02909 if( j0array[0] > IKPI )
02910 {
02911     j0array[0]-=IK2PI;
02912 }
02913 else if( j0array[0] < -IKPI )
02914 {    j0array[0]+=IK2PI;
02915 }
02916 j0valid[0] = true;
02917 for(int ij0 = 0; ij0 < 1; ++ij0)
02918 {
02919 if( !j0valid[ij0] )
02920 {
02921     continue;
02922 }
02923 _ij0[0] = ij0; _ij0[1] = -1;
02924 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
02925 {
02926 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
02927 {
02928     j0valid[iij0]=false; _ij0[1] = iij0; break; 
02929 }
02930 }
02931 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
02932 {
02933 IkReal evalcond[6];
02934 IkReal x631=IKsin(j0);
02935 IkReal x632=IKcos(j0);
02936 IkReal x633=((IkReal(1.00000000000000))*(r10));
02937 IkReal x634=((IkReal(1.00000000000000))*(sj4));
02938 IkReal x635=((cj5)*(r01));
02939 IkReal x636=((cj5)*(r00));
02940 IkReal x637=((cj4)*(r01));
02941 IkReal x638=((IkReal(1.00000000000000))*(cj4));
02942 IkReal x639=((cj4)*(r11));
02943 IkReal x640=((sj5)*(x631));
02944 IkReal x641=((r11)*(x634));
02945 IkReal x642=((sj5)*(x632));
02946 IkReal x643=((r02)*(x632));
02947 IkReal x644=((r12)*(x632));
02948 IkReal x645=((IkReal(1.00000000000000))*(x632));
02949 IkReal x646=((cj4)*(x631));
02950 IkReal x647=((cj5)*(x631));
02951 IkReal x648=((cj5)*(sj4)*(x632));
02952 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x645)))+(((r00)*(x640)))+(((x631)*(x635)))+(((IkReal(-1.00000000000000))*(x633)*(x642))));
02953 evalcond[1]=((((IkReal(-1.00000000000000))*(cj1)*(cj2)))+(((IkReal(-1.00000000000000))*(x633)*(x640)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r00)*(x642)))+(((IkReal(-1.00000000000000))*(x635)*(x645)))+(((IkReal(-1.00000000000000))*(r11)*(x647))));
02954 evalcond[2]=((((IkReal(-1.00000000000000))*(x638)*(x644)))+(((IkReal(-1.00000000000000))*(x631)*(x634)*(x636)))+(((r01)*(sj4)*(x640)))+(((r10)*(x648)))+(((r02)*(x646)))+(((IkReal(-1.00000000000000))*(x641)*(x642))));
02955 evalcond[3]=((IkReal(1.00000000000000))+(((x639)*(x642)))+(((r02)*(sj4)*(x631)))+(((IkReal(-1.00000000000000))*(x637)*(x640)))+(((IkReal(-1.00000000000000))*(x634)*(x644)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x632)*(x633)))+(((x636)*(x646))));
02956 evalcond[4]=((((cj1)*(sj2)))+(((r10)*(sj4)*(x647)))+(((IkReal(-1.00000000000000))*(x640)*(x641)))+(((IkReal(-1.00000000000000))*(r12)*(x631)*(x638)))+(((IkReal(-1.00000000000000))*(r01)*(x634)*(x642)))+(((sj4)*(x632)*(x636)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x638)*(x643))));
02957 evalcond[5]=((((x639)*(x640)))+(((IkReal(-1.00000000000000))*(x632)*(x636)*(x638)))+(((IkReal(-1.00000000000000))*(cj5)*(x633)*(x646)))+(((IkReal(-1.00000000000000))*(r12)*(x631)*(x634)))+(((x637)*(x642)))+(((IkReal(-1.00000000000000))*(x634)*(x643))));
02958 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  )
02959 {
02960 continue;
02961 }
02962 }
02963 
02964 {
02965 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02966 vinfos[0].jointtype = 1;
02967 vinfos[0].foffset = j0;
02968 vinfos[0].indices[0] = _ij0[0];
02969 vinfos[0].indices[1] = _ij0[1];
02970 vinfos[0].maxsolutions = _nj0;
02971 vinfos[1].jointtype = 1;
02972 vinfos[1].foffset = j1;
02973 vinfos[1].indices[0] = _ij1[0];
02974 vinfos[1].indices[1] = _ij1[1];
02975 vinfos[1].maxsolutions = _nj1;
02976 vinfos[2].jointtype = 1;
02977 vinfos[2].foffset = j2;
02978 vinfos[2].indices[0] = _ij2[0];
02979 vinfos[2].indices[1] = _ij2[1];
02980 vinfos[2].maxsolutions = _nj2;
02981 vinfos[3].jointtype = 1;
02982 vinfos[3].foffset = j3;
02983 vinfos[3].indices[0] = _ij3[0];
02984 vinfos[3].indices[1] = _ij3[1];
02985 vinfos[3].maxsolutions = _nj3;
02986 vinfos[4].jointtype = 1;
02987 vinfos[4].foffset = j4;
02988 vinfos[4].indices[0] = _ij4[0];
02989 vinfos[4].indices[1] = _ij4[1];
02990 vinfos[4].maxsolutions = _nj4;
02991 vinfos[5].jointtype = 1;
02992 vinfos[5].foffset = j5;
02993 vinfos[5].indices[0] = _ij5[0];
02994 vinfos[5].indices[1] = _ij5[1];
02995 vinfos[5].maxsolutions = _nj5;
02996 std::vector<int> vfree(0);
02997 solutions.AddSolution(vinfos,vfree);
02998 }
02999 }
03000 }
03001 
03002 }
03003 
03004 }
03005 
03006 } else
03007 {
03008 {
03009 IkReal j0array[1], cj0array[1], sj0array[1];
03010 bool j0valid[1]={false};
03011 _nj0 = 1;
03012 IkReal x649=((IkReal(1.00000000000000))*(cj5));
03013 IkReal x650=((IkReal(1.00000000000000))*(sj5));
03014 if( IKabs(((gconst106)*(((((IkReal(-1.00000000000000))*(r11)*(x649)))+(((IkReal(-1.00000000000000))*(r10)*(x650))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst106)*(((((IkReal(-1.00000000000000))*(r00)*(x650)))+(((IkReal(-1.00000000000000))*(r01)*(x649))))))) < IKFAST_ATAN2_MAGTHRESH )
03015     continue;
03016 j0array[0]=IKatan2(((gconst106)*(((((IkReal(-1.00000000000000))*(r11)*(x649)))+(((IkReal(-1.00000000000000))*(r10)*(x650)))))), ((gconst106)*(((((IkReal(-1.00000000000000))*(r00)*(x650)))+(((IkReal(-1.00000000000000))*(r01)*(x649)))))));
03017 sj0array[0]=IKsin(j0array[0]);
03018 cj0array[0]=IKcos(j0array[0]);
03019 if( j0array[0] > IKPI )
03020 {
03021     j0array[0]-=IK2PI;
03022 }
03023 else if( j0array[0] < -IKPI )
03024 {    j0array[0]+=IK2PI;
03025 }
03026 j0valid[0] = true;
03027 for(int ij0 = 0; ij0 < 1; ++ij0)
03028 {
03029 if( !j0valid[ij0] )
03030 {
03031     continue;
03032 }
03033 _ij0[0] = ij0; _ij0[1] = -1;
03034 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03035 {
03036 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03037 {
03038     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03039 }
03040 }
03041 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03042 {
03043 IkReal evalcond[6];
03044 IkReal x651=IKsin(j0);
03045 IkReal x652=IKcos(j0);
03046 IkReal x653=((IkReal(1.00000000000000))*(r10));
03047 IkReal x654=((IkReal(1.00000000000000))*(sj4));
03048 IkReal x655=((cj5)*(r01));
03049 IkReal x656=((cj5)*(r00));
03050 IkReal x657=((cj4)*(r01));
03051 IkReal x658=((IkReal(1.00000000000000))*(cj4));
03052 IkReal x659=((cj4)*(r11));
03053 IkReal x660=((sj5)*(x651));
03054 IkReal x661=((r11)*(x654));
03055 IkReal x662=((sj5)*(x652));
03056 IkReal x663=((r02)*(x652));
03057 IkReal x664=((r12)*(x652));
03058 IkReal x665=((IkReal(1.00000000000000))*(x652));
03059 IkReal x666=((cj4)*(x651));
03060 IkReal x667=((cj5)*(x651));
03061 IkReal x668=((cj5)*(sj4)*(x652));
03062 evalcond[0]=((((x651)*(x655)))+(((r00)*(x660)))+(((IkReal(-1.00000000000000))*(x653)*(x662)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x665))));
03063 evalcond[1]=((((IkReal(-1.00000000000000))*(cj1)*(cj2)))+(((IkReal(-1.00000000000000))*(r00)*(x662)))+(((IkReal(-1.00000000000000))*(x655)*(x665)))+(((IkReal(-1.00000000000000))*(x653)*(x660)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r11)*(x667))));
03064 evalcond[2]=((((r01)*(sj4)*(x660)))+(((r02)*(x666)))+(((IkReal(-1.00000000000000))*(x661)*(x662)))+(((IkReal(-1.00000000000000))*(x651)*(x654)*(x656)))+(((r10)*(x668)))+(((IkReal(-1.00000000000000))*(x658)*(x664))));
03065 evalcond[3]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x652)*(x653)))+(((IkReal(-1.00000000000000))*(x654)*(x664)))+(((r02)*(sj4)*(x651)))+(((IkReal(-1.00000000000000))*(x657)*(x660)))+(((x659)*(x662)))+(((x656)*(x666))));
03066 evalcond[4]=((((cj1)*(sj2)))+(((r10)*(sj4)*(x667)))+(((IkReal(-1.00000000000000))*(r01)*(x654)*(x662)))+(((IkReal(-1.00000000000000))*(x660)*(x661)))+(((IkReal(-1.00000000000000))*(r12)*(x651)*(x658)))+(((sj4)*(x652)*(x656)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x658)*(x663))));
03067 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(x653)*(x666)))+(((IkReal(-1.00000000000000))*(x652)*(x656)*(x658)))+(((IkReal(-1.00000000000000))*(r12)*(x651)*(x654)))+(((x659)*(x660)))+(((x657)*(x662)))+(((IkReal(-1.00000000000000))*(x654)*(x663))));
03068 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  )
03069 {
03070 continue;
03071 }
03072 }
03073 
03074 {
03075 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03076 vinfos[0].jointtype = 1;
03077 vinfos[0].foffset = j0;
03078 vinfos[0].indices[0] = _ij0[0];
03079 vinfos[0].indices[1] = _ij0[1];
03080 vinfos[0].maxsolutions = _nj0;
03081 vinfos[1].jointtype = 1;
03082 vinfos[1].foffset = j1;
03083 vinfos[1].indices[0] = _ij1[0];
03084 vinfos[1].indices[1] = _ij1[1];
03085 vinfos[1].maxsolutions = _nj1;
03086 vinfos[2].jointtype = 1;
03087 vinfos[2].foffset = j2;
03088 vinfos[2].indices[0] = _ij2[0];
03089 vinfos[2].indices[1] = _ij2[1];
03090 vinfos[2].maxsolutions = _nj2;
03091 vinfos[3].jointtype = 1;
03092 vinfos[3].foffset = j3;
03093 vinfos[3].indices[0] = _ij3[0];
03094 vinfos[3].indices[1] = _ij3[1];
03095 vinfos[3].maxsolutions = _nj3;
03096 vinfos[4].jointtype = 1;
03097 vinfos[4].foffset = j4;
03098 vinfos[4].indices[0] = _ij4[0];
03099 vinfos[4].indices[1] = _ij4[1];
03100 vinfos[4].maxsolutions = _nj4;
03101 vinfos[5].jointtype = 1;
03102 vinfos[5].foffset = j5;
03103 vinfos[5].indices[0] = _ij5[0];
03104 vinfos[5].indices[1] = _ij5[1];
03105 vinfos[5].maxsolutions = _nj5;
03106 std::vector<int> vfree(0);
03107 solutions.AddSolution(vinfos,vfree);
03108 }
03109 }
03110 }
03111 
03112 }
03113 
03114 }
03115 }
03116 }
03117 
03118 }
03119 
03120 }
03121 
03122 } else
03123 {
03124 IkReal x669=((cj5)*(npx));
03125 IkReal x670=((IkReal(1.00000000000000))*(cj4)*(sj5));
03126 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))));
03127 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(0.350000000000000))*(sj2)))+(((npx)*(sj5))));
03128 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x669)))+(((npy)*(sj4)*(sj5))));
03129 evalcond[3]=((((cj4)*(x669)))+(((IkReal(-1.00000000000000))*(npy)*(x670)))+(((npz)*(sj4))));
03130 evalcond[4]=((((cj4)*(cj5)*(r20)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(r21)*(x670))));
03131 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  )
03132 {
03133 {
03134 IkReal dummyeval[1];
03135 IkReal gconst109;
03136 gconst109=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
03137 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
03138 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03139 {
03140 {
03141 IkReal dummyeval[1];
03142 IkReal gconst107;
03143 IkReal x671=(sj5)*(sj5);
03144 IkReal x672=(cj5)*(cj5);
03145 IkReal x673=((cj5)*(sj4));
03146 IkReal x674=((IkReal(1.00000000000000))*(r02));
03147 IkReal x675=((sj4)*(sj5));
03148 IkReal x676=((cj4)*(r01)*(r10));
03149 IkReal x677=((IkReal(1.00000000000000))*(cj4)*(r00)*(r11));
03150 gconst107=IKsign(((((r00)*(r12)*(x675)))+(((x672)*(x676)))+(((IkReal(-1.00000000000000))*(r10)*(x674)*(x675)))+(((IkReal(-1.00000000000000))*(x672)*(x677)))+(((x671)*(x676)))+(((IkReal(-1.00000000000000))*(r11)*(x673)*(x674)))+(((IkReal(-1.00000000000000))*(x671)*(x677)))+(((r01)*(r12)*(x673)))));
03151 IkReal x678=(sj5)*(sj5);
03152 IkReal x679=(cj5)*(cj5);
03153 IkReal x680=((cj5)*(sj4));
03154 IkReal x681=((IkReal(1.00000000000000))*(r02));
03155 IkReal x682=((sj4)*(sj5));
03156 IkReal x683=((cj4)*(r01)*(r10));
03157 IkReal x684=x677;
03158 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(x681)*(x682)))+(((r00)*(r12)*(x682)))+(((IkReal(-1.00000000000000))*(x679)*(x684)))+(((IkReal(-1.00000000000000))*(x678)*(x684)))+(((IkReal(-1.00000000000000))*(r11)*(x680)*(x681)))+(((x679)*(x683)))+(((r01)*(r12)*(x680)))+(((x678)*(x683))));
03159 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03160 {
03161 {
03162 IkReal dummyeval[1];
03163 IkReal gconst108;
03164 IkReal x685=(cj4)*(cj4);
03165 IkReal x686=(sj4)*(sj4);
03166 IkReal x687=((cj5)*(r10));
03167 IkReal x688=((r01)*(sj5));
03168 IkReal x689=((r12)*(x686));
03169 IkReal x690=((IkReal(1.00000000000000))*(cj5)*(r00));
03170 IkReal x691=((r02)*(x685));
03171 IkReal x692=((IkReal(1.00000000000000))*(r11)*(sj5));
03172 IkReal x693=((r12)*(x685));
03173 IkReal x694=((r02)*(x686));
03174 gconst108=IKsign(((((x687)*(x694)))+(((x688)*(x689)))+(((IkReal(-1.00000000000000))*(x692)*(x694)))+(((IkReal(-1.00000000000000))*(x689)*(x690)))+(((x687)*(x691)))+(((x688)*(x693)))+(((IkReal(-1.00000000000000))*(x691)*(x692)))+(((IkReal(-1.00000000000000))*(x690)*(x693)))));
03175 IkReal x695=(cj4)*(cj4);
03176 IkReal x696=(sj4)*(sj4);
03177 IkReal x697=((cj5)*(r10));
03178 IkReal x698=((r01)*(sj5));
03179 IkReal x699=((r12)*(x696));
03180 IkReal x700=((IkReal(1.00000000000000))*(cj5)*(r00));
03181 IkReal x701=((r02)*(x695));
03182 IkReal x702=((IkReal(1.00000000000000))*(r11)*(sj5));
03183 IkReal x703=((r12)*(x695));
03184 IkReal x704=((r02)*(x696));
03185 dummyeval[0]=((((IkReal(-1.00000000000000))*(x700)*(x703)))+(((x698)*(x699)))+(((x697)*(x704)))+(((IkReal(-1.00000000000000))*(x701)*(x702)))+(((x697)*(x701)))+(((IkReal(-1.00000000000000))*(x699)*(x700)))+(((IkReal(-1.00000000000000))*(x702)*(x704)))+(((x698)*(x703))));
03186 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03187 {
03188 continue;
03189 
03190 } else
03191 {
03192 {
03193 IkReal j0array[1], cj0array[1], sj0array[1];
03194 bool j0valid[1]={false};
03195 _nj0 = 1;
03196 IkReal x705=((cj5)*(sj4));
03197 IkReal x706=((IkReal(1.00000000000000))*(cj4));
03198 IkReal x707=((IkReal(1.00000000000000))*(sj4)*(sj5));
03199 if( IKabs(((gconst108)*(((((IkReal(-1.00000000000000))*(r11)*(x707)))+(((IkReal(-1.00000000000000))*(r12)*(x706)))+(((r10)*(x705))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst108)*(((((r00)*(x705)))+(((IkReal(-1.00000000000000))*(r01)*(x707)))+(((IkReal(-1.00000000000000))*(r02)*(x706))))))) < IKFAST_ATAN2_MAGTHRESH )
03200     continue;
03201 j0array[0]=IKatan2(((gconst108)*(((((IkReal(-1.00000000000000))*(r11)*(x707)))+(((IkReal(-1.00000000000000))*(r12)*(x706)))+(((r10)*(x705)))))), ((gconst108)*(((((r00)*(x705)))+(((IkReal(-1.00000000000000))*(r01)*(x707)))+(((IkReal(-1.00000000000000))*(r02)*(x706)))))));
03202 sj0array[0]=IKsin(j0array[0]);
03203 cj0array[0]=IKcos(j0array[0]);
03204 if( j0array[0] > IKPI )
03205 {
03206     j0array[0]-=IK2PI;
03207 }
03208 else if( j0array[0] < -IKPI )
03209 {    j0array[0]+=IK2PI;
03210 }
03211 j0valid[0] = true;
03212 for(int ij0 = 0; ij0 < 1; ++ij0)
03213 {
03214 if( !j0valid[ij0] )
03215 {
03216     continue;
03217 }
03218 _ij0[0] = ij0; _ij0[1] = -1;
03219 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03220 {
03221 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03222 {
03223     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03224 }
03225 }
03226 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03227 {
03228 IkReal evalcond[4];
03229 IkReal x708=IKsin(j0);
03230 IkReal x709=IKcos(j0);
03231 IkReal x710=((IkReal(1.00000000000000))*(sj5));
03232 IkReal x711=((cj5)*(r10));
03233 IkReal x712=((IkReal(1.00000000000000))*(r12));
03234 IkReal x713=((cj4)*(cj5));
03235 IkReal x714=((r11)*(sj5));
03236 IkReal x715=((IkReal(1.00000000000000))*(cj5));
03237 IkReal x716=((r00)*(x708));
03238 IkReal x717=((sj4)*(x709));
03239 IkReal x718=((r01)*(x708));
03240 IkReal x719=((sj4)*(x708));
03241 IkReal x720=((cj4)*(x708));
03242 IkReal x721=((cj4)*(x709));
03243 evalcond[0]=((((IkReal(-1.00000000000000))*(r10)*(x709)*(x710)))+(((IkReal(-1.00000000000000))*(r11)*(x709)*(x715)))+(((cj5)*(x718)))+(((sj5)*(x716))));
03244 evalcond[1]=((((IkReal(-1.00000000000000))*(x712)*(x721)))+(((sj4)*(sj5)*(x718)))+(((IkReal(-1.00000000000000))*(r11)*(x710)*(x717)))+(((x711)*(x717)))+(((IkReal(-1.00000000000000))*(sj4)*(x715)*(x716)))+(((r02)*(x720))));
03245 evalcond[2]=((IkReal(-1.00000000000000))+(((r02)*(x719)))+(((IkReal(-1.00000000000000))*(x711)*(x721)))+(((IkReal(-1.00000000000000))*(x712)*(x717)))+(((x713)*(x716)))+(((IkReal(-1.00000000000000))*(cj4)*(x710)*(x718)))+(((x714)*(x721))));
03246 evalcond[3]=((((IkReal(-1.00000000000000))*(x712)*(x719)))+(((IkReal(-1.00000000000000))*(x711)*(x720)))+(((IkReal(-1.00000000000000))*(r02)*(x717)))+(((x714)*(x720)))+(((r01)*(sj5)*(x721)))+(((IkReal(-1.00000000000000))*(r00)*(x709)*(x713))));
03247 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03248 {
03249 continue;
03250 }
03251 }
03252 
03253 {
03254 IkReal dummyeval[1];
03255 IkReal gconst110;
03256 gconst110=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
03257 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
03258 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03259 {
03260 {
03261 IkReal dummyeval[1];
03262 IkReal gconst111;
03263 gconst111=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
03264 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
03265 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03266 {
03267 continue;
03268 
03269 } else
03270 {
03271 {
03272 IkReal j1array[1], cj1array[1], sj1array[1];
03273 bool j1valid[1]={false};
03274 _nj1 = 1;
03275 IkReal x722=((IkReal(1.00000000000000))*(sj2));
03276 IkReal x723=((r20)*(sj5));
03277 IkReal x724=((IkReal(1.00000000000000))*(cj2));
03278 IkReal x725=((cj5)*(r21));
03279 IkReal x726=((cj5)*(r11)*(sj0));
03280 IkReal x727=((r10)*(sj0)*(sj5));
03281 IkReal x728=((cj0)*(r00)*(sj5));
03282 IkReal x729=((cj0)*(cj5)*(r01));
03283 if( IKabs(((gconst111)*(((((IkReal(-1.00000000000000))*(x723)*(x724)))+(((IkReal(-1.00000000000000))*(x722)*(x726)))+(((IkReal(-1.00000000000000))*(x724)*(x725)))+(((IkReal(-1.00000000000000))*(x722)*(x728)))+(((IkReal(-1.00000000000000))*(x722)*(x727)))+(((IkReal(-1.00000000000000))*(x722)*(x729))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst111)*(((((cj2)*(x727)))+(((cj2)*(x726)))+(((cj2)*(x729)))+(((IkReal(-1.00000000000000))*(x722)*(x723)))+(((IkReal(-1.00000000000000))*(x722)*(x725)))+(((cj2)*(x728))))))) < IKFAST_ATAN2_MAGTHRESH )
03284     continue;
03285 j1array[0]=IKatan2(((gconst111)*(((((IkReal(-1.00000000000000))*(x723)*(x724)))+(((IkReal(-1.00000000000000))*(x722)*(x726)))+(((IkReal(-1.00000000000000))*(x724)*(x725)))+(((IkReal(-1.00000000000000))*(x722)*(x728)))+(((IkReal(-1.00000000000000))*(x722)*(x727)))+(((IkReal(-1.00000000000000))*(x722)*(x729)))))), ((gconst111)*(((((cj2)*(x727)))+(((cj2)*(x726)))+(((cj2)*(x729)))+(((IkReal(-1.00000000000000))*(x722)*(x723)))+(((IkReal(-1.00000000000000))*(x722)*(x725)))+(((cj2)*(x728)))))));
03286 sj1array[0]=IKsin(j1array[0]);
03287 cj1array[0]=IKcos(j1array[0]);
03288 if( j1array[0] > IKPI )
03289 {
03290     j1array[0]-=IK2PI;
03291 }
03292 else if( j1array[0] < -IKPI )
03293 {    j1array[0]+=IK2PI;
03294 }
03295 j1valid[0] = true;
03296 for(int ij1 = 0; ij1 < 1; ++ij1)
03297 {
03298 if( !j1valid[ij1] )
03299 {
03300     continue;
03301 }
03302 _ij1[0] = ij1; _ij1[1] = -1;
03303 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03304 {
03305 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03306 {
03307     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03308 }
03309 }
03310 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03311 {
03312 IkReal evalcond[4];
03313 IkReal x730=IKsin(j1);
03314 IkReal x731=IKcos(j1);
03315 IkReal x732=((cj5)*(sj0));
03316 IkReal x733=((IkReal(1.00000000000000))*(r11));
03317 IkReal x734=((cj5)*(sj4));
03318 IkReal x735=((cj0)*(r00));
03319 IkReal x736=((IkReal(1.00000000000000))*(sj0));
03320 IkReal x737=((sj4)*(sj5));
03321 IkReal x738=((IkReal(1.00000000000000))*(cj0));
03322 IkReal x739=((sj2)*(x731));
03323 IkReal x740=((cj2)*(x730));
03324 IkReal x741=((cj2)*(x731));
03325 IkReal x742=((sj2)*(x730));
03326 IkReal x743=((x740)+(x739));
03327 evalcond[0]=((x743)+(((r20)*(sj5)))+(((cj5)*(r21))));
03328 evalcond[1]=((((IkReal(-1.00000000000000))*(x741)))+(((IkReal(-1.00000000000000))*(r20)*(x734)))+(((r21)*(x737)))+(x742)+(((cj4)*(r22))));
03329 evalcond[2]=((x741)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x738)))+(((IkReal(-1.00000000000000))*(sj5)*(x735)))+(((IkReal(-1.00000000000000))*(x742)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x736)))+(((IkReal(-1.00000000000000))*(x732)*(x733))));
03330 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x738)))+(x743)+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x736)))+(((IkReal(-1.00000000000000))*(sj0)*(x733)*(x737)))+(((x734)*(x735)))+(((IkReal(-1.00000000000000))*(r01)*(x737)*(x738)))+(((r10)*(sj4)*(x732))));
03331 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03332 {
03333 continue;
03334 }
03335 }
03336 
03337 {
03338 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03339 vinfos[0].jointtype = 1;
03340 vinfos[0].foffset = j0;
03341 vinfos[0].indices[0] = _ij0[0];
03342 vinfos[0].indices[1] = _ij0[1];
03343 vinfos[0].maxsolutions = _nj0;
03344 vinfos[1].jointtype = 1;
03345 vinfos[1].foffset = j1;
03346 vinfos[1].indices[0] = _ij1[0];
03347 vinfos[1].indices[1] = _ij1[1];
03348 vinfos[1].maxsolutions = _nj1;
03349 vinfos[2].jointtype = 1;
03350 vinfos[2].foffset = j2;
03351 vinfos[2].indices[0] = _ij2[0];
03352 vinfos[2].indices[1] = _ij2[1];
03353 vinfos[2].maxsolutions = _nj2;
03354 vinfos[3].jointtype = 1;
03355 vinfos[3].foffset = j3;
03356 vinfos[3].indices[0] = _ij3[0];
03357 vinfos[3].indices[1] = _ij3[1];
03358 vinfos[3].maxsolutions = _nj3;
03359 vinfos[4].jointtype = 1;
03360 vinfos[4].foffset = j4;
03361 vinfos[4].indices[0] = _ij4[0];
03362 vinfos[4].indices[1] = _ij4[1];
03363 vinfos[4].maxsolutions = _nj4;
03364 vinfos[5].jointtype = 1;
03365 vinfos[5].foffset = j5;
03366 vinfos[5].indices[0] = _ij5[0];
03367 vinfos[5].indices[1] = _ij5[1];
03368 vinfos[5].maxsolutions = _nj5;
03369 std::vector<int> vfree(0);
03370 solutions.AddSolution(vinfos,vfree);
03371 }
03372 }
03373 }
03374 
03375 }
03376 
03377 }
03378 
03379 } else
03380 {
03381 {
03382 IkReal j1array[1], cj1array[1], sj1array[1];
03383 bool j1valid[1]={false};
03384 _nj1 = 1;
03385 IkReal x744=((cj4)*(r22));
03386 IkReal x745=((r20)*(sj5));
03387 IkReal x746=((cj5)*(r21));
03388 IkReal x747=((sj2)*(sj4));
03389 IkReal x748=((r21)*(sj5));
03390 IkReal x749=((IkReal(1.00000000000000))*(cj2));
03391 IkReal x750=((cj5)*(r20));
03392 if( IKabs(((gconst110)*(((((IkReal(-1.00000000000000))*(x747)*(x750)))+(((sj2)*(x744)))+(((x747)*(x748)))+(((cj2)*(x745)))+(((cj2)*(x746))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst110)*(((((cj2)*(sj4)*(x750)))+(((sj2)*(x746)))+(((IkReal(-1.00000000000000))*(sj4)*(x748)*(x749)))+(((IkReal(-1.00000000000000))*(x744)*(x749)))+(((sj2)*(x745))))))) < IKFAST_ATAN2_MAGTHRESH )
03393     continue;
03394 j1array[0]=IKatan2(((gconst110)*(((((IkReal(-1.00000000000000))*(x747)*(x750)))+(((sj2)*(x744)))+(((x747)*(x748)))+(((cj2)*(x745)))+(((cj2)*(x746)))))), ((gconst110)*(((((cj2)*(sj4)*(x750)))+(((sj2)*(x746)))+(((IkReal(-1.00000000000000))*(sj4)*(x748)*(x749)))+(((IkReal(-1.00000000000000))*(x744)*(x749)))+(((sj2)*(x745)))))));
03395 sj1array[0]=IKsin(j1array[0]);
03396 cj1array[0]=IKcos(j1array[0]);
03397 if( j1array[0] > IKPI )
03398 {
03399     j1array[0]-=IK2PI;
03400 }
03401 else if( j1array[0] < -IKPI )
03402 {    j1array[0]+=IK2PI;
03403 }
03404 j1valid[0] = true;
03405 for(int ij1 = 0; ij1 < 1; ++ij1)
03406 {
03407 if( !j1valid[ij1] )
03408 {
03409     continue;
03410 }
03411 _ij1[0] = ij1; _ij1[1] = -1;
03412 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03413 {
03414 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03415 {
03416     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03417 }
03418 }
03419 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03420 {
03421 IkReal evalcond[4];
03422 IkReal x751=IKsin(j1);
03423 IkReal x752=IKcos(j1);
03424 IkReal x753=((cj5)*(sj0));
03425 IkReal x754=((IkReal(1.00000000000000))*(r11));
03426 IkReal x755=((cj5)*(sj4));
03427 IkReal x756=((cj0)*(r00));
03428 IkReal x757=((IkReal(1.00000000000000))*(sj0));
03429 IkReal x758=((sj4)*(sj5));
03430 IkReal x759=((IkReal(1.00000000000000))*(cj0));
03431 IkReal x760=((sj2)*(x752));
03432 IkReal x761=((cj2)*(x751));
03433 IkReal x762=((cj2)*(x752));
03434 IkReal x763=((sj2)*(x751));
03435 IkReal x764=((x760)+(x761));
03436 evalcond[0]=((x764)+(((r20)*(sj5)))+(((cj5)*(r21))));
03437 evalcond[1]=((((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x762)))+(x763)+(((IkReal(-1.00000000000000))*(r20)*(x755)))+(((r21)*(x758))));
03438 evalcond[2]=((((IkReal(-1.00000000000000))*(cj5)*(r01)*(x759)))+(((IkReal(-1.00000000000000))*(x753)*(x754)))+(x762)+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x757)))+(((IkReal(-1.00000000000000))*(x763)))+(((IkReal(-1.00000000000000))*(sj5)*(x756))));
03439 evalcond[3]=((((IkReal(-1.00000000000000))*(sj0)*(x754)*(x758)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x759)))+(((r10)*(sj4)*(x753)))+(x764)+(((IkReal(-1.00000000000000))*(r01)*(x758)*(x759)))+(((x755)*(x756)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x757))));
03440 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03441 {
03442 continue;
03443 }
03444 }
03445 
03446 {
03447 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03448 vinfos[0].jointtype = 1;
03449 vinfos[0].foffset = j0;
03450 vinfos[0].indices[0] = _ij0[0];
03451 vinfos[0].indices[1] = _ij0[1];
03452 vinfos[0].maxsolutions = _nj0;
03453 vinfos[1].jointtype = 1;
03454 vinfos[1].foffset = j1;
03455 vinfos[1].indices[0] = _ij1[0];
03456 vinfos[1].indices[1] = _ij1[1];
03457 vinfos[1].maxsolutions = _nj1;
03458 vinfos[2].jointtype = 1;
03459 vinfos[2].foffset = j2;
03460 vinfos[2].indices[0] = _ij2[0];
03461 vinfos[2].indices[1] = _ij2[1];
03462 vinfos[2].maxsolutions = _nj2;
03463 vinfos[3].jointtype = 1;
03464 vinfos[3].foffset = j3;
03465 vinfos[3].indices[0] = _ij3[0];
03466 vinfos[3].indices[1] = _ij3[1];
03467 vinfos[3].maxsolutions = _nj3;
03468 vinfos[4].jointtype = 1;
03469 vinfos[4].foffset = j4;
03470 vinfos[4].indices[0] = _ij4[0];
03471 vinfos[4].indices[1] = _ij4[1];
03472 vinfos[4].maxsolutions = _nj4;
03473 vinfos[5].jointtype = 1;
03474 vinfos[5].foffset = j5;
03475 vinfos[5].indices[0] = _ij5[0];
03476 vinfos[5].indices[1] = _ij5[1];
03477 vinfos[5].maxsolutions = _nj5;
03478 std::vector<int> vfree(0);
03479 solutions.AddSolution(vinfos,vfree);
03480 }
03481 }
03482 }
03483 
03484 }
03485 
03486 }
03487 }
03488 }
03489 
03490 }
03491 
03492 }
03493 
03494 } else
03495 {
03496 {
03497 IkReal j0array[1], cj0array[1], sj0array[1];
03498 bool j0valid[1]={false};
03499 _nj0 = 1;
03500 IkReal x765=((IkReal(1.00000000000000))*(cj5));
03501 IkReal x766=((IkReal(1.00000000000000))*(sj5));
03502 if( IKabs(((gconst107)*(((((IkReal(-1.00000000000000))*(r11)*(x765)))+(((IkReal(-1.00000000000000))*(r10)*(x766))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst107)*(((((IkReal(-1.00000000000000))*(r01)*(x765)))+(((IkReal(-1.00000000000000))*(r00)*(x766))))))) < IKFAST_ATAN2_MAGTHRESH )
03503     continue;
03504 j0array[0]=IKatan2(((gconst107)*(((((IkReal(-1.00000000000000))*(r11)*(x765)))+(((IkReal(-1.00000000000000))*(r10)*(x766)))))), ((gconst107)*(((((IkReal(-1.00000000000000))*(r01)*(x765)))+(((IkReal(-1.00000000000000))*(r00)*(x766)))))));
03505 sj0array[0]=IKsin(j0array[0]);
03506 cj0array[0]=IKcos(j0array[0]);
03507 if( j0array[0] > IKPI )
03508 {
03509     j0array[0]-=IK2PI;
03510 }
03511 else if( j0array[0] < -IKPI )
03512 {    j0array[0]+=IK2PI;
03513 }
03514 j0valid[0] = true;
03515 for(int ij0 = 0; ij0 < 1; ++ij0)
03516 {
03517 if( !j0valid[ij0] )
03518 {
03519     continue;
03520 }
03521 _ij0[0] = ij0; _ij0[1] = -1;
03522 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03523 {
03524 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03525 {
03526     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03527 }
03528 }
03529 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03530 {
03531 IkReal evalcond[4];
03532 IkReal x767=IKsin(j0);
03533 IkReal x768=IKcos(j0);
03534 IkReal x769=((IkReal(1.00000000000000))*(sj5));
03535 IkReal x770=((cj5)*(r10));
03536 IkReal x771=((IkReal(1.00000000000000))*(r12));
03537 IkReal x772=((cj4)*(cj5));
03538 IkReal x773=((r11)*(sj5));
03539 IkReal x774=((IkReal(1.00000000000000))*(cj5));
03540 IkReal x775=((r00)*(x767));
03541 IkReal x776=((sj4)*(x768));
03542 IkReal x777=((r01)*(x767));
03543 IkReal x778=((sj4)*(x767));
03544 IkReal x779=((cj4)*(x767));
03545 IkReal x780=((cj4)*(x768));
03546 evalcond[0]=((((IkReal(-1.00000000000000))*(r11)*(x768)*(x774)))+(((cj5)*(x777)))+(((IkReal(-1.00000000000000))*(r10)*(x768)*(x769)))+(((sj5)*(x775))));
03547 evalcond[1]=((((r02)*(x779)))+(((IkReal(-1.00000000000000))*(r11)*(x769)*(x776)))+(((sj4)*(sj5)*(x777)))+(((IkReal(-1.00000000000000))*(sj4)*(x774)*(x775)))+(((x770)*(x776)))+(((IkReal(-1.00000000000000))*(x771)*(x780))));
03548 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x771)*(x776)))+(((x773)*(x780)))+(((IkReal(-1.00000000000000))*(x770)*(x780)))+(((IkReal(-1.00000000000000))*(cj4)*(x769)*(x777)))+(((x772)*(x775)))+(((r02)*(x778))));
03549 evalcond[3]=((((IkReal(-1.00000000000000))*(r02)*(x776)))+(((IkReal(-1.00000000000000))*(r00)*(x768)*(x772)))+(((IkReal(-1.00000000000000))*(x771)*(x778)))+(((IkReal(-1.00000000000000))*(x770)*(x779)))+(((r01)*(sj5)*(x780)))+(((x773)*(x779))));
03550 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03551 {
03552 continue;
03553 }
03554 }
03555 
03556 {
03557 IkReal dummyeval[1];
03558 IkReal gconst110;
03559 gconst110=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
03560 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
03561 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03562 {
03563 {
03564 IkReal dummyeval[1];
03565 IkReal gconst111;
03566 gconst111=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
03567 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
03568 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03569 {
03570 continue;
03571 
03572 } else
03573 {
03574 {
03575 IkReal j1array[1], cj1array[1], sj1array[1];
03576 bool j1valid[1]={false};
03577 _nj1 = 1;
03578 IkReal x781=((IkReal(1.00000000000000))*(sj2));
03579 IkReal x782=((r20)*(sj5));
03580 IkReal x783=((IkReal(1.00000000000000))*(cj2));
03581 IkReal x784=((cj5)*(r21));
03582 IkReal x785=((cj5)*(r11)*(sj0));
03583 IkReal x786=((r10)*(sj0)*(sj5));
03584 IkReal x787=((cj0)*(r00)*(sj5));
03585 IkReal x788=((cj0)*(cj5)*(r01));
03586 if( IKabs(((gconst111)*(((((IkReal(-1.00000000000000))*(x783)*(x784)))+(((IkReal(-1.00000000000000))*(x781)*(x788)))+(((IkReal(-1.00000000000000))*(x781)*(x785)))+(((IkReal(-1.00000000000000))*(x781)*(x786)))+(((IkReal(-1.00000000000000))*(x782)*(x783)))+(((IkReal(-1.00000000000000))*(x781)*(x787))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst111)*(((((IkReal(-1.00000000000000))*(x781)*(x784)))+(((IkReal(-1.00000000000000))*(x781)*(x782)))+(((cj2)*(x785)))+(((cj2)*(x786)))+(((cj2)*(x788)))+(((cj2)*(x787))))))) < IKFAST_ATAN2_MAGTHRESH )
03587     continue;
03588 j1array[0]=IKatan2(((gconst111)*(((((IkReal(-1.00000000000000))*(x783)*(x784)))+(((IkReal(-1.00000000000000))*(x781)*(x788)))+(((IkReal(-1.00000000000000))*(x781)*(x785)))+(((IkReal(-1.00000000000000))*(x781)*(x786)))+(((IkReal(-1.00000000000000))*(x782)*(x783)))+(((IkReal(-1.00000000000000))*(x781)*(x787)))))), ((gconst111)*(((((IkReal(-1.00000000000000))*(x781)*(x784)))+(((IkReal(-1.00000000000000))*(x781)*(x782)))+(((cj2)*(x785)))+(((cj2)*(x786)))+(((cj2)*(x788)))+(((cj2)*(x787)))))));
03589 sj1array[0]=IKsin(j1array[0]);
03590 cj1array[0]=IKcos(j1array[0]);
03591 if( j1array[0] > IKPI )
03592 {
03593     j1array[0]-=IK2PI;
03594 }
03595 else if( j1array[0] < -IKPI )
03596 {    j1array[0]+=IK2PI;
03597 }
03598 j1valid[0] = true;
03599 for(int ij1 = 0; ij1 < 1; ++ij1)
03600 {
03601 if( !j1valid[ij1] )
03602 {
03603     continue;
03604 }
03605 _ij1[0] = ij1; _ij1[1] = -1;
03606 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03607 {
03608 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03609 {
03610     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03611 }
03612 }
03613 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03614 {
03615 IkReal evalcond[4];
03616 IkReal x789=IKsin(j1);
03617 IkReal x790=IKcos(j1);
03618 IkReal x791=((cj5)*(sj0));
03619 IkReal x792=((IkReal(1.00000000000000))*(r11));
03620 IkReal x793=((cj5)*(sj4));
03621 IkReal x794=((cj0)*(r00));
03622 IkReal x795=((IkReal(1.00000000000000))*(sj0));
03623 IkReal x796=((sj4)*(sj5));
03624 IkReal x797=((IkReal(1.00000000000000))*(cj0));
03625 IkReal x798=((sj2)*(x790));
03626 IkReal x799=((cj2)*(x789));
03627 IkReal x800=((cj2)*(x790));
03628 IkReal x801=((sj2)*(x789));
03629 IkReal x802=((x799)+(x798));
03630 evalcond[0]=((x802)+(((r20)*(sj5)))+(((cj5)*(r21))));
03631 evalcond[1]=((x801)+(((IkReal(-1.00000000000000))*(r20)*(x793)))+(((IkReal(-1.00000000000000))*(x800)))+(((cj4)*(r22)))+(((r21)*(x796))));
03632 evalcond[2]=((x800)+(((IkReal(-1.00000000000000))*(x801)))+(((IkReal(-1.00000000000000))*(x791)*(x792)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x797)))+(((IkReal(-1.00000000000000))*(sj5)*(x794)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x795))));
03633 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x797)))+(x802)+(((IkReal(-1.00000000000000))*(sj0)*(x792)*(x796)))+(((IkReal(-1.00000000000000))*(r01)*(x796)*(x797)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x795)))+(((x793)*(x794)))+(((r10)*(sj4)*(x791))));
03634 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03635 {
03636 continue;
03637 }
03638 }
03639 
03640 {
03641 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03642 vinfos[0].jointtype = 1;
03643 vinfos[0].foffset = j0;
03644 vinfos[0].indices[0] = _ij0[0];
03645 vinfos[0].indices[1] = _ij0[1];
03646 vinfos[0].maxsolutions = _nj0;
03647 vinfos[1].jointtype = 1;
03648 vinfos[1].foffset = j1;
03649 vinfos[1].indices[0] = _ij1[0];
03650 vinfos[1].indices[1] = _ij1[1];
03651 vinfos[1].maxsolutions = _nj1;
03652 vinfos[2].jointtype = 1;
03653 vinfos[2].foffset = j2;
03654 vinfos[2].indices[0] = _ij2[0];
03655 vinfos[2].indices[1] = _ij2[1];
03656 vinfos[2].maxsolutions = _nj2;
03657 vinfos[3].jointtype = 1;
03658 vinfos[3].foffset = j3;
03659 vinfos[3].indices[0] = _ij3[0];
03660 vinfos[3].indices[1] = _ij3[1];
03661 vinfos[3].maxsolutions = _nj3;
03662 vinfos[4].jointtype = 1;
03663 vinfos[4].foffset = j4;
03664 vinfos[4].indices[0] = _ij4[0];
03665 vinfos[4].indices[1] = _ij4[1];
03666 vinfos[4].maxsolutions = _nj4;
03667 vinfos[5].jointtype = 1;
03668 vinfos[5].foffset = j5;
03669 vinfos[5].indices[0] = _ij5[0];
03670 vinfos[5].indices[1] = _ij5[1];
03671 vinfos[5].maxsolutions = _nj5;
03672 std::vector<int> vfree(0);
03673 solutions.AddSolution(vinfos,vfree);
03674 }
03675 }
03676 }
03677 
03678 }
03679 
03680 }
03681 
03682 } else
03683 {
03684 {
03685 IkReal j1array[1], cj1array[1], sj1array[1];
03686 bool j1valid[1]={false};
03687 _nj1 = 1;
03688 IkReal x803=((cj4)*(r22));
03689 IkReal x804=((r20)*(sj5));
03690 IkReal x805=((cj5)*(r21));
03691 IkReal x806=((sj2)*(sj4));
03692 IkReal x807=((r21)*(sj5));
03693 IkReal x808=((IkReal(1.00000000000000))*(cj2));
03694 IkReal x809=((cj5)*(r20));
03695 if( IKabs(((gconst110)*(((((cj2)*(x804)))+(((IkReal(-1.00000000000000))*(x806)*(x809)))+(((cj2)*(x805)))+(((sj2)*(x803)))+(((x806)*(x807))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst110)*(((((cj2)*(sj4)*(x809)))+(((sj2)*(x804)))+(((sj2)*(x805)))+(((IkReal(-1.00000000000000))*(x803)*(x808)))+(((IkReal(-1.00000000000000))*(sj4)*(x807)*(x808))))))) < IKFAST_ATAN2_MAGTHRESH )
03696     continue;
03697 j1array[0]=IKatan2(((gconst110)*(((((cj2)*(x804)))+(((IkReal(-1.00000000000000))*(x806)*(x809)))+(((cj2)*(x805)))+(((sj2)*(x803)))+(((x806)*(x807)))))), ((gconst110)*(((((cj2)*(sj4)*(x809)))+(((sj2)*(x804)))+(((sj2)*(x805)))+(((IkReal(-1.00000000000000))*(x803)*(x808)))+(((IkReal(-1.00000000000000))*(sj4)*(x807)*(x808)))))));
03698 sj1array[0]=IKsin(j1array[0]);
03699 cj1array[0]=IKcos(j1array[0]);
03700 if( j1array[0] > IKPI )
03701 {
03702     j1array[0]-=IK2PI;
03703 }
03704 else if( j1array[0] < -IKPI )
03705 {    j1array[0]+=IK2PI;
03706 }
03707 j1valid[0] = true;
03708 for(int ij1 = 0; ij1 < 1; ++ij1)
03709 {
03710 if( !j1valid[ij1] )
03711 {
03712     continue;
03713 }
03714 _ij1[0] = ij1; _ij1[1] = -1;
03715 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03716 {
03717 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03718 {
03719     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03720 }
03721 }
03722 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03723 {
03724 IkReal evalcond[4];
03725 IkReal x810=IKsin(j1);
03726 IkReal x811=IKcos(j1);
03727 IkReal x812=((cj5)*(sj0));
03728 IkReal x813=((IkReal(1.00000000000000))*(r11));
03729 IkReal x814=((cj5)*(sj4));
03730 IkReal x815=((cj0)*(r00));
03731 IkReal x816=((IkReal(1.00000000000000))*(sj0));
03732 IkReal x817=((sj4)*(sj5));
03733 IkReal x818=((IkReal(1.00000000000000))*(cj0));
03734 IkReal x819=((sj2)*(x811));
03735 IkReal x820=((cj2)*(x810));
03736 IkReal x821=((cj2)*(x811));
03737 IkReal x822=((sj2)*(x810));
03738 IkReal x823=((x820)+(x819));
03739 evalcond[0]=((x823)+(((r20)*(sj5)))+(((cj5)*(r21))));
03740 evalcond[1]=((x822)+(((IkReal(-1.00000000000000))*(x821)))+(((cj4)*(r22)))+(((r21)*(x817)))+(((IkReal(-1.00000000000000))*(r20)*(x814))));
03741 evalcond[2]=((x821)+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x816)))+(((IkReal(-1.00000000000000))*(x822)))+(((IkReal(-1.00000000000000))*(sj5)*(x815)))+(((IkReal(-1.00000000000000))*(x812)*(x813)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x818))));
03742 evalcond[3]=((x823)+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x818)))+(((IkReal(-1.00000000000000))*(sj0)*(x813)*(x817)))+(((r10)*(sj4)*(x812)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x816)))+(((x814)*(x815)))+(((IkReal(-1.00000000000000))*(r01)*(x817)*(x818))));
03743 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03744 {
03745 continue;
03746 }
03747 }
03748 
03749 {
03750 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03751 vinfos[0].jointtype = 1;
03752 vinfos[0].foffset = j0;
03753 vinfos[0].indices[0] = _ij0[0];
03754 vinfos[0].indices[1] = _ij0[1];
03755 vinfos[0].maxsolutions = _nj0;
03756 vinfos[1].jointtype = 1;
03757 vinfos[1].foffset = j1;
03758 vinfos[1].indices[0] = _ij1[0];
03759 vinfos[1].indices[1] = _ij1[1];
03760 vinfos[1].maxsolutions = _nj1;
03761 vinfos[2].jointtype = 1;
03762 vinfos[2].foffset = j2;
03763 vinfos[2].indices[0] = _ij2[0];
03764 vinfos[2].indices[1] = _ij2[1];
03765 vinfos[2].maxsolutions = _nj2;
03766 vinfos[3].jointtype = 1;
03767 vinfos[3].foffset = j3;
03768 vinfos[3].indices[0] = _ij3[0];
03769 vinfos[3].indices[1] = _ij3[1];
03770 vinfos[3].maxsolutions = _nj3;
03771 vinfos[4].jointtype = 1;
03772 vinfos[4].foffset = j4;
03773 vinfos[4].indices[0] = _ij4[0];
03774 vinfos[4].indices[1] = _ij4[1];
03775 vinfos[4].maxsolutions = _nj4;
03776 vinfos[5].jointtype = 1;
03777 vinfos[5].foffset = j5;
03778 vinfos[5].indices[0] = _ij5[0];
03779 vinfos[5].indices[1] = _ij5[1];
03780 vinfos[5].maxsolutions = _nj5;
03781 std::vector<int> vfree(0);
03782 solutions.AddSolution(vinfos,vfree);
03783 }
03784 }
03785 }
03786 
03787 }
03788 
03789 }
03790 }
03791 }
03792 
03793 }
03794 
03795 }
03796 
03797 } else
03798 {
03799 {
03800 IkReal j1array[1], cj1array[1], sj1array[1];
03801 bool j1valid[1]={false};
03802 _nj1 = 1;
03803 IkReal x824=((cj4)*(r22));
03804 IkReal x825=((cj2)*(sj5));
03805 IkReal x826=((r21)*(sj4));
03806 IkReal x827=((cj2)*(cj5));
03807 IkReal x828=((sj2)*(sj5));
03808 IkReal x829=((r20)*(sj4));
03809 IkReal x830=((cj5)*(sj2));
03810 if( IKabs(((gconst109)*(((((x826)*(x828)))+(((r21)*(x827)))+(((sj2)*(x824)))+(((r20)*(x825)))+(((IkReal(-1.00000000000000))*(x829)*(x830))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst109)*(((((x827)*(x829)))+(((IkReal(-1.00000000000000))*(cj2)*(x824)))+(((IkReal(-1.00000000000000))*(x825)*(x826)))+(((r21)*(x830)))+(((r20)*(x828))))))) < IKFAST_ATAN2_MAGTHRESH )
03811     continue;
03812 j1array[0]=IKatan2(((gconst109)*(((((x826)*(x828)))+(((r21)*(x827)))+(((sj2)*(x824)))+(((r20)*(x825)))+(((IkReal(-1.00000000000000))*(x829)*(x830)))))), ((gconst109)*(((((x827)*(x829)))+(((IkReal(-1.00000000000000))*(cj2)*(x824)))+(((IkReal(-1.00000000000000))*(x825)*(x826)))+(((r21)*(x830)))+(((r20)*(x828)))))));
03813 sj1array[0]=IKsin(j1array[0]);
03814 cj1array[0]=IKcos(j1array[0]);
03815 if( j1array[0] > IKPI )
03816 {
03817     j1array[0]-=IK2PI;
03818 }
03819 else if( j1array[0] < -IKPI )
03820 {    j1array[0]+=IK2PI;
03821 }
03822 j1valid[0] = true;
03823 for(int ij1 = 0; ij1 < 1; ++ij1)
03824 {
03825 if( !j1valid[ij1] )
03826 {
03827     continue;
03828 }
03829 _ij1[0] = ij1; _ij1[1] = -1;
03830 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
03831 {
03832 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
03833 {
03834     j1valid[iij1]=false; _ij1[1] = iij1; break; 
03835 }
03836 }
03837 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
03838 {
03839 IkReal evalcond[2];
03840 IkReal x831=IKsin(j1);
03841 IkReal x832=IKcos(j1);
03842 evalcond[0]=((((cj2)*(x831)))+(((sj2)*(x832)))+(((r20)*(sj5)))+(((cj5)*(r21))));
03843 evalcond[1]=((((IkReal(-1.00000000000000))*(cj5)*(r20)*(sj4)))+(((sj2)*(x831)))+(((IkReal(-1.00000000000000))*(cj2)*(x832)))+(((cj4)*(r22)))+(((r21)*(sj4)*(sj5))));
03844 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
03845 {
03846 continue;
03847 }
03848 }
03849 
03850 {
03851 IkReal dummyeval[1];
03852 IkReal gconst113;
03853 IkReal x833=(sj5)*(sj5);
03854 IkReal x834=(cj5)*(cj5);
03855 IkReal x835=((cj5)*(sj4));
03856 IkReal x836=((IkReal(1.00000000000000))*(r02));
03857 IkReal x837=((sj4)*(sj5));
03858 IkReal x838=((cj4)*(r01)*(r10));
03859 IkReal x839=((IkReal(1.00000000000000))*(cj4)*(r00)*(r11));
03860 gconst113=IKsign(((((IkReal(-1.00000000000000))*(x834)*(x839)))+(((x833)*(x838)))+(((IkReal(-1.00000000000000))*(r10)*(x836)*(x837)))+(((IkReal(-1.00000000000000))*(r11)*(x835)*(x836)))+(((x834)*(x838)))+(((IkReal(-1.00000000000000))*(x833)*(x839)))+(((r00)*(r12)*(x837)))+(((r01)*(r12)*(x835)))));
03861 IkReal x840=(sj5)*(sj5);
03862 IkReal x841=(cj5)*(cj5);
03863 IkReal x842=((cj5)*(sj4));
03864 IkReal x843=((IkReal(1.00000000000000))*(r02));
03865 IkReal x844=((sj4)*(sj5));
03866 IkReal x845=((cj4)*(r01)*(r10));
03867 IkReal x846=x839;
03868 dummyeval[0]=((((x841)*(x845)))+(((r00)*(r12)*(x844)))+(((IkReal(-1.00000000000000))*(r11)*(x842)*(x843)))+(((IkReal(-1.00000000000000))*(x841)*(x846)))+(((r01)*(r12)*(x842)))+(((IkReal(-1.00000000000000))*(r10)*(x843)*(x844)))+(((x840)*(x845)))+(((IkReal(-1.00000000000000))*(x840)*(x846))));
03869 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03870 {
03871 {
03872 IkReal dummyeval[1];
03873 IkReal gconst112;
03874 IkReal x847=(cj5)*(cj5);
03875 IkReal x848=(sj5)*(sj5);
03876 IkReal x849=((IkReal(1.00000000000000))*(x848));
03877 IkReal x850=((IkReal(2.00000000000000))*(cj5)*(sj5));
03878 IkReal x851=((IkReal(1.00000000000000))*(x847));
03879 gconst112=IKsign(((((IkReal(-1.00000000000000))*(x851)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x849)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x849)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x850)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x850)))+(((IkReal(-1.00000000000000))*(x851)*((r01)*(r01))))));
03880 IkReal x852=(cj5)*(cj5);
03881 IkReal x853=(sj5)*(sj5);
03882 IkReal x854=((IkReal(1.00000000000000))*(x853));
03883 IkReal x855=((IkReal(2.00000000000000))*(cj5)*(sj5));
03884 IkReal x856=((IkReal(1.00000000000000))*(x852));
03885 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(r11)*(x855)))+(((IkReal(-1.00000000000000))*(x854)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x854)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x855)))+(((IkReal(-1.00000000000000))*(x856)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x856)*((r01)*(r01)))));
03886 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03887 {
03888 continue;
03889 
03890 } else
03891 {
03892 {
03893 IkReal j0array[1], cj0array[1], sj0array[1];
03894 bool j0valid[1]={false};
03895 _nj0 = 1;
03896 IkReal x857=((sj1)*(sj2));
03897 IkReal x858=((IkReal(1.00000000000000))*(cj1)*(cj2)*(cj5));
03898 IkReal x859=((IkReal(1.00000000000000))*(cj1)*(cj2)*(sj5));
03899 if( IKabs(((gconst112)*(((((cj5)*(r11)*(x857)))+(((IkReal(-1.00000000000000))*(r11)*(x858)))+(((IkReal(-1.00000000000000))*(r10)*(x859)))+(((r10)*(sj5)*(x857))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst112)*(((((r00)*(sj5)*(x857)))+(((IkReal(-1.00000000000000))*(r01)*(x858)))+(((cj5)*(r01)*(x857)))+(((IkReal(-1.00000000000000))*(r00)*(x859))))))) < IKFAST_ATAN2_MAGTHRESH )
03900     continue;
03901 j0array[0]=IKatan2(((gconst112)*(((((cj5)*(r11)*(x857)))+(((IkReal(-1.00000000000000))*(r11)*(x858)))+(((IkReal(-1.00000000000000))*(r10)*(x859)))+(((r10)*(sj5)*(x857)))))), ((gconst112)*(((((r00)*(sj5)*(x857)))+(((IkReal(-1.00000000000000))*(r01)*(x858)))+(((cj5)*(r01)*(x857)))+(((IkReal(-1.00000000000000))*(r00)*(x859)))))));
03902 sj0array[0]=IKsin(j0array[0]);
03903 cj0array[0]=IKcos(j0array[0]);
03904 if( j0array[0] > IKPI )
03905 {
03906     j0array[0]-=IK2PI;
03907 }
03908 else if( j0array[0] < -IKPI )
03909 {    j0array[0]+=IK2PI;
03910 }
03911 j0valid[0] = true;
03912 for(int ij0 = 0; ij0 < 1; ++ij0)
03913 {
03914 if( !j0valid[ij0] )
03915 {
03916     continue;
03917 }
03918 _ij0[0] = ij0; _ij0[1] = -1;
03919 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
03920 {
03921 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
03922 {
03923     j0valid[iij0]=false; _ij0[1] = iij0; break; 
03924 }
03925 }
03926 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
03927 {
03928 IkReal evalcond[6];
03929 IkReal x860=IKsin(j0);
03930 IkReal x861=IKcos(j0);
03931 IkReal x862=((IkReal(1.00000000000000))*(r10));
03932 IkReal x863=((IkReal(1.00000000000000))*(sj4));
03933 IkReal x864=((cj5)*(r01));
03934 IkReal x865=((cj5)*(r00));
03935 IkReal x866=((cj4)*(r01));
03936 IkReal x867=((IkReal(1.00000000000000))*(cj4));
03937 IkReal x868=((cj4)*(r11));
03938 IkReal x869=((sj5)*(x860));
03939 IkReal x870=((r11)*(x863));
03940 IkReal x871=((sj5)*(x861));
03941 IkReal x872=((r02)*(x861));
03942 IkReal x873=((r12)*(x861));
03943 IkReal x874=((IkReal(1.00000000000000))*(x861));
03944 IkReal x875=((cj4)*(x860));
03945 IkReal x876=((cj5)*(x860));
03946 IkReal x877=((cj5)*(sj4)*(x861));
03947 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x874)))+(((r00)*(x869)))+(((IkReal(-1.00000000000000))*(x862)*(x871)))+(((x860)*(x864))));
03948 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r00)*(x871)))+(((IkReal(-1.00000000000000))*(r11)*(x876)))+(((cj1)*(cj2)))+(((IkReal(-1.00000000000000))*(x864)*(x874)))+(((IkReal(-1.00000000000000))*(x862)*(x869))));
03949 evalcond[2]=((((IkReal(-1.00000000000000))*(x860)*(x863)*(x865)))+(((IkReal(-1.00000000000000))*(x870)*(x871)))+(((r10)*(x877)))+(((r01)*(sj4)*(x869)))+(((IkReal(-1.00000000000000))*(x867)*(x873)))+(((r02)*(x875))));
03950 evalcond[3]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x866)*(x869)))+(((x868)*(x871)))+(((r02)*(sj4)*(x860)))+(((IkReal(-1.00000000000000))*(x863)*(x873)))+(((x865)*(x875)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x861)*(x862))));
03951 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x869)*(x870)))+(((IkReal(-1.00000000000000))*(r01)*(x863)*(x871)))+(((r10)*(sj4)*(x876)))+(((IkReal(-1.00000000000000))*(x867)*(x872)))+(((sj4)*(x861)*(x865)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(r12)*(x860)*(x867))));
03952 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(x862)*(x875)))+(((x866)*(x871)))+(((x868)*(x869)))+(((IkReal(-1.00000000000000))*(x861)*(x865)*(x867)))+(((IkReal(-1.00000000000000))*(x863)*(x872)))+(((IkReal(-1.00000000000000))*(r12)*(x860)*(x863))));
03953 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  )
03954 {
03955 continue;
03956 }
03957 }
03958 
03959 {
03960 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03961 vinfos[0].jointtype = 1;
03962 vinfos[0].foffset = j0;
03963 vinfos[0].indices[0] = _ij0[0];
03964 vinfos[0].indices[1] = _ij0[1];
03965 vinfos[0].maxsolutions = _nj0;
03966 vinfos[1].jointtype = 1;
03967 vinfos[1].foffset = j1;
03968 vinfos[1].indices[0] = _ij1[0];
03969 vinfos[1].indices[1] = _ij1[1];
03970 vinfos[1].maxsolutions = _nj1;
03971 vinfos[2].jointtype = 1;
03972 vinfos[2].foffset = j2;
03973 vinfos[2].indices[0] = _ij2[0];
03974 vinfos[2].indices[1] = _ij2[1];
03975 vinfos[2].maxsolutions = _nj2;
03976 vinfos[3].jointtype = 1;
03977 vinfos[3].foffset = j3;
03978 vinfos[3].indices[0] = _ij3[0];
03979 vinfos[3].indices[1] = _ij3[1];
03980 vinfos[3].maxsolutions = _nj3;
03981 vinfos[4].jointtype = 1;
03982 vinfos[4].foffset = j4;
03983 vinfos[4].indices[0] = _ij4[0];
03984 vinfos[4].indices[1] = _ij4[1];
03985 vinfos[4].maxsolutions = _nj4;
03986 vinfos[5].jointtype = 1;
03987 vinfos[5].foffset = j5;
03988 vinfos[5].indices[0] = _ij5[0];
03989 vinfos[5].indices[1] = _ij5[1];
03990 vinfos[5].maxsolutions = _nj5;
03991 std::vector<int> vfree(0);
03992 solutions.AddSolution(vinfos,vfree);
03993 }
03994 }
03995 }
03996 
03997 }
03998 
03999 }
04000 
04001 } else
04002 {
04003 {
04004 IkReal j0array[1], cj0array[1], sj0array[1];
04005 bool j0valid[1]={false};
04006 _nj0 = 1;
04007 IkReal x878=((IkReal(1.00000000000000))*(cj5));
04008 IkReal x879=((IkReal(1.00000000000000))*(sj5));
04009 if( IKabs(((gconst113)*(((((IkReal(-1.00000000000000))*(r10)*(x879)))+(((IkReal(-1.00000000000000))*(r11)*(x878))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst113)*(((((IkReal(-1.00000000000000))*(r00)*(x879)))+(((IkReal(-1.00000000000000))*(r01)*(x878))))))) < IKFAST_ATAN2_MAGTHRESH )
04010     continue;
04011 j0array[0]=IKatan2(((gconst113)*(((((IkReal(-1.00000000000000))*(r10)*(x879)))+(((IkReal(-1.00000000000000))*(r11)*(x878)))))), ((gconst113)*(((((IkReal(-1.00000000000000))*(r00)*(x879)))+(((IkReal(-1.00000000000000))*(r01)*(x878)))))));
04012 sj0array[0]=IKsin(j0array[0]);
04013 cj0array[0]=IKcos(j0array[0]);
04014 if( j0array[0] > IKPI )
04015 {
04016     j0array[0]-=IK2PI;
04017 }
04018 else if( j0array[0] < -IKPI )
04019 {    j0array[0]+=IK2PI;
04020 }
04021 j0valid[0] = true;
04022 for(int ij0 = 0; ij0 < 1; ++ij0)
04023 {
04024 if( !j0valid[ij0] )
04025 {
04026     continue;
04027 }
04028 _ij0[0] = ij0; _ij0[1] = -1;
04029 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04030 {
04031 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04032 {
04033     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04034 }
04035 }
04036 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04037 {
04038 IkReal evalcond[6];
04039 IkReal x880=IKsin(j0);
04040 IkReal x881=IKcos(j0);
04041 IkReal x882=((IkReal(1.00000000000000))*(r10));
04042 IkReal x883=((IkReal(1.00000000000000))*(sj4));
04043 IkReal x884=((cj5)*(r01));
04044 IkReal x885=((cj5)*(r00));
04045 IkReal x886=((cj4)*(r01));
04046 IkReal x887=((IkReal(1.00000000000000))*(cj4));
04047 IkReal x888=((cj4)*(r11));
04048 IkReal x889=((sj5)*(x880));
04049 IkReal x890=((r11)*(x883));
04050 IkReal x891=((sj5)*(x881));
04051 IkReal x892=((r02)*(x881));
04052 IkReal x893=((r12)*(x881));
04053 IkReal x894=((IkReal(1.00000000000000))*(x881));
04054 IkReal x895=((cj4)*(x880));
04055 IkReal x896=((cj5)*(x880));
04056 IkReal x897=((cj5)*(sj4)*(x881));
04057 evalcond[0]=((((r00)*(x889)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x894)))+(((IkReal(-1.00000000000000))*(x882)*(x891)))+(((x880)*(x884))));
04058 evalcond[1]=((((IkReal(-1.00000000000000))*(sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x884)*(x894)))+(((IkReal(-1.00000000000000))*(r11)*(x896)))+(((IkReal(-1.00000000000000))*(x882)*(x889)))+(((IkReal(-1.00000000000000))*(r00)*(x891)))+(((cj1)*(cj2))));
04059 evalcond[2]=((((IkReal(-1.00000000000000))*(x887)*(x893)))+(((IkReal(-1.00000000000000))*(x880)*(x883)*(x885)))+(((r02)*(x895)))+(((r01)*(sj4)*(x889)))+(((IkReal(-1.00000000000000))*(x890)*(x891)))+(((r10)*(x897))));
04060 evalcond[3]=((IkReal(-1.00000000000000))+(((x888)*(x891)))+(((IkReal(-1.00000000000000))*(x886)*(x889)))+(((IkReal(-1.00000000000000))*(x883)*(x893)))+(((r02)*(sj4)*(x880)))+(((x885)*(x895)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x881)*(x882))));
04061 evalcond[4]=((((cj1)*(sj2)))+(((sj4)*(x881)*(x885)))+(((IkReal(-1.00000000000000))*(x887)*(x892)))+(((IkReal(-1.00000000000000))*(r12)*(x880)*(x887)))+(((r10)*(sj4)*(x896)))+(((IkReal(-1.00000000000000))*(x889)*(x890)))+(((IkReal(-1.00000000000000))*(r01)*(x883)*(x891)))+(((cj2)*(sj1))));
04062 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(x882)*(x895)))+(((x888)*(x889)))+(((x886)*(x891)))+(((IkReal(-1.00000000000000))*(x881)*(x885)*(x887)))+(((IkReal(-1.00000000000000))*(r12)*(x880)*(x883)))+(((IkReal(-1.00000000000000))*(x883)*(x892))));
04063 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  )
04064 {
04065 continue;
04066 }
04067 }
04068 
04069 {
04070 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04071 vinfos[0].jointtype = 1;
04072 vinfos[0].foffset = j0;
04073 vinfos[0].indices[0] = _ij0[0];
04074 vinfos[0].indices[1] = _ij0[1];
04075 vinfos[0].maxsolutions = _nj0;
04076 vinfos[1].jointtype = 1;
04077 vinfos[1].foffset = j1;
04078 vinfos[1].indices[0] = _ij1[0];
04079 vinfos[1].indices[1] = _ij1[1];
04080 vinfos[1].maxsolutions = _nj1;
04081 vinfos[2].jointtype = 1;
04082 vinfos[2].foffset = j2;
04083 vinfos[2].indices[0] = _ij2[0];
04084 vinfos[2].indices[1] = _ij2[1];
04085 vinfos[2].maxsolutions = _nj2;
04086 vinfos[3].jointtype = 1;
04087 vinfos[3].foffset = j3;
04088 vinfos[3].indices[0] = _ij3[0];
04089 vinfos[3].indices[1] = _ij3[1];
04090 vinfos[3].maxsolutions = _nj3;
04091 vinfos[4].jointtype = 1;
04092 vinfos[4].foffset = j4;
04093 vinfos[4].indices[0] = _ij4[0];
04094 vinfos[4].indices[1] = _ij4[1];
04095 vinfos[4].maxsolutions = _nj4;
04096 vinfos[5].jointtype = 1;
04097 vinfos[5].foffset = j5;
04098 vinfos[5].indices[0] = _ij5[0];
04099 vinfos[5].indices[1] = _ij5[1];
04100 vinfos[5].maxsolutions = _nj5;
04101 std::vector<int> vfree(0);
04102 solutions.AddSolution(vinfos,vfree);
04103 }
04104 }
04105 }
04106 
04107 }
04108 
04109 }
04110 }
04111 }
04112 
04113 }
04114 
04115 }
04116 
04117 } else
04118 {
04119 IkReal x898=((cj5)*(npx));
04120 IkReal x899=((npy)*(sj5));
04121 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959))));
04122 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
04123 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-1.00000000000000))*(sj4)*(x898)))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x899))));
04124 evalcond[3]=((((IkReal(0.350000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(cj4)*(x899)))+(((cj4)*(x898)))+(((npz)*(sj4))));
04125 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
04126 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  )
04127 {
04128 {
04129 IkReal dummyeval[1];
04130 IkReal gconst114;
04131 IkReal x900=(sj5)*(sj5);
04132 IkReal x901=(cj5)*(cj5);
04133 IkReal x902=((IkReal(2.00000000000000))*(cj5)*(sj5));
04134 gconst114=IKsign(((((r00)*(r01)*(x902)))+(((x901)*((r11)*(r11))))+(((x900)*((r00)*(r00))))+(((r10)*(r11)*(x902)))+(((x901)*((r01)*(r01))))+(((x900)*((r10)*(r10))))));
04135 IkReal x903=(sj5)*(sj5);
04136 IkReal x904=(cj5)*(cj5);
04137 IkReal x905=((IkReal(2.00000000000000))*(cj5)*(sj5));
04138 dummyeval[0]=((((x904)*((r11)*(r11))))+(((r10)*(r11)*(x905)))+(((x903)*((r10)*(r10))))+(((r00)*(r01)*(x905)))+(((x904)*((r01)*(r01))))+(((x903)*((r00)*(r00)))));
04139 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04140 {
04141 {
04142 IkReal dummyeval[1];
04143 IkReal gconst116;
04144 gconst116=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
04145 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
04146 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04147 {
04148 {
04149 IkReal dummyeval[1];
04150 IkReal gconst115;
04151 IkReal x906=(cj5)*(cj5);
04152 IkReal x907=(sj5)*(sj5);
04153 IkReal x908=((IkReal(1.00000000000000))*(r10));
04154 IkReal x909=((cj4)*(sj5));
04155 IkReal x910=((r00)*(r11));
04156 IkReal x911=((cj4)*(cj5));
04157 IkReal x912=((sj4)*(x906));
04158 IkReal x913=((sj4)*(x907));
04159 gconst115=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x908)*(x913)))+(((IkReal(-1.00000000000000))*(r01)*(x908)*(x912)))+(((x910)*(x913)))+(((IkReal(-1.00000000000000))*(r02)*(x908)*(x909)))+(((x910)*(x912)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x911)))+(((r00)*(r12)*(x909)))+(((r01)*(r12)*(x911)))));
04160 IkReal x914=(cj5)*(cj5);
04161 IkReal x915=(sj5)*(sj5);
04162 IkReal x916=((IkReal(1.00000000000000))*(r10));
04163 IkReal x917=((cj4)*(sj5));
04164 IkReal x918=((r00)*(r11));
04165 IkReal x919=((cj4)*(cj5));
04166 IkReal x920=((sj4)*(x914));
04167 IkReal x921=((sj4)*(x915));
04168 dummyeval[0]=((((x918)*(x921)))+(((IkReal(-1.00000000000000))*(r01)*(x916)*(x920)))+(((IkReal(-1.00000000000000))*(r02)*(x916)*(x917)))+(((r00)*(r12)*(x917)))+(((r01)*(r12)*(x919)))+(((IkReal(-1.00000000000000))*(r01)*(x916)*(x921)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x919)))+(((x918)*(x920))));
04169 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04170 {
04171 continue;
04172 
04173 } else
04174 {
04175 {
04176 IkReal j0array[1], cj0array[1], sj0array[1];
04177 bool j0valid[1]={false};
04178 _nj0 = 1;
04179 IkReal x922=((cj5)*(sj4));
04180 IkReal x923=((IkReal(1.00000000000000))*(cj4));
04181 IkReal x924=((IkReal(1.00000000000000))*(sj4)*(sj5));
04182 if( IKabs(((gconst115)*(((((IkReal(-1.00000000000000))*(r11)*(x924)))+(((IkReal(-1.00000000000000))*(r12)*(x923)))+(((r10)*(x922))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst115)*(((((IkReal(-1.00000000000000))*(r01)*(x924)))+(((r00)*(x922)))+(((IkReal(-1.00000000000000))*(r02)*(x923))))))) < IKFAST_ATAN2_MAGTHRESH )
04183     continue;
04184 j0array[0]=IKatan2(((gconst115)*(((((IkReal(-1.00000000000000))*(r11)*(x924)))+(((IkReal(-1.00000000000000))*(r12)*(x923)))+(((r10)*(x922)))))), ((gconst115)*(((((IkReal(-1.00000000000000))*(r01)*(x924)))+(((r00)*(x922)))+(((IkReal(-1.00000000000000))*(r02)*(x923)))))));
04185 sj0array[0]=IKsin(j0array[0]);
04186 cj0array[0]=IKcos(j0array[0]);
04187 if( j0array[0] > IKPI )
04188 {
04189     j0array[0]-=IK2PI;
04190 }
04191 else if( j0array[0] < -IKPI )
04192 {    j0array[0]+=IK2PI;
04193 }
04194 j0valid[0] = true;
04195 for(int ij0 = 0; ij0 < 1; ++ij0)
04196 {
04197 if( !j0valid[ij0] )
04198 {
04199     continue;
04200 }
04201 _ij0[0] = ij0; _ij0[1] = -1;
04202 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04203 {
04204 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04205 {
04206     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04207 }
04208 }
04209 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04210 {
04211 IkReal evalcond[4];
04212 IkReal x925=IKsin(j0);
04213 IkReal x926=IKcos(j0);
04214 IkReal x927=((IkReal(1.00000000000000))*(cj5));
04215 IkReal x928=((r01)*(sj5));
04216 IkReal x929=((IkReal(1.00000000000000))*(r12));
04217 IkReal x930=((IkReal(1.00000000000000))*(r10));
04218 IkReal x931=((r11)*(sj5));
04219 IkReal x932=((cj4)*(x925));
04220 IkReal x933=((sj4)*(x925));
04221 IkReal x934=((sj4)*(x926));
04222 IkReal x935=((sj5)*(x925));
04223 IkReal x936=((cj4)*(x926));
04224 IkReal x937=((sj5)*(x926));
04225 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x930)*(x937)))+(((r00)*(x935)))+(((IkReal(-1.00000000000000))*(r11)*(x926)*(x927)))+(((cj5)*(r01)*(x925))));
04226 evalcond[1]=((((IkReal(-1.00000000000000))*(r01)*(x926)*(x927)))+(((IkReal(-1.00000000000000))*(r00)*(x937)))+(((IkReal(-1.00000000000000))*(r11)*(x925)*(x927)))+(((IkReal(-1.00000000000000))*(x930)*(x935))));
04227 evalcond[2]=((((IkReal(-1.00000000000000))*(x931)*(x934)))+(((x928)*(x933)))+(((IkReal(-1.00000000000000))*(r00)*(x927)*(x933)))+(((IkReal(-1.00000000000000))*(x929)*(x936)))+(((r02)*(x932)))+(((cj5)*(r10)*(x934))));
04228 evalcond[3]=((((x931)*(x936)))+(((IkReal(-1.00000000000000))*(r10)*(x927)*(x936)))+(((r02)*(x933)))+(((IkReal(-1.00000000000000))*(x928)*(x932)))+(((IkReal(-1.00000000000000))*(x929)*(x934)))+(((cj5)*(r00)*(x932))));
04229 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04230 {
04231 continue;
04232 }
04233 }
04234 
04235 {
04236 IkReal dummyeval[1];
04237 IkReal gconst117;
04238 gconst117=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
04239 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
04240 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04241 {
04242 {
04243 IkReal dummyeval[1];
04244 IkReal gconst118;
04245 gconst118=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
04246 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
04247 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04248 {
04249 continue;
04250 
04251 } else
04252 {
04253 {
04254 IkReal j1array[1], cj1array[1], sj1array[1];
04255 bool j1valid[1]={false};
04256 _nj1 = 1;
04257 IkReal x938=((cj4)*(r22));
04258 IkReal x939=((r11)*(sj0));
04259 IkReal x940=((IkReal(1.00000000000000))*(cj2));
04260 IkReal x941=((sj2)*(sj4));
04261 IkReal x942=((IkReal(1.00000000000000))*(sj2));
04262 IkReal x943=((cj2)*(sj4));
04263 IkReal x944=((cj0)*(r01));
04264 IkReal x945=((cj5)*(r20));
04265 IkReal x946=((IkReal(1.00000000000000))*(sj4)*(sj5));
04266 IkReal x947=((cj0)*(cj4)*(r02));
04267 IkReal x948=((cj4)*(r12)*(sj0));
04268 IkReal x949=((cj5)*(r10)*(sj0));
04269 IkReal x950=((cj0)*(cj5)*(r00));
04270 if( IKabs(((gconst118)*(((((r21)*(sj5)*(x941)))+(((IkReal(-1.00000000000000))*(x941)*(x945)))+(((IkReal(-1.00000000000000))*(x940)*(x948)))+(((IkReal(-1.00000000000000))*(x940)*(x947)))+(((x943)*(x949)))+(((sj2)*(x938)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x940)*(x944)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x939)*(x940)))+(((x943)*(x950))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst118)*(((((IkReal(-1.00000000000000))*(sj5)*(x939)*(x941)))+(((IkReal(-1.00000000000000))*(sj5)*(x941)*(x944)))+(((x941)*(x949)))+(((IkReal(-1.00000000000000))*(x942)*(x947)))+(((x943)*(x945)))+(((IkReal(-1.00000000000000))*(x942)*(x948)))+(((IkReal(-1.00000000000000))*(x938)*(x940)))+(((x941)*(x950)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x940))))))) < IKFAST_ATAN2_MAGTHRESH )
04271     continue;
04272 j1array[0]=IKatan2(((gconst118)*(((((r21)*(sj5)*(x941)))+(((IkReal(-1.00000000000000))*(x941)*(x945)))+(((IkReal(-1.00000000000000))*(x940)*(x948)))+(((IkReal(-1.00000000000000))*(x940)*(x947)))+(((x943)*(x949)))+(((sj2)*(x938)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x940)*(x944)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x939)*(x940)))+(((x943)*(x950)))))), ((gconst118)*(((((IkReal(-1.00000000000000))*(sj5)*(x939)*(x941)))+(((IkReal(-1.00000000000000))*(sj5)*(x941)*(x944)))+(((x941)*(x949)))+(((IkReal(-1.00000000000000))*(x942)*(x947)))+(((x943)*(x945)))+(((IkReal(-1.00000000000000))*(x942)*(x948)))+(((IkReal(-1.00000000000000))*(x938)*(x940)))+(((x941)*(x950)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x940)))))));
04273 sj1array[0]=IKsin(j1array[0]);
04274 cj1array[0]=IKcos(j1array[0]);
04275 if( j1array[0] > IKPI )
04276 {
04277     j1array[0]-=IK2PI;
04278 }
04279 else if( j1array[0] < -IKPI )
04280 {    j1array[0]+=IK2PI;
04281 }
04282 j1valid[0] = true;
04283 for(int ij1 = 0; ij1 < 1; ++ij1)
04284 {
04285 if( !j1valid[ij1] )
04286 {
04287     continue;
04288 }
04289 _ij1[0] = ij1; _ij1[1] = -1;
04290 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04291 {
04292 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04293 {
04294     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04295 }
04296 }
04297 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04298 {
04299 IkReal evalcond[4];
04300 IkReal x951=IKcos(j1);
04301 IkReal x952=IKsin(j1);
04302 IkReal x953=((IkReal(1.00000000000000))*(sj4));
04303 IkReal x954=((cj5)*(r00));
04304 IkReal x955=((cj5)*(r20));
04305 IkReal x956=((r12)*(sj0));
04306 IkReal x957=((r21)*(sj5));
04307 IkReal x958=((IkReal(1.00000000000000))*(cj4));
04308 IkReal x959=((sj2)*(x951));
04309 IkReal x960=((cj2)*(x952));
04310 IkReal x961=((cj2)*(x951));
04311 IkReal x962=((r11)*(sj0)*(sj5));
04312 IkReal x963=((cj0)*(x958));
04313 IkReal x964=((cj0)*(r01)*(sj5));
04314 IkReal x965=((cj5)*(r10)*(sj0));
04315 IkReal x966=((sj2)*(x952));
04316 IkReal x967=((x959)+(x960));
04317 evalcond[0]=((((IkReal(-1.00000000000000))*(x961)))+(((cj4)*(r22)))+(((sj4)*(x957)))+(x966)+(((IkReal(-1.00000000000000))*(x953)*(x955))));
04318 evalcond[1]=((((IkReal(-1.00000000000000))*(x957)*(x958)))+(((r22)*(sj4)))+(((cj4)*(x955)))+(x967));
04319 evalcond[2]=((((IkReal(-1.00000000000000))*(x953)*(x962)))+(((IkReal(-1.00000000000000))*(x953)*(x964)))+(((IkReal(-1.00000000000000))*(x956)*(x958)))+(((cj0)*(sj4)*(x954)))+(x967)+(((sj4)*(x965)))+(((IkReal(-1.00000000000000))*(r02)*(x963))));
04320 evalcond[3]=((((cj4)*(x962)))+(((IkReal(-1.00000000000000))*(x958)*(x965)))+(((IkReal(-1.00000000000000))*(x966)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x953)))+(((IkReal(-1.00000000000000))*(x953)*(x956)))+(((IkReal(-1.00000000000000))*(x954)*(x963)))+(x961)+(((cj4)*(x964))));
04321 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04322 {
04323 continue;
04324 }
04325 }
04326 
04327 {
04328 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04329 vinfos[0].jointtype = 1;
04330 vinfos[0].foffset = j0;
04331 vinfos[0].indices[0] = _ij0[0];
04332 vinfos[0].indices[1] = _ij0[1];
04333 vinfos[0].maxsolutions = _nj0;
04334 vinfos[1].jointtype = 1;
04335 vinfos[1].foffset = j1;
04336 vinfos[1].indices[0] = _ij1[0];
04337 vinfos[1].indices[1] = _ij1[1];
04338 vinfos[1].maxsolutions = _nj1;
04339 vinfos[2].jointtype = 1;
04340 vinfos[2].foffset = j2;
04341 vinfos[2].indices[0] = _ij2[0];
04342 vinfos[2].indices[1] = _ij2[1];
04343 vinfos[2].maxsolutions = _nj2;
04344 vinfos[3].jointtype = 1;
04345 vinfos[3].foffset = j3;
04346 vinfos[3].indices[0] = _ij3[0];
04347 vinfos[3].indices[1] = _ij3[1];
04348 vinfos[3].maxsolutions = _nj3;
04349 vinfos[4].jointtype = 1;
04350 vinfos[4].foffset = j4;
04351 vinfos[4].indices[0] = _ij4[0];
04352 vinfos[4].indices[1] = _ij4[1];
04353 vinfos[4].maxsolutions = _nj4;
04354 vinfos[5].jointtype = 1;
04355 vinfos[5].foffset = j5;
04356 vinfos[5].indices[0] = _ij5[0];
04357 vinfos[5].indices[1] = _ij5[1];
04358 vinfos[5].maxsolutions = _nj5;
04359 std::vector<int> vfree(0);
04360 solutions.AddSolution(vinfos,vfree);
04361 }
04362 }
04363 }
04364 
04365 }
04366 
04367 }
04368 
04369 } else
04370 {
04371 {
04372 IkReal j1array[1], cj1array[1], sj1array[1];
04373 bool j1valid[1]={false};
04374 _nj1 = 1;
04375 IkReal x968=((cj4)*(r22));
04376 IkReal x969=((cj2)*(sj4));
04377 IkReal x970=((sj2)*(sj4));
04378 IkReal x971=((r21)*(sj5));
04379 IkReal x972=((cj5)*(r20));
04380 IkReal x973=((cj4)*(sj2));
04381 IkReal x974=((IkReal(1.00000000000000))*(cj2)*(x971));
04382 if( IKabs(((gconst117)*(((((sj2)*(x968)))+(((IkReal(-1.00000000000000))*(x970)*(x972)))+(((cj2)*(cj4)*(x972)))+(((r22)*(x969)))+(((IkReal(-1.00000000000000))*(cj4)*(x974)))+(((x970)*(x971))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst117)*(((((IkReal(-1.00000000000000))*(cj2)*(x968)))+(((r22)*(x970)))+(((x972)*(x973)))+(((IkReal(-1.00000000000000))*(x971)*(x973)))+(((x969)*(x972)))+(((IkReal(-1.00000000000000))*(x969)*(x971))))))) < IKFAST_ATAN2_MAGTHRESH )
04383     continue;
04384 j1array[0]=IKatan2(((gconst117)*(((((sj2)*(x968)))+(((IkReal(-1.00000000000000))*(x970)*(x972)))+(((cj2)*(cj4)*(x972)))+(((r22)*(x969)))+(((IkReal(-1.00000000000000))*(cj4)*(x974)))+(((x970)*(x971)))))), ((gconst117)*(((((IkReal(-1.00000000000000))*(cj2)*(x968)))+(((r22)*(x970)))+(((x972)*(x973)))+(((IkReal(-1.00000000000000))*(x971)*(x973)))+(((x969)*(x972)))+(((IkReal(-1.00000000000000))*(x969)*(x971)))))));
04385 sj1array[0]=IKsin(j1array[0]);
04386 cj1array[0]=IKcos(j1array[0]);
04387 if( j1array[0] > IKPI )
04388 {
04389     j1array[0]-=IK2PI;
04390 }
04391 else if( j1array[0] < -IKPI )
04392 {    j1array[0]+=IK2PI;
04393 }
04394 j1valid[0] = true;
04395 for(int ij1 = 0; ij1 < 1; ++ij1)
04396 {
04397 if( !j1valid[ij1] )
04398 {
04399     continue;
04400 }
04401 _ij1[0] = ij1; _ij1[1] = -1;
04402 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04403 {
04404 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04405 {
04406     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04407 }
04408 }
04409 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04410 {
04411 IkReal evalcond[4];
04412 IkReal x975=IKcos(j1);
04413 IkReal x976=IKsin(j1);
04414 IkReal x977=((IkReal(1.00000000000000))*(sj4));
04415 IkReal x978=((cj5)*(r00));
04416 IkReal x979=((cj5)*(r20));
04417 IkReal x980=((r12)*(sj0));
04418 IkReal x981=((r21)*(sj5));
04419 IkReal x982=((IkReal(1.00000000000000))*(cj4));
04420 IkReal x983=((sj2)*(x975));
04421 IkReal x984=((cj2)*(x976));
04422 IkReal x985=((cj2)*(x975));
04423 IkReal x986=((r11)*(sj0)*(sj5));
04424 IkReal x987=((cj0)*(x982));
04425 IkReal x988=((cj0)*(r01)*(sj5));
04426 IkReal x989=((cj5)*(r10)*(sj0));
04427 IkReal x990=((sj2)*(x976));
04428 IkReal x991=((x984)+(x983));
04429 evalcond[0]=((((sj4)*(x981)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x985)))+(((IkReal(-1.00000000000000))*(x977)*(x979)))+(x990));
04430 evalcond[1]=((((cj4)*(x979)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x981)*(x982)))+(x991));
04431 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x987)))+(((IkReal(-1.00000000000000))*(x977)*(x986)))+(((sj4)*(x989)))+(((cj0)*(sj4)*(x978)))+(((IkReal(-1.00000000000000))*(x980)*(x982)))+(((IkReal(-1.00000000000000))*(x977)*(x988)))+(x991));
04432 evalcond[3]=((((cj4)*(x986)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x977)))+(((IkReal(-1.00000000000000))*(x978)*(x987)))+(x985)+(((IkReal(-1.00000000000000))*(x977)*(x980)))+(((IkReal(-1.00000000000000))*(x982)*(x989)))+(((IkReal(-1.00000000000000))*(x990)))+(((cj4)*(x988))));
04433 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04434 {
04435 continue;
04436 }
04437 }
04438 
04439 {
04440 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04441 vinfos[0].jointtype = 1;
04442 vinfos[0].foffset = j0;
04443 vinfos[0].indices[0] = _ij0[0];
04444 vinfos[0].indices[1] = _ij0[1];
04445 vinfos[0].maxsolutions = _nj0;
04446 vinfos[1].jointtype = 1;
04447 vinfos[1].foffset = j1;
04448 vinfos[1].indices[0] = _ij1[0];
04449 vinfos[1].indices[1] = _ij1[1];
04450 vinfos[1].maxsolutions = _nj1;
04451 vinfos[2].jointtype = 1;
04452 vinfos[2].foffset = j2;
04453 vinfos[2].indices[0] = _ij2[0];
04454 vinfos[2].indices[1] = _ij2[1];
04455 vinfos[2].maxsolutions = _nj2;
04456 vinfos[3].jointtype = 1;
04457 vinfos[3].foffset = j3;
04458 vinfos[3].indices[0] = _ij3[0];
04459 vinfos[3].indices[1] = _ij3[1];
04460 vinfos[3].maxsolutions = _nj3;
04461 vinfos[4].jointtype = 1;
04462 vinfos[4].foffset = j4;
04463 vinfos[4].indices[0] = _ij4[0];
04464 vinfos[4].indices[1] = _ij4[1];
04465 vinfos[4].maxsolutions = _nj4;
04466 vinfos[5].jointtype = 1;
04467 vinfos[5].foffset = j5;
04468 vinfos[5].indices[0] = _ij5[0];
04469 vinfos[5].indices[1] = _ij5[1];
04470 vinfos[5].maxsolutions = _nj5;
04471 std::vector<int> vfree(0);
04472 solutions.AddSolution(vinfos,vfree);
04473 }
04474 }
04475 }
04476 
04477 }
04478 
04479 }
04480 }
04481 }
04482 
04483 }
04484 
04485 }
04486 
04487 } else
04488 {
04489 {
04490 IkReal j1array[1], cj1array[1], sj1array[1];
04491 bool j1valid[1]={false};
04492 _nj1 = 1;
04493 IkReal x992=((cj4)*(r22));
04494 IkReal x993=((cj2)*(sj4));
04495 IkReal x994=((sj2)*(sj4));
04496 IkReal x995=((r21)*(sj5));
04497 IkReal x996=((cj5)*(r20));
04498 IkReal x997=((cj4)*(sj2));
04499 IkReal x998=((IkReal(1.00000000000000))*(cj2)*(x995));
04500 if( IKabs(((gconst116)*(((((cj2)*(cj4)*(x996)))+(((x994)*(x995)))+(((r22)*(x993)))+(((sj2)*(x992)))+(((IkReal(-1.00000000000000))*(cj4)*(x998)))+(((IkReal(-1.00000000000000))*(x994)*(x996))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst116)*(((((r22)*(x994)))+(((IkReal(-1.00000000000000))*(x993)*(x995)))+(((IkReal(-1.00000000000000))*(x995)*(x997)))+(((IkReal(-1.00000000000000))*(cj2)*(x992)))+(((x996)*(x997)))+(((x993)*(x996))))))) < IKFAST_ATAN2_MAGTHRESH )
04501     continue;
04502 j1array[0]=IKatan2(((gconst116)*(((((cj2)*(cj4)*(x996)))+(((x994)*(x995)))+(((r22)*(x993)))+(((sj2)*(x992)))+(((IkReal(-1.00000000000000))*(cj4)*(x998)))+(((IkReal(-1.00000000000000))*(x994)*(x996)))))), ((gconst116)*(((((r22)*(x994)))+(((IkReal(-1.00000000000000))*(x993)*(x995)))+(((IkReal(-1.00000000000000))*(x995)*(x997)))+(((IkReal(-1.00000000000000))*(cj2)*(x992)))+(((x996)*(x997)))+(((x993)*(x996)))))));
04503 sj1array[0]=IKsin(j1array[0]);
04504 cj1array[0]=IKcos(j1array[0]);
04505 if( j1array[0] > IKPI )
04506 {
04507     j1array[0]-=IK2PI;
04508 }
04509 else if( j1array[0] < -IKPI )
04510 {    j1array[0]+=IK2PI;
04511 }
04512 j1valid[0] = true;
04513 for(int ij1 = 0; ij1 < 1; ++ij1)
04514 {
04515 if( !j1valid[ij1] )
04516 {
04517     continue;
04518 }
04519 _ij1[0] = ij1; _ij1[1] = -1;
04520 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04521 {
04522 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04523 {
04524     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04525 }
04526 }
04527 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04528 {
04529 IkReal evalcond[2];
04530 IkReal x999=IKcos(j1);
04531 IkReal x1000=IKsin(j1);
04532 IkReal x1001=((cj5)*(r20));
04533 IkReal x1002=((r21)*(sj5));
04534 evalcond[0]=((((sj4)*(x1002)))+(((cj4)*(r22)))+(((sj2)*(x1000)))+(((IkReal(-1.00000000000000))*(cj2)*(x999)))+(((IkReal(-1.00000000000000))*(sj4)*(x1001))));
04535 evalcond[1]=((((cj4)*(x1001)))+(((r22)*(sj4)))+(((cj2)*(x1000)))+(((sj2)*(x999)))+(((IkReal(-1.00000000000000))*(cj4)*(x1002))));
04536 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04537 {
04538 continue;
04539 }
04540 }
04541 
04542 {
04543 IkReal dummyeval[1];
04544 IkReal gconst119;
04545 IkReal x1003=(sj5)*(sj5);
04546 IkReal x1004=(cj5)*(cj5);
04547 IkReal x1005=((IkReal(2.00000000000000))*(cj5)*(sj5));
04548 gconst119=IKsign(((((x1003)*((r10)*(r10))))+(((x1004)*((r11)*(r11))))+(((x1003)*((r00)*(r00))))+(((x1004)*((r01)*(r01))))+(((r00)*(r01)*(x1005)))+(((r10)*(r11)*(x1005)))));
04549 IkReal x1006=(sj5)*(sj5);
04550 IkReal x1007=(cj5)*(cj5);
04551 IkReal x1008=((IkReal(2.00000000000000))*(cj5)*(sj5));
04552 dummyeval[0]=((((x1006)*((r10)*(r10))))+(((x1006)*((r00)*(r00))))+(((x1007)*((r11)*(r11))))+(((r10)*(r11)*(x1008)))+(((r00)*(r01)*(x1008)))+(((x1007)*((r01)*(r01)))));
04553 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04554 {
04555 {
04556 IkReal dummyeval[1];
04557 IkReal gconst120;
04558 IkReal x1009=(cj5)*(cj5);
04559 IkReal x1010=(sj5)*(sj5);
04560 IkReal x1011=((IkReal(1.00000000000000))*(r10));
04561 IkReal x1012=((cj4)*(sj5));
04562 IkReal x1013=((r00)*(r11));
04563 IkReal x1014=((cj4)*(cj5));
04564 IkReal x1015=((sj4)*(x1009));
04565 IkReal x1016=((sj4)*(x1010));
04566 gconst120=IKsign(((((x1013)*(x1015)))+(((x1013)*(x1016)))+(((r01)*(r12)*(x1014)))+(((r00)*(r12)*(x1012)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1014)))+(((IkReal(-1.00000000000000))*(r01)*(x1011)*(x1016)))+(((IkReal(-1.00000000000000))*(r01)*(x1011)*(x1015)))+(((IkReal(-1.00000000000000))*(r02)*(x1011)*(x1012)))));
04567 IkReal x1017=(cj5)*(cj5);
04568 IkReal x1018=(sj5)*(sj5);
04569 IkReal x1019=((IkReal(1.00000000000000))*(r10));
04570 IkReal x1020=((cj4)*(sj5));
04571 IkReal x1021=((r00)*(r11));
04572 IkReal x1022=((cj4)*(cj5));
04573 IkReal x1023=((sj4)*(x1017));
04574 IkReal x1024=((sj4)*(x1018));
04575 dummyeval[0]=((((x1021)*(x1024)))+(((IkReal(-1.00000000000000))*(r01)*(x1019)*(x1024)))+(((r00)*(r12)*(x1020)))+(((IkReal(-1.00000000000000))*(r02)*(x1019)*(x1020)))+(((r01)*(r12)*(x1022)))+(((x1021)*(x1023)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1022)))+(((IkReal(-1.00000000000000))*(r01)*(x1019)*(x1023))));
04576 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04577 {
04578 continue;
04579 
04580 } else
04581 {
04582 {
04583 IkReal j0array[1], cj0array[1], sj0array[1];
04584 bool j0valid[1]={false};
04585 _nj0 = 1;
04586 IkReal x1025=((cj5)*(sj4));
04587 IkReal x1026=((IkReal(1.00000000000000))*(cj4));
04588 IkReal x1027=((IkReal(1.00000000000000))*(sj4)*(sj5));
04589 if( IKabs(((gconst120)*(((((IkReal(-1.00000000000000))*(r11)*(x1027)))+(((IkReal(-1.00000000000000))*(r12)*(x1026)))+(((r10)*(x1025))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst120)*(((((IkReal(-1.00000000000000))*(r01)*(x1027)))+(((IkReal(-1.00000000000000))*(r02)*(x1026)))+(((r00)*(x1025))))))) < IKFAST_ATAN2_MAGTHRESH )
04590     continue;
04591 j0array[0]=IKatan2(((gconst120)*(((((IkReal(-1.00000000000000))*(r11)*(x1027)))+(((IkReal(-1.00000000000000))*(r12)*(x1026)))+(((r10)*(x1025)))))), ((gconst120)*(((((IkReal(-1.00000000000000))*(r01)*(x1027)))+(((IkReal(-1.00000000000000))*(r02)*(x1026)))+(((r00)*(x1025)))))));
04592 sj0array[0]=IKsin(j0array[0]);
04593 cj0array[0]=IKcos(j0array[0]);
04594 if( j0array[0] > IKPI )
04595 {
04596     j0array[0]-=IK2PI;
04597 }
04598 else if( j0array[0] < -IKPI )
04599 {    j0array[0]+=IK2PI;
04600 }
04601 j0valid[0] = true;
04602 for(int ij0 = 0; ij0 < 1; ++ij0)
04603 {
04604 if( !j0valid[ij0] )
04605 {
04606     continue;
04607 }
04608 _ij0[0] = ij0; _ij0[1] = -1;
04609 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04610 {
04611 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04612 {
04613     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04614 }
04615 }
04616 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04617 {
04618 IkReal evalcond[6];
04619 IkReal x1028=IKsin(j0);
04620 IkReal x1029=IKcos(j0);
04621 IkReal x1030=((IkReal(1.00000000000000))*(r10));
04622 IkReal x1031=((IkReal(1.00000000000000))*(sj4));
04623 IkReal x1032=((cj5)*(r01));
04624 IkReal x1033=((cj5)*(r00));
04625 IkReal x1034=((cj4)*(r01));
04626 IkReal x1035=((IkReal(1.00000000000000))*(cj4));
04627 IkReal x1036=((cj4)*(r11));
04628 IkReal x1037=((sj5)*(x1028));
04629 IkReal x1038=((r11)*(x1031));
04630 IkReal x1039=((sj5)*(x1029));
04631 IkReal x1040=((r02)*(x1029));
04632 IkReal x1041=((r12)*(x1029));
04633 IkReal x1042=((IkReal(1.00000000000000))*(x1029));
04634 IkReal x1043=((cj4)*(x1028));
04635 IkReal x1044=((cj5)*(x1028));
04636 IkReal x1045=((cj5)*(sj4)*(x1029));
04637 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1030)*(x1039)))+(((r00)*(x1037)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1042)))+(((x1028)*(x1032))));
04638 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x1044)))+(((IkReal(-1.00000000000000))*(x1032)*(x1042)))+(((IkReal(-1.00000000000000))*(r00)*(x1039)))+(((IkReal(-1.00000000000000))*(x1030)*(x1037))));
04639 evalcond[2]=((((r01)*(sj4)*(x1037)))+(((r02)*(x1043)))+(((IkReal(-1.00000000000000))*(x1028)*(x1031)*(x1033)))+(((IkReal(-1.00000000000000))*(x1035)*(x1041)))+(((IkReal(-1.00000000000000))*(x1038)*(x1039)))+(((r10)*(x1045))));
04640 evalcond[3]=((((x1036)*(x1039)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1029)*(x1030)))+(((IkReal(-1.00000000000000))*(x1031)*(x1041)))+(((x1033)*(x1043)))+(((r02)*(sj4)*(x1028)))+(((IkReal(-1.00000000000000))*(x1034)*(x1037))));
04641 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1035)*(x1040)))+(((sj4)*(x1029)*(x1033)))+(((IkReal(-1.00000000000000))*(x1037)*(x1038)))+(((IkReal(-1.00000000000000))*(r01)*(x1031)*(x1039)))+(((IkReal(-1.00000000000000))*(r12)*(x1028)*(x1035)))+(((cj2)*(sj1)))+(((r10)*(sj4)*(x1044))));
04642 evalcond[5]=((((IkReal(-1.00000000000000))*(sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1029)*(x1033)*(x1035)))+(((x1034)*(x1039)))+(((IkReal(-1.00000000000000))*(r12)*(x1028)*(x1031)))+(((IkReal(-1.00000000000000))*(cj5)*(x1030)*(x1043)))+(((IkReal(-1.00000000000000))*(x1031)*(x1040)))+(((cj1)*(cj2)))+(((x1036)*(x1037))));
04643 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  )
04644 {
04645 continue;
04646 }
04647 }
04648 
04649 {
04650 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04651 vinfos[0].jointtype = 1;
04652 vinfos[0].foffset = j0;
04653 vinfos[0].indices[0] = _ij0[0];
04654 vinfos[0].indices[1] = _ij0[1];
04655 vinfos[0].maxsolutions = _nj0;
04656 vinfos[1].jointtype = 1;
04657 vinfos[1].foffset = j1;
04658 vinfos[1].indices[0] = _ij1[0];
04659 vinfos[1].indices[1] = _ij1[1];
04660 vinfos[1].maxsolutions = _nj1;
04661 vinfos[2].jointtype = 1;
04662 vinfos[2].foffset = j2;
04663 vinfos[2].indices[0] = _ij2[0];
04664 vinfos[2].indices[1] = _ij2[1];
04665 vinfos[2].maxsolutions = _nj2;
04666 vinfos[3].jointtype = 1;
04667 vinfos[3].foffset = j3;
04668 vinfos[3].indices[0] = _ij3[0];
04669 vinfos[3].indices[1] = _ij3[1];
04670 vinfos[3].maxsolutions = _nj3;
04671 vinfos[4].jointtype = 1;
04672 vinfos[4].foffset = j4;
04673 vinfos[4].indices[0] = _ij4[0];
04674 vinfos[4].indices[1] = _ij4[1];
04675 vinfos[4].maxsolutions = _nj4;
04676 vinfos[5].jointtype = 1;
04677 vinfos[5].foffset = j5;
04678 vinfos[5].indices[0] = _ij5[0];
04679 vinfos[5].indices[1] = _ij5[1];
04680 vinfos[5].maxsolutions = _nj5;
04681 std::vector<int> vfree(0);
04682 solutions.AddSolution(vinfos,vfree);
04683 }
04684 }
04685 }
04686 
04687 }
04688 
04689 }
04690 
04691 } else
04692 {
04693 {
04694 IkReal j0array[1], cj0array[1], sj0array[1];
04695 bool j0valid[1]={false};
04696 _nj0 = 1;
04697 if( IKabs(((gconst119)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst119)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
04698     continue;
04699 j0array[0]=IKatan2(((gconst119)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst119)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
04700 sj0array[0]=IKsin(j0array[0]);
04701 cj0array[0]=IKcos(j0array[0]);
04702 if( j0array[0] > IKPI )
04703 {
04704     j0array[0]-=IK2PI;
04705 }
04706 else if( j0array[0] < -IKPI )
04707 {    j0array[0]+=IK2PI;
04708 }
04709 j0valid[0] = true;
04710 for(int ij0 = 0; ij0 < 1; ++ij0)
04711 {
04712 if( !j0valid[ij0] )
04713 {
04714     continue;
04715 }
04716 _ij0[0] = ij0; _ij0[1] = -1;
04717 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04718 {
04719 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04720 {
04721     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04722 }
04723 }
04724 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04725 {
04726 IkReal evalcond[6];
04727 IkReal x1046=IKsin(j0);
04728 IkReal x1047=IKcos(j0);
04729 IkReal x1048=((IkReal(1.00000000000000))*(r10));
04730 IkReal x1049=((IkReal(1.00000000000000))*(sj4));
04731 IkReal x1050=((cj5)*(r01));
04732 IkReal x1051=((cj5)*(r00));
04733 IkReal x1052=((cj4)*(r01));
04734 IkReal x1053=((IkReal(1.00000000000000))*(cj4));
04735 IkReal x1054=((cj4)*(r11));
04736 IkReal x1055=((sj5)*(x1046));
04737 IkReal x1056=((r11)*(x1049));
04738 IkReal x1057=((sj5)*(x1047));
04739 IkReal x1058=((r02)*(x1047));
04740 IkReal x1059=((r12)*(x1047));
04741 IkReal x1060=((IkReal(1.00000000000000))*(x1047));
04742 IkReal x1061=((cj4)*(x1046));
04743 IkReal x1062=((cj5)*(x1046));
04744 IkReal x1063=((cj5)*(sj4)*(x1047));
04745 evalcond[0]=((IkReal(1.00000000000000))+(((x1046)*(x1050)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1060)))+(((r00)*(x1055)))+(((IkReal(-1.00000000000000))*(x1048)*(x1057))));
04746 evalcond[1]=((((IkReal(-1.00000000000000))*(x1050)*(x1060)))+(((IkReal(-1.00000000000000))*(r00)*(x1057)))+(((IkReal(-1.00000000000000))*(x1048)*(x1055)))+(((IkReal(-1.00000000000000))*(r11)*(x1062))));
04747 evalcond[2]=((((IkReal(-1.00000000000000))*(x1046)*(x1049)*(x1051)))+(((IkReal(-1.00000000000000))*(x1056)*(x1057)))+(((IkReal(-1.00000000000000))*(x1053)*(x1059)))+(((r02)*(x1061)))+(((r10)*(x1063)))+(((r01)*(sj4)*(x1055))));
04748 evalcond[3]=((((x1054)*(x1057)))+(((x1051)*(x1061)))+(((r02)*(sj4)*(x1046)))+(((IkReal(-1.00000000000000))*(x1052)*(x1055)))+(((IkReal(-1.00000000000000))*(x1049)*(x1059)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1047)*(x1048))));
04749 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r01)*(x1049)*(x1057)))+(((IkReal(-1.00000000000000))*(x1053)*(x1058)))+(((IkReal(-1.00000000000000))*(r12)*(x1046)*(x1053)))+(((IkReal(-1.00000000000000))*(x1055)*(x1056)))+(((sj4)*(x1047)*(x1051)))+(((r10)*(sj4)*(x1062)))+(((cj2)*(sj1))));
04750 evalcond[5]=((((IkReal(-1.00000000000000))*(sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1049)*(x1058)))+(((IkReal(-1.00000000000000))*(cj5)*(x1048)*(x1061)))+(((IkReal(-1.00000000000000))*(r12)*(x1046)*(x1049)))+(((IkReal(-1.00000000000000))*(x1047)*(x1051)*(x1053)))+(((cj1)*(cj2)))+(((x1054)*(x1055)))+(((x1052)*(x1057))));
04751 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  )
04752 {
04753 continue;
04754 }
04755 }
04756 
04757 {
04758 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04759 vinfos[0].jointtype = 1;
04760 vinfos[0].foffset = j0;
04761 vinfos[0].indices[0] = _ij0[0];
04762 vinfos[0].indices[1] = _ij0[1];
04763 vinfos[0].maxsolutions = _nj0;
04764 vinfos[1].jointtype = 1;
04765 vinfos[1].foffset = j1;
04766 vinfos[1].indices[0] = _ij1[0];
04767 vinfos[1].indices[1] = _ij1[1];
04768 vinfos[1].maxsolutions = _nj1;
04769 vinfos[2].jointtype = 1;
04770 vinfos[2].foffset = j2;
04771 vinfos[2].indices[0] = _ij2[0];
04772 vinfos[2].indices[1] = _ij2[1];
04773 vinfos[2].maxsolutions = _nj2;
04774 vinfos[3].jointtype = 1;
04775 vinfos[3].foffset = j3;
04776 vinfos[3].indices[0] = _ij3[0];
04777 vinfos[3].indices[1] = _ij3[1];
04778 vinfos[3].maxsolutions = _nj3;
04779 vinfos[4].jointtype = 1;
04780 vinfos[4].foffset = j4;
04781 vinfos[4].indices[0] = _ij4[0];
04782 vinfos[4].indices[1] = _ij4[1];
04783 vinfos[4].maxsolutions = _nj4;
04784 vinfos[5].jointtype = 1;
04785 vinfos[5].foffset = j5;
04786 vinfos[5].indices[0] = _ij5[0];
04787 vinfos[5].indices[1] = _ij5[1];
04788 vinfos[5].maxsolutions = _nj5;
04789 std::vector<int> vfree(0);
04790 solutions.AddSolution(vinfos,vfree);
04791 }
04792 }
04793 }
04794 
04795 }
04796 
04797 }
04798 }
04799 }
04800 
04801 }
04802 
04803 }
04804 
04805 } else
04806 {
04807 {
04808 IkReal j0array[1], cj0array[1], sj0array[1];
04809 bool j0valid[1]={false};
04810 _nj0 = 1;
04811 if( IKabs(((gconst114)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst114)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
04812     continue;
04813 j0array[0]=IKatan2(((gconst114)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst114)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
04814 sj0array[0]=IKsin(j0array[0]);
04815 cj0array[0]=IKcos(j0array[0]);
04816 if( j0array[0] > IKPI )
04817 {
04818     j0array[0]-=IK2PI;
04819 }
04820 else if( j0array[0] < -IKPI )
04821 {    j0array[0]+=IK2PI;
04822 }
04823 j0valid[0] = true;
04824 for(int ij0 = 0; ij0 < 1; ++ij0)
04825 {
04826 if( !j0valid[ij0] )
04827 {
04828     continue;
04829 }
04830 _ij0[0] = ij0; _ij0[1] = -1;
04831 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
04832 {
04833 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
04834 {
04835     j0valid[iij0]=false; _ij0[1] = iij0; break; 
04836 }
04837 }
04838 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
04839 {
04840 IkReal evalcond[4];
04841 IkReal x1064=IKsin(j0);
04842 IkReal x1065=IKcos(j0);
04843 IkReal x1066=((IkReal(1.00000000000000))*(cj5));
04844 IkReal x1067=((r01)*(sj5));
04845 IkReal x1068=((IkReal(1.00000000000000))*(r12));
04846 IkReal x1069=((IkReal(1.00000000000000))*(r10));
04847 IkReal x1070=((r11)*(sj5));
04848 IkReal x1071=((cj4)*(x1064));
04849 IkReal x1072=((sj4)*(x1064));
04850 IkReal x1073=((sj4)*(x1065));
04851 IkReal x1074=((sj5)*(x1064));
04852 IkReal x1075=((cj4)*(x1065));
04853 IkReal x1076=((sj5)*(x1065));
04854 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1069)*(x1076)))+(((IkReal(-1.00000000000000))*(r11)*(x1065)*(x1066)))+(((cj5)*(r01)*(x1064)))+(((r00)*(x1074))));
04855 evalcond[1]=((((IkReal(-1.00000000000000))*(r11)*(x1064)*(x1066)))+(((IkReal(-1.00000000000000))*(r00)*(x1076)))+(((IkReal(-1.00000000000000))*(x1069)*(x1074)))+(((IkReal(-1.00000000000000))*(r01)*(x1065)*(x1066))));
04856 evalcond[2]=((((r02)*(x1071)))+(((IkReal(-1.00000000000000))*(x1068)*(x1075)))+(((x1067)*(x1072)))+(((IkReal(-1.00000000000000))*(x1070)*(x1073)))+(((cj5)*(r10)*(x1073)))+(((IkReal(-1.00000000000000))*(r00)*(x1066)*(x1072))));
04857 evalcond[3]=((((r02)*(x1072)))+(((x1070)*(x1075)))+(((cj5)*(r00)*(x1071)))+(((IkReal(-1.00000000000000))*(r10)*(x1066)*(x1075)))+(((IkReal(-1.00000000000000))*(x1067)*(x1071)))+(((IkReal(-1.00000000000000))*(x1068)*(x1073))));
04858 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04859 {
04860 continue;
04861 }
04862 }
04863 
04864 {
04865 IkReal dummyeval[1];
04866 IkReal gconst117;
04867 gconst117=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
04868 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
04869 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04870 {
04871 {
04872 IkReal dummyeval[1];
04873 IkReal gconst118;
04874 gconst118=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
04875 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
04876 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04877 {
04878 continue;
04879 
04880 } else
04881 {
04882 {
04883 IkReal j1array[1], cj1array[1], sj1array[1];
04884 bool j1valid[1]={false};
04885 _nj1 = 1;
04886 IkReal x1077=((cj4)*(r22));
04887 IkReal x1078=((r11)*(sj0));
04888 IkReal x1079=((IkReal(1.00000000000000))*(cj2));
04889 IkReal x1080=((sj2)*(sj4));
04890 IkReal x1081=((IkReal(1.00000000000000))*(sj2));
04891 IkReal x1082=((cj2)*(sj4));
04892 IkReal x1083=((cj0)*(r01));
04893 IkReal x1084=((cj5)*(r20));
04894 IkReal x1085=((IkReal(1.00000000000000))*(sj4)*(sj5));
04895 IkReal x1086=((cj0)*(cj4)*(r02));
04896 IkReal x1087=((cj4)*(r12)*(sj0));
04897 IkReal x1088=((cj5)*(r10)*(sj0));
04898 IkReal x1089=((cj0)*(cj5)*(r00));
04899 if( IKabs(((gconst118)*(((((IkReal(-1.00000000000000))*(x1079)*(x1087)))+(((x1082)*(x1089)))+(((sj2)*(x1077)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(x1080)*(x1084)))+(((IkReal(-1.00000000000000))*(x1079)*(x1086)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1079)*(x1083)))+(((r21)*(sj5)*(x1080)))+(((x1082)*(x1088))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst118)*(((((IkReal(-1.00000000000000))*(sj5)*(x1080)*(x1083)))+(((IkReal(-1.00000000000000))*(x1081)*(x1087)))+(((IkReal(-1.00000000000000))*(sj5)*(x1078)*(x1080)))+(((x1082)*(x1084)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1079)))+(((IkReal(-1.00000000000000))*(x1077)*(x1079)))+(((IkReal(-1.00000000000000))*(x1081)*(x1086)))+(((x1080)*(x1088)))+(((x1080)*(x1089))))))) < IKFAST_ATAN2_MAGTHRESH )
04900     continue;
04901 j1array[0]=IKatan2(((gconst118)*(((((IkReal(-1.00000000000000))*(x1079)*(x1087)))+(((x1082)*(x1089)))+(((sj2)*(x1077)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1078)*(x1079)))+(((IkReal(-1.00000000000000))*(x1080)*(x1084)))+(((IkReal(-1.00000000000000))*(x1079)*(x1086)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1079)*(x1083)))+(((r21)*(sj5)*(x1080)))+(((x1082)*(x1088)))))), ((gconst118)*(((((IkReal(-1.00000000000000))*(sj5)*(x1080)*(x1083)))+(((IkReal(-1.00000000000000))*(x1081)*(x1087)))+(((IkReal(-1.00000000000000))*(sj5)*(x1078)*(x1080)))+(((x1082)*(x1084)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1079)))+(((IkReal(-1.00000000000000))*(x1077)*(x1079)))+(((IkReal(-1.00000000000000))*(x1081)*(x1086)))+(((x1080)*(x1088)))+(((x1080)*(x1089)))))));
04902 sj1array[0]=IKsin(j1array[0]);
04903 cj1array[0]=IKcos(j1array[0]);
04904 if( j1array[0] > IKPI )
04905 {
04906     j1array[0]-=IK2PI;
04907 }
04908 else if( j1array[0] < -IKPI )
04909 {    j1array[0]+=IK2PI;
04910 }
04911 j1valid[0] = true;
04912 for(int ij1 = 0; ij1 < 1; ++ij1)
04913 {
04914 if( !j1valid[ij1] )
04915 {
04916     continue;
04917 }
04918 _ij1[0] = ij1; _ij1[1] = -1;
04919 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
04920 {
04921 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
04922 {
04923     j1valid[iij1]=false; _ij1[1] = iij1; break; 
04924 }
04925 }
04926 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
04927 {
04928 IkReal evalcond[4];
04929 IkReal x1090=IKcos(j1);
04930 IkReal x1091=IKsin(j1);
04931 IkReal x1092=((IkReal(1.00000000000000))*(sj4));
04932 IkReal x1093=((cj5)*(r00));
04933 IkReal x1094=((cj5)*(r20));
04934 IkReal x1095=((r12)*(sj0));
04935 IkReal x1096=((r21)*(sj5));
04936 IkReal x1097=((IkReal(1.00000000000000))*(cj4));
04937 IkReal x1098=((sj2)*(x1090));
04938 IkReal x1099=((cj2)*(x1091));
04939 IkReal x1100=((cj2)*(x1090));
04940 IkReal x1101=((r11)*(sj0)*(sj5));
04941 IkReal x1102=((cj0)*(x1097));
04942 IkReal x1103=((cj0)*(r01)*(sj5));
04943 IkReal x1104=((cj5)*(r10)*(sj0));
04944 IkReal x1105=((sj2)*(x1091));
04945 IkReal x1106=((x1098)+(x1099));
04946 evalcond[0]=((x1105)+(((IkReal(-1.00000000000000))*(x1100)))+(((sj4)*(x1096)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1092)*(x1094))));
04947 evalcond[1]=((x1106)+(((r22)*(sj4)))+(((cj4)*(x1094)))+(((IkReal(-1.00000000000000))*(x1096)*(x1097))));
04948 evalcond[2]=((((IkReal(-1.00000000000000))*(x1095)*(x1097)))+(x1106)+(((sj4)*(x1104)))+(((IkReal(-1.00000000000000))*(x1092)*(x1101)))+(((IkReal(-1.00000000000000))*(x1092)*(x1103)))+(((cj0)*(sj4)*(x1093)))+(((IkReal(-1.00000000000000))*(r02)*(x1102))));
04949 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1092)))+(x1100)+(((cj4)*(x1101)))+(((IkReal(-1.00000000000000))*(x1093)*(x1102)))+(((IkReal(-1.00000000000000))*(x1092)*(x1095)))+(((IkReal(-1.00000000000000))*(x1097)*(x1104)))+(((cj4)*(x1103)))+(((IkReal(-1.00000000000000))*(x1105))));
04950 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04951 {
04952 continue;
04953 }
04954 }
04955 
04956 {
04957 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04958 vinfos[0].jointtype = 1;
04959 vinfos[0].foffset = j0;
04960 vinfos[0].indices[0] = _ij0[0];
04961 vinfos[0].indices[1] = _ij0[1];
04962 vinfos[0].maxsolutions = _nj0;
04963 vinfos[1].jointtype = 1;
04964 vinfos[1].foffset = j1;
04965 vinfos[1].indices[0] = _ij1[0];
04966 vinfos[1].indices[1] = _ij1[1];
04967 vinfos[1].maxsolutions = _nj1;
04968 vinfos[2].jointtype = 1;
04969 vinfos[2].foffset = j2;
04970 vinfos[2].indices[0] = _ij2[0];
04971 vinfos[2].indices[1] = _ij2[1];
04972 vinfos[2].maxsolutions = _nj2;
04973 vinfos[3].jointtype = 1;
04974 vinfos[3].foffset = j3;
04975 vinfos[3].indices[0] = _ij3[0];
04976 vinfos[3].indices[1] = _ij3[1];
04977 vinfos[3].maxsolutions = _nj3;
04978 vinfos[4].jointtype = 1;
04979 vinfos[4].foffset = j4;
04980 vinfos[4].indices[0] = _ij4[0];
04981 vinfos[4].indices[1] = _ij4[1];
04982 vinfos[4].maxsolutions = _nj4;
04983 vinfos[5].jointtype = 1;
04984 vinfos[5].foffset = j5;
04985 vinfos[5].indices[0] = _ij5[0];
04986 vinfos[5].indices[1] = _ij5[1];
04987 vinfos[5].maxsolutions = _nj5;
04988 std::vector<int> vfree(0);
04989 solutions.AddSolution(vinfos,vfree);
04990 }
04991 }
04992 }
04993 
04994 }
04995 
04996 }
04997 
04998 } else
04999 {
05000 {
05001 IkReal j1array[1], cj1array[1], sj1array[1];
05002 bool j1valid[1]={false};
05003 _nj1 = 1;
05004 IkReal x1107=((cj4)*(r22));
05005 IkReal x1108=((cj2)*(sj4));
05006 IkReal x1109=((sj2)*(sj4));
05007 IkReal x1110=((r21)*(sj5));
05008 IkReal x1111=((cj5)*(r20));
05009 IkReal x1112=((cj4)*(sj2));
05010 IkReal x1113=((IkReal(1.00000000000000))*(cj2)*(x1110));
05011 if( IKabs(((gconst117)*(((((cj2)*(cj4)*(x1111)))+(((IkReal(-1.00000000000000))*(x1109)*(x1111)))+(((IkReal(-1.00000000000000))*(cj4)*(x1113)))+(((sj2)*(x1107)))+(((r22)*(x1108)))+(((x1109)*(x1110))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst117)*(((((IkReal(-1.00000000000000))*(x1108)*(x1110)))+(((IkReal(-1.00000000000000))*(x1110)*(x1112)))+(((IkReal(-1.00000000000000))*(cj2)*(x1107)))+(((x1111)*(x1112)))+(((r22)*(x1109)))+(((x1108)*(x1111))))))) < IKFAST_ATAN2_MAGTHRESH )
05012     continue;
05013 j1array[0]=IKatan2(((gconst117)*(((((cj2)*(cj4)*(x1111)))+(((IkReal(-1.00000000000000))*(x1109)*(x1111)))+(((IkReal(-1.00000000000000))*(cj4)*(x1113)))+(((sj2)*(x1107)))+(((r22)*(x1108)))+(((x1109)*(x1110)))))), ((gconst117)*(((((IkReal(-1.00000000000000))*(x1108)*(x1110)))+(((IkReal(-1.00000000000000))*(x1110)*(x1112)))+(((IkReal(-1.00000000000000))*(cj2)*(x1107)))+(((x1111)*(x1112)))+(((r22)*(x1109)))+(((x1108)*(x1111)))))));
05014 sj1array[0]=IKsin(j1array[0]);
05015 cj1array[0]=IKcos(j1array[0]);
05016 if( j1array[0] > IKPI )
05017 {
05018     j1array[0]-=IK2PI;
05019 }
05020 else if( j1array[0] < -IKPI )
05021 {    j1array[0]+=IK2PI;
05022 }
05023 j1valid[0] = true;
05024 for(int ij1 = 0; ij1 < 1; ++ij1)
05025 {
05026 if( !j1valid[ij1] )
05027 {
05028     continue;
05029 }
05030 _ij1[0] = ij1; _ij1[1] = -1;
05031 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05032 {
05033 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05034 {
05035     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05036 }
05037 }
05038 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05039 {
05040 IkReal evalcond[4];
05041 IkReal x1114=IKcos(j1);
05042 IkReal x1115=IKsin(j1);
05043 IkReal x1116=((IkReal(1.00000000000000))*(sj4));
05044 IkReal x1117=((cj5)*(r00));
05045 IkReal x1118=((cj5)*(r20));
05046 IkReal x1119=((r12)*(sj0));
05047 IkReal x1120=((r21)*(sj5));
05048 IkReal x1121=((IkReal(1.00000000000000))*(cj4));
05049 IkReal x1122=((sj2)*(x1114));
05050 IkReal x1123=((cj2)*(x1115));
05051 IkReal x1124=((cj2)*(x1114));
05052 IkReal x1125=((r11)*(sj0)*(sj5));
05053 IkReal x1126=((cj0)*(x1121));
05054 IkReal x1127=((cj0)*(r01)*(sj5));
05055 IkReal x1128=((cj5)*(r10)*(sj0));
05056 IkReal x1129=((sj2)*(x1115));
05057 IkReal x1130=((x1122)+(x1123));
05058 evalcond[0]=((((IkReal(-1.00000000000000))*(x1116)*(x1118)))+(((cj4)*(r22)))+(x1129)+(((sj4)*(x1120)))+(((IkReal(-1.00000000000000))*(x1124))));
05059 evalcond[1]=((((IkReal(-1.00000000000000))*(x1120)*(x1121)))+(x1130)+(((r22)*(sj4)))+(((cj4)*(x1118))));
05060 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x1126)))+(((IkReal(-1.00000000000000))*(x1119)*(x1121)))+(((cj0)*(sj4)*(x1117)))+(x1130)+(((IkReal(-1.00000000000000))*(x1116)*(x1127)))+(((sj4)*(x1128)))+(((IkReal(-1.00000000000000))*(x1116)*(x1125))));
05061 evalcond[3]=((((IkReal(-1.00000000000000))*(x1116)*(x1119)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1116)))+(((cj4)*(x1125)))+(((cj4)*(x1127)))+(((IkReal(-1.00000000000000))*(x1117)*(x1126)))+(((IkReal(-1.00000000000000))*(x1129)))+(x1124)+(((IkReal(-1.00000000000000))*(x1121)*(x1128))));
05062 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05063 {
05064 continue;
05065 }
05066 }
05067 
05068 {
05069 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05070 vinfos[0].jointtype = 1;
05071 vinfos[0].foffset = j0;
05072 vinfos[0].indices[0] = _ij0[0];
05073 vinfos[0].indices[1] = _ij0[1];
05074 vinfos[0].maxsolutions = _nj0;
05075 vinfos[1].jointtype = 1;
05076 vinfos[1].foffset = j1;
05077 vinfos[1].indices[0] = _ij1[0];
05078 vinfos[1].indices[1] = _ij1[1];
05079 vinfos[1].maxsolutions = _nj1;
05080 vinfos[2].jointtype = 1;
05081 vinfos[2].foffset = j2;
05082 vinfos[2].indices[0] = _ij2[0];
05083 vinfos[2].indices[1] = _ij2[1];
05084 vinfos[2].maxsolutions = _nj2;
05085 vinfos[3].jointtype = 1;
05086 vinfos[3].foffset = j3;
05087 vinfos[3].indices[0] = _ij3[0];
05088 vinfos[3].indices[1] = _ij3[1];
05089 vinfos[3].maxsolutions = _nj3;
05090 vinfos[4].jointtype = 1;
05091 vinfos[4].foffset = j4;
05092 vinfos[4].indices[0] = _ij4[0];
05093 vinfos[4].indices[1] = _ij4[1];
05094 vinfos[4].maxsolutions = _nj4;
05095 vinfos[5].jointtype = 1;
05096 vinfos[5].foffset = j5;
05097 vinfos[5].indices[0] = _ij5[0];
05098 vinfos[5].indices[1] = _ij5[1];
05099 vinfos[5].maxsolutions = _nj5;
05100 std::vector<int> vfree(0);
05101 solutions.AddSolution(vinfos,vfree);
05102 }
05103 }
05104 }
05105 
05106 }
05107 
05108 }
05109 }
05110 }
05111 
05112 }
05113 
05114 }
05115 
05116 } else
05117 {
05118 IkReal x1131=((cj5)*(npx));
05119 IkReal x1132=((npy)*(sj5));
05120 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j3, IkReal(6.28318530717959))));
05121 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
05122 evalcond[2]=((IkReal(-0.350000000000000))+(((sj4)*(x1132)))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(sj4)*(x1131))));
05123 evalcond[3]=((((cj4)*(x1131)))+(((IkReal(-0.350000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(cj4)*(x1132)))+(((npz)*(sj4))));
05124 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
05125 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  )
05126 {
05127 {
05128 IkReal dummyeval[1];
05129 IkReal gconst121;
05130 IkReal x1133=(cj5)*(cj5);
05131 IkReal x1134=(sj5)*(sj5);
05132 IkReal x1135=((IkReal(1.00000000000000))*(x1134));
05133 IkReal x1136=((IkReal(2.00000000000000))*(cj5)*(sj5));
05134 IkReal x1137=((IkReal(1.00000000000000))*(x1133));
05135 gconst121=IKsign(((((IkReal(-1.00000000000000))*(x1135)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1137)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1136)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1136)))+(((IkReal(-1.00000000000000))*(x1137)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1135)*((r00)*(r00))))));
05136 IkReal x1138=(cj5)*(cj5);
05137 IkReal x1139=(sj5)*(sj5);
05138 IkReal x1140=((IkReal(1.00000000000000))*(x1139));
05139 IkReal x1141=((IkReal(2.00000000000000))*(cj5)*(sj5));
05140 IkReal x1142=((IkReal(1.00000000000000))*(x1138));
05141 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1140)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1142)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1140)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1142)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1141)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1141))));
05142 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05143 {
05144 {
05145 IkReal dummyeval[1];
05146 IkReal gconst123;
05147 gconst123=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
05148 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
05149 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05150 {
05151 {
05152 IkReal dummyeval[1];
05153 IkReal gconst122;
05154 IkReal x1143=(sj5)*(sj5);
05155 IkReal x1144=(cj5)*(cj5);
05156 IkReal x1145=((cj4)*(cj5));
05157 IkReal x1146=((IkReal(1.00000000000000))*(r12));
05158 IkReal x1147=((cj4)*(sj5));
05159 IkReal x1148=((r01)*(r10));
05160 IkReal x1149=((sj4)*(x1144));
05161 IkReal x1150=((IkReal(1.00000000000000))*(r00)*(r11));
05162 IkReal x1151=((sj4)*(x1143));
05163 gconst122=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x1145)*(x1146)))+(((IkReal(-1.00000000000000))*(x1150)*(x1151)))+(((r02)*(r10)*(x1147)))+(((r02)*(r11)*(x1145)))+(((x1148)*(x1149)))+(((IkReal(-1.00000000000000))*(x1149)*(x1150)))+(((IkReal(-1.00000000000000))*(r00)*(x1146)*(x1147)))+(((x1148)*(x1151)))));
05164 IkReal x1152=(sj5)*(sj5);
05165 IkReal x1153=(cj5)*(cj5);
05166 IkReal x1154=((cj4)*(cj5));
05167 IkReal x1155=((IkReal(1.00000000000000))*(r12));
05168 IkReal x1156=((cj4)*(sj5));
05169 IkReal x1157=((r01)*(r10));
05170 IkReal x1158=((sj4)*(x1153));
05171 IkReal x1159=((IkReal(1.00000000000000))*(r00)*(r11));
05172 IkReal x1160=((sj4)*(x1152));
05173 dummyeval[0]=((((x1157)*(x1160)))+(((r02)*(r10)*(x1156)))+(((r02)*(r11)*(x1154)))+(((IkReal(-1.00000000000000))*(r01)*(x1154)*(x1155)))+(((IkReal(-1.00000000000000))*(x1159)*(x1160)))+(((x1157)*(x1158)))+(((IkReal(-1.00000000000000))*(r00)*(x1155)*(x1156)))+(((IkReal(-1.00000000000000))*(x1158)*(x1159))));
05174 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05175 {
05176 continue;
05177 
05178 } else
05179 {
05180 {
05181 IkReal j0array[1], cj0array[1], sj0array[1];
05182 bool j0valid[1]={false};
05183 _nj0 = 1;
05184 IkReal x1161=((cj5)*(sj4));
05185 IkReal x1162=((IkReal(1.00000000000000))*(cj4));
05186 IkReal x1163=((IkReal(1.00000000000000))*(sj4)*(sj5));
05187 if( IKabs(((gconst122)*(((((r10)*(x1161)))+(((IkReal(-1.00000000000000))*(r11)*(x1163)))+(((IkReal(-1.00000000000000))*(r12)*(x1162))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst122)*(((((IkReal(-1.00000000000000))*(r01)*(x1163)))+(((r00)*(x1161)))+(((IkReal(-1.00000000000000))*(r02)*(x1162))))))) < IKFAST_ATAN2_MAGTHRESH )
05188     continue;
05189 j0array[0]=IKatan2(((gconst122)*(((((r10)*(x1161)))+(((IkReal(-1.00000000000000))*(r11)*(x1163)))+(((IkReal(-1.00000000000000))*(r12)*(x1162)))))), ((gconst122)*(((((IkReal(-1.00000000000000))*(r01)*(x1163)))+(((r00)*(x1161)))+(((IkReal(-1.00000000000000))*(r02)*(x1162)))))));
05190 sj0array[0]=IKsin(j0array[0]);
05191 cj0array[0]=IKcos(j0array[0]);
05192 if( j0array[0] > IKPI )
05193 {
05194     j0array[0]-=IK2PI;
05195 }
05196 else if( j0array[0] < -IKPI )
05197 {    j0array[0]+=IK2PI;
05198 }
05199 j0valid[0] = true;
05200 for(int ij0 = 0; ij0 < 1; ++ij0)
05201 {
05202 if( !j0valid[ij0] )
05203 {
05204     continue;
05205 }
05206 _ij0[0] = ij0; _ij0[1] = -1;
05207 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05208 {
05209 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05210 {
05211     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05212 }
05213 }
05214 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05215 {
05216 IkReal evalcond[4];
05217 IkReal x1164=IKsin(j0);
05218 IkReal x1165=IKcos(j0);
05219 IkReal x1166=((IkReal(1.00000000000000))*(cj5));
05220 IkReal x1167=((r01)*(sj5));
05221 IkReal x1168=((IkReal(1.00000000000000))*(r12));
05222 IkReal x1169=((IkReal(1.00000000000000))*(r10));
05223 IkReal x1170=((r11)*(sj5));
05224 IkReal x1171=((cj4)*(x1164));
05225 IkReal x1172=((sj4)*(x1164));
05226 IkReal x1173=((sj4)*(x1165));
05227 IkReal x1174=((sj5)*(x1164));
05228 IkReal x1175=((cj4)*(x1165));
05229 IkReal x1176=((sj5)*(x1165));
05230 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1169)*(x1176)))+(((IkReal(-1.00000000000000))*(r11)*(x1165)*(x1166)))+(((r00)*(x1174)))+(((cj5)*(r01)*(x1164))));
05231 evalcond[1]=((((IkReal(-1.00000000000000))*(x1169)*(x1174)))+(((IkReal(-1.00000000000000))*(r00)*(x1176)))+(((IkReal(-1.00000000000000))*(r11)*(x1164)*(x1166)))+(((IkReal(-1.00000000000000))*(r01)*(x1165)*(x1166))));
05232 evalcond[2]=((((IkReal(-1.00000000000000))*(x1170)*(x1173)))+(((IkReal(-1.00000000000000))*(x1168)*(x1175)))+(((r02)*(x1171)))+(((cj5)*(r10)*(x1173)))+(((IkReal(-1.00000000000000))*(r00)*(x1166)*(x1172)))+(((x1167)*(x1172))));
05233 evalcond[3]=((((x1170)*(x1175)))+(((IkReal(-1.00000000000000))*(r10)*(x1166)*(x1175)))+(((cj5)*(r00)*(x1171)))+(((IkReal(-1.00000000000000))*(x1168)*(x1173)))+(((IkReal(-1.00000000000000))*(x1167)*(x1171)))+(((r02)*(x1172))));
05234 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05235 {
05236 continue;
05237 }
05238 }
05239 
05240 {
05241 IkReal dummyeval[1];
05242 IkReal gconst124;
05243 gconst124=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
05244 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
05245 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05246 {
05247 {
05248 IkReal dummyeval[1];
05249 IkReal gconst125;
05250 gconst125=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
05251 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
05252 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05253 {
05254 continue;
05255 
05256 } else
05257 {
05258 {
05259 IkReal j1array[1], cj1array[1], sj1array[1];
05260 bool j1valid[1]={false};
05261 _nj1 = 1;
05262 IkReal x1177=((cj4)*(r22));
05263 IkReal x1178=((r11)*(sj0));
05264 IkReal x1179=((IkReal(1.00000000000000))*(cj2));
05265 IkReal x1180=((sj2)*(sj4));
05266 IkReal x1181=((IkReal(1.00000000000000))*(sj2));
05267 IkReal x1182=((cj2)*(sj4));
05268 IkReal x1183=((cj0)*(r01));
05269 IkReal x1184=((cj5)*(r20));
05270 IkReal x1185=((IkReal(1.00000000000000))*(sj4)*(sj5));
05271 IkReal x1186=((cj0)*(cj4)*(r02));
05272 IkReal x1187=((cj4)*(r12)*(sj0));
05273 IkReal x1188=((cj5)*(r10)*(sj0));
05274 IkReal x1189=((cj0)*(cj5)*(r00));
05275 if( IKabs(((gconst125)*(((((sj2)*(x1177)))+(((IkReal(-1.00000000000000))*(x1179)*(x1187)))+(((r21)*(sj5)*(x1180)))+(((x1182)*(x1188)))+(((IkReal(-1.00000000000000))*(x1180)*(x1184)))+(((x1182)*(x1189)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1179)*(x1183)))+(((IkReal(-1.00000000000000))*(x1179)*(x1186)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1178)*(x1179))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst125)*(((((IkReal(-1.00000000000000))*(sj5)*(x1178)*(x1180)))+(((IkReal(-1.00000000000000))*(x1181)*(x1187)))+(((IkReal(-1.00000000000000))*(x1177)*(x1179)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1179)))+(((x1180)*(x1189)))+(((x1182)*(x1184)))+(((IkReal(-1.00000000000000))*(x1181)*(x1186)))+(((IkReal(-1.00000000000000))*(sj5)*(x1180)*(x1183)))+(((x1180)*(x1188))))))) < IKFAST_ATAN2_MAGTHRESH )
05276     continue;
05277 j1array[0]=IKatan2(((gconst125)*(((((sj2)*(x1177)))+(((IkReal(-1.00000000000000))*(x1179)*(x1187)))+(((r21)*(sj5)*(x1180)))+(((x1182)*(x1188)))+(((IkReal(-1.00000000000000))*(x1180)*(x1184)))+(((x1182)*(x1189)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1179)*(x1183)))+(((IkReal(-1.00000000000000))*(x1179)*(x1186)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1178)*(x1179)))))), ((gconst125)*(((((IkReal(-1.00000000000000))*(sj5)*(x1178)*(x1180)))+(((IkReal(-1.00000000000000))*(x1181)*(x1187)))+(((IkReal(-1.00000000000000))*(x1177)*(x1179)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1179)))+(((x1180)*(x1189)))+(((x1182)*(x1184)))+(((IkReal(-1.00000000000000))*(x1181)*(x1186)))+(((IkReal(-1.00000000000000))*(sj5)*(x1180)*(x1183)))+(((x1180)*(x1188)))))));
05278 sj1array[0]=IKsin(j1array[0]);
05279 cj1array[0]=IKcos(j1array[0]);
05280 if( j1array[0] > IKPI )
05281 {
05282     j1array[0]-=IK2PI;
05283 }
05284 else if( j1array[0] < -IKPI )
05285 {    j1array[0]+=IK2PI;
05286 }
05287 j1valid[0] = true;
05288 for(int ij1 = 0; ij1 < 1; ++ij1)
05289 {
05290 if( !j1valid[ij1] )
05291 {
05292     continue;
05293 }
05294 _ij1[0] = ij1; _ij1[1] = -1;
05295 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05296 {
05297 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05298 {
05299     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05300 }
05301 }
05302 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05303 {
05304 IkReal evalcond[4];
05305 IkReal x1190=IKcos(j1);
05306 IkReal x1191=IKsin(j1);
05307 IkReal x1192=((IkReal(1.00000000000000))*(sj4));
05308 IkReal x1193=((cj5)*(r00));
05309 IkReal x1194=((cj5)*(r20));
05310 IkReal x1195=((r12)*(sj0));
05311 IkReal x1196=((r21)*(sj5));
05312 IkReal x1197=((IkReal(1.00000000000000))*(cj4));
05313 IkReal x1198=((sj2)*(x1191));
05314 IkReal x1199=((IkReal(1.00000000000000))*(x1190));
05315 IkReal x1200=((r11)*(sj0)*(sj5));
05316 IkReal x1201=((cj0)*(x1197));
05317 IkReal x1202=((cj0)*(r01)*(sj5));
05318 IkReal x1203=((cj2)*(x1191));
05319 IkReal x1204=((cj5)*(r10)*(sj0));
05320 IkReal x1205=((cj2)*(x1199));
05321 evalcond[0]=((((IkReal(-1.00000000000000))*(x1205)))+(((sj4)*(x1196)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1192)*(x1194)))+(x1198));
05322 evalcond[1]=((((IkReal(-1.00000000000000))*(x1196)*(x1197)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1203)))+(((IkReal(-1.00000000000000))*(sj2)*(x1199)))+(((cj4)*(x1194))));
05323 evalcond[2]=((((IkReal(-1.00000000000000))*(x1195)*(x1197)))+(((IkReal(-1.00000000000000))*(r02)*(x1201)))+(((sj2)*(x1190)))+(((IkReal(-1.00000000000000))*(x1192)*(x1200)))+(((sj4)*(x1204)))+(x1203)+(((cj0)*(sj4)*(x1193)))+(((IkReal(-1.00000000000000))*(x1192)*(x1202))));
05324 evalcond[3]=((((IkReal(-1.00000000000000))*(x1205)))+(((cj4)*(x1200)))+(((IkReal(-1.00000000000000))*(x1197)*(x1204)))+(x1198)+(((IkReal(-1.00000000000000))*(x1193)*(x1201)))+(((IkReal(-1.00000000000000))*(x1192)*(x1195)))+(((cj4)*(x1202)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1192))));
05325 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05326 {
05327 continue;
05328 }
05329 }
05330 
05331 {
05332 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05333 vinfos[0].jointtype = 1;
05334 vinfos[0].foffset = j0;
05335 vinfos[0].indices[0] = _ij0[0];
05336 vinfos[0].indices[1] = _ij0[1];
05337 vinfos[0].maxsolutions = _nj0;
05338 vinfos[1].jointtype = 1;
05339 vinfos[1].foffset = j1;
05340 vinfos[1].indices[0] = _ij1[0];
05341 vinfos[1].indices[1] = _ij1[1];
05342 vinfos[1].maxsolutions = _nj1;
05343 vinfos[2].jointtype = 1;
05344 vinfos[2].foffset = j2;
05345 vinfos[2].indices[0] = _ij2[0];
05346 vinfos[2].indices[1] = _ij2[1];
05347 vinfos[2].maxsolutions = _nj2;
05348 vinfos[3].jointtype = 1;
05349 vinfos[3].foffset = j3;
05350 vinfos[3].indices[0] = _ij3[0];
05351 vinfos[3].indices[1] = _ij3[1];
05352 vinfos[3].maxsolutions = _nj3;
05353 vinfos[4].jointtype = 1;
05354 vinfos[4].foffset = j4;
05355 vinfos[4].indices[0] = _ij4[0];
05356 vinfos[4].indices[1] = _ij4[1];
05357 vinfos[4].maxsolutions = _nj4;
05358 vinfos[5].jointtype = 1;
05359 vinfos[5].foffset = j5;
05360 vinfos[5].indices[0] = _ij5[0];
05361 vinfos[5].indices[1] = _ij5[1];
05362 vinfos[5].maxsolutions = _nj5;
05363 std::vector<int> vfree(0);
05364 solutions.AddSolution(vinfos,vfree);
05365 }
05366 }
05367 }
05368 
05369 }
05370 
05371 }
05372 
05373 } else
05374 {
05375 {
05376 IkReal j1array[1], cj1array[1], sj1array[1];
05377 bool j1valid[1]={false};
05378 _nj1 = 1;
05379 IkReal x1206=((IkReal(1.00000000000000))*(cj2));
05380 IkReal x1207=((cj2)*(r22));
05381 IkReal x1208=((r21)*(sj5));
05382 IkReal x1209=((r22)*(sj2));
05383 IkReal x1210=((cj5)*(r20)*(sj4));
05384 IkReal x1211=((cj4)*(cj5)*(r20));
05385 IkReal x1212=((IkReal(1.00000000000000))*(sj2)*(x1208));
05386 if( IKabs(((gconst124)*(((((IkReal(-1.00000000000000))*(sj4)*(x1212)))+(((sj2)*(x1210)))+(((IkReal(-1.00000000000000))*(cj4)*(x1206)*(x1208)))+(((sj4)*(x1207)))+(((IkReal(-1.00000000000000))*(cj4)*(x1209)))+(((cj2)*(x1211))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst124)*(((((sj4)*(x1209)))+(((cj4)*(x1207)))+(((sj2)*(x1211)))+(((IkReal(-1.00000000000000))*(x1206)*(x1210)))+(((IkReal(-1.00000000000000))*(cj4)*(x1212)))+(((cj2)*(sj4)*(x1208))))))) < IKFAST_ATAN2_MAGTHRESH )
05387     continue;
05388 j1array[0]=IKatan2(((gconst124)*(((((IkReal(-1.00000000000000))*(sj4)*(x1212)))+(((sj2)*(x1210)))+(((IkReal(-1.00000000000000))*(cj4)*(x1206)*(x1208)))+(((sj4)*(x1207)))+(((IkReal(-1.00000000000000))*(cj4)*(x1209)))+(((cj2)*(x1211)))))), ((gconst124)*(((((sj4)*(x1209)))+(((cj4)*(x1207)))+(((sj2)*(x1211)))+(((IkReal(-1.00000000000000))*(x1206)*(x1210)))+(((IkReal(-1.00000000000000))*(cj4)*(x1212)))+(((cj2)*(sj4)*(x1208)))))));
05389 sj1array[0]=IKsin(j1array[0]);
05390 cj1array[0]=IKcos(j1array[0]);
05391 if( j1array[0] > IKPI )
05392 {
05393     j1array[0]-=IK2PI;
05394 }
05395 else if( j1array[0] < -IKPI )
05396 {    j1array[0]+=IK2PI;
05397 }
05398 j1valid[0] = true;
05399 for(int ij1 = 0; ij1 < 1; ++ij1)
05400 {
05401 if( !j1valid[ij1] )
05402 {
05403     continue;
05404 }
05405 _ij1[0] = ij1; _ij1[1] = -1;
05406 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05407 {
05408 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05409 {
05410     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05411 }
05412 }
05413 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05414 {
05415 IkReal evalcond[4];
05416 IkReal x1213=IKcos(j1);
05417 IkReal x1214=IKsin(j1);
05418 IkReal x1215=((IkReal(1.00000000000000))*(sj4));
05419 IkReal x1216=((cj5)*(r00));
05420 IkReal x1217=((cj5)*(r20));
05421 IkReal x1218=((r12)*(sj0));
05422 IkReal x1219=((r21)*(sj5));
05423 IkReal x1220=((IkReal(1.00000000000000))*(cj4));
05424 IkReal x1221=((sj2)*(x1214));
05425 IkReal x1222=((IkReal(1.00000000000000))*(x1213));
05426 IkReal x1223=((r11)*(sj0)*(sj5));
05427 IkReal x1224=((cj0)*(x1220));
05428 IkReal x1225=((cj0)*(r01)*(sj5));
05429 IkReal x1226=((cj2)*(x1214));
05430 IkReal x1227=((cj5)*(r10)*(sj0));
05431 IkReal x1228=((cj2)*(x1222));
05432 evalcond[0]=((((sj4)*(x1219)))+(x1221)+(((IkReal(-1.00000000000000))*(x1228)))+(((IkReal(-1.00000000000000))*(x1215)*(x1217)))+(((cj4)*(r22))));
05433 evalcond[1]=((((IkReal(-1.00000000000000))*(sj2)*(x1222)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(x1226)))+(((cj4)*(x1217)))+(((IkReal(-1.00000000000000))*(x1219)*(x1220))));
05434 evalcond[2]=((((IkReal(-1.00000000000000))*(x1218)*(x1220)))+(x1226)+(((IkReal(-1.00000000000000))*(x1215)*(x1225)))+(((sj4)*(x1227)))+(((IkReal(-1.00000000000000))*(r02)*(x1224)))+(((sj2)*(x1213)))+(((IkReal(-1.00000000000000))*(x1215)*(x1223)))+(((cj0)*(sj4)*(x1216))));
05435 evalcond[3]=((((cj4)*(x1223)))+(((IkReal(-1.00000000000000))*(x1215)*(x1218)))+(x1221)+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1215)))+(((IkReal(-1.00000000000000))*(x1216)*(x1224)))+(((IkReal(-1.00000000000000))*(x1228)))+(((IkReal(-1.00000000000000))*(x1220)*(x1227)))+(((cj4)*(x1225))));
05436 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05437 {
05438 continue;
05439 }
05440 }
05441 
05442 {
05443 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05444 vinfos[0].jointtype = 1;
05445 vinfos[0].foffset = j0;
05446 vinfos[0].indices[0] = _ij0[0];
05447 vinfos[0].indices[1] = _ij0[1];
05448 vinfos[0].maxsolutions = _nj0;
05449 vinfos[1].jointtype = 1;
05450 vinfos[1].foffset = j1;
05451 vinfos[1].indices[0] = _ij1[0];
05452 vinfos[1].indices[1] = _ij1[1];
05453 vinfos[1].maxsolutions = _nj1;
05454 vinfos[2].jointtype = 1;
05455 vinfos[2].foffset = j2;
05456 vinfos[2].indices[0] = _ij2[0];
05457 vinfos[2].indices[1] = _ij2[1];
05458 vinfos[2].maxsolutions = _nj2;
05459 vinfos[3].jointtype = 1;
05460 vinfos[3].foffset = j3;
05461 vinfos[3].indices[0] = _ij3[0];
05462 vinfos[3].indices[1] = _ij3[1];
05463 vinfos[3].maxsolutions = _nj3;
05464 vinfos[4].jointtype = 1;
05465 vinfos[4].foffset = j4;
05466 vinfos[4].indices[0] = _ij4[0];
05467 vinfos[4].indices[1] = _ij4[1];
05468 vinfos[4].maxsolutions = _nj4;
05469 vinfos[5].jointtype = 1;
05470 vinfos[5].foffset = j5;
05471 vinfos[5].indices[0] = _ij5[0];
05472 vinfos[5].indices[1] = _ij5[1];
05473 vinfos[5].maxsolutions = _nj5;
05474 std::vector<int> vfree(0);
05475 solutions.AddSolution(vinfos,vfree);
05476 }
05477 }
05478 }
05479 
05480 }
05481 
05482 }
05483 }
05484 }
05485 
05486 }
05487 
05488 }
05489 
05490 } else
05491 {
05492 {
05493 IkReal j1array[1], cj1array[1], sj1array[1];
05494 bool j1valid[1]={false};
05495 _nj1 = 1;
05496 IkReal x1229=((IkReal(1.00000000000000))*(cj2));
05497 IkReal x1230=((cj2)*(r22));
05498 IkReal x1231=((r21)*(sj5));
05499 IkReal x1232=((r22)*(sj2));
05500 IkReal x1233=((cj5)*(r20)*(sj4));
05501 IkReal x1234=((cj4)*(cj5)*(r20));
05502 IkReal x1235=((IkReal(1.00000000000000))*(sj2)*(x1231));
05503 if( IKabs(((gconst123)*(((((IkReal(-1.00000000000000))*(cj4)*(x1229)*(x1231)))+(((cj2)*(x1234)))+(((IkReal(-1.00000000000000))*(cj4)*(x1232)))+(((sj4)*(x1230)))+(((IkReal(-1.00000000000000))*(sj4)*(x1235)))+(((sj2)*(x1233))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst123)*(((((IkReal(-1.00000000000000))*(cj4)*(x1235)))+(((IkReal(-1.00000000000000))*(x1229)*(x1233)))+(((sj4)*(x1232)))+(((cj2)*(sj4)*(x1231)))+(((sj2)*(x1234)))+(((cj4)*(x1230))))))) < IKFAST_ATAN2_MAGTHRESH )
05504     continue;
05505 j1array[0]=IKatan2(((gconst123)*(((((IkReal(-1.00000000000000))*(cj4)*(x1229)*(x1231)))+(((cj2)*(x1234)))+(((IkReal(-1.00000000000000))*(cj4)*(x1232)))+(((sj4)*(x1230)))+(((IkReal(-1.00000000000000))*(sj4)*(x1235)))+(((sj2)*(x1233)))))), ((gconst123)*(((((IkReal(-1.00000000000000))*(cj4)*(x1235)))+(((IkReal(-1.00000000000000))*(x1229)*(x1233)))+(((sj4)*(x1232)))+(((cj2)*(sj4)*(x1231)))+(((sj2)*(x1234)))+(((cj4)*(x1230)))))));
05506 sj1array[0]=IKsin(j1array[0]);
05507 cj1array[0]=IKcos(j1array[0]);
05508 if( j1array[0] > IKPI )
05509 {
05510     j1array[0]-=IK2PI;
05511 }
05512 else if( j1array[0] < -IKPI )
05513 {    j1array[0]+=IK2PI;
05514 }
05515 j1valid[0] = true;
05516 for(int ij1 = 0; ij1 < 1; ++ij1)
05517 {
05518 if( !j1valid[ij1] )
05519 {
05520     continue;
05521 }
05522 _ij1[0] = ij1; _ij1[1] = -1;
05523 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05524 {
05525 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05526 {
05527     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05528 }
05529 }
05530 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05531 {
05532 IkReal evalcond[2];
05533 IkReal x1236=IKcos(j1);
05534 IkReal x1237=IKsin(j1);
05535 IkReal x1238=((cj5)*(r20));
05536 IkReal x1239=((r21)*(sj5));
05537 IkReal x1240=((IkReal(1.00000000000000))*(x1236));
05538 evalcond[0]=((((IkReal(-1.00000000000000))*(sj4)*(x1238)))+(((IkReal(-1.00000000000000))*(cj2)*(x1240)))+(((cj4)*(r22)))+(((sj4)*(x1239)))+(((sj2)*(x1237))));
05539 evalcond[1]=((((IkReal(-1.00000000000000))*(cj2)*(x1237)))+(((cj4)*(x1238)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x1240)))+(((IkReal(-1.00000000000000))*(cj4)*(x1239))));
05540 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
05541 {
05542 continue;
05543 }
05544 }
05545 
05546 {
05547 IkReal dummyeval[1];
05548 IkReal gconst126;
05549 IkReal x1241=(cj5)*(cj5);
05550 IkReal x1242=(sj5)*(sj5);
05551 IkReal x1243=((IkReal(1.00000000000000))*(x1242));
05552 IkReal x1244=((IkReal(2.00000000000000))*(cj5)*(sj5));
05553 IkReal x1245=((IkReal(1.00000000000000))*(x1241));
05554 gconst126=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1244)))+(((IkReal(-1.00000000000000))*(x1245)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1243)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1244)))+(((IkReal(-1.00000000000000))*(x1245)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1243)*((r10)*(r10))))));
05555 IkReal x1246=(cj5)*(cj5);
05556 IkReal x1247=(sj5)*(sj5);
05557 IkReal x1248=((IkReal(1.00000000000000))*(x1247));
05558 IkReal x1249=((IkReal(2.00000000000000))*(cj5)*(sj5));
05559 IkReal x1250=((IkReal(1.00000000000000))*(x1246));
05560 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(r01)*(x1249)))+(((IkReal(-1.00000000000000))*(x1248)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1249)))+(((IkReal(-1.00000000000000))*(x1248)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1250)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1250)*((r11)*(r11)))));
05561 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05562 {
05563 {
05564 IkReal dummyeval[1];
05565 IkReal gconst127;
05566 IkReal x1251=(sj5)*(sj5);
05567 IkReal x1252=(cj5)*(cj5);
05568 IkReal x1253=((cj4)*(cj5));
05569 IkReal x1254=((IkReal(1.00000000000000))*(r12));
05570 IkReal x1255=((cj4)*(sj5));
05571 IkReal x1256=((r01)*(r10));
05572 IkReal x1257=((sj4)*(x1252));
05573 IkReal x1258=((IkReal(1.00000000000000))*(r00)*(r11));
05574 IkReal x1259=((sj4)*(x1251));
05575 gconst127=IKsign(((((IkReal(-1.00000000000000))*(x1257)*(x1258)))+(((x1256)*(x1259)))+(((IkReal(-1.00000000000000))*(x1258)*(x1259)))+(((r02)*(r11)*(x1253)))+(((r02)*(r10)*(x1255)))+(((x1256)*(x1257)))+(((IkReal(-1.00000000000000))*(r00)*(x1254)*(x1255)))+(((IkReal(-1.00000000000000))*(r01)*(x1253)*(x1254)))));
05576 IkReal x1260=(sj5)*(sj5);
05577 IkReal x1261=(cj5)*(cj5);
05578 IkReal x1262=((cj4)*(cj5));
05579 IkReal x1263=((IkReal(1.00000000000000))*(r12));
05580 IkReal x1264=((cj4)*(sj5));
05581 IkReal x1265=((r01)*(r10));
05582 IkReal x1266=((sj4)*(x1261));
05583 IkReal x1267=((IkReal(1.00000000000000))*(r00)*(r11));
05584 IkReal x1268=((sj4)*(x1260));
05585 dummyeval[0]=((((IkReal(-1.00000000000000))*(r01)*(x1262)*(x1263)))+(((IkReal(-1.00000000000000))*(r00)*(x1263)*(x1264)))+(((IkReal(-1.00000000000000))*(x1266)*(x1267)))+(((r02)*(r11)*(x1262)))+(((IkReal(-1.00000000000000))*(x1267)*(x1268)))+(((x1265)*(x1268)))+(((r02)*(r10)*(x1264)))+(((x1265)*(x1266))));
05586 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05587 {
05588 continue;
05589 
05590 } else
05591 {
05592 {
05593 IkReal j0array[1], cj0array[1], sj0array[1];
05594 bool j0valid[1]={false};
05595 _nj0 = 1;
05596 IkReal x1269=((cj5)*(sj4));
05597 IkReal x1270=((IkReal(1.00000000000000))*(cj4));
05598 IkReal x1271=((IkReal(1.00000000000000))*(sj4)*(sj5));
05599 if( IKabs(((gconst127)*(((((IkReal(-1.00000000000000))*(r11)*(x1271)))+(((r10)*(x1269)))+(((IkReal(-1.00000000000000))*(r12)*(x1270))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst127)*(((((IkReal(-1.00000000000000))*(r02)*(x1270)))+(((r00)*(x1269)))+(((IkReal(-1.00000000000000))*(r01)*(x1271))))))) < IKFAST_ATAN2_MAGTHRESH )
05600     continue;
05601 j0array[0]=IKatan2(((gconst127)*(((((IkReal(-1.00000000000000))*(r11)*(x1271)))+(((r10)*(x1269)))+(((IkReal(-1.00000000000000))*(r12)*(x1270)))))), ((gconst127)*(((((IkReal(-1.00000000000000))*(r02)*(x1270)))+(((r00)*(x1269)))+(((IkReal(-1.00000000000000))*(r01)*(x1271)))))));
05602 sj0array[0]=IKsin(j0array[0]);
05603 cj0array[0]=IKcos(j0array[0]);
05604 if( j0array[0] > IKPI )
05605 {
05606     j0array[0]-=IK2PI;
05607 }
05608 else if( j0array[0] < -IKPI )
05609 {    j0array[0]+=IK2PI;
05610 }
05611 j0valid[0] = true;
05612 for(int ij0 = 0; ij0 < 1; ++ij0)
05613 {
05614 if( !j0valid[ij0] )
05615 {
05616     continue;
05617 }
05618 _ij0[0] = ij0; _ij0[1] = -1;
05619 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05620 {
05621 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05622 {
05623     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05624 }
05625 }
05626 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05627 {
05628 IkReal evalcond[6];
05629 IkReal x1272=IKsin(j0);
05630 IkReal x1273=IKcos(j0);
05631 IkReal x1274=((IkReal(1.00000000000000))*(r10));
05632 IkReal x1275=((IkReal(1.00000000000000))*(sj4));
05633 IkReal x1276=((cj5)*(r01));
05634 IkReal x1277=((cj5)*(r00));
05635 IkReal x1278=((cj4)*(r01));
05636 IkReal x1279=((IkReal(1.00000000000000))*(cj4));
05637 IkReal x1280=((cj4)*(r11));
05638 IkReal x1281=((sj5)*(x1272));
05639 IkReal x1282=((r11)*(x1275));
05640 IkReal x1283=((sj5)*(x1273));
05641 IkReal x1284=((r02)*(x1273));
05642 IkReal x1285=((r12)*(x1273));
05643 IkReal x1286=((IkReal(1.00000000000000))*(x1273));
05644 IkReal x1287=((cj4)*(x1272));
05645 IkReal x1288=((cj5)*(x1272));
05646 IkReal x1289=((cj5)*(sj4)*(x1273));
05647 evalcond[0]=((IkReal(-1.00000000000000))+(((r00)*(x1281)))+(((IkReal(-1.00000000000000))*(x1274)*(x1283)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1286)))+(((x1272)*(x1276))));
05648 evalcond[1]=((((IkReal(-1.00000000000000))*(x1274)*(x1281)))+(((IkReal(-1.00000000000000))*(x1276)*(x1286)))+(((IkReal(-1.00000000000000))*(r00)*(x1283)))+(((IkReal(-1.00000000000000))*(r11)*(x1288))));
05649 evalcond[2]=((((IkReal(-1.00000000000000))*(x1282)*(x1283)))+(((r10)*(x1289)))+(((r02)*(x1287)))+(((r01)*(sj4)*(x1281)))+(((IkReal(-1.00000000000000))*(x1279)*(x1285)))+(((IkReal(-1.00000000000000))*(x1272)*(x1275)*(x1277))));
05650 evalcond[3]=((((x1277)*(x1287)))+(((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1273)*(x1274)))+(((r02)*(sj4)*(x1272)))+(((IkReal(-1.00000000000000))*(x1275)*(x1285)))+(((x1280)*(x1283)))+(((IkReal(-1.00000000000000))*(x1278)*(x1281))));
05651 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1279)*(x1284)))+(((r10)*(sj4)*(x1288)))+(((IkReal(-1.00000000000000))*(x1281)*(x1282)))+(((sj4)*(x1273)*(x1277)))+(((IkReal(-1.00000000000000))*(r12)*(x1272)*(x1279)))+(((IkReal(-1.00000000000000))*(r01)*(x1275)*(x1283)))+(((cj2)*(sj1))));
05652 evalcond[5]=((((IkReal(-1.00000000000000))*(cj5)*(x1274)*(x1287)))+(((IkReal(-1.00000000000000))*(cj1)*(cj2)))+(((IkReal(-1.00000000000000))*(x1273)*(x1277)*(x1279)))+(((IkReal(-1.00000000000000))*(x1275)*(x1284)))+(((IkReal(-1.00000000000000))*(r12)*(x1272)*(x1275)))+(((x1278)*(x1283)))+(((sj1)*(sj2)))+(((x1280)*(x1281))));
05653 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  )
05654 {
05655 continue;
05656 }
05657 }
05658 
05659 {
05660 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05661 vinfos[0].jointtype = 1;
05662 vinfos[0].foffset = j0;
05663 vinfos[0].indices[0] = _ij0[0];
05664 vinfos[0].indices[1] = _ij0[1];
05665 vinfos[0].maxsolutions = _nj0;
05666 vinfos[1].jointtype = 1;
05667 vinfos[1].foffset = j1;
05668 vinfos[1].indices[0] = _ij1[0];
05669 vinfos[1].indices[1] = _ij1[1];
05670 vinfos[1].maxsolutions = _nj1;
05671 vinfos[2].jointtype = 1;
05672 vinfos[2].foffset = j2;
05673 vinfos[2].indices[0] = _ij2[0];
05674 vinfos[2].indices[1] = _ij2[1];
05675 vinfos[2].maxsolutions = _nj2;
05676 vinfos[3].jointtype = 1;
05677 vinfos[3].foffset = j3;
05678 vinfos[3].indices[0] = _ij3[0];
05679 vinfos[3].indices[1] = _ij3[1];
05680 vinfos[3].maxsolutions = _nj3;
05681 vinfos[4].jointtype = 1;
05682 vinfos[4].foffset = j4;
05683 vinfos[4].indices[0] = _ij4[0];
05684 vinfos[4].indices[1] = _ij4[1];
05685 vinfos[4].maxsolutions = _nj4;
05686 vinfos[5].jointtype = 1;
05687 vinfos[5].foffset = j5;
05688 vinfos[5].indices[0] = _ij5[0];
05689 vinfos[5].indices[1] = _ij5[1];
05690 vinfos[5].maxsolutions = _nj5;
05691 std::vector<int> vfree(0);
05692 solutions.AddSolution(vinfos,vfree);
05693 }
05694 }
05695 }
05696 
05697 }
05698 
05699 }
05700 
05701 } else
05702 {
05703 {
05704 IkReal j0array[1], cj0array[1], sj0array[1];
05705 bool j0valid[1]={false};
05706 _nj0 = 1;
05707 if( IKabs(((gconst126)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst126)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
05708     continue;
05709 j0array[0]=IKatan2(((gconst126)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst126)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
05710 sj0array[0]=IKsin(j0array[0]);
05711 cj0array[0]=IKcos(j0array[0]);
05712 if( j0array[0] > IKPI )
05713 {
05714     j0array[0]-=IK2PI;
05715 }
05716 else if( j0array[0] < -IKPI )
05717 {    j0array[0]+=IK2PI;
05718 }
05719 j0valid[0] = true;
05720 for(int ij0 = 0; ij0 < 1; ++ij0)
05721 {
05722 if( !j0valid[ij0] )
05723 {
05724     continue;
05725 }
05726 _ij0[0] = ij0; _ij0[1] = -1;
05727 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05728 {
05729 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05730 {
05731     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05732 }
05733 }
05734 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05735 {
05736 IkReal evalcond[6];
05737 IkReal x1290=IKsin(j0);
05738 IkReal x1291=IKcos(j0);
05739 IkReal x1292=((IkReal(1.00000000000000))*(r10));
05740 IkReal x1293=((IkReal(1.00000000000000))*(sj4));
05741 IkReal x1294=((cj5)*(r01));
05742 IkReal x1295=((cj5)*(r00));
05743 IkReal x1296=((cj4)*(r01));
05744 IkReal x1297=((IkReal(1.00000000000000))*(cj4));
05745 IkReal x1298=((cj4)*(r11));
05746 IkReal x1299=((sj5)*(x1290));
05747 IkReal x1300=((r11)*(x1293));
05748 IkReal x1301=((sj5)*(x1291));
05749 IkReal x1302=((r02)*(x1291));
05750 IkReal x1303=((r12)*(x1291));
05751 IkReal x1304=((IkReal(1.00000000000000))*(x1291));
05752 IkReal x1305=((cj4)*(x1290));
05753 IkReal x1306=((cj5)*(x1290));
05754 IkReal x1307=((cj5)*(sj4)*(x1291));
05755 evalcond[0]=((IkReal(-1.00000000000000))+(((r00)*(x1299)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1304)))+(((x1290)*(x1294)))+(((IkReal(-1.00000000000000))*(x1292)*(x1301))));
05756 evalcond[1]=((((IkReal(-1.00000000000000))*(x1292)*(x1299)))+(((IkReal(-1.00000000000000))*(r11)*(x1306)))+(((IkReal(-1.00000000000000))*(x1294)*(x1304)))+(((IkReal(-1.00000000000000))*(r00)*(x1301))));
05757 evalcond[2]=((((r01)*(sj4)*(x1299)))+(((IkReal(-1.00000000000000))*(x1300)*(x1301)))+(((IkReal(-1.00000000000000))*(x1290)*(x1293)*(x1295)))+(((r02)*(x1305)))+(((r10)*(x1307)))+(((IkReal(-1.00000000000000))*(x1297)*(x1303))));
05758 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(cj5)*(x1291)*(x1292)))+(((x1295)*(x1305)))+(((IkReal(-1.00000000000000))*(x1296)*(x1299)))+(((IkReal(-1.00000000000000))*(x1293)*(x1303)))+(((r02)*(sj4)*(x1290)))+(((x1298)*(x1301))));
05759 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(r01)*(x1293)*(x1301)))+(((sj4)*(x1291)*(x1295)))+(((IkReal(-1.00000000000000))*(x1299)*(x1300)))+(((IkReal(-1.00000000000000))*(r12)*(x1290)*(x1297)))+(((r10)*(sj4)*(x1306)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x1297)*(x1302))));
05760 evalcond[5]=((((IkReal(-1.00000000000000))*(cj1)*(cj2)))+(((IkReal(-1.00000000000000))*(x1293)*(x1302)))+(((IkReal(-1.00000000000000))*(r12)*(x1290)*(x1293)))+(((x1296)*(x1301)))+(((sj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1291)*(x1295)*(x1297)))+(((IkReal(-1.00000000000000))*(cj5)*(x1292)*(x1305)))+(((x1298)*(x1299))));
05761 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  )
05762 {
05763 continue;
05764 }
05765 }
05766 
05767 {
05768 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05769 vinfos[0].jointtype = 1;
05770 vinfos[0].foffset = j0;
05771 vinfos[0].indices[0] = _ij0[0];
05772 vinfos[0].indices[1] = _ij0[1];
05773 vinfos[0].maxsolutions = _nj0;
05774 vinfos[1].jointtype = 1;
05775 vinfos[1].foffset = j1;
05776 vinfos[1].indices[0] = _ij1[0];
05777 vinfos[1].indices[1] = _ij1[1];
05778 vinfos[1].maxsolutions = _nj1;
05779 vinfos[2].jointtype = 1;
05780 vinfos[2].foffset = j2;
05781 vinfos[2].indices[0] = _ij2[0];
05782 vinfos[2].indices[1] = _ij2[1];
05783 vinfos[2].maxsolutions = _nj2;
05784 vinfos[3].jointtype = 1;
05785 vinfos[3].foffset = j3;
05786 vinfos[3].indices[0] = _ij3[0];
05787 vinfos[3].indices[1] = _ij3[1];
05788 vinfos[3].maxsolutions = _nj3;
05789 vinfos[4].jointtype = 1;
05790 vinfos[4].foffset = j4;
05791 vinfos[4].indices[0] = _ij4[0];
05792 vinfos[4].indices[1] = _ij4[1];
05793 vinfos[4].maxsolutions = _nj4;
05794 vinfos[5].jointtype = 1;
05795 vinfos[5].foffset = j5;
05796 vinfos[5].indices[0] = _ij5[0];
05797 vinfos[5].indices[1] = _ij5[1];
05798 vinfos[5].maxsolutions = _nj5;
05799 std::vector<int> vfree(0);
05800 solutions.AddSolution(vinfos,vfree);
05801 }
05802 }
05803 }
05804 
05805 }
05806 
05807 }
05808 }
05809 }
05810 
05811 }
05812 
05813 }
05814 
05815 } else
05816 {
05817 {
05818 IkReal j0array[1], cj0array[1], sj0array[1];
05819 bool j0valid[1]={false};
05820 _nj0 = 1;
05821 if( IKabs(((gconst121)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst121)*(((((cj5)*(r11)))+(((r10)*(sj5))))))) < IKFAST_ATAN2_MAGTHRESH )
05822     continue;
05823 j0array[0]=IKatan2(((gconst121)*(((((IkReal(-1.00000000000000))*(r00)*(sj5)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)))))), ((gconst121)*(((((cj5)*(r11)))+(((r10)*(sj5)))))));
05824 sj0array[0]=IKsin(j0array[0]);
05825 cj0array[0]=IKcos(j0array[0]);
05826 if( j0array[0] > IKPI )
05827 {
05828     j0array[0]-=IK2PI;
05829 }
05830 else if( j0array[0] < -IKPI )
05831 {    j0array[0]+=IK2PI;
05832 }
05833 j0valid[0] = true;
05834 for(int ij0 = 0; ij0 < 1; ++ij0)
05835 {
05836 if( !j0valid[ij0] )
05837 {
05838     continue;
05839 }
05840 _ij0[0] = ij0; _ij0[1] = -1;
05841 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
05842 {
05843 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
05844 {
05845     j0valid[iij0]=false; _ij0[1] = iij0; break; 
05846 }
05847 }
05848 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
05849 {
05850 IkReal evalcond[4];
05851 IkReal x1308=IKsin(j0);
05852 IkReal x1309=IKcos(j0);
05853 IkReal x1310=((IkReal(1.00000000000000))*(cj5));
05854 IkReal x1311=((r01)*(sj5));
05855 IkReal x1312=((IkReal(1.00000000000000))*(r12));
05856 IkReal x1313=((IkReal(1.00000000000000))*(r10));
05857 IkReal x1314=((r11)*(sj5));
05858 IkReal x1315=((cj4)*(x1308));
05859 IkReal x1316=((sj4)*(x1308));
05860 IkReal x1317=((sj4)*(x1309));
05861 IkReal x1318=((sj5)*(x1308));
05862 IkReal x1319=((cj4)*(x1309));
05863 IkReal x1320=((sj5)*(x1309));
05864 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1313)*(x1320)))+(((r00)*(x1318)))+(((IkReal(-1.00000000000000))*(r11)*(x1309)*(x1310)))+(((cj5)*(r01)*(x1308))));
05865 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(x1320)))+(((IkReal(-1.00000000000000))*(x1313)*(x1318)))+(((IkReal(-1.00000000000000))*(r11)*(x1308)*(x1310)))+(((IkReal(-1.00000000000000))*(r01)*(x1309)*(x1310))));
05866 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x1310)*(x1316)))+(((x1311)*(x1316)))+(((cj5)*(r10)*(x1317)))+(((IkReal(-1.00000000000000))*(x1314)*(x1317)))+(((r02)*(x1315)))+(((IkReal(-1.00000000000000))*(x1312)*(x1319))));
05867 evalcond[3]=((((IkReal(-1.00000000000000))*(x1312)*(x1317)))+(((cj5)*(r00)*(x1315)))+(((r02)*(x1316)))+(((IkReal(-1.00000000000000))*(r10)*(x1310)*(x1319)))+(((x1314)*(x1319)))+(((IkReal(-1.00000000000000))*(x1311)*(x1315))));
05868 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05869 {
05870 continue;
05871 }
05872 }
05873 
05874 {
05875 IkReal dummyeval[1];
05876 IkReal gconst124;
05877 gconst124=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
05878 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
05879 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05880 {
05881 {
05882 IkReal dummyeval[1];
05883 IkReal gconst125;
05884 gconst125=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
05885 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
05886 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05887 {
05888 continue;
05889 
05890 } else
05891 {
05892 {
05893 IkReal j1array[1], cj1array[1], sj1array[1];
05894 bool j1valid[1]={false};
05895 _nj1 = 1;
05896 IkReal x1321=((cj4)*(r22));
05897 IkReal x1322=((r11)*(sj0));
05898 IkReal x1323=((IkReal(1.00000000000000))*(cj2));
05899 IkReal x1324=((sj2)*(sj4));
05900 IkReal x1325=((IkReal(1.00000000000000))*(sj2));
05901 IkReal x1326=((cj2)*(sj4));
05902 IkReal x1327=((cj0)*(r01));
05903 IkReal x1328=((cj5)*(r20));
05904 IkReal x1329=((IkReal(1.00000000000000))*(sj4)*(sj5));
05905 IkReal x1330=((cj0)*(cj4)*(r02));
05906 IkReal x1331=((cj4)*(r12)*(sj0));
05907 IkReal x1332=((cj5)*(r10)*(sj0));
05908 IkReal x1333=((cj0)*(cj5)*(r00));
05909 if( IKabs(((gconst125)*(((((sj2)*(x1321)))+(((r21)*(sj5)*(x1324)))+(((IkReal(-1.00000000000000))*(x1323)*(x1331)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1322)*(x1323)))+(((x1326)*(x1333)))+(((IkReal(-1.00000000000000))*(x1323)*(x1330)))+(((x1326)*(x1332)))+(((IkReal(-1.00000000000000))*(x1324)*(x1328)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1323)*(x1327))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst125)*(((((IkReal(-1.00000000000000))*(sj5)*(x1324)*(x1327)))+(((IkReal(-1.00000000000000))*(x1325)*(x1330)))+(((x1324)*(x1332)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1323)))+(((IkReal(-1.00000000000000))*(sj5)*(x1322)*(x1324)))+(((x1326)*(x1328)))+(((IkReal(-1.00000000000000))*(x1321)*(x1323)))+(((x1324)*(x1333)))+(((IkReal(-1.00000000000000))*(x1325)*(x1331))))))) < IKFAST_ATAN2_MAGTHRESH )
05910     continue;
05911 j1array[0]=IKatan2(((gconst125)*(((((sj2)*(x1321)))+(((r21)*(sj5)*(x1324)))+(((IkReal(-1.00000000000000))*(x1323)*(x1331)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1322)*(x1323)))+(((x1326)*(x1333)))+(((IkReal(-1.00000000000000))*(x1323)*(x1330)))+(((x1326)*(x1332)))+(((IkReal(-1.00000000000000))*(x1324)*(x1328)))+(((IkReal(-1.00000000000000))*(sj4)*(sj5)*(x1323)*(x1327)))))), ((gconst125)*(((((IkReal(-1.00000000000000))*(sj5)*(x1324)*(x1327)))+(((IkReal(-1.00000000000000))*(x1325)*(x1330)))+(((x1324)*(x1332)))+(((IkReal(-1.00000000000000))*(r21)*(sj4)*(sj5)*(x1323)))+(((IkReal(-1.00000000000000))*(sj5)*(x1322)*(x1324)))+(((x1326)*(x1328)))+(((IkReal(-1.00000000000000))*(x1321)*(x1323)))+(((x1324)*(x1333)))+(((IkReal(-1.00000000000000))*(x1325)*(x1331)))))));
05912 sj1array[0]=IKsin(j1array[0]);
05913 cj1array[0]=IKcos(j1array[0]);
05914 if( j1array[0] > IKPI )
05915 {
05916     j1array[0]-=IK2PI;
05917 }
05918 else if( j1array[0] < -IKPI )
05919 {    j1array[0]+=IK2PI;
05920 }
05921 j1valid[0] = true;
05922 for(int ij1 = 0; ij1 < 1; ++ij1)
05923 {
05924 if( !j1valid[ij1] )
05925 {
05926     continue;
05927 }
05928 _ij1[0] = ij1; _ij1[1] = -1;
05929 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
05930 {
05931 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
05932 {
05933     j1valid[iij1]=false; _ij1[1] = iij1; break; 
05934 }
05935 }
05936 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
05937 {
05938 IkReal evalcond[4];
05939 IkReal x1334=IKcos(j1);
05940 IkReal x1335=IKsin(j1);
05941 IkReal x1336=((IkReal(1.00000000000000))*(sj4));
05942 IkReal x1337=((cj5)*(r00));
05943 IkReal x1338=((cj5)*(r20));
05944 IkReal x1339=((r12)*(sj0));
05945 IkReal x1340=((r21)*(sj5));
05946 IkReal x1341=((IkReal(1.00000000000000))*(cj4));
05947 IkReal x1342=((sj2)*(x1335));
05948 IkReal x1343=((IkReal(1.00000000000000))*(x1334));
05949 IkReal x1344=((r11)*(sj0)*(sj5));
05950 IkReal x1345=((cj0)*(x1341));
05951 IkReal x1346=((cj0)*(r01)*(sj5));
05952 IkReal x1347=((cj2)*(x1335));
05953 IkReal x1348=((cj5)*(r10)*(sj0));
05954 IkReal x1349=((cj2)*(x1343));
05955 evalcond[0]=((((sj4)*(x1340)))+(((IkReal(-1.00000000000000))*(x1336)*(x1338)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1349)))+(x1342));
05956 evalcond[1]=((((cj4)*(x1338)))+(((IkReal(-1.00000000000000))*(x1340)*(x1341)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x1343)))+(((IkReal(-1.00000000000000))*(x1347))));
05957 evalcond[2]=((((sj2)*(x1334)))+(((IkReal(-1.00000000000000))*(x1339)*(x1341)))+(((cj0)*(sj4)*(x1337)))+(((sj4)*(x1348)))+(((IkReal(-1.00000000000000))*(r02)*(x1345)))+(x1347)+(((IkReal(-1.00000000000000))*(x1336)*(x1344)))+(((IkReal(-1.00000000000000))*(x1336)*(x1346))));
05958 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1336)))+(((cj4)*(x1344)))+(((IkReal(-1.00000000000000))*(x1336)*(x1339)))+(((IkReal(-1.00000000000000))*(x1337)*(x1345)))+(((IkReal(-1.00000000000000))*(x1341)*(x1348)))+(((cj4)*(x1346)))+(((IkReal(-1.00000000000000))*(x1349)))+(x1342));
05959 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05960 {
05961 continue;
05962 }
05963 }
05964 
05965 {
05966 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05967 vinfos[0].jointtype = 1;
05968 vinfos[0].foffset = j0;
05969 vinfos[0].indices[0] = _ij0[0];
05970 vinfos[0].indices[1] = _ij0[1];
05971 vinfos[0].maxsolutions = _nj0;
05972 vinfos[1].jointtype = 1;
05973 vinfos[1].foffset = j1;
05974 vinfos[1].indices[0] = _ij1[0];
05975 vinfos[1].indices[1] = _ij1[1];
05976 vinfos[1].maxsolutions = _nj1;
05977 vinfos[2].jointtype = 1;
05978 vinfos[2].foffset = j2;
05979 vinfos[2].indices[0] = _ij2[0];
05980 vinfos[2].indices[1] = _ij2[1];
05981 vinfos[2].maxsolutions = _nj2;
05982 vinfos[3].jointtype = 1;
05983 vinfos[3].foffset = j3;
05984 vinfos[3].indices[0] = _ij3[0];
05985 vinfos[3].indices[1] = _ij3[1];
05986 vinfos[3].maxsolutions = _nj3;
05987 vinfos[4].jointtype = 1;
05988 vinfos[4].foffset = j4;
05989 vinfos[4].indices[0] = _ij4[0];
05990 vinfos[4].indices[1] = _ij4[1];
05991 vinfos[4].maxsolutions = _nj4;
05992 vinfos[5].jointtype = 1;
05993 vinfos[5].foffset = j5;
05994 vinfos[5].indices[0] = _ij5[0];
05995 vinfos[5].indices[1] = _ij5[1];
05996 vinfos[5].maxsolutions = _nj5;
05997 std::vector<int> vfree(0);
05998 solutions.AddSolution(vinfos,vfree);
05999 }
06000 }
06001 }
06002 
06003 }
06004 
06005 }
06006 
06007 } else
06008 {
06009 {
06010 IkReal j1array[1], cj1array[1], sj1array[1];
06011 bool j1valid[1]={false};
06012 _nj1 = 1;
06013 IkReal x1350=((IkReal(1.00000000000000))*(cj2));
06014 IkReal x1351=((cj2)*(r22));
06015 IkReal x1352=((r21)*(sj5));
06016 IkReal x1353=((r22)*(sj2));
06017 IkReal x1354=((cj5)*(r20)*(sj4));
06018 IkReal x1355=((cj4)*(cj5)*(r20));
06019 IkReal x1356=((IkReal(1.00000000000000))*(sj2)*(x1352));
06020 if( IKabs(((gconst124)*(((((IkReal(-1.00000000000000))*(cj4)*(x1350)*(x1352)))+(((sj4)*(x1351)))+(((cj2)*(x1355)))+(((IkReal(-1.00000000000000))*(cj4)*(x1353)))+(((IkReal(-1.00000000000000))*(sj4)*(x1356)))+(((sj2)*(x1354))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst124)*(((((cj4)*(x1351)))+(((IkReal(-1.00000000000000))*(cj4)*(x1356)))+(((IkReal(-1.00000000000000))*(x1350)*(x1354)))+(((cj2)*(sj4)*(x1352)))+(((sj2)*(x1355)))+(((sj4)*(x1353))))))) < IKFAST_ATAN2_MAGTHRESH )
06021     continue;
06022 j1array[0]=IKatan2(((gconst124)*(((((IkReal(-1.00000000000000))*(cj4)*(x1350)*(x1352)))+(((sj4)*(x1351)))+(((cj2)*(x1355)))+(((IkReal(-1.00000000000000))*(cj4)*(x1353)))+(((IkReal(-1.00000000000000))*(sj4)*(x1356)))+(((sj2)*(x1354)))))), ((gconst124)*(((((cj4)*(x1351)))+(((IkReal(-1.00000000000000))*(cj4)*(x1356)))+(((IkReal(-1.00000000000000))*(x1350)*(x1354)))+(((cj2)*(sj4)*(x1352)))+(((sj2)*(x1355)))+(((sj4)*(x1353)))))));
06023 sj1array[0]=IKsin(j1array[0]);
06024 cj1array[0]=IKcos(j1array[0]);
06025 if( j1array[0] > IKPI )
06026 {
06027     j1array[0]-=IK2PI;
06028 }
06029 else if( j1array[0] < -IKPI )
06030 {    j1array[0]+=IK2PI;
06031 }
06032 j1valid[0] = true;
06033 for(int ij1 = 0; ij1 < 1; ++ij1)
06034 {
06035 if( !j1valid[ij1] )
06036 {
06037     continue;
06038 }
06039 _ij1[0] = ij1; _ij1[1] = -1;
06040 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06041 {
06042 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06043 {
06044     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06045 }
06046 }
06047 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06048 {
06049 IkReal evalcond[4];
06050 IkReal x1357=IKcos(j1);
06051 IkReal x1358=IKsin(j1);
06052 IkReal x1359=((IkReal(1.00000000000000))*(sj4));
06053 IkReal x1360=((cj5)*(r00));
06054 IkReal x1361=((cj5)*(r20));
06055 IkReal x1362=((r12)*(sj0));
06056 IkReal x1363=((r21)*(sj5));
06057 IkReal x1364=((IkReal(1.00000000000000))*(cj4));
06058 IkReal x1365=((sj2)*(x1358));
06059 IkReal x1366=((IkReal(1.00000000000000))*(x1357));
06060 IkReal x1367=((r11)*(sj0)*(sj5));
06061 IkReal x1368=((cj0)*(x1364));
06062 IkReal x1369=((cj0)*(r01)*(sj5));
06063 IkReal x1370=((cj2)*(x1358));
06064 IkReal x1371=((cj5)*(r10)*(sj0));
06065 IkReal x1372=((cj2)*(x1366));
06066 evalcond[0]=((x1365)+(((IkReal(-1.00000000000000))*(x1359)*(x1361)))+(((IkReal(-1.00000000000000))*(x1372)))+(((cj4)*(r22)))+(((sj4)*(x1363))));
06067 evalcond[1]=((((r22)*(sj4)))+(((cj4)*(x1361)))+(((IkReal(-1.00000000000000))*(x1370)))+(((IkReal(-1.00000000000000))*(x1363)*(x1364)))+(((IkReal(-1.00000000000000))*(sj2)*(x1366))));
06068 evalcond[2]=((((IkReal(-1.00000000000000))*(x1362)*(x1364)))+(((IkReal(-1.00000000000000))*(r02)*(x1368)))+(((sj4)*(x1371)))+(((cj0)*(sj4)*(x1360)))+(((IkReal(-1.00000000000000))*(x1359)*(x1367)))+(x1370)+(((IkReal(-1.00000000000000))*(x1359)*(x1369)))+(((sj2)*(x1357))));
06069 evalcond[3]=((((IkReal(-1.00000000000000))*(x1359)*(x1362)))+(x1365)+(((IkReal(-1.00000000000000))*(x1372)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1359)))+(((cj4)*(x1367)))+(((IkReal(-1.00000000000000))*(x1364)*(x1371)))+(((IkReal(-1.00000000000000))*(x1360)*(x1368)))+(((cj4)*(x1369))));
06070 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06071 {
06072 continue;
06073 }
06074 }
06075 
06076 {
06077 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06078 vinfos[0].jointtype = 1;
06079 vinfos[0].foffset = j0;
06080 vinfos[0].indices[0] = _ij0[0];
06081 vinfos[0].indices[1] = _ij0[1];
06082 vinfos[0].maxsolutions = _nj0;
06083 vinfos[1].jointtype = 1;
06084 vinfos[1].foffset = j1;
06085 vinfos[1].indices[0] = _ij1[0];
06086 vinfos[1].indices[1] = _ij1[1];
06087 vinfos[1].maxsolutions = _nj1;
06088 vinfos[2].jointtype = 1;
06089 vinfos[2].foffset = j2;
06090 vinfos[2].indices[0] = _ij2[0];
06091 vinfos[2].indices[1] = _ij2[1];
06092 vinfos[2].maxsolutions = _nj2;
06093 vinfos[3].jointtype = 1;
06094 vinfos[3].foffset = j3;
06095 vinfos[3].indices[0] = _ij3[0];
06096 vinfos[3].indices[1] = _ij3[1];
06097 vinfos[3].maxsolutions = _nj3;
06098 vinfos[4].jointtype = 1;
06099 vinfos[4].foffset = j4;
06100 vinfos[4].indices[0] = _ij4[0];
06101 vinfos[4].indices[1] = _ij4[1];
06102 vinfos[4].maxsolutions = _nj4;
06103 vinfos[5].jointtype = 1;
06104 vinfos[5].foffset = j5;
06105 vinfos[5].indices[0] = _ij5[0];
06106 vinfos[5].indices[1] = _ij5[1];
06107 vinfos[5].maxsolutions = _nj5;
06108 std::vector<int> vfree(0);
06109 solutions.AddSolution(vinfos,vfree);
06110 }
06111 }
06112 }
06113 
06114 }
06115 
06116 }
06117 }
06118 }
06119 
06120 }
06121 
06122 }
06123 
06124 } else
06125 {
06126 if( 1 )
06127 {
06128 continue;
06129 
06130 } else
06131 {
06132 }
06133 }
06134 }
06135 }
06136 }
06137 }
06138 
06139 } else
06140 {
06141 {
06142 IkReal j0array[1], cj0array[1], sj0array[1];
06143 bool j0valid[1]={false};
06144 _nj0 = 1;
06145 IkReal x1373=((cj3)*(sj4));
06146 IkReal x1374=((IkReal(1.00000000000000))*(sj5));
06147 IkReal x1375=((IkReal(1.00000000000000))*(cj3)*(cj4));
06148 if( IKabs(((gconst84)*(((((IkReal(-1.00000000000000))*(r12)*(x1375)))+(((cj5)*(r10)*(x1373)))+(((IkReal(-1.00000000000000))*(r11)*(x1373)*(x1374))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst84)*(((((cj5)*(r00)*(x1373)))+(((IkReal(-1.00000000000000))*(r01)*(x1373)*(x1374)))+(((IkReal(-1.00000000000000))*(r02)*(x1375))))))) < IKFAST_ATAN2_MAGTHRESH )
06149     continue;
06150 j0array[0]=IKatan2(((gconst84)*(((((IkReal(-1.00000000000000))*(r12)*(x1375)))+(((cj5)*(r10)*(x1373)))+(((IkReal(-1.00000000000000))*(r11)*(x1373)*(x1374)))))), ((gconst84)*(((((cj5)*(r00)*(x1373)))+(((IkReal(-1.00000000000000))*(r01)*(x1373)*(x1374)))+(((IkReal(-1.00000000000000))*(r02)*(x1375)))))));
06151 sj0array[0]=IKsin(j0array[0]);
06152 cj0array[0]=IKcos(j0array[0]);
06153 if( j0array[0] > IKPI )
06154 {
06155     j0array[0]-=IK2PI;
06156 }
06157 else if( j0array[0] < -IKPI )
06158 {    j0array[0]+=IK2PI;
06159 }
06160 j0valid[0] = true;
06161 for(int ij0 = 0; ij0 < 1; ++ij0)
06162 {
06163 if( !j0valid[ij0] )
06164 {
06165     continue;
06166 }
06167 _ij0[0] = ij0; _ij0[1] = -1;
06168 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
06169 {
06170 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
06171 {
06172     j0valid[iij0]=false; _ij0[1] = iij0; break; 
06173 }
06174 }
06175 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
06176 {
06177 IkReal evalcond[3];
06178 IkReal x1376=IKsin(j0);
06179 IkReal x1377=IKcos(j0);
06180 IkReal x1378=((cj5)*(r00));
06181 IkReal x1379=((r01)*(sj5));
06182 IkReal x1380=((cj5)*(r10));
06183 IkReal x1381=((IkReal(1.00000000000000))*(r12));
06184 IkReal x1382=((r11)*(sj5));
06185 IkReal x1383=((cj4)*(x1376));
06186 IkReal x1384=((sj4)*(x1376));
06187 IkReal x1385=((sj4)*(x1377));
06188 IkReal x1386=((cj4)*(x1377));
06189 IkReal x1387=((IkReal(1.00000000000000))*(x1377));
06190 evalcond[0]=((((r00)*(sj5)*(x1376)))+(cj3)+(((cj5)*(r01)*(x1376)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1387)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1387))));
06191 evalcond[1]=((((IkReal(-1.00000000000000))*(x1378)*(x1384)))+(((x1379)*(x1384)))+(((IkReal(-1.00000000000000))*(x1382)*(x1385)))+(((x1380)*(x1385)))+(((r02)*(x1383)))+(((IkReal(-1.00000000000000))*(x1381)*(x1386))));
06192 evalcond[2]=((((r02)*(x1384)))+(sj3)+(((IkReal(-1.00000000000000))*(x1381)*(x1385)))+(((IkReal(-1.00000000000000))*(x1380)*(x1386)))+(((x1378)*(x1383)))+(((x1382)*(x1386)))+(((IkReal(-1.00000000000000))*(x1379)*(x1383))));
06193 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
06194 {
06195 continue;
06196 }
06197 }
06198 
06199 {
06200 IkReal dummyeval[1];
06201 IkReal gconst88;
06202 gconst88=IKsign(((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2))))));
06203 dummyeval[0]=((((sj3)*((cj2)*(cj2))))+(((sj3)*((sj2)*(sj2)))));
06204 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06205 {
06206 {
06207 IkReal dummyeval[1];
06208 IkReal gconst89;
06209 gconst89=IKsign(((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2))))));
06210 dummyeval[0]=((((cj3)*((sj2)*(sj2))))+(((cj3)*((cj2)*(cj2)))));
06211 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06212 {
06213 {
06214 IkReal evalcond[9];
06215 IkReal x1388=((sj0)*(sj4));
06216 IkReal x1389=((IkReal(1.00000000000000))*(r12));
06217 IkReal x1390=((cj4)*(cj5));
06218 IkReal x1391=((IkReal(1.00000000000000))*(cj0));
06219 IkReal x1392=((cj4)*(sj0));
06220 IkReal x1393=((IkReal(1.00000000000000))*(sj5));
06221 IkReal x1394=((cj0)*(cj4));
06222 IkReal x1395=((r00)*(sj0));
06223 IkReal x1396=((sj4)*(sj5));
06224 IkReal x1397=((IkReal(1.00000000000000))*(cj5));
06225 IkReal x1398=((r01)*(sj5));
06226 IkReal x1399=((cj0)*(sj4));
06227 IkReal x1400=((r11)*(sj5));
06228 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j3)), IkReal(6.28318530717959))));
06229 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(-0.350000000000000))*(sj2)))+(((npx)*(sj5))));
06230 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1397)))+(((npy)*(x1396))));
06231 evalcond[3]=((((IkReal(-1.00000000000000))*(cj4)*(npy)*(x1393)))+(((npz)*(sj4)))+(((npx)*(x1390))));
06232 evalcond[4]=((((cj5)*(r01)*(sj0)))+(((sj5)*(x1395)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1391)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1391))));
06233 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(r21)*(x1393)))+(((r22)*(sj4)))+(((r20)*(x1390))));
06234 evalcond[6]=((((IkReal(-1.00000000000000))*(x1389)*(x1394)))+(((cj5)*(r10)*(x1399)))+(((IkReal(-1.00000000000000))*(r00)*(x1388)*(x1397)))+(((r02)*(x1392)))+(((x1388)*(x1398)))+(((IkReal(-1.00000000000000))*(r11)*(x1391)*(x1396))));
06235 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1389)*(x1399)))+(((x1390)*(x1395)))+(((IkReal(-1.00000000000000))*(r01)*(x1392)*(x1393)))+(((r02)*(x1388)))+(((x1394)*(x1400)))+(((IkReal(-1.00000000000000))*(r10)*(x1390)*(x1391))));
06236 evalcond[8]=((((x1392)*(x1400)))+(((IkReal(-1.00000000000000))*(x1388)*(x1389)))+(((IkReal(-1.00000000000000))*(r00)*(x1390)*(x1391)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1390)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1391)))+(((x1394)*(x1398))));
06237 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  )
06238 {
06239 {
06240 IkReal dummyeval[1];
06241 IkReal gconst90;
06242 gconst90=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
06243 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
06244 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06245 {
06246 {
06247 IkReal dummyeval[1];
06248 IkReal gconst91;
06249 gconst91=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
06250 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
06251 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06252 {
06253 continue;
06254 
06255 } else
06256 {
06257 {
06258 IkReal j1array[1], cj1array[1], sj1array[1];
06259 bool j1valid[1]={false};
06260 _nj1 = 1;
06261 IkReal x1401=((cj2)*(sj5));
06262 IkReal x1402=((r10)*(sj0));
06263 IkReal x1403=((cj2)*(cj5));
06264 IkReal x1404=((cj0)*(r00));
06265 IkReal x1405=((sj2)*(sj5));
06266 IkReal x1406=((r11)*(sj0));
06267 IkReal x1407=((cj5)*(sj2));
06268 IkReal x1408=((cj0)*(r01));
06269 if( IKabs(((gconst91)*(((((r20)*(x1401)))+(((x1406)*(x1407)))+(((x1404)*(x1405)))+(((x1407)*(x1408)))+(((r21)*(x1403)))+(((x1402)*(x1405))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst91)*(((((IkReal(-1.00000000000000))*(x1403)*(x1408)))+(((r20)*(x1405)))+(((IkReal(-1.00000000000000))*(x1401)*(x1404)))+(((IkReal(-1.00000000000000))*(x1401)*(x1402)))+(((r21)*(x1407)))+(((IkReal(-1.00000000000000))*(x1403)*(x1406))))))) < IKFAST_ATAN2_MAGTHRESH )
06270     continue;
06271 j1array[0]=IKatan2(((gconst91)*(((((r20)*(x1401)))+(((x1406)*(x1407)))+(((x1404)*(x1405)))+(((x1407)*(x1408)))+(((r21)*(x1403)))+(((x1402)*(x1405)))))), ((gconst91)*(((((IkReal(-1.00000000000000))*(x1403)*(x1408)))+(((r20)*(x1405)))+(((IkReal(-1.00000000000000))*(x1401)*(x1404)))+(((IkReal(-1.00000000000000))*(x1401)*(x1402)))+(((r21)*(x1407)))+(((IkReal(-1.00000000000000))*(x1403)*(x1406)))))));
06272 sj1array[0]=IKsin(j1array[0]);
06273 cj1array[0]=IKcos(j1array[0]);
06274 if( j1array[0] > IKPI )
06275 {
06276     j1array[0]-=IK2PI;
06277 }
06278 else if( j1array[0] < -IKPI )
06279 {    j1array[0]+=IK2PI;
06280 }
06281 j1valid[0] = true;
06282 for(int ij1 = 0; ij1 < 1; ++ij1)
06283 {
06284 if( !j1valid[ij1] )
06285 {
06286     continue;
06287 }
06288 _ij1[0] = ij1; _ij1[1] = -1;
06289 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06290 {
06291 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06292 {
06293     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06294 }
06295 }
06296 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06297 {
06298 IkReal evalcond[4];
06299 IkReal x1409=IKsin(j1);
06300 IkReal x1410=IKcos(j1);
06301 IkReal x1411=((cj0)*(sj4));
06302 IkReal x1412=((IkReal(1.00000000000000))*(sj5));
06303 IkReal x1413=((cj5)*(sj0));
06304 IkReal x1414=((IkReal(1.00000000000000))*(cj4));
06305 IkReal x1415=((IkReal(1.00000000000000))*(cj5));
06306 IkReal x1416=((sj2)*(x1409));
06307 IkReal x1417=((IkReal(1.00000000000000))*(x1410));
06308 IkReal x1418=((cj2)*(x1409));
06309 IkReal x1419=((cj2)*(x1417));
06310 evalcond[0]=((((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(x1418)))+(((cj5)*(r21)))+(((IkReal(-1.00000000000000))*(sj2)*(x1417))));
06311 evalcond[1]=((x1416)+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x1415)))+(((IkReal(-1.00000000000000))*(x1419)))+(((cj4)*(r22)))+(((r21)*(sj4)*(sj5))));
06312 evalcond[2]=((((IkReal(-1.00000000000000))*(r11)*(x1413)))+(x1416)+(((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1415)))+(((IkReal(-1.00000000000000))*(x1419)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1412)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1412))));
06313 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x1411)*(x1412)))+(((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1414)))+(x1418)+(((sj2)*(x1410)))+(((r10)*(sj4)*(x1413)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1414)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x1412)))+(((cj5)*(r00)*(x1411))));
06314 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06315 {
06316 continue;
06317 }
06318 }
06319 
06320 {
06321 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06322 vinfos[0].jointtype = 1;
06323 vinfos[0].foffset = j0;
06324 vinfos[0].indices[0] = _ij0[0];
06325 vinfos[0].indices[1] = _ij0[1];
06326 vinfos[0].maxsolutions = _nj0;
06327 vinfos[1].jointtype = 1;
06328 vinfos[1].foffset = j1;
06329 vinfos[1].indices[0] = _ij1[0];
06330 vinfos[1].indices[1] = _ij1[1];
06331 vinfos[1].maxsolutions = _nj1;
06332 vinfos[2].jointtype = 1;
06333 vinfos[2].foffset = j2;
06334 vinfos[2].indices[0] = _ij2[0];
06335 vinfos[2].indices[1] = _ij2[1];
06336 vinfos[2].maxsolutions = _nj2;
06337 vinfos[3].jointtype = 1;
06338 vinfos[3].foffset = j3;
06339 vinfos[3].indices[0] = _ij3[0];
06340 vinfos[3].indices[1] = _ij3[1];
06341 vinfos[3].maxsolutions = _nj3;
06342 vinfos[4].jointtype = 1;
06343 vinfos[4].foffset = j4;
06344 vinfos[4].indices[0] = _ij4[0];
06345 vinfos[4].indices[1] = _ij4[1];
06346 vinfos[4].maxsolutions = _nj4;
06347 vinfos[5].jointtype = 1;
06348 vinfos[5].foffset = j5;
06349 vinfos[5].indices[0] = _ij5[0];
06350 vinfos[5].indices[1] = _ij5[1];
06351 vinfos[5].maxsolutions = _nj5;
06352 std::vector<int> vfree(0);
06353 solutions.AddSolution(vinfos,vfree);
06354 }
06355 }
06356 }
06357 
06358 }
06359 
06360 }
06361 
06362 } else
06363 {
06364 {
06365 IkReal j1array[1], cj1array[1], sj1array[1];
06366 bool j1valid[1]={false};
06367 _nj1 = 1;
06368 IkReal x1420=((r20)*(sj5));
06369 IkReal x1421=((cj4)*(r22));
06370 IkReal x1422=((sj2)*(sj4));
06371 IkReal x1423=((cj5)*(r20));
06372 IkReal x1424=((cj5)*(r21));
06373 IkReal x1425=((r21)*(sj5));
06374 IkReal x1426=((cj2)*(sj4));
06375 if( IKabs(((gconst90)*(((((IkReal(-1.00000000000000))*(sj2)*(x1421)))+(((cj2)*(x1420)))+(((x1422)*(x1423)))+(((cj2)*(x1424)))+(((IkReal(-1.00000000000000))*(x1422)*(x1425))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst90)*(((((sj2)*(x1424)))+(((sj2)*(x1420)))+(((cj2)*(x1421)))+(((x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(x1423)*(x1426))))))) < IKFAST_ATAN2_MAGTHRESH )
06376     continue;
06377 j1array[0]=IKatan2(((gconst90)*(((((IkReal(-1.00000000000000))*(sj2)*(x1421)))+(((cj2)*(x1420)))+(((x1422)*(x1423)))+(((cj2)*(x1424)))+(((IkReal(-1.00000000000000))*(x1422)*(x1425)))))), ((gconst90)*(((((sj2)*(x1424)))+(((sj2)*(x1420)))+(((cj2)*(x1421)))+(((x1425)*(x1426)))+(((IkReal(-1.00000000000000))*(x1423)*(x1426)))))));
06378 sj1array[0]=IKsin(j1array[0]);
06379 cj1array[0]=IKcos(j1array[0]);
06380 if( j1array[0] > IKPI )
06381 {
06382     j1array[0]-=IK2PI;
06383 }
06384 else if( j1array[0] < -IKPI )
06385 {    j1array[0]+=IK2PI;
06386 }
06387 j1valid[0] = true;
06388 for(int ij1 = 0; ij1 < 1; ++ij1)
06389 {
06390 if( !j1valid[ij1] )
06391 {
06392     continue;
06393 }
06394 _ij1[0] = ij1; _ij1[1] = -1;
06395 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06396 {
06397 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06398 {
06399     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06400 }
06401 }
06402 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06403 {
06404 IkReal evalcond[4];
06405 IkReal x1427=IKsin(j1);
06406 IkReal x1428=IKcos(j1);
06407 IkReal x1429=((cj0)*(sj4));
06408 IkReal x1430=((IkReal(1.00000000000000))*(sj5));
06409 IkReal x1431=((cj5)*(sj0));
06410 IkReal x1432=((IkReal(1.00000000000000))*(cj4));
06411 IkReal x1433=((IkReal(1.00000000000000))*(cj5));
06412 IkReal x1434=((sj2)*(x1427));
06413 IkReal x1435=((IkReal(1.00000000000000))*(x1428));
06414 IkReal x1436=((cj2)*(x1427));
06415 IkReal x1437=((cj2)*(x1435));
06416 evalcond[0]=((((IkReal(-1.00000000000000))*(x1436)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(sj2)*(x1435)))+(((cj5)*(r21))));
06417 evalcond[1]=((x1434)+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1437)))+(((IkReal(-1.00000000000000))*(r20)*(sj4)*(x1433)))+(((r21)*(sj4)*(sj5))));
06418 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(r01)*(x1433)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1430)))+(x1434)+(((IkReal(-1.00000000000000))*(x1437)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1430)))+(((IkReal(-1.00000000000000))*(r11)*(x1431))));
06419 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj0)*(x1432)))+(((IkReal(-1.00000000000000))*(r01)*(x1429)*(x1430)))+(((cj5)*(r00)*(x1429)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(x1430)))+(((r10)*(sj4)*(x1431)))+(x1436)+(((sj2)*(x1428)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1432))));
06420 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06421 {
06422 continue;
06423 }
06424 }
06425 
06426 {
06427 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06428 vinfos[0].jointtype = 1;
06429 vinfos[0].foffset = j0;
06430 vinfos[0].indices[0] = _ij0[0];
06431 vinfos[0].indices[1] = _ij0[1];
06432 vinfos[0].maxsolutions = _nj0;
06433 vinfos[1].jointtype = 1;
06434 vinfos[1].foffset = j1;
06435 vinfos[1].indices[0] = _ij1[0];
06436 vinfos[1].indices[1] = _ij1[1];
06437 vinfos[1].maxsolutions = _nj1;
06438 vinfos[2].jointtype = 1;
06439 vinfos[2].foffset = j2;
06440 vinfos[2].indices[0] = _ij2[0];
06441 vinfos[2].indices[1] = _ij2[1];
06442 vinfos[2].maxsolutions = _nj2;
06443 vinfos[3].jointtype = 1;
06444 vinfos[3].foffset = j3;
06445 vinfos[3].indices[0] = _ij3[0];
06446 vinfos[3].indices[1] = _ij3[1];
06447 vinfos[3].maxsolutions = _nj3;
06448 vinfos[4].jointtype = 1;
06449 vinfos[4].foffset = j4;
06450 vinfos[4].indices[0] = _ij4[0];
06451 vinfos[4].indices[1] = _ij4[1];
06452 vinfos[4].maxsolutions = _nj4;
06453 vinfos[5].jointtype = 1;
06454 vinfos[5].foffset = j5;
06455 vinfos[5].indices[0] = _ij5[0];
06456 vinfos[5].indices[1] = _ij5[1];
06457 vinfos[5].maxsolutions = _nj5;
06458 std::vector<int> vfree(0);
06459 solutions.AddSolution(vinfos,vfree);
06460 }
06461 }
06462 }
06463 
06464 }
06465 
06466 }
06467 
06468 } else
06469 {
06470 IkReal x1438=((sj0)*(sj4));
06471 IkReal x1439=((IkReal(1.00000000000000))*(r12));
06472 IkReal x1440=((cj4)*(cj5));
06473 IkReal x1441=((IkReal(1.00000000000000))*(cj0));
06474 IkReal x1442=((cj4)*(sj0));
06475 IkReal x1443=((IkReal(1.00000000000000))*(sj5));
06476 IkReal x1444=((cj0)*(cj4));
06477 IkReal x1445=((r00)*(sj0));
06478 IkReal x1446=((sj4)*(sj5));
06479 IkReal x1447=((IkReal(1.00000000000000))*(cj5));
06480 IkReal x1448=((r01)*(sj5));
06481 IkReal x1449=((cj0)*(sj4));
06482 IkReal x1450=((r11)*(sj5));
06483 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j3)), IkReal(6.28318530717959))));
06484 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((IkReal(0.350000000000000))*(sj2)))+(((npx)*(sj5))));
06485 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(npx)*(sj4)*(x1447)))+(((cj4)*(npz)))+(((npy)*(x1446))));
06486 evalcond[3]=((((npx)*(x1440)))+(((IkReal(-1.00000000000000))*(cj4)*(npy)*(x1443)))+(((npz)*(sj4))));
06487 evalcond[4]=((((cj5)*(r01)*(sj0)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1441)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1441)))+(((sj5)*(x1445))));
06488 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(r21)*(x1443)))+(((r22)*(sj4)))+(((r20)*(x1440))));
06489 evalcond[6]=((((IkReal(-1.00000000000000))*(r00)*(x1438)*(x1447)))+(((r02)*(x1442)))+(((x1438)*(x1448)))+(((cj5)*(r10)*(x1449)))+(((IkReal(-1.00000000000000))*(r11)*(x1441)*(x1446)))+(((IkReal(-1.00000000000000))*(x1439)*(x1444))));
06490 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1439)*(x1449)))+(((x1444)*(x1450)))+(((IkReal(-1.00000000000000))*(r10)*(x1440)*(x1441)))+(((IkReal(-1.00000000000000))*(r01)*(x1442)*(x1443)))+(((x1440)*(x1445)))+(((r02)*(x1438))));
06491 evalcond[8]=((((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1441)))+(((x1444)*(x1448)))+(((IkReal(-1.00000000000000))*(x1438)*(x1439)))+(((IkReal(-1.00000000000000))*(r00)*(x1440)*(x1441)))+(((IkReal(-1.00000000000000))*(r10)*(sj0)*(x1440)))+(((x1442)*(x1450))));
06492 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  )
06493 {
06494 {
06495 IkReal dummyeval[1];
06496 IkReal gconst92;
06497 gconst92=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
06498 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
06499 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06500 {
06501 {
06502 IkReal dummyeval[1];
06503 IkReal gconst93;
06504 gconst93=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
06505 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
06506 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06507 {
06508 continue;
06509 
06510 } else
06511 {
06512 {
06513 IkReal j1array[1], cj1array[1], sj1array[1];
06514 bool j1valid[1]={false};
06515 _nj1 = 1;
06516 IkReal x1451=((IkReal(1.00000000000000))*(sj2));
06517 IkReal x1452=((cj5)*(r21));
06518 IkReal x1453=((r20)*(sj5));
06519 IkReal x1454=((IkReal(1.00000000000000))*(cj2));
06520 IkReal x1455=((cj5)*(r11)*(sj0));
06521 IkReal x1456=((r10)*(sj0)*(sj5));
06522 IkReal x1457=((cj0)*(r00)*(sj5));
06523 IkReal x1458=((cj0)*(cj5)*(r01));
06524 if( IKabs(((gconst93)*(((((IkReal(-1.00000000000000))*(x1452)*(x1454)))+(((IkReal(-1.00000000000000))*(x1451)*(x1457)))+(((IkReal(-1.00000000000000))*(x1451)*(x1456)))+(((IkReal(-1.00000000000000))*(x1451)*(x1458)))+(((IkReal(-1.00000000000000))*(x1453)*(x1454)))+(((IkReal(-1.00000000000000))*(x1451)*(x1455))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst93)*(((((cj2)*(x1456)))+(((IkReal(-1.00000000000000))*(x1451)*(x1452)))+(((cj2)*(x1455)))+(((cj2)*(x1458)))+(((IkReal(-1.00000000000000))*(x1451)*(x1453)))+(((cj2)*(x1457))))))) < IKFAST_ATAN2_MAGTHRESH )
06525     continue;
06526 j1array[0]=IKatan2(((gconst93)*(((((IkReal(-1.00000000000000))*(x1452)*(x1454)))+(((IkReal(-1.00000000000000))*(x1451)*(x1457)))+(((IkReal(-1.00000000000000))*(x1451)*(x1456)))+(((IkReal(-1.00000000000000))*(x1451)*(x1458)))+(((IkReal(-1.00000000000000))*(x1453)*(x1454)))+(((IkReal(-1.00000000000000))*(x1451)*(x1455)))))), ((gconst93)*(((((cj2)*(x1456)))+(((IkReal(-1.00000000000000))*(x1451)*(x1452)))+(((cj2)*(x1455)))+(((cj2)*(x1458)))+(((IkReal(-1.00000000000000))*(x1451)*(x1453)))+(((cj2)*(x1457)))))));
06527 sj1array[0]=IKsin(j1array[0]);
06528 cj1array[0]=IKcos(j1array[0]);
06529 if( j1array[0] > IKPI )
06530 {
06531     j1array[0]-=IK2PI;
06532 }
06533 else if( j1array[0] < -IKPI )
06534 {    j1array[0]+=IK2PI;
06535 }
06536 j1valid[0] = true;
06537 for(int ij1 = 0; ij1 < 1; ++ij1)
06538 {
06539 if( !j1valid[ij1] )
06540 {
06541     continue;
06542 }
06543 _ij1[0] = ij1; _ij1[1] = -1;
06544 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06545 {
06546 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06547 {
06548     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06549 }
06550 }
06551 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06552 {
06553 IkReal evalcond[4];
06554 IkReal x1459=IKsin(j1);
06555 IkReal x1460=IKcos(j1);
06556 IkReal x1461=((cj5)*(sj0));
06557 IkReal x1462=((IkReal(1.00000000000000))*(r11));
06558 IkReal x1463=((cj5)*(sj4));
06559 IkReal x1464=((cj0)*(r00));
06560 IkReal x1465=((IkReal(1.00000000000000))*(sj0));
06561 IkReal x1466=((sj4)*(sj5));
06562 IkReal x1467=((IkReal(1.00000000000000))*(cj0));
06563 IkReal x1468=((sj2)*(x1460));
06564 IkReal x1469=((cj2)*(x1459));
06565 IkReal x1470=((cj2)*(x1460));
06566 IkReal x1471=((sj2)*(x1459));
06567 IkReal x1472=((x1469)+(x1468));
06568 evalcond[0]=((((r20)*(sj5)))+(x1472)+(((cj5)*(r21))));
06569 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x1463)))+(((IkReal(-1.00000000000000))*(x1470)))+(((cj4)*(r22)))+(((r21)*(x1466)))+(x1471));
06570 evalcond[2]=((((IkReal(-1.00000000000000))*(x1461)*(x1462)))+(((IkReal(-1.00000000000000))*(sj5)*(x1464)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1465)))+(((IkReal(-1.00000000000000))*(x1471)))+(x1470)+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1467))));
06571 evalcond[3]=((((r10)*(sj4)*(x1461)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1467)))+(((x1463)*(x1464)))+(((IkReal(-1.00000000000000))*(sj0)*(x1462)*(x1466)))+(((IkReal(-1.00000000000000))*(r01)*(x1466)*(x1467)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1465)))+(x1472));
06572 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06573 {
06574 continue;
06575 }
06576 }
06577 
06578 {
06579 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06580 vinfos[0].jointtype = 1;
06581 vinfos[0].foffset = j0;
06582 vinfos[0].indices[0] = _ij0[0];
06583 vinfos[0].indices[1] = _ij0[1];
06584 vinfos[0].maxsolutions = _nj0;
06585 vinfos[1].jointtype = 1;
06586 vinfos[1].foffset = j1;
06587 vinfos[1].indices[0] = _ij1[0];
06588 vinfos[1].indices[1] = _ij1[1];
06589 vinfos[1].maxsolutions = _nj1;
06590 vinfos[2].jointtype = 1;
06591 vinfos[2].foffset = j2;
06592 vinfos[2].indices[0] = _ij2[0];
06593 vinfos[2].indices[1] = _ij2[1];
06594 vinfos[2].maxsolutions = _nj2;
06595 vinfos[3].jointtype = 1;
06596 vinfos[3].foffset = j3;
06597 vinfos[3].indices[0] = _ij3[0];
06598 vinfos[3].indices[1] = _ij3[1];
06599 vinfos[3].maxsolutions = _nj3;
06600 vinfos[4].jointtype = 1;
06601 vinfos[4].foffset = j4;
06602 vinfos[4].indices[0] = _ij4[0];
06603 vinfos[4].indices[1] = _ij4[1];
06604 vinfos[4].maxsolutions = _nj4;
06605 vinfos[5].jointtype = 1;
06606 vinfos[5].foffset = j5;
06607 vinfos[5].indices[0] = _ij5[0];
06608 vinfos[5].indices[1] = _ij5[1];
06609 vinfos[5].maxsolutions = _nj5;
06610 std::vector<int> vfree(0);
06611 solutions.AddSolution(vinfos,vfree);
06612 }
06613 }
06614 }
06615 
06616 }
06617 
06618 }
06619 
06620 } else
06621 {
06622 {
06623 IkReal j1array[1], cj1array[1], sj1array[1];
06624 bool j1valid[1]={false};
06625 _nj1 = 1;
06626 IkReal x1473=((cj4)*(r22));
06627 IkReal x1474=((r20)*(sj5));
06628 IkReal x1475=((cj5)*(r21));
06629 IkReal x1476=((sj2)*(sj4));
06630 IkReal x1477=((r21)*(sj5));
06631 IkReal x1478=((IkReal(1.00000000000000))*(cj2));
06632 IkReal x1479=((cj5)*(r20));
06633 if( IKabs(((gconst92)*(((((cj2)*(x1475)))+(((IkReal(-1.00000000000000))*(x1476)*(x1479)))+(((sj2)*(x1473)))+(((x1476)*(x1477)))+(((cj2)*(x1474))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst92)*(((((sj2)*(x1474)))+(((IkReal(-1.00000000000000))*(sj4)*(x1477)*(x1478)))+(((IkReal(-1.00000000000000))*(x1473)*(x1478)))+(((cj2)*(sj4)*(x1479)))+(((sj2)*(x1475))))))) < IKFAST_ATAN2_MAGTHRESH )
06634     continue;
06635 j1array[0]=IKatan2(((gconst92)*(((((cj2)*(x1475)))+(((IkReal(-1.00000000000000))*(x1476)*(x1479)))+(((sj2)*(x1473)))+(((x1476)*(x1477)))+(((cj2)*(x1474)))))), ((gconst92)*(((((sj2)*(x1474)))+(((IkReal(-1.00000000000000))*(sj4)*(x1477)*(x1478)))+(((IkReal(-1.00000000000000))*(x1473)*(x1478)))+(((cj2)*(sj4)*(x1479)))+(((sj2)*(x1475)))))));
06636 sj1array[0]=IKsin(j1array[0]);
06637 cj1array[0]=IKcos(j1array[0]);
06638 if( j1array[0] > IKPI )
06639 {
06640     j1array[0]-=IK2PI;
06641 }
06642 else if( j1array[0] < -IKPI )
06643 {    j1array[0]+=IK2PI;
06644 }
06645 j1valid[0] = true;
06646 for(int ij1 = 0; ij1 < 1; ++ij1)
06647 {
06648 if( !j1valid[ij1] )
06649 {
06650     continue;
06651 }
06652 _ij1[0] = ij1; _ij1[1] = -1;
06653 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06654 {
06655 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06656 {
06657     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06658 }
06659 }
06660 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06661 {
06662 IkReal evalcond[4];
06663 IkReal x1480=IKsin(j1);
06664 IkReal x1481=IKcos(j1);
06665 IkReal x1482=((cj5)*(sj0));
06666 IkReal x1483=((IkReal(1.00000000000000))*(r11));
06667 IkReal x1484=((cj5)*(sj4));
06668 IkReal x1485=((cj0)*(r00));
06669 IkReal x1486=((IkReal(1.00000000000000))*(sj0));
06670 IkReal x1487=((sj4)*(sj5));
06671 IkReal x1488=((IkReal(1.00000000000000))*(cj0));
06672 IkReal x1489=((sj2)*(x1481));
06673 IkReal x1490=((cj2)*(x1480));
06674 IkReal x1491=((cj2)*(x1481));
06675 IkReal x1492=((sj2)*(x1480));
06676 IkReal x1493=((x1489)+(x1490));
06677 evalcond[0]=((x1493)+(((r20)*(sj5)))+(((cj5)*(r21))));
06678 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x1484)))+(((IkReal(-1.00000000000000))*(x1491)))+(x1492)+(((cj4)*(r22)))+(((r21)*(x1487))));
06679 evalcond[2]=((x1491)+(((IkReal(-1.00000000000000))*(x1482)*(x1483)))+(((IkReal(-1.00000000000000))*(cj5)*(r01)*(x1488)))+(((IkReal(-1.00000000000000))*(x1492)))+(((IkReal(-1.00000000000000))*(r10)*(sj5)*(x1486)))+(((IkReal(-1.00000000000000))*(sj5)*(x1485))));
06680 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x1487)*(x1488)))+(((IkReal(-1.00000000000000))*(sj0)*(x1483)*(x1487)))+(((r10)*(sj4)*(x1482)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1488)))+(x1493)+(((x1484)*(x1485)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1486))));
06681 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06682 {
06683 continue;
06684 }
06685 }
06686 
06687 {
06688 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06689 vinfos[0].jointtype = 1;
06690 vinfos[0].foffset = j0;
06691 vinfos[0].indices[0] = _ij0[0];
06692 vinfos[0].indices[1] = _ij0[1];
06693 vinfos[0].maxsolutions = _nj0;
06694 vinfos[1].jointtype = 1;
06695 vinfos[1].foffset = j1;
06696 vinfos[1].indices[0] = _ij1[0];
06697 vinfos[1].indices[1] = _ij1[1];
06698 vinfos[1].maxsolutions = _nj1;
06699 vinfos[2].jointtype = 1;
06700 vinfos[2].foffset = j2;
06701 vinfos[2].indices[0] = _ij2[0];
06702 vinfos[2].indices[1] = _ij2[1];
06703 vinfos[2].maxsolutions = _nj2;
06704 vinfos[3].jointtype = 1;
06705 vinfos[3].foffset = j3;
06706 vinfos[3].indices[0] = _ij3[0];
06707 vinfos[3].indices[1] = _ij3[1];
06708 vinfos[3].maxsolutions = _nj3;
06709 vinfos[4].jointtype = 1;
06710 vinfos[4].foffset = j4;
06711 vinfos[4].indices[0] = _ij4[0];
06712 vinfos[4].indices[1] = _ij4[1];
06713 vinfos[4].maxsolutions = _nj4;
06714 vinfos[5].jointtype = 1;
06715 vinfos[5].foffset = j5;
06716 vinfos[5].indices[0] = _ij5[0];
06717 vinfos[5].indices[1] = _ij5[1];
06718 vinfos[5].maxsolutions = _nj5;
06719 std::vector<int> vfree(0);
06720 solutions.AddSolution(vinfos,vfree);
06721 }
06722 }
06723 }
06724 
06725 }
06726 
06727 }
06728 
06729 } else
06730 {
06731 IkReal x1494=((IkReal(1.00000000000000))*(r10));
06732 IkReal x1495=((sj0)*(sj5));
06733 IkReal x1496=((r02)*(sj0));
06734 IkReal x1497=((cj4)*(cj5));
06735 IkReal x1498=((IkReal(1.00000000000000))*(cj4));
06736 IkReal x1499=((cj0)*(r12));
06737 IkReal x1500=((IkReal(1.00000000000000))*(cj0));
06738 IkReal x1501=((cj5)*(r11));
06739 IkReal x1502=((cj5)*(r01));
06740 IkReal x1503=((r00)*(sj0));
06741 IkReal x1504=((npy)*(sj5));
06742 IkReal x1505=((IkReal(1.00000000000000))*(sj4));
06743 IkReal x1506=((cj0)*(sj5));
06744 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j3)), IkReal(6.28318530717959))));
06745 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
06746 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(x1505)))+(((cj4)*(npz)))+(((sj4)*(x1504))));
06747 evalcond[3]=((((npx)*(x1497)))+(((IkReal(0.350000000000000))*(sj2)))+(((npz)*(sj4)))+(((IkReal(-1.00000000000000))*(x1498)*(x1504))));
06748 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
06749 evalcond[5]=((IkReal(1.00000000000000))+(((sj0)*(x1502)))+(((IkReal(-1.00000000000000))*(x1500)*(x1501)))+(((r00)*(x1495)))+(((IkReal(-1.00000000000000))*(x1494)*(x1506))));
06750 evalcond[6]=((((IkReal(-1.00000000000000))*(x1494)*(x1495)))+(((IkReal(-1.00000000000000))*(x1500)*(x1502)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1500)))+(((IkReal(-1.00000000000000))*(sj0)*(x1501))));
06751 evalcond[7]=((((IkReal(-1.00000000000000))*(cj5)*(x1503)*(x1505)))+(((cj4)*(x1496)))+(((cj0)*(cj5)*(r10)*(sj4)))+(((r01)*(sj4)*(x1495)))+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(sj5)*(x1500)))+(((IkReal(-1.00000000000000))*(x1498)*(x1499))));
06752 evalcond[8]=((((IkReal(-1.00000000000000))*(cj0)*(x1494)*(x1497)))+(((sj4)*(x1496)))+(((IkReal(-1.00000000000000))*(r01)*(x1495)*(x1498)))+(((IkReal(-1.00000000000000))*(x1499)*(x1505)))+(((x1497)*(x1503)))+(((cj4)*(r11)*(x1506))));
06753 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  )
06754 {
06755 {
06756 IkReal dummyeval[1];
06757 IkReal gconst94;
06758 gconst94=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
06759 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
06760 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06761 {
06762 {
06763 IkReal dummyeval[1];
06764 IkReal gconst95;
06765 gconst95=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
06766 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
06767 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06768 {
06769 continue;
06770 
06771 } else
06772 {
06773 {
06774 IkReal j1array[1], cj1array[1], sj1array[1];
06775 bool j1valid[1]={false};
06776 _nj1 = 1;
06777 IkReal x1507=((cj4)*(r22));
06778 IkReal x1508=((IkReal(1.00000000000000))*(cj2));
06779 IkReal x1509=((sj2)*(sj4));
06780 IkReal x1510=((r21)*(sj5));
06781 IkReal x1511=((IkReal(1.00000000000000))*(sj2));
06782 IkReal x1512=((cj2)*(sj4));
06783 IkReal x1513=((cj5)*(r20));
06784 IkReal x1514=((cj0)*(cj4)*(r02));
06785 IkReal x1515=((cj4)*(r12)*(sj0));
06786 IkReal x1516=((cj5)*(r10)*(sj0));
06787 IkReal x1517=((cj0)*(cj5)*(r00));
06788 IkReal x1518=((cj0)*(r01)*(sj5));
06789 IkReal x1519=((IkReal(1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5));
06790 if( IKabs(((gconst95)*(((((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5)*(x1508)))+(((IkReal(-1.00000000000000))*(x1508)*(x1514)))+(((x1512)*(x1517)))+(((IkReal(-1.00000000000000))*(sj4)*(x1508)*(x1518)))+(((x1509)*(x1510)))+(((IkReal(-1.00000000000000))*(x1508)*(x1515)))+(((x1512)*(x1516)))+(((sj2)*(x1507)))+(((IkReal(-1.00000000000000))*(x1509)*(x1513))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst95)*(((((x1512)*(x1513)))+(((IkReal(-1.00000000000000))*(x1509)*(x1518)))+(((IkReal(-1.00000000000000))*(x1507)*(x1508)))+(((IkReal(-1.00000000000000))*(x1511)*(x1515)))+(((x1509)*(x1517)))+(((IkReal(-1.00000000000000))*(x1511)*(x1514)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1509)))+(((x1509)*(x1516)))+(((IkReal(-1.00000000000000))*(sj4)*(x1508)*(x1510))))))) < IKFAST_ATAN2_MAGTHRESH )
06791     continue;
06792 j1array[0]=IKatan2(((gconst95)*(((((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5)*(x1508)))+(((IkReal(-1.00000000000000))*(x1508)*(x1514)))+(((x1512)*(x1517)))+(((IkReal(-1.00000000000000))*(sj4)*(x1508)*(x1518)))+(((x1509)*(x1510)))+(((IkReal(-1.00000000000000))*(x1508)*(x1515)))+(((x1512)*(x1516)))+(((sj2)*(x1507)))+(((IkReal(-1.00000000000000))*(x1509)*(x1513)))))), ((gconst95)*(((((x1512)*(x1513)))+(((IkReal(-1.00000000000000))*(x1509)*(x1518)))+(((IkReal(-1.00000000000000))*(x1507)*(x1508)))+(((IkReal(-1.00000000000000))*(x1511)*(x1515)))+(((x1509)*(x1517)))+(((IkReal(-1.00000000000000))*(x1511)*(x1514)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1509)))+(((x1509)*(x1516)))+(((IkReal(-1.00000000000000))*(sj4)*(x1508)*(x1510)))))));
06793 sj1array[0]=IKsin(j1array[0]);
06794 cj1array[0]=IKcos(j1array[0]);
06795 if( j1array[0] > IKPI )
06796 {
06797     j1array[0]-=IK2PI;
06798 }
06799 else if( j1array[0] < -IKPI )
06800 {    j1array[0]+=IK2PI;
06801 }
06802 j1valid[0] = true;
06803 for(int ij1 = 0; ij1 < 1; ++ij1)
06804 {
06805 if( !j1valid[ij1] )
06806 {
06807     continue;
06808 }
06809 _ij1[0] = ij1; _ij1[1] = -1;
06810 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06811 {
06812 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06813 {
06814     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06815 }
06816 }
06817 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06818 {
06819 IkReal evalcond[4];
06820 IkReal x1520=IKcos(j1);
06821 IkReal x1521=IKsin(j1);
06822 IkReal x1522=((IkReal(1.00000000000000))*(sj4));
06823 IkReal x1523=((cj5)*(r00));
06824 IkReal x1524=((cj5)*(r20));
06825 IkReal x1525=((r12)*(sj0));
06826 IkReal x1526=((r21)*(sj5));
06827 IkReal x1527=((IkReal(1.00000000000000))*(cj4));
06828 IkReal x1528=((sj2)*(x1520));
06829 IkReal x1529=((cj2)*(x1521));
06830 IkReal x1530=((cj2)*(x1520));
06831 IkReal x1531=((r11)*(sj0)*(sj5));
06832 IkReal x1532=((cj0)*(x1527));
06833 IkReal x1533=((cj0)*(r01)*(sj5));
06834 IkReal x1534=((cj5)*(r10)*(sj0));
06835 IkReal x1535=((sj2)*(x1521));
06836 IkReal x1536=((x1528)+(x1529));
06837 evalcond[0]=((((IkReal(-1.00000000000000))*(x1522)*(x1524)))+(((IkReal(-1.00000000000000))*(x1530)))+(((cj4)*(r22)))+(((sj4)*(x1526)))+(x1535));
06838 evalcond[1]=((((IkReal(-1.00000000000000))*(x1526)*(x1527)))+(((cj4)*(x1524)))+(((r22)*(sj4)))+(x1536));
06839 evalcond[2]=((((IkReal(-1.00000000000000))*(x1522)*(x1531)))+(((IkReal(-1.00000000000000))*(r02)*(x1532)))+(((IkReal(-1.00000000000000))*(x1522)*(x1533)))+(((cj0)*(sj4)*(x1523)))+(((sj4)*(x1534)))+(x1536)+(((IkReal(-1.00000000000000))*(x1525)*(x1527))));
06840 evalcond[3]=((((IkReal(-1.00000000000000))*(x1535)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1522)))+(((cj4)*(x1531)))+(((IkReal(-1.00000000000000))*(x1522)*(x1525)))+(((cj4)*(x1533)))+(((IkReal(-1.00000000000000))*(x1527)*(x1534)))+(((IkReal(-1.00000000000000))*(x1523)*(x1532)))+(x1530));
06841 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06842 {
06843 continue;
06844 }
06845 }
06846 
06847 {
06848 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06849 vinfos[0].jointtype = 1;
06850 vinfos[0].foffset = j0;
06851 vinfos[0].indices[0] = _ij0[0];
06852 vinfos[0].indices[1] = _ij0[1];
06853 vinfos[0].maxsolutions = _nj0;
06854 vinfos[1].jointtype = 1;
06855 vinfos[1].foffset = j1;
06856 vinfos[1].indices[0] = _ij1[0];
06857 vinfos[1].indices[1] = _ij1[1];
06858 vinfos[1].maxsolutions = _nj1;
06859 vinfos[2].jointtype = 1;
06860 vinfos[2].foffset = j2;
06861 vinfos[2].indices[0] = _ij2[0];
06862 vinfos[2].indices[1] = _ij2[1];
06863 vinfos[2].maxsolutions = _nj2;
06864 vinfos[3].jointtype = 1;
06865 vinfos[3].foffset = j3;
06866 vinfos[3].indices[0] = _ij3[0];
06867 vinfos[3].indices[1] = _ij3[1];
06868 vinfos[3].maxsolutions = _nj3;
06869 vinfos[4].jointtype = 1;
06870 vinfos[4].foffset = j4;
06871 vinfos[4].indices[0] = _ij4[0];
06872 vinfos[4].indices[1] = _ij4[1];
06873 vinfos[4].maxsolutions = _nj4;
06874 vinfos[5].jointtype = 1;
06875 vinfos[5].foffset = j5;
06876 vinfos[5].indices[0] = _ij5[0];
06877 vinfos[5].indices[1] = _ij5[1];
06878 vinfos[5].maxsolutions = _nj5;
06879 std::vector<int> vfree(0);
06880 solutions.AddSolution(vinfos,vfree);
06881 }
06882 }
06883 }
06884 
06885 }
06886 
06887 }
06888 
06889 } else
06890 {
06891 {
06892 IkReal j1array[1], cj1array[1], sj1array[1];
06893 bool j1valid[1]={false};
06894 _nj1 = 1;
06895 IkReal x1537=((cj4)*(r22));
06896 IkReal x1538=((cj2)*(sj4));
06897 IkReal x1539=((sj2)*(sj4));
06898 IkReal x1540=((r21)*(sj5));
06899 IkReal x1541=((cj5)*(r20));
06900 IkReal x1542=((cj4)*(sj2));
06901 IkReal x1543=((IkReal(1.00000000000000))*(cj2)*(x1540));
06902 if( IKabs(((gconst94)*(((((r22)*(x1538)))+(((IkReal(-1.00000000000000))*(x1539)*(x1541)))+(((cj2)*(cj4)*(x1541)))+(((x1539)*(x1540)))+(((IkReal(-1.00000000000000))*(cj4)*(x1543)))+(((sj2)*(x1537))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst94)*(((((IkReal(-1.00000000000000))*(cj2)*(x1537)))+(((r22)*(x1539)))+(((IkReal(-1.00000000000000))*(x1540)*(x1542)))+(((IkReal(-1.00000000000000))*(x1538)*(x1540)))+(((x1541)*(x1542)))+(((x1538)*(x1541))))))) < IKFAST_ATAN2_MAGTHRESH )
06903     continue;
06904 j1array[0]=IKatan2(((gconst94)*(((((r22)*(x1538)))+(((IkReal(-1.00000000000000))*(x1539)*(x1541)))+(((cj2)*(cj4)*(x1541)))+(((x1539)*(x1540)))+(((IkReal(-1.00000000000000))*(cj4)*(x1543)))+(((sj2)*(x1537)))))), ((gconst94)*(((((IkReal(-1.00000000000000))*(cj2)*(x1537)))+(((r22)*(x1539)))+(((IkReal(-1.00000000000000))*(x1540)*(x1542)))+(((IkReal(-1.00000000000000))*(x1538)*(x1540)))+(((x1541)*(x1542)))+(((x1538)*(x1541)))))));
06905 sj1array[0]=IKsin(j1array[0]);
06906 cj1array[0]=IKcos(j1array[0]);
06907 if( j1array[0] > IKPI )
06908 {
06909     j1array[0]-=IK2PI;
06910 }
06911 else if( j1array[0] < -IKPI )
06912 {    j1array[0]+=IK2PI;
06913 }
06914 j1valid[0] = true;
06915 for(int ij1 = 0; ij1 < 1; ++ij1)
06916 {
06917 if( !j1valid[ij1] )
06918 {
06919     continue;
06920 }
06921 _ij1[0] = ij1; _ij1[1] = -1;
06922 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
06923 {
06924 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
06925 {
06926     j1valid[iij1]=false; _ij1[1] = iij1; break; 
06927 }
06928 }
06929 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
06930 {
06931 IkReal evalcond[4];
06932 IkReal x1544=IKcos(j1);
06933 IkReal x1545=IKsin(j1);
06934 IkReal x1546=((IkReal(1.00000000000000))*(sj4));
06935 IkReal x1547=((cj5)*(r00));
06936 IkReal x1548=((cj5)*(r20));
06937 IkReal x1549=((r12)*(sj0));
06938 IkReal x1550=((r21)*(sj5));
06939 IkReal x1551=((IkReal(1.00000000000000))*(cj4));
06940 IkReal x1552=((sj2)*(x1544));
06941 IkReal x1553=((cj2)*(x1545));
06942 IkReal x1554=((cj2)*(x1544));
06943 IkReal x1555=((r11)*(sj0)*(sj5));
06944 IkReal x1556=((cj0)*(x1551));
06945 IkReal x1557=((cj0)*(r01)*(sj5));
06946 IkReal x1558=((cj5)*(r10)*(sj0));
06947 IkReal x1559=((sj2)*(x1545));
06948 IkReal x1560=((x1553)+(x1552));
06949 evalcond[0]=((x1559)+(((cj4)*(r22)))+(((sj4)*(x1550)))+(((IkReal(-1.00000000000000))*(x1546)*(x1548)))+(((IkReal(-1.00000000000000))*(x1554))));
06950 evalcond[1]=((((IkReal(-1.00000000000000))*(x1550)*(x1551)))+(((cj4)*(x1548)))+(((r22)*(sj4)))+(x1560));
06951 evalcond[2]=((((IkReal(-1.00000000000000))*(x1546)*(x1557)))+(((IkReal(-1.00000000000000))*(x1546)*(x1555)))+(((sj4)*(x1558)))+(x1560)+(((IkReal(-1.00000000000000))*(r02)*(x1556)))+(((cj0)*(sj4)*(x1547)))+(((IkReal(-1.00000000000000))*(x1549)*(x1551))));
06952 evalcond[3]=((((IkReal(-1.00000000000000))*(x1551)*(x1558)))+(((IkReal(-1.00000000000000))*(x1559)))+(((IkReal(-1.00000000000000))*(x1546)*(x1549)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1546)))+(x1554)+(((cj4)*(x1557)))+(((IkReal(-1.00000000000000))*(x1547)*(x1556)))+(((cj4)*(x1555))));
06953 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06954 {
06955 continue;
06956 }
06957 }
06958 
06959 {
06960 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06961 vinfos[0].jointtype = 1;
06962 vinfos[0].foffset = j0;
06963 vinfos[0].indices[0] = _ij0[0];
06964 vinfos[0].indices[1] = _ij0[1];
06965 vinfos[0].maxsolutions = _nj0;
06966 vinfos[1].jointtype = 1;
06967 vinfos[1].foffset = j1;
06968 vinfos[1].indices[0] = _ij1[0];
06969 vinfos[1].indices[1] = _ij1[1];
06970 vinfos[1].maxsolutions = _nj1;
06971 vinfos[2].jointtype = 1;
06972 vinfos[2].foffset = j2;
06973 vinfos[2].indices[0] = _ij2[0];
06974 vinfos[2].indices[1] = _ij2[1];
06975 vinfos[2].maxsolutions = _nj2;
06976 vinfos[3].jointtype = 1;
06977 vinfos[3].foffset = j3;
06978 vinfos[3].indices[0] = _ij3[0];
06979 vinfos[3].indices[1] = _ij3[1];
06980 vinfos[3].maxsolutions = _nj3;
06981 vinfos[4].jointtype = 1;
06982 vinfos[4].foffset = j4;
06983 vinfos[4].indices[0] = _ij4[0];
06984 vinfos[4].indices[1] = _ij4[1];
06985 vinfos[4].maxsolutions = _nj4;
06986 vinfos[5].jointtype = 1;
06987 vinfos[5].foffset = j5;
06988 vinfos[5].indices[0] = _ij5[0];
06989 vinfos[5].indices[1] = _ij5[1];
06990 vinfos[5].maxsolutions = _nj5;
06991 std::vector<int> vfree(0);
06992 solutions.AddSolution(vinfos,vfree);
06993 }
06994 }
06995 }
06996 
06997 }
06998 
06999 }
07000 
07001 } else
07002 {
07003 IkReal x1561=((IkReal(1.00000000000000))*(r10));
07004 IkReal x1562=((sj0)*(sj5));
07005 IkReal x1563=((r02)*(sj0));
07006 IkReal x1564=((cj4)*(cj5));
07007 IkReal x1565=((IkReal(1.00000000000000))*(cj4));
07008 IkReal x1566=((cj0)*(r12));
07009 IkReal x1567=((IkReal(1.00000000000000))*(cj0));
07010 IkReal x1568=((cj5)*(r11));
07011 IkReal x1569=((cj5)*(r01));
07012 IkReal x1570=((r00)*(sj0));
07013 IkReal x1571=((npy)*(sj5));
07014 IkReal x1572=((IkReal(1.00000000000000))*(sj4));
07015 IkReal x1573=((cj0)*(sj5));
07016 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j3, IkReal(6.28318530717959))));
07017 evalcond[1]=((IkReal(0.0950000000000000))+(((cj5)*(npy)))+(((npx)*(sj5))));
07018 evalcond[2]=((IkReal(-0.350000000000000))+(((IkReal(-0.350000000000000))*(cj2)))+(((cj4)*(npz)))+(((sj4)*(x1571)))+(((IkReal(-1.00000000000000))*(cj5)*(npx)*(x1572))));
07019 evalcond[3]=((((IkReal(-1.00000000000000))*(x1565)*(x1571)))+(((npx)*(x1564)))+(((IkReal(-0.350000000000000))*(sj2)))+(((npz)*(sj4))));
07020 evalcond[4]=((((r20)*(sj5)))+(((cj5)*(r21))));
07021 evalcond[5]=((IkReal(-1.00000000000000))+(((r00)*(x1562)))+(((sj0)*(x1569)))+(((IkReal(-1.00000000000000))*(x1561)*(x1573)))+(((IkReal(-1.00000000000000))*(x1567)*(x1568))));
07022 evalcond[6]=((((IkReal(-1.00000000000000))*(x1561)*(x1562)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1567)))+(((IkReal(-1.00000000000000))*(x1567)*(x1569)))+(((IkReal(-1.00000000000000))*(sj0)*(x1568))));
07023 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(sj4)*(sj5)*(x1567)))+(((IkReal(-1.00000000000000))*(cj5)*(x1570)*(x1572)))+(((r01)*(sj4)*(x1562)))+(((cj4)*(x1563)))+(((IkReal(-1.00000000000000))*(x1565)*(x1566)))+(((cj0)*(cj5)*(r10)*(sj4))));
07024 evalcond[8]=((((x1564)*(x1570)))+(((sj4)*(x1563)))+(((cj4)*(r11)*(x1573)))+(((IkReal(-1.00000000000000))*(x1566)*(x1572)))+(((IkReal(-1.00000000000000))*(r01)*(x1562)*(x1565)))+(((IkReal(-1.00000000000000))*(cj0)*(x1561)*(x1564))));
07025 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  )
07026 {
07027 {
07028 IkReal dummyeval[1];
07029 IkReal gconst96;
07030 gconst96=IKsign((((cj2)*(cj2))+((sj2)*(sj2))));
07031 dummyeval[0]=(((cj2)*(cj2))+((sj2)*(sj2)));
07032 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07033 {
07034 {
07035 IkReal dummyeval[1];
07036 IkReal gconst97;
07037 gconst97=IKsign(((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2))))));
07038 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*((cj2)*(cj2)))));
07039 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07040 {
07041 continue;
07042 
07043 } else
07044 {
07045 {
07046 IkReal j1array[1], cj1array[1], sj1array[1];
07047 bool j1valid[1]={false};
07048 _nj1 = 1;
07049 IkReal x1574=((cj4)*(r22));
07050 IkReal x1575=((IkReal(1.00000000000000))*(cj2));
07051 IkReal x1576=((sj2)*(sj4));
07052 IkReal x1577=((r21)*(sj5));
07053 IkReal x1578=((cj2)*(sj4));
07054 IkReal x1579=((cj5)*(r20));
07055 IkReal x1580=((IkReal(1.00000000000000))*(sj2));
07056 IkReal x1581=((cj0)*(cj4)*(r02));
07057 IkReal x1582=((cj5)*(r10)*(sj0));
07058 IkReal x1583=((cj4)*(r12)*(sj0));
07059 IkReal x1584=((cj0)*(cj5)*(r00));
07060 IkReal x1585=((cj0)*(r01)*(sj5));
07061 IkReal x1586=((IkReal(1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5));
07062 if( IKabs(((gconst97)*(((((sj2)*(x1574)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5)*(x1575)))+(((x1576)*(x1577)))+(((x1578)*(x1582)))+(((x1578)*(x1584)))+(((IkReal(-1.00000000000000))*(x1575)*(x1583)))+(((IkReal(-1.00000000000000))*(sj4)*(x1575)*(x1585)))+(((IkReal(-1.00000000000000))*(x1575)*(x1581)))+(((IkReal(-1.00000000000000))*(x1576)*(x1579))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst97)*(((((IkReal(-1.00000000000000))*(x1580)*(x1583)))+(((x1576)*(x1584)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1576)))+(((IkReal(-1.00000000000000))*(x1574)*(x1575)))+(((IkReal(-1.00000000000000))*(sj4)*(x1575)*(x1577)))+(((IkReal(-1.00000000000000))*(x1580)*(x1581)))+(((x1578)*(x1579)))+(((IkReal(-1.00000000000000))*(x1576)*(x1585)))+(((x1576)*(x1582))))))) < IKFAST_ATAN2_MAGTHRESH )
07063     continue;
07064 j1array[0]=IKatan2(((gconst97)*(((((sj2)*(x1574)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj4)*(sj5)*(x1575)))+(((x1576)*(x1577)))+(((x1578)*(x1582)))+(((x1578)*(x1584)))+(((IkReal(-1.00000000000000))*(x1575)*(x1583)))+(((IkReal(-1.00000000000000))*(sj4)*(x1575)*(x1585)))+(((IkReal(-1.00000000000000))*(x1575)*(x1581)))+(((IkReal(-1.00000000000000))*(x1576)*(x1579)))))), ((gconst97)*(((((IkReal(-1.00000000000000))*(x1580)*(x1583)))+(((x1576)*(x1584)))+(((IkReal(-1.00000000000000))*(r11)*(sj0)*(sj5)*(x1576)))+(((IkReal(-1.00000000000000))*(x1574)*(x1575)))+(((IkReal(-1.00000000000000))*(sj4)*(x1575)*(x1577)))+(((IkReal(-1.00000000000000))*(x1580)*(x1581)))+(((x1578)*(x1579)))+(((IkReal(-1.00000000000000))*(x1576)*(x1585)))+(((x1576)*(x1582)))))));
07065 sj1array[0]=IKsin(j1array[0]);
07066 cj1array[0]=IKcos(j1array[0]);
07067 if( j1array[0] > IKPI )
07068 {
07069     j1array[0]-=IK2PI;
07070 }
07071 else if( j1array[0] < -IKPI )
07072 {    j1array[0]+=IK2PI;
07073 }
07074 j1valid[0] = true;
07075 for(int ij1 = 0; ij1 < 1; ++ij1)
07076 {
07077 if( !j1valid[ij1] )
07078 {
07079     continue;
07080 }
07081 _ij1[0] = ij1; _ij1[1] = -1;
07082 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07083 {
07084 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07085 {
07086     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07087 }
07088 }
07089 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07090 {
07091 IkReal evalcond[4];
07092 IkReal x1587=IKcos(j1);
07093 IkReal x1588=IKsin(j1);
07094 IkReal x1589=((IkReal(1.00000000000000))*(sj4));
07095 IkReal x1590=((cj5)*(r00));
07096 IkReal x1591=((cj5)*(r20));
07097 IkReal x1592=((r12)*(sj0));
07098 IkReal x1593=((r21)*(sj5));
07099 IkReal x1594=((IkReal(1.00000000000000))*(cj4));
07100 IkReal x1595=((sj2)*(x1588));
07101 IkReal x1596=((IkReal(1.00000000000000))*(x1587));
07102 IkReal x1597=((r11)*(sj0)*(sj5));
07103 IkReal x1598=((cj0)*(x1594));
07104 IkReal x1599=((cj0)*(r01)*(sj5));
07105 IkReal x1600=((cj2)*(x1588));
07106 IkReal x1601=((cj5)*(r10)*(sj0));
07107 IkReal x1602=((cj2)*(x1596));
07108 evalcond[0]=((((IkReal(-1.00000000000000))*(x1602)))+(x1595)+(((sj4)*(x1593)))+(((IkReal(-1.00000000000000))*(x1589)*(x1591)))+(((cj4)*(r22))));
07109 evalcond[1]=((((IkReal(-1.00000000000000))*(x1600)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(sj2)*(x1596)))+(((cj4)*(x1591)))+(((IkReal(-1.00000000000000))*(x1593)*(x1594))));
07110 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x1598)))+(((IkReal(-1.00000000000000))*(x1589)*(x1597)))+(((IkReal(-1.00000000000000))*(x1589)*(x1599)))+(((sj2)*(x1587)))+(((IkReal(-1.00000000000000))*(x1592)*(x1594)))+(((cj0)*(sj4)*(x1590)))+(((sj4)*(x1601)))+(x1600));
07111 evalcond[3]=((((IkReal(-1.00000000000000))*(x1602)))+(x1595)+(((IkReal(-1.00000000000000))*(x1594)*(x1601)))+(((IkReal(-1.00000000000000))*(x1589)*(x1592)))+(((cj4)*(x1597)))+(((cj4)*(x1599)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1589)))+(((IkReal(-1.00000000000000))*(x1590)*(x1598))));
07112 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07113 {
07114 continue;
07115 }
07116 }
07117 
07118 {
07119 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07120 vinfos[0].jointtype = 1;
07121 vinfos[0].foffset = j0;
07122 vinfos[0].indices[0] = _ij0[0];
07123 vinfos[0].indices[1] = _ij0[1];
07124 vinfos[0].maxsolutions = _nj0;
07125 vinfos[1].jointtype = 1;
07126 vinfos[1].foffset = j1;
07127 vinfos[1].indices[0] = _ij1[0];
07128 vinfos[1].indices[1] = _ij1[1];
07129 vinfos[1].maxsolutions = _nj1;
07130 vinfos[2].jointtype = 1;
07131 vinfos[2].foffset = j2;
07132 vinfos[2].indices[0] = _ij2[0];
07133 vinfos[2].indices[1] = _ij2[1];
07134 vinfos[2].maxsolutions = _nj2;
07135 vinfos[3].jointtype = 1;
07136 vinfos[3].foffset = j3;
07137 vinfos[3].indices[0] = _ij3[0];
07138 vinfos[3].indices[1] = _ij3[1];
07139 vinfos[3].maxsolutions = _nj3;
07140 vinfos[4].jointtype = 1;
07141 vinfos[4].foffset = j4;
07142 vinfos[4].indices[0] = _ij4[0];
07143 vinfos[4].indices[1] = _ij4[1];
07144 vinfos[4].maxsolutions = _nj4;
07145 vinfos[5].jointtype = 1;
07146 vinfos[5].foffset = j5;
07147 vinfos[5].indices[0] = _ij5[0];
07148 vinfos[5].indices[1] = _ij5[1];
07149 vinfos[5].maxsolutions = _nj5;
07150 std::vector<int> vfree(0);
07151 solutions.AddSolution(vinfos,vfree);
07152 }
07153 }
07154 }
07155 
07156 }
07157 
07158 }
07159 
07160 } else
07161 {
07162 {
07163 IkReal j1array[1], cj1array[1], sj1array[1];
07164 bool j1valid[1]={false};
07165 _nj1 = 1;
07166 IkReal x1603=((IkReal(1.00000000000000))*(cj2));
07167 IkReal x1604=((cj2)*(cj4));
07168 IkReal x1605=((r21)*(sj5));
07169 IkReal x1606=((cj5)*(r20));
07170 IkReal x1607=((r22)*(sj4));
07171 IkReal x1608=((cj4)*(sj2));
07172 IkReal x1609=((sj4)*(x1606));
07173 IkReal x1610=((IkReal(1.00000000000000))*(sj2)*(x1605));
07174 if( IKabs(((gconst96)*(((((sj2)*(x1609)))+(((x1604)*(x1606)))+(((IkReal(-1.00000000000000))*(r22)*(x1608)))+(((cj2)*(x1607)))+(((IkReal(-1.00000000000000))*(sj4)*(x1610)))+(((IkReal(-1.00000000000000))*(cj4)*(x1603)*(x1605))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst96)*(((((sj2)*(x1607)))+(((IkReal(-1.00000000000000))*(x1605)*(x1608)))+(((cj2)*(sj4)*(x1605)))+(((r22)*(x1604)))+(((x1606)*(x1608)))+(((IkReal(-1.00000000000000))*(x1603)*(x1609))))))) < IKFAST_ATAN2_MAGTHRESH )
07175     continue;
07176 j1array[0]=IKatan2(((gconst96)*(((((sj2)*(x1609)))+(((x1604)*(x1606)))+(((IkReal(-1.00000000000000))*(r22)*(x1608)))+(((cj2)*(x1607)))+(((IkReal(-1.00000000000000))*(sj4)*(x1610)))+(((IkReal(-1.00000000000000))*(cj4)*(x1603)*(x1605)))))), ((gconst96)*(((((sj2)*(x1607)))+(((IkReal(-1.00000000000000))*(x1605)*(x1608)))+(((cj2)*(sj4)*(x1605)))+(((r22)*(x1604)))+(((x1606)*(x1608)))+(((IkReal(-1.00000000000000))*(x1603)*(x1609)))))));
07177 sj1array[0]=IKsin(j1array[0]);
07178 cj1array[0]=IKcos(j1array[0]);
07179 if( j1array[0] > IKPI )
07180 {
07181     j1array[0]-=IK2PI;
07182 }
07183 else if( j1array[0] < -IKPI )
07184 {    j1array[0]+=IK2PI;
07185 }
07186 j1valid[0] = true;
07187 for(int ij1 = 0; ij1 < 1; ++ij1)
07188 {
07189 if( !j1valid[ij1] )
07190 {
07191     continue;
07192 }
07193 _ij1[0] = ij1; _ij1[1] = -1;
07194 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07195 {
07196 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07197 {
07198     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07199 }
07200 }
07201 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07202 {
07203 IkReal evalcond[4];
07204 IkReal x1611=IKcos(j1);
07205 IkReal x1612=IKsin(j1);
07206 IkReal x1613=((IkReal(1.00000000000000))*(sj4));
07207 IkReal x1614=((cj5)*(r00));
07208 IkReal x1615=((cj5)*(r20));
07209 IkReal x1616=((r12)*(sj0));
07210 IkReal x1617=((r21)*(sj5));
07211 IkReal x1618=((IkReal(1.00000000000000))*(cj4));
07212 IkReal x1619=((sj2)*(x1612));
07213 IkReal x1620=((IkReal(1.00000000000000))*(x1611));
07214 IkReal x1621=((r11)*(sj0)*(sj5));
07215 IkReal x1622=((cj0)*(x1618));
07216 IkReal x1623=((cj0)*(r01)*(sj5));
07217 IkReal x1624=((cj2)*(x1612));
07218 IkReal x1625=((cj5)*(r10)*(sj0));
07219 IkReal x1626=((cj2)*(x1620));
07220 evalcond[0]=((((IkReal(-1.00000000000000))*(x1626)))+(x1619)+(((cj4)*(r22)))+(((sj4)*(x1617)))+(((IkReal(-1.00000000000000))*(x1613)*(x1615))));
07221 evalcond[1]=((((IkReal(-1.00000000000000))*(x1624)))+(((IkReal(-1.00000000000000))*(sj2)*(x1620)))+(((r22)*(sj4)))+(((cj4)*(x1615)))+(((IkReal(-1.00000000000000))*(x1617)*(x1618))));
07222 evalcond[2]=((((IkReal(-1.00000000000000))*(x1616)*(x1618)))+(((sj2)*(x1611)))+(x1624)+(((IkReal(-1.00000000000000))*(x1613)*(x1623)))+(((cj0)*(sj4)*(x1614)))+(((sj4)*(x1625)))+(((IkReal(-1.00000000000000))*(r02)*(x1622)))+(((IkReal(-1.00000000000000))*(x1613)*(x1621))));
07223 evalcond[3]=((((IkReal(-1.00000000000000))*(x1626)))+(x1619)+(((IkReal(-1.00000000000000))*(x1613)*(x1616)))+(((IkReal(-1.00000000000000))*(x1614)*(x1622)))+(((IkReal(-1.00000000000000))*(x1618)*(x1625)))+(((IkReal(-1.00000000000000))*(cj0)*(r02)*(x1613)))+(((cj4)*(x1623)))+(((cj4)*(x1621))));
07224 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07225 {
07226 continue;
07227 }
07228 }
07229 
07230 {
07231 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07232 vinfos[0].jointtype = 1;
07233 vinfos[0].foffset = j0;
07234 vinfos[0].indices[0] = _ij0[0];
07235 vinfos[0].indices[1] = _ij0[1];
07236 vinfos[0].maxsolutions = _nj0;
07237 vinfos[1].jointtype = 1;
07238 vinfos[1].foffset = j1;
07239 vinfos[1].indices[0] = _ij1[0];
07240 vinfos[1].indices[1] = _ij1[1];
07241 vinfos[1].maxsolutions = _nj1;
07242 vinfos[2].jointtype = 1;
07243 vinfos[2].foffset = j2;
07244 vinfos[2].indices[0] = _ij2[0];
07245 vinfos[2].indices[1] = _ij2[1];
07246 vinfos[2].maxsolutions = _nj2;
07247 vinfos[3].jointtype = 1;
07248 vinfos[3].foffset = j3;
07249 vinfos[3].indices[0] = _ij3[0];
07250 vinfos[3].indices[1] = _ij3[1];
07251 vinfos[3].maxsolutions = _nj3;
07252 vinfos[4].jointtype = 1;
07253 vinfos[4].foffset = j4;
07254 vinfos[4].indices[0] = _ij4[0];
07255 vinfos[4].indices[1] = _ij4[1];
07256 vinfos[4].maxsolutions = _nj4;
07257 vinfos[5].jointtype = 1;
07258 vinfos[5].foffset = j5;
07259 vinfos[5].indices[0] = _ij5[0];
07260 vinfos[5].indices[1] = _ij5[1];
07261 vinfos[5].maxsolutions = _nj5;
07262 std::vector<int> vfree(0);
07263 solutions.AddSolution(vinfos,vfree);
07264 }
07265 }
07266 }
07267 
07268 }
07269 
07270 }
07271 
07272 } else
07273 {
07274 if( 1 )
07275 {
07276 continue;
07277 
07278 } else
07279 {
07280 }
07281 }
07282 }
07283 }
07284 }
07285 }
07286 
07287 } else
07288 {
07289 {
07290 IkReal j1array[1], cj1array[1], sj1array[1];
07291 bool j1valid[1]={false};
07292 _nj1 = 1;
07293 IkReal x1627=((IkReal(1.00000000000000))*(sj4));
07294 IkReal x1628=((r22)*(sj2));
07295 IkReal x1629=((cj3)*(cj4));
07296 IkReal x1630=((cj2)*(r22));
07297 IkReal x1631=((cj3)*(cj5)*(r20));
07298 IkReal x1632=((cj2)*(r21)*(sj5));
07299 IkReal x1633=((r21)*(sj2)*(sj5));
07300 IkReal x1634=((IkReal(1.00000000000000))*(cj4)*(cj5)*(r20));
07301 if( IKabs(((gconst89)*(((((sj2)*(sj4)*(x1631)))+(((IkReal(-1.00000000000000))*(x1627)*(x1630)))+(((cj4)*(x1632)))+(((IkReal(-1.00000000000000))*(cj2)*(x1634)))+(((IkReal(-1.00000000000000))*(x1628)*(x1629)))+(((IkReal(-1.00000000000000))*(cj3)*(x1627)*(x1633))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst89)*(((((cj3)*(sj4)*(x1632)))+(((IkReal(-1.00000000000000))*(cj2)*(x1627)*(x1631)))+(((cj4)*(x1633)))+(((x1629)*(x1630)))+(((IkReal(-1.00000000000000))*(sj2)*(x1634)))+(((IkReal(-1.00000000000000))*(x1627)*(x1628))))))) < IKFAST_ATAN2_MAGTHRESH )
07302     continue;
07303 j1array[0]=IKatan2(((gconst89)*(((((sj2)*(sj4)*(x1631)))+(((IkReal(-1.00000000000000))*(x1627)*(x1630)))+(((cj4)*(x1632)))+(((IkReal(-1.00000000000000))*(cj2)*(x1634)))+(((IkReal(-1.00000000000000))*(x1628)*(x1629)))+(((IkReal(-1.00000000000000))*(cj3)*(x1627)*(x1633)))))), ((gconst89)*(((((cj3)*(sj4)*(x1632)))+(((IkReal(-1.00000000000000))*(cj2)*(x1627)*(x1631)))+(((cj4)*(x1633)))+(((x1629)*(x1630)))+(((IkReal(-1.00000000000000))*(sj2)*(x1634)))+(((IkReal(-1.00000000000000))*(x1627)*(x1628)))))));
07304 sj1array[0]=IKsin(j1array[0]);
07305 cj1array[0]=IKcos(j1array[0]);
07306 if( j1array[0] > IKPI )
07307 {
07308     j1array[0]-=IK2PI;
07309 }
07310 else if( j1array[0] < -IKPI )
07311 {    j1array[0]+=IK2PI;
07312 }
07313 j1valid[0] = true;
07314 for(int ij1 = 0; ij1 < 1; ++ij1)
07315 {
07316 if( !j1valid[ij1] )
07317 {
07318     continue;
07319 }
07320 _ij1[0] = ij1; _ij1[1] = -1;
07321 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07322 {
07323 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07324 {
07325     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07326 }
07327 }
07328 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07329 {
07330 IkReal evalcond[6];
07331 IkReal x1635=IKsin(j1);
07332 IkReal x1636=IKcos(j1);
07333 IkReal x1637=((IkReal(1.00000000000000))*(sj2));
07334 IkReal x1638=((cj5)*(r00));
07335 IkReal x1639=((cj0)*(sj4));
07336 IkReal x1640=((cj5)*(sj4));
07337 IkReal x1641=((IkReal(1.00000000000000))*(sj5));
07338 IkReal x1642=((r10)*(sj0));
07339 IkReal x1643=((IkReal(1.00000000000000))*(sj0));
07340 IkReal x1644=((cj0)*(r01));
07341 IkReal x1645=((cj4)*(sj5));
07342 IkReal x1646=((IkReal(1.00000000000000))*(cj5));
07343 IkReal x1647=((cj2)*(x1636));
07344 IkReal x1648=((sj0)*(x1641));
07345 IkReal x1649=((cj3)*(x1635));
07346 IkReal x1650=((IkReal(1.00000000000000))*(cj0)*(cj4));
07347 IkReal x1651=((sj3)*(x1635));
07348 IkReal x1652=((sj2)*(x1636));
07349 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x1651)))+(((IkReal(-1.00000000000000))*(sj3)*(x1636)*(x1637)))+(((r20)*(sj5)))+(((cj5)*(r21))));
07350 evalcond[1]=((((sj2)*(x1635)))+(((IkReal(-1.00000000000000))*(x1647)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(r20)*(x1640)))+(((r21)*(sj4)*(sj5))));
07351 evalcond[2]=((((cj2)*(x1649)))+(((cj3)*(x1652)))+(((cj4)*(cj5)*(r20)))+(((r22)*(sj4)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x1641))));
07352 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1641)))+(((IkReal(-1.00000000000000))*(x1644)*(x1646)))+(((IkReal(-1.00000000000000))*(x1641)*(x1642)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1643)))+(((sj2)*(x1651)))+(((IkReal(-1.00000000000000))*(sj3)*(x1647))));
07353 evalcond[4]=((((x1638)*(x1639)))+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(x1648)))+(((x1640)*(x1642)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1643)))+(((IkReal(-1.00000000000000))*(r01)*(x1639)*(x1641)))+(x1652)+(((cj2)*(x1635)))+(((IkReal(-1.00000000000000))*(r02)*(x1650))));
07354 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(x1642)*(x1646)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1643)))+(((IkReal(-1.00000000000000))*(r02)*(x1639)))+(((x1644)*(x1645)))+(((cj3)*(x1647)))+(((IkReal(-1.00000000000000))*(x1637)*(x1649)))+(((r11)*(sj0)*(x1645)))+(((IkReal(-1.00000000000000))*(x1638)*(x1650))));
07355 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  )
07356 {
07357 continue;
07358 }
07359 }
07360 
07361 {
07362 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07363 vinfos[0].jointtype = 1;
07364 vinfos[0].foffset = j0;
07365 vinfos[0].indices[0] = _ij0[0];
07366 vinfos[0].indices[1] = _ij0[1];
07367 vinfos[0].maxsolutions = _nj0;
07368 vinfos[1].jointtype = 1;
07369 vinfos[1].foffset = j1;
07370 vinfos[1].indices[0] = _ij1[0];
07371 vinfos[1].indices[1] = _ij1[1];
07372 vinfos[1].maxsolutions = _nj1;
07373 vinfos[2].jointtype = 1;
07374 vinfos[2].foffset = j2;
07375 vinfos[2].indices[0] = _ij2[0];
07376 vinfos[2].indices[1] = _ij2[1];
07377 vinfos[2].maxsolutions = _nj2;
07378 vinfos[3].jointtype = 1;
07379 vinfos[3].foffset = j3;
07380 vinfos[3].indices[0] = _ij3[0];
07381 vinfos[3].indices[1] = _ij3[1];
07382 vinfos[3].maxsolutions = _nj3;
07383 vinfos[4].jointtype = 1;
07384 vinfos[4].foffset = j4;
07385 vinfos[4].indices[0] = _ij4[0];
07386 vinfos[4].indices[1] = _ij4[1];
07387 vinfos[4].maxsolutions = _nj4;
07388 vinfos[5].jointtype = 1;
07389 vinfos[5].foffset = j5;
07390 vinfos[5].indices[0] = _ij5[0];
07391 vinfos[5].indices[1] = _ij5[1];
07392 vinfos[5].maxsolutions = _nj5;
07393 std::vector<int> vfree(0);
07394 solutions.AddSolution(vinfos,vfree);
07395 }
07396 }
07397 }
07398 
07399 }
07400 
07401 }
07402 
07403 } else
07404 {
07405 {
07406 IkReal j1array[1], cj1array[1], sj1array[1];
07407 bool j1valid[1]={false};
07408 _nj1 = 1;
07409 IkReal x1653=((r20)*(sj5));
07410 IkReal x1654=((cj5)*(r21));
07411 IkReal x1655=((IkReal(1.00000000000000))*(sj2));
07412 IkReal x1656=((cj2)*(sj3));
07413 IkReal x1657=((cj4)*(r22));
07414 IkReal x1658=((cj5)*(r20)*(sj4));
07415 IkReal x1659=((r21)*(sj3)*(sj4)*(sj5));
07416 if( IKabs(((gconst88)*(((((IkReal(-1.00000000000000))*(x1655)*(x1659)))+(((cj2)*(x1654)))+(((sj2)*(sj3)*(x1658)))+(((IkReal(-1.00000000000000))*(sj3)*(x1655)*(x1657)))+(((cj2)*(x1653))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst88)*(((((r21)*(sj4)*(sj5)*(x1656)))+(((IkReal(-1.00000000000000))*(x1656)*(x1658)))+(((x1656)*(x1657)))+(((sj2)*(x1654)))+(((sj2)*(x1653))))))) < IKFAST_ATAN2_MAGTHRESH )
07417     continue;
07418 j1array[0]=IKatan2(((gconst88)*(((((IkReal(-1.00000000000000))*(x1655)*(x1659)))+(((cj2)*(x1654)))+(((sj2)*(sj3)*(x1658)))+(((IkReal(-1.00000000000000))*(sj3)*(x1655)*(x1657)))+(((cj2)*(x1653)))))), ((gconst88)*(((((r21)*(sj4)*(sj5)*(x1656)))+(((IkReal(-1.00000000000000))*(x1656)*(x1658)))+(((x1656)*(x1657)))+(((sj2)*(x1654)))+(((sj2)*(x1653)))))));
07419 sj1array[0]=IKsin(j1array[0]);
07420 cj1array[0]=IKcos(j1array[0]);
07421 if( j1array[0] > IKPI )
07422 {
07423     j1array[0]-=IK2PI;
07424 }
07425 else if( j1array[0] < -IKPI )
07426 {    j1array[0]+=IK2PI;
07427 }
07428 j1valid[0] = true;
07429 for(int ij1 = 0; ij1 < 1; ++ij1)
07430 {
07431 if( !j1valid[ij1] )
07432 {
07433     continue;
07434 }
07435 _ij1[0] = ij1; _ij1[1] = -1;
07436 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07437 {
07438 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07439 {
07440     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07441 }
07442 }
07443 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07444 {
07445 IkReal evalcond[6];
07446 IkReal x1660=IKsin(j1);
07447 IkReal x1661=IKcos(j1);
07448 IkReal x1662=((IkReal(1.00000000000000))*(sj2));
07449 IkReal x1663=((cj5)*(r00));
07450 IkReal x1664=((cj0)*(sj4));
07451 IkReal x1665=((cj5)*(sj4));
07452 IkReal x1666=((IkReal(1.00000000000000))*(sj5));
07453 IkReal x1667=((r10)*(sj0));
07454 IkReal x1668=((IkReal(1.00000000000000))*(sj0));
07455 IkReal x1669=((cj0)*(r01));
07456 IkReal x1670=((cj4)*(sj5));
07457 IkReal x1671=((IkReal(1.00000000000000))*(cj5));
07458 IkReal x1672=((cj2)*(x1661));
07459 IkReal x1673=((sj0)*(x1666));
07460 IkReal x1674=((cj3)*(x1660));
07461 IkReal x1675=((IkReal(1.00000000000000))*(cj0)*(cj4));
07462 IkReal x1676=((sj3)*(x1660));
07463 IkReal x1677=((sj2)*(x1661));
07464 evalcond[0]=((((IkReal(-1.00000000000000))*(cj2)*(x1676)))+(((IkReal(-1.00000000000000))*(sj3)*(x1661)*(x1662)))+(((r20)*(sj5)))+(((cj5)*(r21))));
07465 evalcond[1]=((((sj2)*(x1660)))+(((IkReal(-1.00000000000000))*(r20)*(x1665)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(x1672)))+(((r21)*(sj4)*(sj5))));
07466 evalcond[2]=((((cj3)*(x1677)))+(((cj2)*(x1674)))+(((cj4)*(cj5)*(r20)))+(((IkReal(-1.00000000000000))*(cj4)*(r21)*(x1666)))+(((r22)*(sj4))));
07467 evalcond[3]=((((IkReal(-1.00000000000000))*(x1669)*(x1671)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1666)))+(((sj2)*(x1676)))+(((IkReal(-1.00000000000000))*(x1666)*(x1667)))+(((IkReal(-1.00000000000000))*(sj3)*(x1672)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1668))));
07468 evalcond[4]=((((cj2)*(x1660)))+(((IkReal(-1.00000000000000))*(cj4)*(r12)*(x1668)))+(x1677)+(((IkReal(-1.00000000000000))*(r11)*(sj4)*(x1673)))+(((x1665)*(x1667)))+(((x1663)*(x1664)))+(((IkReal(-1.00000000000000))*(r01)*(x1664)*(x1666)))+(((IkReal(-1.00000000000000))*(r02)*(x1675))));
07469 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x1664)))+(((r11)*(sj0)*(x1670)))+(((cj3)*(x1672)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1668)))+(((IkReal(-1.00000000000000))*(x1662)*(x1674)))+(((IkReal(-1.00000000000000))*(cj4)*(x1667)*(x1671)))+(((x1669)*(x1670)))+(((IkReal(-1.00000000000000))*(x1663)*(x1675))));
07470 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  )
07471 {
07472 continue;
07473 }
07474 }
07475 
07476 {
07477 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07478 vinfos[0].jointtype = 1;
07479 vinfos[0].foffset = j0;
07480 vinfos[0].indices[0] = _ij0[0];
07481 vinfos[0].indices[1] = _ij0[1];
07482 vinfos[0].maxsolutions = _nj0;
07483 vinfos[1].jointtype = 1;
07484 vinfos[1].foffset = j1;
07485 vinfos[1].indices[0] = _ij1[0];
07486 vinfos[1].indices[1] = _ij1[1];
07487 vinfos[1].maxsolutions = _nj1;
07488 vinfos[2].jointtype = 1;
07489 vinfos[2].foffset = j2;
07490 vinfos[2].indices[0] = _ij2[0];
07491 vinfos[2].indices[1] = _ij2[1];
07492 vinfos[2].maxsolutions = _nj2;
07493 vinfos[3].jointtype = 1;
07494 vinfos[3].foffset = j3;
07495 vinfos[3].indices[0] = _ij3[0];
07496 vinfos[3].indices[1] = _ij3[1];
07497 vinfos[3].maxsolutions = _nj3;
07498 vinfos[4].jointtype = 1;
07499 vinfos[4].foffset = j4;
07500 vinfos[4].indices[0] = _ij4[0];
07501 vinfos[4].indices[1] = _ij4[1];
07502 vinfos[4].maxsolutions = _nj4;
07503 vinfos[5].jointtype = 1;
07504 vinfos[5].foffset = j5;
07505 vinfos[5].indices[0] = _ij5[0];
07506 vinfos[5].indices[1] = _ij5[1];
07507 vinfos[5].maxsolutions = _nj5;
07508 std::vector<int> vfree(0);
07509 solutions.AddSolution(vinfos,vfree);
07510 }
07511 }
07512 }
07513 
07514 }
07515 
07516 }
07517 }
07518 }
07519 
07520 }
07521 
07522 }
07523 
07524 } else
07525 {
07526 {
07527 IkReal j1array[1], cj1array[1], sj1array[1];
07528 bool j1valid[1]={false};
07529 _nj1 = 1;
07530 IkReal x1678=((IkReal(1.00000000000000))*(sj4));
07531 IkReal x1679=((r22)*(sj2));
07532 IkReal x1680=((cj2)*(cj4));
07533 IkReal x1681=((r21)*(sj5));
07534 IkReal x1682=((cj4)*(sj2));
07535 IkReal x1683=((cj3)*(cj5)*(r20));
07536 IkReal x1684=((cj3)*(x1681));
07537 IkReal x1685=((IkReal(1.00000000000000))*(cj5)*(r20));
07538 if( IKabs(((gconst87)*(((((IkReal(-1.00000000000000))*(cj2)*(r22)*(x1678)))+(((sj2)*(sj4)*(x1683)))+(((IkReal(-1.00000000000000))*(sj2)*(x1678)*(x1684)))+(((IkReal(-1.00000000000000))*(x1680)*(x1685)))+(((x1680)*(x1681)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x1679))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst87)*(((((x1681)*(x1682)))+(((cj2)*(sj4)*(x1684)))+(((IkReal(-1.00000000000000))*(x1682)*(x1685)))+(((IkReal(-1.00000000000000))*(cj2)*(x1678)*(x1683)))+(((cj3)*(r22)*(x1680)))+(((IkReal(-1.00000000000000))*(x1678)*(x1679))))))) < IKFAST_ATAN2_MAGTHRESH )
07539     continue;
07540 j1array[0]=IKatan2(((gconst87)*(((((IkReal(-1.00000000000000))*(cj2)*(r22)*(x1678)))+(((sj2)*(sj4)*(x1683)))+(((IkReal(-1.00000000000000))*(sj2)*(x1678)*(x1684)))+(((IkReal(-1.00000000000000))*(x1680)*(x1685)))+(((x1680)*(x1681)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x1679)))))), ((gconst87)*(((((x1681)*(x1682)))+(((cj2)*(sj4)*(x1684)))+(((IkReal(-1.00000000000000))*(x1682)*(x1685)))+(((IkReal(-1.00000000000000))*(cj2)*(x1678)*(x1683)))+(((cj3)*(r22)*(x1680)))+(((IkReal(-1.00000000000000))*(x1678)*(x1679)))))));
07541 sj1array[0]=IKsin(j1array[0]);
07542 cj1array[0]=IKcos(j1array[0]);
07543 if( j1array[0] > IKPI )
07544 {
07545     j1array[0]-=IK2PI;
07546 }
07547 else if( j1array[0] < -IKPI )
07548 {    j1array[0]+=IK2PI;
07549 }
07550 j1valid[0] = true;
07551 for(int ij1 = 0; ij1 < 1; ++ij1)
07552 {
07553 if( !j1valid[ij1] )
07554 {
07555     continue;
07556 }
07557 _ij1[0] = ij1; _ij1[1] = -1;
07558 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07559 {
07560 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07561 {
07562     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07563 }
07564 }
07565 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07566 {
07567 IkReal evalcond[3];
07568 IkReal x1686=IKsin(j1);
07569 IkReal x1687=IKcos(j1);
07570 IkReal x1688=((IkReal(1.00000000000000))*(cj2));
07571 IkReal x1689=((cj5)*(r20));
07572 IkReal x1690=((r21)*(sj5));
07573 IkReal x1691=((sj2)*(x1687));
07574 evalcond[0]=((((IkReal(-1.00000000000000))*(sj3)*(x1686)*(x1688)))+(((IkReal(-1.00000000000000))*(sj3)*(x1691)))+(((r20)*(sj5)))+(((cj5)*(r21))));
07575 evalcond[1]=((((sj4)*(x1690)))+(((cj4)*(r22)))+(((IkReal(-1.00000000000000))*(sj4)*(x1689)))+(((IkReal(-1.00000000000000))*(x1687)*(x1688)))+(((sj2)*(x1686))));
07576 evalcond[2]=((((IkReal(-1.00000000000000))*(cj4)*(x1690)))+(((cj2)*(cj3)*(x1686)))+(((r22)*(sj4)))+(((cj3)*(x1691)))+(((cj4)*(x1689))));
07577 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
07578 {
07579 continue;
07580 }
07581 }
07582 
07583 {
07584 IkReal dummyeval[1];
07585 IkReal gconst98;
07586 IkReal x1692=(cj5)*(cj5);
07587 IkReal x1693=(sj5)*(sj5);
07588 IkReal x1694=((IkReal(1.00000000000000))*(r10));
07589 IkReal x1695=((cj4)*(sj5));
07590 IkReal x1696=((r00)*(r11));
07591 IkReal x1697=((cj4)*(cj5));
07592 IkReal x1698=((sj4)*(x1692));
07593 IkReal x1699=((sj4)*(x1693));
07594 gconst98=IKsign(((((IkReal(-1.00000000000000))*(r01)*(x1694)*(x1699)))+(((IkReal(-1.00000000000000))*(r02)*(x1694)*(x1695)))+(((x1696)*(x1698)))+(((IkReal(-1.00000000000000))*(r01)*(x1694)*(x1698)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1697)))+(((r01)*(r12)*(x1697)))+(((r00)*(r12)*(x1695)))+(((x1696)*(x1699)))));
07595 IkReal x1700=(cj5)*(cj5);
07596 IkReal x1701=(sj5)*(sj5);
07597 IkReal x1702=((IkReal(1.00000000000000))*(r10));
07598 IkReal x1703=((cj4)*(sj5));
07599 IkReal x1704=((r00)*(r11));
07600 IkReal x1705=((cj4)*(cj5));
07601 IkReal x1706=((sj4)*(x1700));
07602 IkReal x1707=((sj4)*(x1701));
07603 dummyeval[0]=((((x1704)*(x1706)))+(((r00)*(r12)*(x1703)))+(((IkReal(-1.00000000000000))*(r01)*(x1702)*(x1706)))+(((r01)*(r12)*(x1705)))+(((x1704)*(x1707)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1705)))+(((IkReal(-1.00000000000000))*(r02)*(x1702)*(x1703)))+(((IkReal(-1.00000000000000))*(r01)*(x1702)*(x1707))));
07604 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07605 {
07606 {
07607 IkReal dummyeval[1];
07608 IkReal gconst99;
07609 IkReal x1708=(sj5)*(sj5);
07610 IkReal x1709=(cj5)*(cj5);
07611 IkReal x1710=((cj5)*(sj4));
07612 IkReal x1711=((IkReal(1.00000000000000))*(r02));
07613 IkReal x1712=((sj4)*(sj5));
07614 IkReal x1713=((cj4)*(r01)*(r10));
07615 IkReal x1714=((IkReal(1.00000000000000))*(cj4)*(r00)*(r11));
07616 gconst99=IKsign(((((r01)*(r12)*(x1710)))+(((IkReal(-1.00000000000000))*(x1708)*(x1714)))+(((x1708)*(x1713)))+(((IkReal(-1.00000000000000))*(r10)*(x1711)*(x1712)))+(((IkReal(-1.00000000000000))*(x1709)*(x1714)))+(((x1709)*(x1713)))+(((IkReal(-1.00000000000000))*(r11)*(x1710)*(x1711)))+(((r00)*(r12)*(x1712)))));
07617 IkReal x1715=(sj5)*(sj5);
07618 IkReal x1716=(cj5)*(cj5);
07619 IkReal x1717=((cj5)*(sj4));
07620 IkReal x1718=((IkReal(1.00000000000000))*(r02));
07621 IkReal x1719=((sj4)*(sj5));
07622 IkReal x1720=((cj4)*(r01)*(r10));
07623 IkReal x1721=x1714;
07624 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1715)*(x1721)))+(((x1716)*(x1720)))+(((IkReal(-1.00000000000000))*(r10)*(x1718)*(x1719)))+(((r01)*(r12)*(x1717)))+(((x1715)*(x1720)))+(((IkReal(-1.00000000000000))*(x1716)*(x1721)))+(((r00)*(r12)*(x1719)))+(((IkReal(-1.00000000000000))*(r11)*(x1717)*(x1718))));
07625 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07626 {
07627 continue;
07628 
07629 } else
07630 {
07631 {
07632 IkReal j0array[1], cj0array[1], sj0array[1];
07633 bool j0valid[1]={false};
07634 _nj0 = 1;
07635 IkReal x1722=((IkReal(1.00000000000000))*(cj3));
07636 IkReal x1723=((cj4)*(cj5));
07637 IkReal x1724=((cj5)*(sj3));
07638 IkReal x1725=((sj3)*(sj5));
07639 IkReal x1726=((cj3)*(cj4)*(sj5));
07640 if( IKabs(((gconst99)*(((((r11)*(x1724)))+(((r10)*(x1725)))+(((IkReal(-1.00000000000000))*(r10)*(x1722)*(x1723)))+(((r11)*(x1726)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1722))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst99)*(((((r00)*(x1725)))+(((r01)*(x1724)))+(((r01)*(x1726)))+(((IkReal(-1.00000000000000))*(r00)*(x1722)*(x1723)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1722))))))) < IKFAST_ATAN2_MAGTHRESH )
07641     continue;
07642 j0array[0]=IKatan2(((gconst99)*(((((r11)*(x1724)))+(((r10)*(x1725)))+(((IkReal(-1.00000000000000))*(r10)*(x1722)*(x1723)))+(((r11)*(x1726)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1722)))))), ((gconst99)*(((((r00)*(x1725)))+(((r01)*(x1724)))+(((r01)*(x1726)))+(((IkReal(-1.00000000000000))*(r00)*(x1722)*(x1723)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1722)))))));
07643 sj0array[0]=IKsin(j0array[0]);
07644 cj0array[0]=IKcos(j0array[0]);
07645 if( j0array[0] > IKPI )
07646 {
07647     j0array[0]-=IK2PI;
07648 }
07649 else if( j0array[0] < -IKPI )
07650 {    j0array[0]+=IK2PI;
07651 }
07652 j0valid[0] = true;
07653 for(int ij0 = 0; ij0 < 1; ++ij0)
07654 {
07655 if( !j0valid[ij0] )
07656 {
07657     continue;
07658 }
07659 _ij0[0] = ij0; _ij0[1] = -1;
07660 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
07661 {
07662 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
07663 {
07664     j0valid[iij0]=false; _ij0[1] = iij0; break; 
07665 }
07666 }
07667 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
07668 {
07669 IkReal evalcond[6];
07670 IkReal x1727=IKsin(j0);
07671 IkReal x1728=IKcos(j0);
07672 IkReal x1729=((cj4)*(r12));
07673 IkReal x1730=((cj1)*(cj2));
07674 IkReal x1731=((IkReal(1.00000000000000))*(sj4));
07675 IkReal x1732=((IkReal(1.00000000000000))*(r10));
07676 IkReal x1733=((r01)*(sj5));
07677 IkReal x1734=((r02)*(sj4));
07678 IkReal x1735=((sj1)*(sj2));
07679 IkReal x1736=((cj5)*(r01));
07680 IkReal x1737=((cj5)*(r00));
07681 IkReal x1738=((r11)*(sj5));
07682 IkReal x1739=((sj5)*(x1727));
07683 IkReal x1740=((IkReal(1.00000000000000))*(x1728));
07684 IkReal x1741=((cj4)*(x1727));
07685 IkReal x1742=((cj5)*(x1727));
07686 IkReal x1743=((cj4)*(x1728));
07687 IkReal x1744=((cj5)*(sj4)*(x1728));
07688 evalcond[0]=((((x1727)*(x1736)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1740)))+(cj3)+(((r00)*(x1739)))+(((IkReal(-1.00000000000000))*(sj5)*(x1728)*(x1732))));
07689 evalcond[1]=((((IkReal(-1.00000000000000))*(x1736)*(x1740)))+(((IkReal(-1.00000000000000))*(r11)*(x1742)))+(((IkReal(-1.00000000000000))*(sj3)*(x1730)))+(((IkReal(-1.00000000000000))*(x1732)*(x1739)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1740)))+(((sj3)*(x1735))));
07690 evalcond[2]=((((IkReal(-1.00000000000000))*(x1728)*(x1731)*(x1738)))+(((sj4)*(x1727)*(x1733)))+(((IkReal(-1.00000000000000))*(x1729)*(x1740)))+(((r10)*(x1744)))+(((IkReal(-1.00000000000000))*(x1727)*(x1731)*(x1737)))+(((r02)*(x1741))));
07691 evalcond[3]=((((x1737)*(x1741)))+(sj3)+(((IkReal(-1.00000000000000))*(x1733)*(x1741)))+(((IkReal(-1.00000000000000))*(r12)*(x1728)*(x1731)))+(((x1727)*(x1734)))+(((x1738)*(x1743)))+(((IkReal(-1.00000000000000))*(cj5)*(x1732)*(x1743))));
07692 evalcond[4]=((((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1728)*(x1731)*(x1733)))+(((sj4)*(x1728)*(x1737)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1740)))+(((IkReal(-1.00000000000000))*(x1727)*(x1731)*(x1738)))+(((r10)*(sj4)*(x1742)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x1727)*(x1729))));
07693 evalcond[5]=((((IkReal(-1.00000000000000))*(r12)*(x1727)*(x1731)))+(((IkReal(-1.00000000000000))*(r02)*(x1728)*(x1731)))+(((IkReal(-1.00000000000000))*(cj4)*(x1737)*(x1740)))+(((x1738)*(x1741)))+(((IkReal(-1.00000000000000))*(cj3)*(x1735)))+(((IkReal(-1.00000000000000))*(cj5)*(x1732)*(x1741)))+(((cj3)*(x1730)))+(((x1733)*(x1743))));
07694 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  )
07695 {
07696 continue;
07697 }
07698 }
07699 
07700 {
07701 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07702 vinfos[0].jointtype = 1;
07703 vinfos[0].foffset = j0;
07704 vinfos[0].indices[0] = _ij0[0];
07705 vinfos[0].indices[1] = _ij0[1];
07706 vinfos[0].maxsolutions = _nj0;
07707 vinfos[1].jointtype = 1;
07708 vinfos[1].foffset = j1;
07709 vinfos[1].indices[0] = _ij1[0];
07710 vinfos[1].indices[1] = _ij1[1];
07711 vinfos[1].maxsolutions = _nj1;
07712 vinfos[2].jointtype = 1;
07713 vinfos[2].foffset = j2;
07714 vinfos[2].indices[0] = _ij2[0];
07715 vinfos[2].indices[1] = _ij2[1];
07716 vinfos[2].maxsolutions = _nj2;
07717 vinfos[3].jointtype = 1;
07718 vinfos[3].foffset = j3;
07719 vinfos[3].indices[0] = _ij3[0];
07720 vinfos[3].indices[1] = _ij3[1];
07721 vinfos[3].maxsolutions = _nj3;
07722 vinfos[4].jointtype = 1;
07723 vinfos[4].foffset = j4;
07724 vinfos[4].indices[0] = _ij4[0];
07725 vinfos[4].indices[1] = _ij4[1];
07726 vinfos[4].maxsolutions = _nj4;
07727 vinfos[5].jointtype = 1;
07728 vinfos[5].foffset = j5;
07729 vinfos[5].indices[0] = _ij5[0];
07730 vinfos[5].indices[1] = _ij5[1];
07731 vinfos[5].maxsolutions = _nj5;
07732 std::vector<int> vfree(0);
07733 solutions.AddSolution(vinfos,vfree);
07734 }
07735 }
07736 }
07737 
07738 }
07739 
07740 }
07741 
07742 } else
07743 {
07744 {
07745 IkReal j0array[1], cj0array[1], sj0array[1];
07746 bool j0valid[1]={false};
07747 _nj0 = 1;
07748 IkReal x1745=((cj3)*(sj4));
07749 IkReal x1746=((IkReal(1.00000000000000))*(sj5));
07750 IkReal x1747=((IkReal(1.00000000000000))*(cj3)*(cj4));
07751 if( IKabs(((gconst98)*(((((IkReal(-1.00000000000000))*(r12)*(x1747)))+(((cj5)*(r10)*(x1745)))+(((IkReal(-1.00000000000000))*(r11)*(x1745)*(x1746))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst98)*(((((IkReal(-1.00000000000000))*(r01)*(x1745)*(x1746)))+(((cj5)*(r00)*(x1745)))+(((IkReal(-1.00000000000000))*(r02)*(x1747))))))) < IKFAST_ATAN2_MAGTHRESH )
07752     continue;
07753 j0array[0]=IKatan2(((gconst98)*(((((IkReal(-1.00000000000000))*(r12)*(x1747)))+(((cj5)*(r10)*(x1745)))+(((IkReal(-1.00000000000000))*(r11)*(x1745)*(x1746)))))), ((gconst98)*(((((IkReal(-1.00000000000000))*(r01)*(x1745)*(x1746)))+(((cj5)*(r00)*(x1745)))+(((IkReal(-1.00000000000000))*(r02)*(x1747)))))));
07754 sj0array[0]=IKsin(j0array[0]);
07755 cj0array[0]=IKcos(j0array[0]);
07756 if( j0array[0] > IKPI )
07757 {
07758     j0array[0]-=IK2PI;
07759 }
07760 else if( j0array[0] < -IKPI )
07761 {    j0array[0]+=IK2PI;
07762 }
07763 j0valid[0] = true;
07764 for(int ij0 = 0; ij0 < 1; ++ij0)
07765 {
07766 if( !j0valid[ij0] )
07767 {
07768     continue;
07769 }
07770 _ij0[0] = ij0; _ij0[1] = -1;
07771 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
07772 {
07773 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
07774 {
07775     j0valid[iij0]=false; _ij0[1] = iij0; break; 
07776 }
07777 }
07778 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
07779 {
07780 IkReal evalcond[6];
07781 IkReal x1748=IKsin(j0);
07782 IkReal x1749=IKcos(j0);
07783 IkReal x1750=((cj4)*(r12));
07784 IkReal x1751=((cj1)*(cj2));
07785 IkReal x1752=((IkReal(1.00000000000000))*(sj4));
07786 IkReal x1753=((IkReal(1.00000000000000))*(r10));
07787 IkReal x1754=((r01)*(sj5));
07788 IkReal x1755=((r02)*(sj4));
07789 IkReal x1756=((sj1)*(sj2));
07790 IkReal x1757=((cj5)*(r01));
07791 IkReal x1758=((cj5)*(r00));
07792 IkReal x1759=((r11)*(sj5));
07793 IkReal x1760=((sj5)*(x1748));
07794 IkReal x1761=((IkReal(1.00000000000000))*(x1749));
07795 IkReal x1762=((cj4)*(x1748));
07796 IkReal x1763=((cj5)*(x1748));
07797 IkReal x1764=((cj4)*(x1749));
07798 IkReal x1765=((cj5)*(sj4)*(x1749));
07799 evalcond[0]=((((x1748)*(x1757)))+(((r00)*(x1760)))+(cj3)+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1761)))+(((IkReal(-1.00000000000000))*(sj5)*(x1749)*(x1753))));
07800 evalcond[1]=((((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1761)))+(((sj3)*(x1756)))+(((IkReal(-1.00000000000000))*(r11)*(x1763)))+(((IkReal(-1.00000000000000))*(sj3)*(x1751)))+(((IkReal(-1.00000000000000))*(x1753)*(x1760)))+(((IkReal(-1.00000000000000))*(x1757)*(x1761))));
07801 evalcond[2]=((((IkReal(-1.00000000000000))*(x1748)*(x1752)*(x1758)))+(((IkReal(-1.00000000000000))*(x1749)*(x1752)*(x1759)))+(((sj4)*(x1748)*(x1754)))+(((r10)*(x1765)))+(((IkReal(-1.00000000000000))*(x1750)*(x1761)))+(((r02)*(x1762))));
07802 evalcond[3]=((((x1759)*(x1764)))+(((x1758)*(x1762)))+(((x1748)*(x1755)))+(sj3)+(((IkReal(-1.00000000000000))*(r12)*(x1749)*(x1752)))+(((IkReal(-1.00000000000000))*(x1754)*(x1762)))+(((IkReal(-1.00000000000000))*(cj5)*(x1753)*(x1764))));
07803 evalcond[4]=((((IkReal(-1.00000000000000))*(x1748)*(x1750)))+(((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1748)*(x1752)*(x1759)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1761)))+(((sj4)*(x1749)*(x1758)))+(((r10)*(sj4)*(x1763)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x1749)*(x1752)*(x1754))));
07804 evalcond[5]=((((x1754)*(x1764)))+(((IkReal(-1.00000000000000))*(r02)*(x1749)*(x1752)))+(((x1759)*(x1762)))+(((IkReal(-1.00000000000000))*(r12)*(x1748)*(x1752)))+(((IkReal(-1.00000000000000))*(cj5)*(x1753)*(x1762)))+(((IkReal(-1.00000000000000))*(cj4)*(x1758)*(x1761)))+(((cj3)*(x1751)))+(((IkReal(-1.00000000000000))*(cj3)*(x1756))));
07805 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  )
07806 {
07807 continue;
07808 }
07809 }
07810 
07811 {
07812 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07813 vinfos[0].jointtype = 1;
07814 vinfos[0].foffset = j0;
07815 vinfos[0].indices[0] = _ij0[0];
07816 vinfos[0].indices[1] = _ij0[1];
07817 vinfos[0].maxsolutions = _nj0;
07818 vinfos[1].jointtype = 1;
07819 vinfos[1].foffset = j1;
07820 vinfos[1].indices[0] = _ij1[0];
07821 vinfos[1].indices[1] = _ij1[1];
07822 vinfos[1].maxsolutions = _nj1;
07823 vinfos[2].jointtype = 1;
07824 vinfos[2].foffset = j2;
07825 vinfos[2].indices[0] = _ij2[0];
07826 vinfos[2].indices[1] = _ij2[1];
07827 vinfos[2].maxsolutions = _nj2;
07828 vinfos[3].jointtype = 1;
07829 vinfos[3].foffset = j3;
07830 vinfos[3].indices[0] = _ij3[0];
07831 vinfos[3].indices[1] = _ij3[1];
07832 vinfos[3].maxsolutions = _nj3;
07833 vinfos[4].jointtype = 1;
07834 vinfos[4].foffset = j4;
07835 vinfos[4].indices[0] = _ij4[0];
07836 vinfos[4].indices[1] = _ij4[1];
07837 vinfos[4].maxsolutions = _nj4;
07838 vinfos[5].jointtype = 1;
07839 vinfos[5].foffset = j5;
07840 vinfos[5].indices[0] = _ij5[0];
07841 vinfos[5].indices[1] = _ij5[1];
07842 vinfos[5].maxsolutions = _nj5;
07843 std::vector<int> vfree(0);
07844 solutions.AddSolution(vinfos,vfree);
07845 }
07846 }
07847 }
07848 
07849 }
07850 
07851 }
07852 }
07853 }
07854 
07855 }
07856 
07857 }
07858 
07859 } else
07860 {
07861 {
07862 IkReal j1array[1], cj1array[1], sj1array[1];
07863 bool j1valid[1]={false};
07864 _nj1 = 1;
07865 IkReal x1766=((cj2)*(sj5));
07866 IkReal x1767=((cj5)*(r21));
07867 IkReal x1768=((cj2)*(sj3));
07868 IkReal x1769=((cj4)*(r22));
07869 IkReal x1770=((sj2)*(sj5));
07870 IkReal x1771=((sj2)*(sj3));
07871 IkReal x1772=((r21)*(sj3)*(sj4));
07872 IkReal x1773=((cj5)*(r20)*(sj4));
07873 if( IKabs(((gconst86)*(((((x1771)*(x1773)))+(((IkReal(-1.00000000000000))*(x1769)*(x1771)))+(((cj2)*(x1767)))+(((r20)*(x1766)))+(((IkReal(-1.00000000000000))*(x1770)*(x1772))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst86)*(((((r20)*(x1770)))+(((IkReal(-1.00000000000000))*(x1768)*(x1773)))+(((x1768)*(x1769)))+(((sj2)*(x1767)))+(((x1766)*(x1772))))))) < IKFAST_ATAN2_MAGTHRESH )
07874     continue;
07875 j1array[0]=IKatan2(((gconst86)*(((((x1771)*(x1773)))+(((IkReal(-1.00000000000000))*(x1769)*(x1771)))+(((cj2)*(x1767)))+(((r20)*(x1766)))+(((IkReal(-1.00000000000000))*(x1770)*(x1772)))))), ((gconst86)*(((((r20)*(x1770)))+(((IkReal(-1.00000000000000))*(x1768)*(x1773)))+(((x1768)*(x1769)))+(((sj2)*(x1767)))+(((x1766)*(x1772)))))));
07876 sj1array[0]=IKsin(j1array[0]);
07877 cj1array[0]=IKcos(j1array[0]);
07878 if( j1array[0] > IKPI )
07879 {
07880     j1array[0]-=IK2PI;
07881 }
07882 else if( j1array[0] < -IKPI )
07883 {    j1array[0]+=IK2PI;
07884 }
07885 j1valid[0] = true;
07886 for(int ij1 = 0; ij1 < 1; ++ij1)
07887 {
07888 if( !j1valid[ij1] )
07889 {
07890     continue;
07891 }
07892 _ij1[0] = ij1; _ij1[1] = -1;
07893 for(int iij1 = ij1+1; iij1 < 1; ++iij1)
07894 {
07895 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
07896 {
07897     j1valid[iij1]=false; _ij1[1] = iij1; break; 
07898 }
07899 }
07900 j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
07901 {
07902 IkReal evalcond[3];
07903 IkReal x1774=IKsin(j1);
07904 IkReal x1775=IKcos(j1);
07905 IkReal x1776=((IkReal(1.00000000000000))*(cj2));
07906 IkReal x1777=((cj5)*(r20));
07907 IkReal x1778=((r21)*(sj5));
07908 IkReal x1779=((sj2)*(x1775));
07909 evalcond[0]=((((IkReal(-1.00000000000000))*(sj3)*(x1779)))+(((r20)*(sj5)))+(((IkReal(-1.00000000000000))*(sj3)*(x1774)*(x1776)))+(((cj5)*(r21))));
07910 evalcond[1]=((((IkReal(-1.00000000000000))*(sj4)*(x1777)))+(((IkReal(-1.00000000000000))*(x1775)*(x1776)))+(((sj2)*(x1774)))+(((cj4)*(r22)))+(((sj4)*(x1778))));
07911 evalcond[2]=((((r22)*(sj4)))+(((cj2)*(cj3)*(x1774)))+(((cj3)*(x1779)))+(((cj4)*(x1777)))+(((IkReal(-1.00000000000000))*(cj4)*(x1778))));
07912 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
07913 {
07914 continue;
07915 }
07916 }
07917 
07918 {
07919 IkReal dummyeval[1];
07920 IkReal gconst98;
07921 IkReal x1780=(cj5)*(cj5);
07922 IkReal x1781=(sj5)*(sj5);
07923 IkReal x1782=((IkReal(1.00000000000000))*(r10));
07924 IkReal x1783=((cj4)*(sj5));
07925 IkReal x1784=((r00)*(r11));
07926 IkReal x1785=((cj4)*(cj5));
07927 IkReal x1786=((sj4)*(x1780));
07928 IkReal x1787=((sj4)*(x1781));
07929 gconst98=IKsign(((((x1784)*(x1786)))+(((r00)*(r12)*(x1783)))+(((IkReal(-1.00000000000000))*(r02)*(x1782)*(x1783)))+(((IkReal(-1.00000000000000))*(r01)*(x1782)*(x1786)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1785)))+(((IkReal(-1.00000000000000))*(r01)*(x1782)*(x1787)))+(((r01)*(r12)*(x1785)))+(((x1784)*(x1787)))));
07930 IkReal x1788=(cj5)*(cj5);
07931 IkReal x1789=(sj5)*(sj5);
07932 IkReal x1790=((IkReal(1.00000000000000))*(r10));
07933 IkReal x1791=((cj4)*(sj5));
07934 IkReal x1792=((r00)*(r11));
07935 IkReal x1793=((cj4)*(cj5));
07936 IkReal x1794=((sj4)*(x1788));
07937 IkReal x1795=((sj4)*(x1789));
07938 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(x1790)*(x1791)))+(((x1792)*(x1794)))+(((IkReal(-1.00000000000000))*(r01)*(x1790)*(x1794)))+(((IkReal(-1.00000000000000))*(r01)*(x1790)*(x1795)))+(((r01)*(r12)*(x1793)))+(((x1792)*(x1795)))+(((IkReal(-1.00000000000000))*(r02)*(r11)*(x1793)))+(((r00)*(r12)*(x1791))));
07939 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07940 {
07941 {
07942 IkReal dummyeval[1];
07943 IkReal gconst99;
07944 IkReal x1796=(sj5)*(sj5);
07945 IkReal x1797=(cj5)*(cj5);
07946 IkReal x1798=((cj5)*(sj4));
07947 IkReal x1799=((IkReal(1.00000000000000))*(r02));
07948 IkReal x1800=((sj4)*(sj5));
07949 IkReal x1801=((cj4)*(r01)*(r10));
07950 IkReal x1802=((IkReal(1.00000000000000))*(cj4)*(r00)*(r11));
07951 gconst99=IKsign(((((r00)*(r12)*(x1800)))+(((IkReal(-1.00000000000000))*(r11)*(x1798)*(x1799)))+(((x1796)*(x1801)))+(((IkReal(-1.00000000000000))*(x1797)*(x1802)))+(((x1797)*(x1801)))+(((IkReal(-1.00000000000000))*(r10)*(x1799)*(x1800)))+(((IkReal(-1.00000000000000))*(x1796)*(x1802)))+(((r01)*(r12)*(x1798)))));
07952 IkReal x1803=(sj5)*(sj5);
07953 IkReal x1804=(cj5)*(cj5);
07954 IkReal x1805=((cj5)*(sj4));
07955 IkReal x1806=((IkReal(1.00000000000000))*(r02));
07956 IkReal x1807=((sj4)*(sj5));
07957 IkReal x1808=((cj4)*(r01)*(r10));
07958 IkReal x1809=x1802;
07959 dummyeval[0]=((((x1803)*(x1808)))+(((r00)*(r12)*(x1807)))+(((IkReal(-1.00000000000000))*(r10)*(x1806)*(x1807)))+(((IkReal(-1.00000000000000))*(x1803)*(x1809)))+(((x1804)*(x1808)))+(((r01)*(r12)*(x1805)))+(((IkReal(-1.00000000000000))*(r11)*(x1805)*(x1806)))+(((IkReal(-1.00000000000000))*(x1804)*(x1809))));
07960 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07961 {
07962 continue;
07963 
07964 } else
07965 {
07966 {
07967 IkReal j0array[1], cj0array[1], sj0array[1];
07968 bool j0valid[1]={false};
07969 _nj0 = 1;
07970 IkReal x1810=((IkReal(1.00000000000000))*(cj3));
07971 IkReal x1811=((cj4)*(cj5));
07972 IkReal x1812=((cj5)*(sj3));
07973 IkReal x1813=((sj3)*(sj5));
07974 IkReal x1814=((cj3)*(cj4)*(sj5));
07975 if( IKabs(((gconst99)*(((((r11)*(x1812)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1810)))+(((r11)*(x1814)))+(((r10)*(x1813)))+(((IkReal(-1.00000000000000))*(r10)*(x1810)*(x1811))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst99)*(((((r01)*(x1814)))+(((IkReal(-1.00000000000000))*(r00)*(x1810)*(x1811)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1810)))+(((r00)*(x1813)))+(((r01)*(x1812))))))) < IKFAST_ATAN2_MAGTHRESH )
07976     continue;
07977 j0array[0]=IKatan2(((gconst99)*(((((r11)*(x1812)))+(((IkReal(-1.00000000000000))*(r12)*(sj4)*(x1810)))+(((r11)*(x1814)))+(((r10)*(x1813)))+(((IkReal(-1.00000000000000))*(r10)*(x1810)*(x1811)))))), ((gconst99)*(((((r01)*(x1814)))+(((IkReal(-1.00000000000000))*(r00)*(x1810)*(x1811)))+(((IkReal(-1.00000000000000))*(r02)*(sj4)*(x1810)))+(((r00)*(x1813)))+(((r01)*(x1812)))))));
07978 sj0array[0]=IKsin(j0array[0]);
07979 cj0array[0]=IKcos(j0array[0]);
07980 if( j0array[0] > IKPI )
07981 {
07982     j0array[0]-=IK2PI;
07983 }
07984 else if( j0array[0] < -IKPI )
07985 {    j0array[0]+=IK2PI;
07986 }
07987 j0valid[0] = true;
07988 for(int ij0 = 0; ij0 < 1; ++ij0)
07989 {
07990 if( !j0valid[ij0] )
07991 {
07992     continue;
07993 }
07994 _ij0[0] = ij0; _ij0[1] = -1;
07995 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
07996 {
07997 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
07998 {
07999     j0valid[iij0]=false; _ij0[1] = iij0; break; 
08000 }
08001 }
08002 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
08003 {
08004 IkReal evalcond[6];
08005 IkReal x1815=IKsin(j0);
08006 IkReal x1816=IKcos(j0);
08007 IkReal x1817=((cj4)*(r12));
08008 IkReal x1818=((cj1)*(cj2));
08009 IkReal x1819=((IkReal(1.00000000000000))*(sj4));
08010 IkReal x1820=((IkReal(1.00000000000000))*(r10));
08011 IkReal x1821=((r01)*(sj5));
08012 IkReal x1822=((r02)*(sj4));
08013 IkReal x1823=((sj1)*(sj2));
08014 IkReal x1824=((cj5)*(r01));
08015 IkReal x1825=((cj5)*(r00));
08016 IkReal x1826=((r11)*(sj5));
08017 IkReal x1827=((sj5)*(x1815));
08018 IkReal x1828=((IkReal(1.00000000000000))*(x1816));
08019 IkReal x1829=((cj4)*(x1815));
08020 IkReal x1830=((cj5)*(x1815));
08021 IkReal x1831=((cj4)*(x1816));
08022 IkReal x1832=((cj5)*(sj4)*(x1816));
08023 evalcond[0]=((((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1828)))+(cj3)+(((x1815)*(x1824)))+(((IkReal(-1.00000000000000))*(sj5)*(x1816)*(x1820)))+(((r00)*(x1827))));
08024 evalcond[1]=((((IkReal(-1.00000000000000))*(x1824)*(x1828)))+(((IkReal(-1.00000000000000))*(r11)*(x1830)))+(((sj3)*(x1823)))+(((IkReal(-1.00000000000000))*(sj3)*(x1818)))+(((IkReal(-1.00000000000000))*(x1820)*(x1827)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1828))));
08025 evalcond[2]=((((sj4)*(x1815)*(x1821)))+(((IkReal(-1.00000000000000))*(x1817)*(x1828)))+(((r10)*(x1832)))+(((IkReal(-1.00000000000000))*(x1816)*(x1819)*(x1826)))+(((r02)*(x1829)))+(((IkReal(-1.00000000000000))*(x1815)*(x1819)*(x1825))));
08026 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(x1816)*(x1819)))+(sj3)+(((x1815)*(x1822)))+(((IkReal(-1.00000000000000))*(cj5)*(x1820)*(x1831)))+(((IkReal(-1.00000000000000))*(x1821)*(x1829)))+(((x1826)*(x1831)))+(((x1825)*(x1829))));
08027 evalcond[4]=((((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1828)))+(((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(x1815)*(x1819)*(x1826)))+(((r10)*(sj4)*(x1830)))+(((IkReal(-1.00000000000000))*(x1816)*(x1819)*(x1821)))+(((sj4)*(x1816)*(x1825)))+(((IkReal(-1.00000000000000))*(x1815)*(x1817)))+(((cj2)*(sj1))));
08028 evalcond[5]=((((cj3)*(x1818)))+(((IkReal(-1.00000000000000))*(cj4)*(x1825)*(x1828)))+(((x1826)*(x1829)))+(((IkReal(-1.00000000000000))*(r12)*(x1815)*(x1819)))+(((x1821)*(x1831)))+(((IkReal(-1.00000000000000))*(cj3)*(x1823)))+(((IkReal(-1.00000000000000))*(r02)*(x1816)*(x1819)))+(((IkReal(-1.00000000000000))*(cj5)*(x1820)*(x1829))));
08029 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  )
08030 {
08031 continue;
08032 }
08033 }
08034 
08035 {
08036 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08037 vinfos[0].jointtype = 1;
08038 vinfos[0].foffset = j0;
08039 vinfos[0].indices[0] = _ij0[0];
08040 vinfos[0].indices[1] = _ij0[1];
08041 vinfos[0].maxsolutions = _nj0;
08042 vinfos[1].jointtype = 1;
08043 vinfos[1].foffset = j1;
08044 vinfos[1].indices[0] = _ij1[0];
08045 vinfos[1].indices[1] = _ij1[1];
08046 vinfos[1].maxsolutions = _nj1;
08047 vinfos[2].jointtype = 1;
08048 vinfos[2].foffset = j2;
08049 vinfos[2].indices[0] = _ij2[0];
08050 vinfos[2].indices[1] = _ij2[1];
08051 vinfos[2].maxsolutions = _nj2;
08052 vinfos[3].jointtype = 1;
08053 vinfos[3].foffset = j3;
08054 vinfos[3].indices[0] = _ij3[0];
08055 vinfos[3].indices[1] = _ij3[1];
08056 vinfos[3].maxsolutions = _nj3;
08057 vinfos[4].jointtype = 1;
08058 vinfos[4].foffset = j4;
08059 vinfos[4].indices[0] = _ij4[0];
08060 vinfos[4].indices[1] = _ij4[1];
08061 vinfos[4].maxsolutions = _nj4;
08062 vinfos[5].jointtype = 1;
08063 vinfos[5].foffset = j5;
08064 vinfos[5].indices[0] = _ij5[0];
08065 vinfos[5].indices[1] = _ij5[1];
08066 vinfos[5].maxsolutions = _nj5;
08067 std::vector<int> vfree(0);
08068 solutions.AddSolution(vinfos,vfree);
08069 }
08070 }
08071 }
08072 
08073 }
08074 
08075 }
08076 
08077 } else
08078 {
08079 {
08080 IkReal j0array[1], cj0array[1], sj0array[1];
08081 bool j0valid[1]={false};
08082 _nj0 = 1;
08083 IkReal x1833=((cj3)*(sj4));
08084 IkReal x1834=((IkReal(1.00000000000000))*(sj5));
08085 IkReal x1835=((IkReal(1.00000000000000))*(cj3)*(cj4));
08086 if( IKabs(((gconst98)*(((((IkReal(-1.00000000000000))*(r12)*(x1835)))+(((IkReal(-1.00000000000000))*(r11)*(x1833)*(x1834)))+(((cj5)*(r10)*(x1833))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst98)*(((((IkReal(-1.00000000000000))*(r02)*(x1835)))+(((IkReal(-1.00000000000000))*(r01)*(x1833)*(x1834)))+(((cj5)*(r00)*(x1833))))))) < IKFAST_ATAN2_MAGTHRESH )
08087     continue;
08088 j0array[0]=IKatan2(((gconst98)*(((((IkReal(-1.00000000000000))*(r12)*(x1835)))+(((IkReal(-1.00000000000000))*(r11)*(x1833)*(x1834)))+(((cj5)*(r10)*(x1833)))))), ((gconst98)*(((((IkReal(-1.00000000000000))*(r02)*(x1835)))+(((IkReal(-1.00000000000000))*(r01)*(x1833)*(x1834)))+(((cj5)*(r00)*(x1833)))))));
08089 sj0array[0]=IKsin(j0array[0]);
08090 cj0array[0]=IKcos(j0array[0]);
08091 if( j0array[0] > IKPI )
08092 {
08093     j0array[0]-=IK2PI;
08094 }
08095 else if( j0array[0] < -IKPI )
08096 {    j0array[0]+=IK2PI;
08097 }
08098 j0valid[0] = true;
08099 for(int ij0 = 0; ij0 < 1; ++ij0)
08100 {
08101 if( !j0valid[ij0] )
08102 {
08103     continue;
08104 }
08105 _ij0[0] = ij0; _ij0[1] = -1;
08106 for(int iij0 = ij0+1; iij0 < 1; ++iij0)
08107 {
08108 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
08109 {
08110     j0valid[iij0]=false; _ij0[1] = iij0; break; 
08111 }
08112 }
08113 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
08114 {
08115 IkReal evalcond[6];
08116 IkReal x1836=IKsin(j0);
08117 IkReal x1837=IKcos(j0);
08118 IkReal x1838=((cj4)*(r12));
08119 IkReal x1839=((cj1)*(cj2));
08120 IkReal x1840=((IkReal(1.00000000000000))*(sj4));
08121 IkReal x1841=((IkReal(1.00000000000000))*(r10));
08122 IkReal x1842=((r01)*(sj5));
08123 IkReal x1843=((r02)*(sj4));
08124 IkReal x1844=((sj1)*(sj2));
08125 IkReal x1845=((cj5)*(r01));
08126 IkReal x1846=((cj5)*(r00));
08127 IkReal x1847=((r11)*(sj5));
08128 IkReal x1848=((sj5)*(x1836));
08129 IkReal x1849=((IkReal(1.00000000000000))*(x1837));
08130 IkReal x1850=((cj4)*(x1836));
08131 IkReal x1851=((cj5)*(x1836));
08132 IkReal x1852=((cj4)*(x1837));
08133 IkReal x1853=((cj5)*(sj4)*(x1837));
08134 evalcond[0]=((((r00)*(x1848)))+(((IkReal(-1.00000000000000))*(cj5)*(r11)*(x1849)))+(((IkReal(-1.00000000000000))*(sj5)*(x1837)*(x1841)))+(cj3)+(((x1836)*(x1845))));
08135 evalcond[1]=((((IkReal(-1.00000000000000))*(x1845)*(x1849)))+(((IkReal(-1.00000000000000))*(r00)*(sj5)*(x1849)))+(((sj3)*(x1844)))+(((IkReal(-1.00000000000000))*(sj3)*(x1839)))+(((IkReal(-1.00000000000000))*(r11)*(x1851)))+(((IkReal(-1.00000000000000))*(x1841)*(x1848))));
08136 evalcond[2]=((((IkReal(-1.00000000000000))*(x1837)*(x1840)*(x1847)))+(((IkReal(-1.00000000000000))*(x1838)*(x1849)))+(((r02)*(x1850)))+(((sj4)*(x1836)*(x1842)))+(((IkReal(-1.00000000000000))*(x1836)*(x1840)*(x1846)))+(((r10)*(x1853))));
08137 evalcond[3]=((((x1846)*(x1850)))+(((IkReal(-1.00000000000000))*(x1842)*(x1850)))+(((IkReal(-1.00000000000000))*(r12)*(x1837)*(x1840)))+(sj3)+(((x1847)*(x1852)))+(((x1836)*(x1843)))+(((IkReal(-1.00000000000000))*(cj5)*(x1841)*(x1852))));
08138 evalcond[4]=((((r10)*(sj4)*(x1851)))+(((cj1)*(sj2)))+(((IkReal(-1.00000000000000))*(cj4)*(r02)*(x1849)))+(((sj4)*(x1837)*(x1846)))+(((IkReal(-1.00000000000000))*(x1837)*(x1840)*(x1842)))+(((cj2)*(sj1)))+(((IkReal(-1.00000000000000))*(x1836)*(x1838)))+(((IkReal(-1.00000000000000))*(x1836)*(x1840)*(x1847))));
08139 evalcond[5]=((((IkReal(-1.00000000000000))*(cj4)*(x1846)*(x1849)))+(((IkReal(-1.00000000000000))*(r02)*(x1837)*(x1840)))+(((IkReal(-1.00000000000000))*(r12)*(x1836)*(x1840)))+(((IkReal(-1.00000000000000))*(cj3)*(x1844)))+(((cj3)*(x1839)))+(((x1847)*(x1850)))+(((IkReal(-1.00000000000000))*(cj5)*(x1841)*(x1850)))+(((x1842)*(x1852))));
08140 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  )
08141 {
08142 continue;
08143 }
08144 }
08145 
08146 {
08147 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08148 vinfos[0].jointtype = 1;
08149 vinfos[0].foffset = j0;
08150 vinfos[0].indices[0] = _ij0[0];
08151 vinfos[0].indices[1] = _ij0[1];
08152 vinfos[0].maxsolutions = _nj0;
08153 vinfos[1].jointtype = 1;
08154 vinfos[1].foffset = j1;
08155 vinfos[1].indices[0] = _ij1[0];
08156 vinfos[1].indices[1] = _ij1[1];
08157 vinfos[1].maxsolutions = _nj1;
08158 vinfos[2].jointtype = 1;
08159 vinfos[2].foffset = j2;
08160 vinfos[2].indices[0] = _ij2[0];
08161 vinfos[2].indices[1] = _ij2[1];
08162 vinfos[2].maxsolutions = _nj2;
08163 vinfos[3].jointtype = 1;
08164 vinfos[3].foffset = j3;
08165 vinfos[3].indices[0] = _ij3[0];
08166 vinfos[3].indices[1] = _ij3[1];
08167 vinfos[3].maxsolutions = _nj3;
08168 vinfos[4].jointtype = 1;
08169 vinfos[4].foffset = j4;
08170 vinfos[4].indices[0] = _ij4[0];
08171 vinfos[4].indices[1] = _ij4[1];
08172 vinfos[4].maxsolutions = _nj4;
08173 vinfos[5].jointtype = 1;
08174 vinfos[5].foffset = j5;
08175 vinfos[5].indices[0] = _ij5[0];
08176 vinfos[5].indices[1] = _ij5[1];
08177 vinfos[5].maxsolutions = _nj5;
08178 std::vector<int> vfree(0);
08179 solutions.AddSolution(vinfos,vfree);
08180 }
08181 }
08182 }
08183 
08184 }
08185 
08186 }
08187 }
08188 }
08189 
08190 }
08191 
08192 }
08193 }
08194 }
08195 
08196 }
08197 
08198 }
08199 }
08200 }
08201 }
08202 }
08203 
08204 }
08205 
08206 }
08207     }
08208 }
08209 return solutions.GetNumSolutions()>0;
08210 }
08211 static inline void polyroots8(IkReal rawcoeffs[8+1], IkReal rawroots[8], int& numroots)
08212 {
08213     using std::complex;
08214     IKFAST_ASSERT(rawcoeffs[0] != 0);
08215     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
08216     const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
08217     complex<IkReal> coeffs[8];
08218     const int maxsteps = 110;
08219     for(int i = 0; i < 8; ++i) {
08220         coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
08221     }
08222     complex<IkReal> roots[8];
08223     IkReal err[8];
08224     roots[0] = complex<IkReal>(1,0);
08225     roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
08226     err[0] = 1.0;
08227     err[1] = 1.0;
08228     for(int i = 2; i < 8; ++i) {
08229         roots[i] = roots[i-1]*roots[1];
08230         err[i] = 1.0;
08231     }
08232     for(int step = 0; step < maxsteps; ++step) {
08233         bool changed = false;
08234         for(int i = 0; i < 8; ++i) {
08235             if ( err[i] >= tol ) {
08236                 changed = true;
08237                 // evaluate
08238                 complex<IkReal> x = roots[i] + coeffs[0];
08239                 for(int j = 1; j < 8; ++j) {
08240                     x = roots[i] * x + coeffs[j];
08241                 }
08242                 for(int j = 0; j < 8; ++j) {
08243                     if( i != j ) {
08244                         if( roots[i] != roots[j] ) {
08245                             x /= (roots[i] - roots[j]);
08246                         }
08247                     }
08248                 }
08249                 roots[i] -= x;
08250                 err[i] = abs(x);
08251             }
08252         }
08253         if( !changed ) {
08254             break;
08255         }
08256     }
08257 
08258     numroots = 0;
08259     bool visited[8] = {false};
08260     for(int i = 0; i < 8; ++i) {
08261         if( !visited[i] ) {
08262             // might be a multiple root, in which case it will have more error than the other roots
08263             // find any neighboring roots, and take the average
08264             complex<IkReal> newroot=roots[i];
08265             int n = 1;
08266             for(int j = i+1; j < 8; ++j) {
08267                 if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
08268                     newroot += roots[j];
08269                     n += 1;
08270                     visited[j] = true;
08271                 }
08272             }
08273             if( n > 1 ) {
08274                 newroot /= n;
08275             }
08276             // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
08277             if( IKabs(imag(newroot)) < tolsqrt ) {
08278                 rawroots[numroots++] = real(newroot);
08279             }
08280         }
08281     }
08282 }
08283 };
08284 
08285 
08288 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
08289 IKSolver solver;
08290 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
08291 }
08292 
08293 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - fanuc_m430ia2p (f1cfe1db779d431226bee8068f3d5170)>"; }
08294 
08295 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
08296 
08297 #ifdef IKFAST_NAMESPACE
08298 } // end namespace
08299 #endif
08300 
08301 #ifndef IKFAST_NO_MAIN
08302 #include <stdio.h>
08303 #include <stdlib.h>
08304 #ifdef IKFAST_NAMESPACE
08305 using namespace IKFAST_NAMESPACE;
08306 #endif
08307 int main(int argc, char** argv)
08308 {
08309     if( argc != 12+GetNumFreeParameters()+1 ) {
08310         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
08311                "Returns the ik solutions given the transformation of the end effector specified by\n"
08312                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
08313                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
08314         return 1;
08315     }
08316 
08317     IkSolutionList<IkReal> solutions;
08318     std::vector<IkReal> vfree(GetNumFreeParameters());
08319     IkReal eerot[9],eetrans[3];
08320     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
08321     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
08322     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
08323     for(std::size_t i = 0; i < vfree.size(); ++i)
08324         vfree[i] = atof(argv[13+i]);
08325     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
08326 
08327     if( !bSuccess ) {
08328         fprintf(stderr,"Failed to get ik solution\n");
08329         return -1;
08330     }
08331 
08332     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
08333     std::vector<IkReal> solvalues(GetNumJoints());
08334     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
08335         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
08336         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
08337         std::vector<IkReal> vsolfree(sol.GetFree().size());
08338         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
08339         for( std::size_t j = 0; j < solvalues.size(); ++j)
08340             printf("%.15f, ", solvalues[j]);
08341         printf("\n");
08342     }
08343     return 0;
08344 }
08345 
08346 #endif


fanuc_m430ia_moveit_plugins
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Wed Aug 2 2017 03:13:50