nextage_right_arm_ikfast_solver.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 #define IKFAST_HAS_LIBRARY
00021 #include "nextage_ik_plugin/ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
00022 using namespace ikfast;
00023 
00024 // check if the included ikfast version matches what this file was compiled with
00025 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
00026 IKFAST_COMPILE_ASSERT(IKFAST_VERSION==61);
00027 
00028 #include <cmath>
00029 #include <vector>
00030 #include <limits>
00031 #include <algorithm>
00032 #include <complex>
00033 
00034 #define IKFAST_STRINGIZE2(s) #s
00035 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
00036 
00037 #ifndef IKFAST_ASSERT
00038 #include <stdexcept>
00039 #include <sstream>
00040 #include <iostream>
00041 
00042 #ifdef _MSC_VER
00043 #ifndef __PRETTY_FUNCTION__
00044 #define __PRETTY_FUNCTION__ __FUNCDNAME__
00045 #endif
00046 #endif
00047 
00048 #ifndef __PRETTY_FUNCTION__
00049 #define __PRETTY_FUNCTION__ __func__
00050 #endif
00051 
00052 #define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } }
00053 
00054 #endif
00055 
00056 #if defined(_MSC_VER)
00057 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
00058 #else
00059 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
00060 #endif
00061 
00062 #define IK2PI  ((IkReal)6.28318530717959)
00063 #define IKPI  ((IkReal)3.14159265358979)
00064 #define IKPI_2  ((IkReal)1.57079632679490)
00065 
00066 #ifdef _MSC_VER
00067 #ifndef isnan
00068 #define isnan _isnan
00069 #endif
00070 #endif // _MSC_VER
00071 
00072 // lapack routines
00073 extern "C" {
00074   void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
00075   void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
00076   void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
00077   void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
00078   void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info);
00079   void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info);
00080 }
00081 
00082 using namespace std; // necessary to get std math routines
00083 
00084 #ifdef IKFAST_NAMESPACE
00085 namespace IKFAST_NAMESPACE {
00086 #endif
00087 
00088 inline float IKabs(float f) { return fabsf(f); }
00089 inline double IKabs(double f) { return fabs(f); }
00090 
00091 inline float IKsqr(float f) { return f*f; }
00092 inline double IKsqr(double f) { return f*f; }
00093 
00094 inline float IKlog(float f) { return logf(f); }
00095 inline double IKlog(double f) { return log(f); }
00096 
00097 // allows asin and acos to exceed 1
00098 #ifndef IKFAST_SINCOS_THRESH
00099 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
00100 #endif
00101 
00102 // used to check input to atan2 for degenerate cases
00103 #ifndef IKFAST_ATAN2_MAGTHRESH
00104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
00105 #endif
00106 
00107 // minimum distance of separate solutions
00108 #ifndef IKFAST_SOLUTION_THRESH
00109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
00110 #endif
00111 
00112 inline float IKasin(float f)
00113 {
00114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00115 if( f <= -1 ) return float(-IKPI_2);
00116 else if( f >= 1 ) return float(IKPI_2);
00117 return asinf(f);
00118 }
00119 inline double IKasin(double f)
00120 {
00121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00122 if( f <= -1 ) return -IKPI_2;
00123 else if( f >= 1 ) return IKPI_2;
00124 return asin(f);
00125 }
00126 
00127 // return positive value in [0,y)
00128 inline float IKfmod(float x, float y)
00129 {
00130     while(x < 0) {
00131         x += y;
00132     }
00133     return fmodf(x,y);
00134 }
00135 
00136 // return positive value in [0,y)
00137 inline double IKfmod(double x, double y)
00138 {
00139     while(x < 0) {
00140         x += y;
00141     }
00142     return fmod(x,y);
00143 }
00144 
00145 inline float IKacos(float f)
00146 {
00147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00148 if( f <= -1 ) return float(IKPI);
00149 else if( f >= 1 ) return float(0);
00150 return acosf(f);
00151 }
00152 inline double IKacos(double f)
00153 {
00154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00155 if( f <= -1 ) return IKPI;
00156 else if( f >= 1 ) return 0;
00157 return acos(f);
00158 }
00159 inline float IKsin(float f) { return sinf(f); }
00160 inline double IKsin(double f) { return sin(f); }
00161 inline float IKcos(float f) { return cosf(f); }
00162 inline double IKcos(double f) { return cos(f); }
00163 inline float IKtan(float f) { return tanf(f); }
00164 inline double IKtan(double f) { return tan(f); }
00165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
00166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
00167 inline float IKatan2(float fy, float fx) {
00168     if( isnan(fy) ) {
00169         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00170         return float(IKPI_2);
00171     }
00172     else if( isnan(fx) ) {
00173         return 0;
00174     }
00175     return atan2f(fy,fx);
00176 }
00177 inline double IKatan2(double fy, double fx) {
00178     if( isnan(fy) ) {
00179         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00180         return IKPI_2;
00181     }
00182     else if( isnan(fx) ) {
00183         return 0;
00184     }
00185     return atan2(fy,fx);
00186 }
00187 
00188 inline float IKsign(float f) {
00189     if( f > 0 ) {
00190         return float(1);
00191     }
00192     else if( f < 0 ) {
00193         return float(-1);
00194     }
00195     return 0;
00196 }
00197 
00198 inline double IKsign(double f) {
00199     if( f > 0 ) {
00200         return 1.0;
00201     }
00202     else if( f < 0 ) {
00203         return -1.0;
00204     }
00205     return 0;
00206 }
00207 
00210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
00211 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42,x43,x44,x45,x46,x47,x48,x49,x50,x51,x52,x53,x54,x55,x56,x57,x58,x59,x60,x61,x62,x63,x64,x65,x66,x67,x68,x69,x70,x71,x72,x73,x74,x75,x76;
00212 x0=IKcos(j[0]);
00213 x1=IKcos(j[1]);
00214 x2=IKsin(j[2]);
00215 x3=IKcos(j[2]);
00216 x4=IKsin(j[1]);
00217 x5=IKsin(j[3]);
00218 x6=IKcos(j[3]);
00219 x7=IKsin(j[0]);
00220 x8=IKcos(j[4]);
00221 x9=IKsin(j[4]);
00222 x10=IKcos(j[5]);
00223 x11=IKsin(j[5]);
00224 x12=((IkReal(0.258820826967441))*(x9));
00225 x13=((IkReal(0.0900000000000000))*(x4));
00226 x14=((IkReal(0.258820826967441))*(x11));
00227 x15=((IkReal(1.00000000000000))*(x8));
00228 x16=((IkReal(1.00000000000000))*(x5));
00229 x17=((IkReal(0.965925348838040))*(x11));
00230 x18=((IkReal(0.0470000000000000))*(x3));
00231 x19=((IkReal(0.965925348838040))*(x9));
00232 x20=((IkReal(1.00000000000000))*(x9));
00233 x21=((IkReal(0.00776462480902323))*(x2));
00234 x22=((IkReal(0.965925348838040))*(x8));
00235 x23=((IkReal(1.00000000000000))*(x2));
00236 x24=((IkReal(0.258820826967441))*(x8));
00237 x25=((IkReal(1.00000000000000))*(x7));
00238 x26=((IkReal(1.00000000000000))*(x3));
00239 x27=((IkReal(0.0900000000000000))*(x6));
00240 x28=((IkReal(0.965925348838040))*(x10));
00241 x29=((IkReal(0.258820826967441))*(x10));
00242 x30=((IkReal(1.00000000000000))*(x6));
00243 x31=((x0)*(x5));
00244 x32=((x1)*(x3));
00245 x33=((x6)*(x9));
00246 x34=((x4)*(x7));
00247 x35=((x0)*(x4));
00248 x36=((IkReal(-0.0470000000000000))*(x6));
00249 x37=((x3)*(x4));
00250 x38=((x2)*(x4));
00251 x39=((x1)*(x7));
00252 x40=((x1)*(x2));
00253 x41=((x5)*(x7));
00254 x42=((x16)*(x7));
00255 x43=((x25)*(x6));
00256 x44=((IkReal(0.0470000000000000))*(x40));
00257 x45=((x23)*(x35));
00258 x46=((x23)*(x34));
00259 x47=((((IkReal(-1.00000000000000))*(x1)*(x26)))+(x38));
00260 x48=((((x1)*(x18)))+(((IkReal(-0.0470000000000000))*(x38))));
00261 x49=((((IkReal(-0.0900000000000000))*(x32)))+(((x13)*(x2))));
00262 x50=((((x1)*(x23)))+(((x26)*(x4))));
00263 x51=((IkReal(-1.00000000000000))*(x50));
00264 x52=((((x18)*(x4)))+(x44));
00265 x53=((((IkReal(0.0900000000000000))*(x40)))+(((x13)*(x3))));
00266 x54=((((IkReal(-1.00000000000000))*(x45)))+(((x0)*(x32))));
00267 x55=((((IkReal(-1.00000000000000))*(x46)))+(((x32)*(x7))));
00268 x56=((x52)*(x6));
00269 x57=((x5)*(x51));
00270 x58=((x51)*(x6));
00271 x59=((((IkReal(-1.00000000000000))*(x0)*(x1)*(x26)))+(x45));
00272 x60=((((IkReal(-1.00000000000000))*(x25)*(x32)))+(x46));
00273 x61=((((IkReal(-1.00000000000000))*(x0)*(x1)*(x23)))+(((IkReal(-1.00000000000000))*(x26)*(x35))));
00274 x62=((((IkReal(-1.00000000000000))*(x25)*(x37)))+(((IkReal(-1.00000000000000))*(x23)*(x39))));
00275 x63=((((IkReal(0.0470000000000000))*(x2)*(x39)))+(((x18)*(x34))));
00276 x64=((((IkReal(-0.0900000000000000))*(x2)*(x39)))+(((IkReal(-1.00000000000000))*(x13)*(x3)*(x7))));
00277 x65=((x55)*(x6));
00278 x66=((x54)*(x6));
00279 x67=((x10)*(x5)*(x50));
00280 x68=((x5)*(x59));
00281 x69=((x31)+(x65));
00282 x70=((((x0)*(x6)))+(((x5)*(x60))));
00283 x71=((((IkReal(-1.00000000000000))*(x0)*(x30)))+(((IkReal(-1.00000000000000))*(x16)*(x60))));
00284 x72=((((IkReal(-1.00000000000000))*(x15)*(x47)))+(((IkReal(-1.00000000000000))*(x20)*(x50)*(x6))));
00285 x73=((x11)*(x72));
00286 x74=((((x20)*(((((IkReal(-1.00000000000000))*(x42)))+(((x30)*(x54)))))))+(((IkReal(-1.00000000000000))*(x15)*(x61))));
00287 x75=((((x20)*(((((x0)*(x16)))+(((x30)*(x55)))))))+(((IkReal(-1.00000000000000))*(x15)*(x62))));
00288 x76=((x10)*(x75));
00289 eerot[0]=((((x8)*(((((IkReal(-1.00000000000000))*(x42)))+(x66)))))+(((x61)*(x9))));
00290 eerot[1]=((((x11)*(x74)))+(((x10)*(((((IkReal(-1.00000000000000))*(x43)))+(x68))))));
00291 eerot[2]=((((x10)*(x74)))+(((x11)*(((x43)+(((IkReal(-1.00000000000000))*(x16)*(x59))))))));
00292 IkReal x77=((x0)*(x40));
00293 eetrans[0]=((((IkReal(-0.235000000000000))*(x77)))+(((IkReal(-0.235000000000000))*(x3)*(x35)))+(((IkReal(-0.250000000000000))*(x35)))+(((x8)*(((((x36)*(x54)))+(((IkReal(0.0470000000000000))*(x41)))))))+(((IkReal(0.0950000000000000))*(x7)))+(((x9)*(((((IkReal(0.0900000000000000))*(x41)))+(((IkReal(-1.00000000000000))*(x27)*(x54)))))))+(((IkReal(0.0300000000000000))*(x2)*(x35)))+(((x8)*(((((IkReal(-1.00000000000000))*(x0)*(x13)*(x3)))+(((IkReal(-0.0900000000000000))*(x77)))))))+(((IkReal(-0.0300000000000000))*(x0)*(x32)))+(((x9)*(((((x18)*(x35)))+(((x0)*(x44))))))));
00294 eerot[3]=((((IkReal(-1.00000000000000))*(x12)*(x47)))+(((x19)*(x62)))+(((x22)*(x69)))+(((IkReal(-1.00000000000000))*(x24)*(x58))));
00295 eerot[4]=((((x17)*(x75)))+(((x28)*(x70)))+(((IkReal(-1.00000000000000))*(x29)*(x5)*(x50)))+(((IkReal(-1.00000000000000))*(x14)*(x72))));
00296 eerot[5]=((((x17)*(x71)))+(((x28)*(x75)))+(((IkReal(-1.00000000000000))*(x14)*(x57)))+(((IkReal(-1.00000000000000))*(x29)*(x72))));
00297 IkReal x78=((IkReal(1.00000000000000))*(x24));
00298 IkReal x79=((IkReal(1.00000000000000))*(x12));
00299 eetrans[1]=((IkReal(-0.145000000000000))+(((IkReal(-0.0608228943373486))*(x38)))+(((IkReal(-0.226992456976939))*(x3)*(x34)))+(((IkReal(0.0647052067418602))*(x1)))+(((IkReal(-0.226992456976939))*(x2)*(x39)))+(((IkReal(-1.00000000000000))*(x53)*(x6)*(x79)))+(((x22)*(((((x36)*(x55)))+(((IkReal(-0.0470000000000000))*(x31)))))))+(((IkReal(-1.00000000000000))*(x1)*(x21)))+(((IkReal(-0.0289777604651412))*(x32)*(x7)))+(((x19)*(x63)))+(((IkReal(-0.241481337209510))*(x34)))+(((x19)*(((((IkReal(-1.00000000000000))*(x27)*(x55)))+(((IkReal(-0.0900000000000000))*(x31)))))))+(((IkReal(-1.00000000000000))*(x49)*(x78)))+(((IkReal(-1.00000000000000))*(x48)*(x79)))+(((IkReal(0.0608228943373486))*(x32)))+(((IkReal(0.0289777604651412))*(x2)*(x34)))+(((IkReal(-0.0917629081396138))*(x0)))+(((IkReal(-1.00000000000000))*(x56)*(x78)))+(((IkReal(-0.00776462480902323))*(x37)))+(((x22)*(x64))));
00300 eerot[6]=((((x12)*(x62)))+(((x19)*(x47)))+(((x24)*(x69)))+(((x22)*(x58))));
00301 eerot[7]=((((x14)*(x75)))+(((x17)*(x72)))+(((x28)*(x5)*(x50)))+(((x29)*(x70))));
00302 eerot[8]=((((x14)*(x71)))+(((x17)*(x57)))+(((x28)*(x72)))+(((x29)*(x75))));
00303 eetrans[2]=((IkReal(0.370300000000000))+(((x12)*(x63)))+(((IkReal(-0.226992456976939))*(x32)))+(((IkReal(0.0289777604651412))*(x37)))+(((x19)*(x48)))+(((x24)*(((((IkReal(-0.0470000000000000))*(x65)))+(((IkReal(-0.0470000000000000))*(x31)))))))+(((IkReal(-0.00776462480902323))*(x32)*(x7)))+(((IkReal(0.0289777604651412))*(x40)))+(((IkReal(0.226992456976939))*(x38)))+(((x19)*(x53)*(x6)))+(((x22)*(x49)))+(((x21)*(x34)))+(((x24)*(x64)))+(((IkReal(-0.0245879785619069))*(x0)))+(((IkReal(-0.241481337209510))*(x1)))+(((IkReal(-0.0608228943373486))*(x2)*(x39)))+(((x12)*(((((IkReal(-0.0900000000000000))*(x65)))+(((IkReal(-0.0900000000000000))*(x31)))))))+(((IkReal(-0.0608228943373486))*(x3)*(x34)))+(((x22)*(x56)))+(((IkReal(-0.0647052067418602))*(x34))));
00304 }
00305 
00306 IKFAST_API int GetNumFreeParameters() { return 0; }
00307 IKFAST_API int* GetFreeParameters() { return NULL; }
00308 IKFAST_API int GetNumJoints() { return 6; }
00309 
00310 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00311 
00312 IKFAST_API int GetIkType() { return 0x67000001; }
00313 
00314 class IKSolver {
00315 public:
00316 IkReal j9,cj9,sj9,htj9,j10,cj10,sj10,htj10,j11,cj11,sj11,htj11,j12,cj12,sj12,htj12,j13,cj13,sj13,htj13,j14,cj14,sj14,htj14,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_r10,r10,rxp1_0,new_r11,r11,rxp1_1,new_r12,r12,rxp1_2,new_r20,r20,rxp2_0,new_r21,r21,rxp2_1,new_r22,r22,rxp2_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp;
00317 unsigned char _ij9[2], _nj9,_ij10[2], _nj10,_ij11[2], _nj11,_ij12[2], _nj12,_ij13[2], _nj13,_ij14[2], _nj14;
00318 
00319 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00320 j9=numeric_limits<IkReal>::quiet_NaN(); _ij9[0] = -1; _ij9[1] = -1; _nj9 = -1; j10=numeric_limits<IkReal>::quiet_NaN(); _ij10[0] = -1; _ij10[1] = -1; _nj10 = -1; j11=numeric_limits<IkReal>::quiet_NaN(); _ij11[0] = -1; _ij11[1] = -1; _nj11 = -1; j12=numeric_limits<IkReal>::quiet_NaN(); _ij12[0] = -1; _ij12[1] = -1; _nj12 = -1; j13=numeric_limits<IkReal>::quiet_NaN(); _ij13[0] = -1; _ij13[1] = -1; _nj13 = -1; j14=numeric_limits<IkReal>::quiet_NaN(); _ij14[0] = -1; _ij14[1] = -1; _nj14 = -1; 
00321 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00322     solutions.Clear();
00323 r00 = eerot[0*3+0];
00324 r01 = eerot[0*3+1];
00325 r02 = eerot[0*3+2];
00326 r10 = eerot[1*3+0];
00327 r11 = eerot[1*3+1];
00328 r12 = eerot[1*3+2];
00329 r20 = eerot[2*3+0];
00330 r21 = eerot[2*3+1];
00331 r22 = eerot[2*3+2];
00332 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00333 
00334 new_r00=((IkReal(-1.00000000000000))*(r02));
00335 new_r01=r01;
00336 new_r02=r00;
00337 new_px=((px)+(((IkReal(0.0470000000000000))*(r00))));
00338 new_r10=((((IkReal(-0.965925348838040))*(r12)))+(((IkReal(-0.258820826967441))*(r22))));
00339 new_r11=((((IkReal(0.258820826967441))*(r21)))+(((IkReal(0.965925348838040))*(r11))));
00340 new_r12=((((IkReal(0.258820826967441))*(r20)))+(((IkReal(0.965925348838040))*(r10))));
00341 new_py=((IkReal(0.0442178233554725))+(((IkReal(0.965925348838040))*(py)))+(((IkReal(0.0453984913953879))*(r10)))+(((IkReal(0.258820826967441))*(pz)))+(((IkReal(0.0121645788674697))*(r20))));
00342 new_r20=((((IkReal(0.258820826967441))*(r12)))+(((IkReal(-0.965925348838040))*(r22))));
00343 new_r21=((((IkReal(0.965925348838040))*(r21)))+(((IkReal(-0.258820826967441))*(r11))));
00344 new_r22=((((IkReal(0.965925348838040))*(r20)))+(((IkReal(-0.258820826967441))*(r10))));
00345 new_pz=((IkReal(-0.395211176585005))+(((IkReal(0.965925348838040))*(pz)))+(((IkReal(-0.0121645788674697))*(r10)))+(((IkReal(0.0453984913953879))*(r20)))+(((IkReal(-0.258820826967441))*(py))));
00346 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;
00347 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
00348 npx=((((px)*(r00)))+(((py)*(r10)))+(((pz)*(r20))));
00349 npy=((((px)*(r01)))+(((py)*(r11)))+(((pz)*(r21))));
00350 npz=((((px)*(r02)))+(((py)*(r12)))+(((pz)*(r22))));
00351 rxp0_0=((((IkReal(-1.00000000000000))*(py)*(r20)))+(((pz)*(r10))));
00352 rxp0_1=((((px)*(r20)))+(((IkReal(-1.00000000000000))*(pz)*(r00))));
00353 rxp0_2=((((IkReal(-1.00000000000000))*(px)*(r10)))+(((py)*(r00))));
00354 rxp1_0=((((IkReal(-1.00000000000000))*(py)*(r21)))+(((pz)*(r11))));
00355 rxp1_1=((((px)*(r21)))+(((IkReal(-1.00000000000000))*(pz)*(r01))));
00356 rxp1_2=((((IkReal(-1.00000000000000))*(px)*(r11)))+(((py)*(r01))));
00357 rxp2_0=((((IkReal(-1.00000000000000))*(py)*(r22)))+(((pz)*(r12))));
00358 rxp2_1=((((px)*(r22)))+(((IkReal(-1.00000000000000))*(pz)*(r02))));
00359 rxp2_2=((((IkReal(-1.00000000000000))*(px)*(r12)))+(((py)*(r02))));
00360 IkReal op[72], zeror[48];
00361 int numroots;
00362 IkReal x80=((IkReal(0.650000000000000))*(npx));
00363 IkReal x81=((IkReal(0.0600000000000000))*(npz));
00364 IkReal x82=((IkReal(1.00000000000000))*(pp));
00365 IkReal x83=((IkReal(0.0600000000000000))*(npy));
00366 IkReal x84=((IkReal(0.0950000000000000))*(r22));
00367 IkReal x85=((IkReal(0.120000000000000))*(npx));
00368 IkReal x86=((IkReal(0.0950000000000000))*(r21));
00369 IkReal x87=((IkReal(1.00000000000000))*(rxp0_2));
00370 IkReal x88=((IkReal(0.190000000000000))*(r20));
00371 IkReal x89=((IkReal(2.00000000000000))*(rxp1_2));
00372 IkReal x90=((IkReal(0.940000000000000))*(npz));
00373 IkReal x91=((IkReal(2.00000000000000))*(rxp2_2));
00374 IkReal x92=((IkReal(0.180000000000000))*(r21));
00375 IkReal x93=((IkReal(0.360000000000000))*(r20));
00376 IkReal x94=((IkReal(0.380000000000000))*(r21));
00377 IkReal x95=((IkReal(0.290000000000000))*(npx));
00378 IkReal x96=((IkReal(-0.00570000000000000))+(((IkReal(-1.00000000000000))*(x83))));
00379 IkReal x97=((IkReal(0.580000000000000))*(npy));
00380 IkReal x98=((IkReal(0.00570000000000000))+(((IkReal(-1.00000000000000))*(x83))));
00381 IkReal x99=((rxp0_2)+(((IkReal(-1.00000000000000))*(x84))));
00382 IkReal x100=((IkReal(-1.30000000000000))*(npy));
00383 IkReal x101=((IkReal(-0.0950000000000000))*(r21));
00384 IkReal x102=((IkReal(-0.00570000000000000))+(x83));
00385 IkReal x103=((rxp0_2)+(x84));
00386 IkReal x104=((x84)+(((IkReal(-1.00000000000000))*(x87))));
00387 IkReal x105=((IkReal(0.00570000000000000))+(x83));
00388 IkReal x106=((IkReal(-2.00000000000000))*(rxp1_2));
00389 IkReal x107=((IkReal(-0.0350000000000000))+(x80));
00390 IkReal x108=((IkReal(0.0496000000000000))+(x81));
00391 IkReal x109=((x82)+(x81));
00392 IkReal x110=((((IkReal(-1.00000000000000))*(x84)))+(((IkReal(-1.00000000000000))*(x87))));
00393 IkReal x111=((x85)+(x90));
00394 IkReal x112=((x91)+(x92));
00395 op[0]=((((IkReal(-1.00000000000000))*(x109)))+(x107));
00396 op[1]=x102;
00397 op[2]=x100;
00398 op[3]=x85;
00399 op[4]=((IkReal(-0.0350000000000000))+(((IkReal(-1.00000000000000))*(x109)))+(((IkReal(-1.00000000000000))*(x80))));
00400 op[5]=x96;
00401 op[6]=x110;
00402 op[7]=x86;
00403 op[8]=x89;
00404 op[9]=x88;
00405 op[10]=x99;
00406 op[11]=x101;
00407 op[12]=x105;
00408 op[13]=((x107)+(x81)+(((IkReal(-1.00000000000000))*(x82))));
00409 op[14]=x85;
00410 op[15]=x100;
00411 op[16]=x98;
00412 op[17]=((IkReal(-0.0350000000000000))+(x81)+(((IkReal(-1.00000000000000))*(x80)))+(((IkReal(-1.00000000000000))*(x82))));
00413 op[18]=x86;
00414 op[19]=x104;
00415 op[20]=x88;
00416 op[21]=x89;
00417 op[22]=x101;
00418 op[23]=x103;
00419 op[24]=((IkReal(-0.0108000000000000))+(x111));
00420 op[25]=IkReal(0);
00421 op[26]=((IkReal(-0.240000000000000))*(npy));
00422 op[27]=IkReal(0);
00423 op[28]=((IkReal(-0.0108000000000000))+(x90)+(((IkReal(-1.00000000000000))*(x85))));
00424 op[29]=IkReal(0);
00425 op[30]=((x88)+(x92)+(((IkReal(-1.00000000000000))*(x91))));
00426 op[31]=IkReal(0);
00427 op[32]=((x93)+(((IkReal(-1.00000000000000))*(x94))));
00428 op[33]=IkReal(0);
00429 op[34]=((((IkReal(-1.00000000000000))*(x112)))+(((IkReal(-1.00000000000000))*(x88))));
00430 op[35]=IkReal(0);
00431 op[36]=IkReal(0);
00432 op[37]=((IkReal(0.0108000000000000))+(x90)+(((IkReal(-1.00000000000000))*(x85))));
00433 op[38]=IkReal(0);
00434 op[39]=((IkReal(0.240000000000000))*(npy));
00435 op[40]=IkReal(0);
00436 op[41]=((IkReal(0.0108000000000000))+(x111));
00437 op[42]=IkReal(0);
00438 op[43]=((x92)+(((IkReal(-1.00000000000000))*(x91)))+(((IkReal(-1.00000000000000))*(x88))));
00439 op[44]=IkReal(0);
00440 op[45]=((x93)+(x94));
00441 op[46]=IkReal(0);
00442 op[47]=((((IkReal(-1.00000000000000))*(x112)))+(x88));
00443 op[48]=((x108)+(((IkReal(-1.00000000000000))*(x95)))+(((IkReal(-1.00000000000000))*(x82))));
00444 op[49]=x102;
00445 op[50]=x97;
00446 op[51]=x85;
00447 op[52]=((x108)+(x95)+(((IkReal(-1.00000000000000))*(x82))));
00448 op[53]=x96;
00449 op[54]=x103;
00450 op[55]=x86;
00451 op[56]=x106;
00452 op[57]=x88;
00453 op[58]=x104;
00454 op[59]=x101;
00455 op[60]=x105;
00456 op[61]=((IkReal(0.0496000000000000))+(((IkReal(-1.00000000000000))*(x109)))+(((IkReal(-1.00000000000000))*(x95))));
00457 op[62]=x85;
00458 op[63]=x97;
00459 op[64]=x98;
00460 op[65]=((IkReal(0.0496000000000000))+(((IkReal(-1.00000000000000))*(x109)))+(x95));
00461 op[66]=x86;
00462 op[67]=x99;
00463 op[68]=x88;
00464 op[69]=x106;
00465 op[70]=x101;
00466 op[71]=x110;
00467 solvedialyticpoly8qep(op,zeror,numroots);
00468 IkReal j13array[16], cj13array[16], sj13array[16], j14array[16], cj14array[16], sj14array[16], j12array[16], cj12array[16], sj12array[16];
00469 int numsolutions = 0;
00470 for(int ij13 = 0; ij13 < numroots; ij13 += 3)
00471 {
00472 IkReal htj13 = zeror[ij13+0], htj14 = zeror[ij13+1], htj12 = zeror[ij13+2];
00473 j13array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj13)));
00474 j14array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj14)));
00475 j12array[numsolutions]=((IkReal(2.00000000000000))*(atan(htj12)));
00476 IkReal x113=(htj13)*(htj13);
00477 IkReal x114=(htj14)*(htj14);
00478 IkReal x115=(htj12)*(htj12);
00479 cj13array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x113))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x113)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x113))))));
00480 cj14array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x114))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x114)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x114))))));
00481 cj12array[numsolutions]=((((IKabs(((IkReal(1.00000000000000))+(x115))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+(x115)))):(IkReal)1.0e30))*(((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x115))))));
00482 sj13array[numsolutions]=((IkReal(2.00000000000000))*(htj13)*(((IKabs(((IkReal(1.00000000000000))+((htj13)*(htj13)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj13)*(htj13))))):(IkReal)1.0e30)));
00483 sj14array[numsolutions]=((IkReal(2.00000000000000))*(htj14)*(((IKabs(((IkReal(1.00000000000000))+((htj14)*(htj14)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj14)*(htj14))))):(IkReal)1.0e30)));
00484 sj12array[numsolutions]=((IkReal(2.00000000000000))*(htj12)*(((IKabs(((IkReal(1.00000000000000))+((htj12)*(htj12)))) != 0)?((IkReal)1/(((IkReal(1.00000000000000))+((htj12)*(htj12))))):(IkReal)1.0e30)));
00485 if( j13array[numsolutions] > IKPI )
00486 {
00487     j13array[numsolutions]-=IK2PI;
00488 }
00489 else if( j13array[numsolutions] < -IKPI )
00490 {
00491     j13array[numsolutions]+=IK2PI;
00492 }
00493 if( j14array[numsolutions] > IKPI )
00494 {
00495     j14array[numsolutions]-=IK2PI;
00496 }
00497 else if( j14array[numsolutions] < -IKPI )
00498 {
00499     j14array[numsolutions]+=IK2PI;
00500 }
00501 if( j12array[numsolutions] > IKPI )
00502 {
00503     j12array[numsolutions]-=IK2PI;
00504 }
00505 else if( j12array[numsolutions] < -IKPI )
00506 {
00507     j12array[numsolutions]+=IK2PI;
00508 }
00509 numsolutions++;
00510 }
00511 bool j13valid[16]={true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true};
00512 _nj13 = 16;
00513 _nj14 = 1;
00514 _nj12 = 1;
00515 for(int ij13 = 0; ij13 < numsolutions; ++ij13)
00516     {
00517 if( !j13valid[ij13] )
00518 {
00519     continue;
00520 }
00521 _ij13[0] = ij13; _ij13[1] = -1;
00522 _ij14[0] = 0; _ij14[1] = -1;
00523 _ij12[0] = 0; _ij12[1] = -1;
00524 for(int iij13 = ij13+1; iij13 < numsolutions; ++iij13)
00525 {
00526 if( !j13valid[iij13] ) { continue; }
00527 if( IKabs(cj13array[ij13]-cj13array[iij13]) < IKFAST_SOLUTION_THRESH && IKabs(sj13array[ij13]-sj13array[iij13]) < IKFAST_SOLUTION_THRESH && IKabs(cj14array[ij13]-cj14array[iij13]) < IKFAST_SOLUTION_THRESH && IKabs(sj14array[ij13]-sj14array[iij13]) < IKFAST_SOLUTION_THRESH && IKabs(cj12array[ij13]-cj12array[iij13]) < IKFAST_SOLUTION_THRESH && IKabs(sj12array[ij13]-sj12array[iij13]) < IKFAST_SOLUTION_THRESH &&  1 )
00528 {
00529     j13valid[iij13]=false; _ij13[1] = iij13; _ij14[1] = 0; _ij12[1] = 0;  break; 
00530 }
00531 }
00532     j13 = j13array[ij13]; cj13 = cj13array[ij13]; sj13 = sj13array[ij13];
00533 
00534     j14 = j14array[ij13]; cj14 = cj14array[ij13]; sj14 = sj14array[ij13];
00535 
00536     j12 = j12array[ij13]; cj12 = cj12array[ij13]; sj12 = sj12array[ij13];
00537 
00538 {
00539 IkReal dummyeval[1];
00540 IkReal gconst0;
00541 IkReal x116=(cj14)*(cj14);
00542 IkReal x117=(sj14)*(sj14);
00543 IkReal x118=((IkReal(1.00000000000000))*(r01));
00544 IkReal x119=((sj13)*(sj14));
00545 IkReal x120=((cj14)*(sj13));
00546 IkReal x121=((r00)*(r11));
00547 IkReal x122=((cj13)*(x116));
00548 IkReal x123=((cj13)*(x117));
00549 gconst0=IKsign(((((IkReal(-1.00000000000000))*(r12)*(x118)*(x120)))+(((x121)*(x122)))+(((x121)*(x123)))+(((r02)*(r10)*(x119)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x119)))+(((IkReal(-1.00000000000000))*(r10)*(x118)*(x123)))+(((IkReal(-1.00000000000000))*(r10)*(x118)*(x122)))+(((r02)*(r11)*(x120)))));
00550 IkReal x124=(cj14)*(cj14);
00551 IkReal x125=(sj14)*(sj14);
00552 IkReal x126=((IkReal(1.00000000000000))*(r01));
00553 IkReal x127=((sj13)*(sj14));
00554 IkReal x128=((cj14)*(sj13));
00555 IkReal x129=((r00)*(r11));
00556 IkReal x130=((cj13)*(x124));
00557 IkReal x131=((cj13)*(x125));
00558 dummyeval[0]=((((IkReal(-1.00000000000000))*(r12)*(x126)*(x128)))+(((x129)*(x130)))+(((x129)*(x131)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x127)))+(((r02)*(r11)*(x128)))+(((r02)*(r10)*(x127)))+(((IkReal(-1.00000000000000))*(r10)*(x126)*(x130)))+(((IkReal(-1.00000000000000))*(r10)*(x126)*(x131))));
00559 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00560 {
00561 {
00562 IkReal dummyeval[1];
00563 IkReal gconst1;
00564 IkReal x132=(sj14)*(sj14);
00565 IkReal x133=(cj14)*(cj14);
00566 IkReal x134=((cj13)*(r12));
00567 IkReal x135=((IkReal(1.00000000000000))*(r10));
00568 IkReal x136=((cj13)*(r02));
00569 IkReal x137=((r01)*(sj13));
00570 IkReal x138=((r00)*(r11)*(sj13));
00571 gconst1=IKsign(((((r00)*(sj14)*(x134)))+(((IkReal(-1.00000000000000))*(x132)*(x135)*(x137)))+(((x133)*(x138)))+(((x132)*(x138)))+(((cj14)*(r01)*(x134)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x136)))+(((IkReal(-1.00000000000000))*(sj14)*(x135)*(x136)))+(((IkReal(-1.00000000000000))*(x133)*(x135)*(x137)))));
00572 IkReal x139=(sj14)*(sj14);
00573 IkReal x140=(cj14)*(cj14);
00574 IkReal x141=((cj13)*(r12));
00575 IkReal x142=((IkReal(1.00000000000000))*(r10));
00576 IkReal x143=((cj13)*(r02));
00577 IkReal x144=((r01)*(sj13));
00578 IkReal x145=((r00)*(r11)*(sj13));
00579 dummyeval[0]=((((x140)*(x145)))+(((cj14)*(r01)*(x141)))+(((IkReal(-1.00000000000000))*(x140)*(x142)*(x144)))+(((IkReal(-1.00000000000000))*(sj14)*(x142)*(x143)))+(((r00)*(sj14)*(x141)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x143)))+(((IkReal(-1.00000000000000))*(x139)*(x142)*(x144)))+(((x139)*(x145))));
00580 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00581 {
00582 {
00583 IkReal dummyeval[1];
00584 dummyeval[0]=sj12;
00585 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00586 {
00587 {
00588 IkReal evalcond[3];
00589 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
00590 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
00591 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
00592 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  )
00593 {
00594 {
00595 IkReal j11array[1], cj11array[1], sj11array[1];
00596 bool j11valid[1]={false};
00597 _nj11 = 1;
00598 IkReal x146=((IkReal(4.00000000000000))*(cj13));
00599 IkReal x147=((npy)*(sj14));
00600 IkReal x148=((cj14)*(npx));
00601 IkReal x149=((IkReal(4.00000000000000))*(sj13));
00602 if( IKabs(((IkReal(0.120000000000000))+(((npz)*(x146)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x148)*(x149)))+(((x147)*(x149))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x149)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x146)*(x147)))+(((x146)*(x148))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((npz)*(x146)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x148)*(x149)))+(((x147)*(x149)))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x149)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x146)*(x147)))+(((x146)*(x148)))))-1) <= IKFAST_SINCOS_THRESH )
00603     continue;
00604 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((npz)*(x146)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x148)*(x149)))+(((x147)*(x149)))), ((IkReal(-0.940000000000000))+(((npz)*(x149)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x146)*(x147)))+(((x146)*(x148)))));
00605 sj11array[0]=IKsin(j11array[0]);
00606 cj11array[0]=IKcos(j11array[0]);
00607 if( j11array[0] > IKPI )
00608 {
00609     j11array[0]-=IK2PI;
00610 }
00611 else if( j11array[0] < -IKPI )
00612 {    j11array[0]+=IK2PI;
00613 }
00614 j11valid[0] = true;
00615 for(int ij11 = 0; ij11 < 1; ++ij11)
00616 {
00617 if( !j11valid[ij11] )
00618 {
00619     continue;
00620 }
00621 _ij11[0] = ij11; _ij11[1] = -1;
00622 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
00623 {
00624 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
00625 {
00626     j11valid[iij11]=false; _ij11[1] = iij11; break; 
00627 }
00628 }
00629 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
00630 {
00631 IkReal evalcond[2];
00632 IkReal x150=((IkReal(1.00000000000000))*(sj13));
00633 IkReal x151=((cj14)*(npx));
00634 IkReal x152=((npy)*(sj14));
00635 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x152)))+(((IkReal(-1.00000000000000))*(cj13)*(x151)))+(((IkReal(-1.00000000000000))*(npz)*(x150))));
00636 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(IKsin(j11))))+(((IkReal(-1.00000000000000))*(x150)*(x151)))+(((sj13)*(x152)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
00637 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00638 {
00639 continue;
00640 }
00641 }
00642 
00643 {
00644 IkReal dummyeval[1];
00645 IkReal gconst66;
00646 IkReal x153=(sj14)*(sj14);
00647 IkReal x154=(cj14)*(cj14);
00648 IkReal x155=((IkReal(2.00000000000000))*(cj14)*(sj14));
00649 gconst66=IKsign(((((x153)*((r00)*(r00))))+(((x154)*((r01)*(r01))))+(((x154)*((r11)*(r11))))+(((r10)*(r11)*(x155)))+(((x153)*((r10)*(r10))))+(((r00)*(r01)*(x155)))));
00650 IkReal x156=(sj14)*(sj14);
00651 IkReal x157=(cj14)*(cj14);
00652 IkReal x158=((IkReal(2.00000000000000))*(cj14)*(sj14));
00653 dummyeval[0]=((((x156)*((r00)*(r00))))+(((x157)*((r01)*(r01))))+(((x156)*((r10)*(r10))))+(((r10)*(r11)*(x158)))+(((x157)*((r11)*(r11))))+(((r00)*(r01)*(x158))));
00654 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00655 {
00656 {
00657 IkReal dummyeval[1];
00658 IkReal gconst68;
00659 gconst68=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
00660 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
00661 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00662 {
00663 {
00664 IkReal dummyeval[1];
00665 IkReal gconst67;
00666 IkReal x159=(cj14)*(cj14);
00667 IkReal x160=(sj14)*(sj14);
00668 IkReal x161=((IkReal(1.00000000000000))*(r01));
00669 IkReal x162=((sj13)*(sj14));
00670 IkReal x163=((cj14)*(sj13));
00671 IkReal x164=((r00)*(r11));
00672 IkReal x165=((cj13)*(x159));
00673 IkReal x166=((cj13)*(x160));
00674 gconst67=IKsign(((((IkReal(-1.00000000000000))*(r12)*(x161)*(x163)))+(((IkReal(-1.00000000000000))*(r10)*(x161)*(x165)))+(((IkReal(-1.00000000000000))*(r10)*(x161)*(x166)))+(((x164)*(x166)))+(((x164)*(x165)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x162)))+(((r02)*(r11)*(x163)))+(((r02)*(r10)*(x162)))));
00675 IkReal x167=(cj14)*(cj14);
00676 IkReal x168=(sj14)*(sj14);
00677 IkReal x169=((IkReal(1.00000000000000))*(r01));
00678 IkReal x170=((sj13)*(sj14));
00679 IkReal x171=((cj14)*(sj13));
00680 IkReal x172=((r00)*(r11));
00681 IkReal x173=((cj13)*(x167));
00682 IkReal x174=((cj13)*(x168));
00683 dummyeval[0]=((((x172)*(x174)))+(((x172)*(x173)))+(((IkReal(-1.00000000000000))*(r10)*(x169)*(x174)))+(((IkReal(-1.00000000000000))*(r10)*(x169)*(x173)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x170)))+(((r02)*(r10)*(x170)))+(((r02)*(r11)*(x171)))+(((IkReal(-1.00000000000000))*(r12)*(x169)*(x171))));
00684 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00685 {
00686 continue;
00687 
00688 } else
00689 {
00690 {
00691 IkReal j9array[1], cj9array[1], sj9array[1];
00692 bool j9valid[1]={false};
00693 _nj9 = 1;
00694 IkReal x175=((cj13)*(cj14));
00695 IkReal x176=((IkReal(1.00000000000000))*(cj13)*(sj14));
00696 if( IKabs(((gconst67)*(((((IkReal(-1.00000000000000))*(r11)*(x176)))+(((r12)*(sj13)))+(((r10)*(x175))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst67)*(((((r02)*(sj13)))+(((r00)*(x175)))+(((IkReal(-1.00000000000000))*(r01)*(x176))))))) < IKFAST_ATAN2_MAGTHRESH )
00697     continue;
00698 j9array[0]=IKatan2(((gconst67)*(((((IkReal(-1.00000000000000))*(r11)*(x176)))+(((r12)*(sj13)))+(((r10)*(x175)))))), ((gconst67)*(((((r02)*(sj13)))+(((r00)*(x175)))+(((IkReal(-1.00000000000000))*(r01)*(x176)))))));
00699 sj9array[0]=IKsin(j9array[0]);
00700 cj9array[0]=IKcos(j9array[0]);
00701 if( j9array[0] > IKPI )
00702 {
00703     j9array[0]-=IK2PI;
00704 }
00705 else if( j9array[0] < -IKPI )
00706 {    j9array[0]+=IK2PI;
00707 }
00708 j9valid[0] = true;
00709 for(int ij9 = 0; ij9 < 1; ++ij9)
00710 {
00711 if( !j9valid[ij9] )
00712 {
00713     continue;
00714 }
00715 _ij9[0] = ij9; _ij9[1] = -1;
00716 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
00717 {
00718 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
00719 {
00720     j9valid[iij9]=false; _ij9[1] = iij9; break; 
00721 }
00722 }
00723 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
00724 {
00725 IkReal evalcond[4];
00726 IkReal x177=IKsin(j9);
00727 IkReal x178=IKcos(j9);
00728 IkReal x179=((r10)*(sj14));
00729 IkReal x180=((cj14)*(r11));
00730 IkReal x181=((cj14)*(r10));
00731 IkReal x182=((cj14)*(r00));
00732 IkReal x183=((r11)*(sj14));
00733 IkReal x184=((r00)*(sj14));
00734 IkReal x185=((IkReal(1.00000000000000))*(x177));
00735 IkReal x186=((cj13)*(x177));
00736 IkReal x187=((sj13)*(x178));
00737 IkReal x188=((r01)*(x177));
00738 IkReal x189=((IkReal(1.00000000000000))*(x178));
00739 evalcond[0]=((IkReal(1.00000000000000))+(((x177)*(x184)))+(((cj14)*(x188)))+(((IkReal(-1.00000000000000))*(x180)*(x189)))+(((IkReal(-1.00000000000000))*(x179)*(x189))));
00740 evalcond[1]=((((IkReal(-1.00000000000000))*(x180)*(x185)))+(((IkReal(-1.00000000000000))*(x184)*(x189)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x189)))+(((IkReal(-1.00000000000000))*(x179)*(x185))));
00741 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x183)*(x189)))+(((IkReal(-1.00000000000000))*(cj13)*(x182)*(x185)))+(((r12)*(x187)))+(((r01)*(sj14)*(x186)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x185)))+(((cj13)*(x178)*(x181))));
00742 evalcond[3]=((((IkReal(-1.00000000000000))*(sj13)*(x182)*(x185)))+(((IkReal(-1.00000000000000))*(x183)*(x187)))+(((r02)*(x186)))+(((sj13)*(sj14)*(x188)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x189)))+(((x181)*(x187))));
00743 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00744 {
00745 continue;
00746 }
00747 }
00748 
00749 {
00750 IkReal dummyeval[1];
00751 IkReal gconst69;
00752 gconst69=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
00753 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
00754 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00755 {
00756 {
00757 IkReal dummyeval[1];
00758 IkReal gconst70;
00759 gconst70=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
00760 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
00761 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00762 {
00763 continue;
00764 
00765 } else
00766 {
00767 {
00768 IkReal j10array[1], cj10array[1], sj10array[1];
00769 bool j10valid[1]={false};
00770 _nj10 = 1;
00771 IkReal x190=((cj13)*(sj14));
00772 IkReal x191=((IkReal(1.00000000000000))*(cj11));
00773 IkReal x192=((r11)*(sj9));
00774 IkReal x193=((IkReal(1.00000000000000))*(sj11));
00775 IkReal x194=((cj13)*(cj14));
00776 IkReal x195=((cj11)*(sj13));
00777 IkReal x196=((r12)*(sj9));
00778 IkReal x197=((cj9)*(r01));
00779 IkReal x198=((sj11)*(sj13));
00780 IkReal x199=((r10)*(sj9));
00781 IkReal x200=((cj9)*(r00));
00782 IkReal x201=((cj9)*(r02));
00783 if( IKabs(((gconst70)*(((((IkReal(-1.00000000000000))*(r20)*(x193)*(x194)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x193)))+(((r21)*(sj11)*(x190)))+(((x195)*(x201)))+(((x195)*(x196)))+(((IkReal(-1.00000000000000))*(x190)*(x191)*(x197)))+(((IkReal(-1.00000000000000))*(x190)*(x191)*(x192)))+(((cj11)*(x194)*(x199)))+(((cj11)*(x194)*(x200))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((IkReal(-1.00000000000000))*(x190)*(x193)*(x197)))+(((x198)*(x201)))+(((sj11)*(x194)*(x200)))+(((cj11)*(r20)*(x194)))+(((x196)*(x198)))+(((IkReal(-1.00000000000000))*(r21)*(x190)*(x191)))+(((IkReal(-1.00000000000000))*(x190)*(x192)*(x193)))+(((sj11)*(x194)*(x199)))+(((r22)*(x195))))))) < IKFAST_ATAN2_MAGTHRESH )
00784     continue;
00785 j10array[0]=IKatan2(((gconst70)*(((((IkReal(-1.00000000000000))*(r20)*(x193)*(x194)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x193)))+(((r21)*(sj11)*(x190)))+(((x195)*(x201)))+(((x195)*(x196)))+(((IkReal(-1.00000000000000))*(x190)*(x191)*(x197)))+(((IkReal(-1.00000000000000))*(x190)*(x191)*(x192)))+(((cj11)*(x194)*(x199)))+(((cj11)*(x194)*(x200)))))), ((gconst70)*(((((IkReal(-1.00000000000000))*(x190)*(x193)*(x197)))+(((x198)*(x201)))+(((sj11)*(x194)*(x200)))+(((cj11)*(r20)*(x194)))+(((x196)*(x198)))+(((IkReal(-1.00000000000000))*(r21)*(x190)*(x191)))+(((IkReal(-1.00000000000000))*(x190)*(x192)*(x193)))+(((sj11)*(x194)*(x199)))+(((r22)*(x195)))))));
00786 sj10array[0]=IKsin(j10array[0]);
00787 cj10array[0]=IKcos(j10array[0]);
00788 if( j10array[0] > IKPI )
00789 {
00790     j10array[0]-=IK2PI;
00791 }
00792 else if( j10array[0] < -IKPI )
00793 {    j10array[0]+=IK2PI;
00794 }
00795 j10valid[0] = true;
00796 for(int ij10 = 0; ij10 < 1; ++ij10)
00797 {
00798 if( !j10valid[ij10] )
00799 {
00800     continue;
00801 }
00802 _ij10[0] = ij10; _ij10[1] = -1;
00803 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
00804 {
00805 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
00806 {
00807     j10valid[iij10]=false; _ij10[1] = iij10; break; 
00808 }
00809 }
00810 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
00811 {
00812 IkReal evalcond[4];
00813 IkReal x202=IKsin(j10);
00814 IkReal x203=IKcos(j10);
00815 IkReal x204=((IkReal(1.00000000000000))*(sj13));
00816 IkReal x205=((r11)*(sj9));
00817 IkReal x206=((cj9)*(r01));
00818 IkReal x207=((r21)*(sj14));
00819 IkReal x208=((cj9)*(r02));
00820 IkReal x209=((sj13)*(sj9));
00821 IkReal x210=((cj14)*(r10));
00822 IkReal x211=((IkReal(1.00000000000000))*(cj13));
00823 IkReal x212=((cj14)*(r20));
00824 IkReal x213=((cj11)*(x202));
00825 IkReal x214=((sj11)*(x203));
00826 IkReal x215=((sj14)*(x211));
00827 IkReal x216=((sj11)*(x202));
00828 IkReal x217=((cj11)*(x203));
00829 IkReal x218=((cj14)*(cj9)*(r00));
00830 IkReal x219=((x213)+(x214));
00831 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x204)))+(((cj13)*(x207)))+(x216)+(((IkReal(-1.00000000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x211)*(x212))));
00832 evalcond[1]=((((IkReal(-1.00000000000000))*(x204)*(x212)))+(((sj13)*(x207)))+(x219)+(((cj13)*(r22))));
00833 evalcond[2]=((((cj13)*(x218)))+(((IkReal(-1.00000000000000))*(x206)*(x215)))+(((sj13)*(x208)))+(((IkReal(-1.00000000000000))*(x205)*(x215)))+(x219)+(((cj13)*(sj9)*(x210)))+(((r12)*(x209))));
00834 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x211)))+(((x209)*(x210)))+(x217)+(((IkReal(-1.00000000000000))*(sj14)*(x204)*(x206)))+(((IkReal(-1.00000000000000))*(sj14)*(x204)*(x205)))+(((IkReal(-1.00000000000000))*(x216)))+(((IkReal(-1.00000000000000))*(x208)*(x211)))+(((sj13)*(x218))));
00835 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00836 {
00837 continue;
00838 }
00839 }
00840 
00841 {
00842 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00843 vinfos[0].jointtype = 1;
00844 vinfos[0].foffset = j9;
00845 vinfos[0].indices[0] = _ij9[0];
00846 vinfos[0].indices[1] = _ij9[1];
00847 vinfos[0].maxsolutions = _nj9;
00848 vinfos[1].jointtype = 1;
00849 vinfos[1].foffset = j10;
00850 vinfos[1].indices[0] = _ij10[0];
00851 vinfos[1].indices[1] = _ij10[1];
00852 vinfos[1].maxsolutions = _nj10;
00853 vinfos[2].jointtype = 1;
00854 vinfos[2].foffset = j11;
00855 vinfos[2].indices[0] = _ij11[0];
00856 vinfos[2].indices[1] = _ij11[1];
00857 vinfos[2].maxsolutions = _nj11;
00858 vinfos[3].jointtype = 1;
00859 vinfos[3].foffset = j12;
00860 vinfos[3].indices[0] = _ij12[0];
00861 vinfos[3].indices[1] = _ij12[1];
00862 vinfos[3].maxsolutions = _nj12;
00863 vinfos[4].jointtype = 1;
00864 vinfos[4].foffset = j13;
00865 vinfos[4].indices[0] = _ij13[0];
00866 vinfos[4].indices[1] = _ij13[1];
00867 vinfos[4].maxsolutions = _nj13;
00868 vinfos[5].jointtype = 1;
00869 vinfos[5].foffset = j14;
00870 vinfos[5].indices[0] = _ij14[0];
00871 vinfos[5].indices[1] = _ij14[1];
00872 vinfos[5].maxsolutions = _nj14;
00873 std::vector<int> vfree(0);
00874 solutions.AddSolution(vinfos,vfree);
00875 }
00876 }
00877 }
00878 
00879 }
00880 
00881 }
00882 
00883 } else
00884 {
00885 {
00886 IkReal j10array[1], cj10array[1], sj10array[1];
00887 bool j10valid[1]={false};
00888 _nj10 = 1;
00889 IkReal x220=((cj13)*(sj11));
00890 IkReal x221=((r21)*(sj14));
00891 IkReal x222=((cj11)*(cj13));
00892 IkReal x223=((r22)*(sj13));
00893 IkReal x224=((sj11)*(sj13));
00894 IkReal x225=((cj11)*(sj13));
00895 IkReal x226=((IkReal(1.00000000000000))*(cj14)*(r20));
00896 if( IKabs(((gconst69)*(((((IkReal(-1.00000000000000))*(x225)*(x226)))+(((x220)*(x221)))+(((IkReal(-1.00000000000000))*(sj11)*(x223)))+(((IkReal(-1.00000000000000))*(x220)*(x226)))+(((x221)*(x225)))+(((r22)*(x222))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst69)*(((((cj11)*(x223)))+(((IkReal(-1.00000000000000))*(x224)*(x226)))+(((cj14)*(r20)*(x222)))+(((x221)*(x224)))+(((r22)*(x220)))+(((IkReal(-1.00000000000000))*(x221)*(x222))))))) < IKFAST_ATAN2_MAGTHRESH )
00897     continue;
00898 j10array[0]=IKatan2(((gconst69)*(((((IkReal(-1.00000000000000))*(x225)*(x226)))+(((x220)*(x221)))+(((IkReal(-1.00000000000000))*(sj11)*(x223)))+(((IkReal(-1.00000000000000))*(x220)*(x226)))+(((x221)*(x225)))+(((r22)*(x222)))))), ((gconst69)*(((((cj11)*(x223)))+(((IkReal(-1.00000000000000))*(x224)*(x226)))+(((cj14)*(r20)*(x222)))+(((x221)*(x224)))+(((r22)*(x220)))+(((IkReal(-1.00000000000000))*(x221)*(x222)))))));
00899 sj10array[0]=IKsin(j10array[0]);
00900 cj10array[0]=IKcos(j10array[0]);
00901 if( j10array[0] > IKPI )
00902 {
00903     j10array[0]-=IK2PI;
00904 }
00905 else if( j10array[0] < -IKPI )
00906 {    j10array[0]+=IK2PI;
00907 }
00908 j10valid[0] = true;
00909 for(int ij10 = 0; ij10 < 1; ++ij10)
00910 {
00911 if( !j10valid[ij10] )
00912 {
00913     continue;
00914 }
00915 _ij10[0] = ij10; _ij10[1] = -1;
00916 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
00917 {
00918 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
00919 {
00920     j10valid[iij10]=false; _ij10[1] = iij10; break; 
00921 }
00922 }
00923 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
00924 {
00925 IkReal evalcond[4];
00926 IkReal x227=IKsin(j10);
00927 IkReal x228=IKcos(j10);
00928 IkReal x229=((IkReal(1.00000000000000))*(sj13));
00929 IkReal x230=((r11)*(sj9));
00930 IkReal x231=((cj9)*(r01));
00931 IkReal x232=((r21)*(sj14));
00932 IkReal x233=((cj9)*(r02));
00933 IkReal x234=((sj13)*(sj9));
00934 IkReal x235=((cj14)*(r10));
00935 IkReal x236=((IkReal(1.00000000000000))*(cj13));
00936 IkReal x237=((cj14)*(r20));
00937 IkReal x238=((cj11)*(x227));
00938 IkReal x239=((sj11)*(x228));
00939 IkReal x240=((sj14)*(x236));
00940 IkReal x241=((sj11)*(x227));
00941 IkReal x242=((cj11)*(x228));
00942 IkReal x243=((cj14)*(cj9)*(r00));
00943 IkReal x244=((x238)+(x239));
00944 evalcond[0]=((((IkReal(-1.00000000000000))*(x242)))+(x241)+(((cj13)*(x232)))+(((IkReal(-1.00000000000000))*(x236)*(x237)))+(((IkReal(-1.00000000000000))*(r22)*(x229))));
00945 evalcond[1]=((((sj13)*(x232)))+(x244)+(((IkReal(-1.00000000000000))*(x229)*(x237)))+(((cj13)*(r22))));
00946 evalcond[2]=((((IkReal(-1.00000000000000))*(x231)*(x240)))+(((sj13)*(x233)))+(((IkReal(-1.00000000000000))*(x230)*(x240)))+(x244)+(((cj13)*(x243)))+(((cj13)*(sj9)*(x235)))+(((r12)*(x234))));
00947 evalcond[3]=((((x234)*(x235)))+(((IkReal(-1.00000000000000))*(x233)*(x236)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x236)))+(((IkReal(-1.00000000000000))*(x241)))+(((IkReal(-1.00000000000000))*(sj14)*(x229)*(x231)))+(((IkReal(-1.00000000000000))*(sj14)*(x229)*(x230)))+(x242)+(((sj13)*(x243))));
00948 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00949 {
00950 continue;
00951 }
00952 }
00953 
00954 {
00955 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
00956 vinfos[0].jointtype = 1;
00957 vinfos[0].foffset = j9;
00958 vinfos[0].indices[0] = _ij9[0];
00959 vinfos[0].indices[1] = _ij9[1];
00960 vinfos[0].maxsolutions = _nj9;
00961 vinfos[1].jointtype = 1;
00962 vinfos[1].foffset = j10;
00963 vinfos[1].indices[0] = _ij10[0];
00964 vinfos[1].indices[1] = _ij10[1];
00965 vinfos[1].maxsolutions = _nj10;
00966 vinfos[2].jointtype = 1;
00967 vinfos[2].foffset = j11;
00968 vinfos[2].indices[0] = _ij11[0];
00969 vinfos[2].indices[1] = _ij11[1];
00970 vinfos[2].maxsolutions = _nj11;
00971 vinfos[3].jointtype = 1;
00972 vinfos[3].foffset = j12;
00973 vinfos[3].indices[0] = _ij12[0];
00974 vinfos[3].indices[1] = _ij12[1];
00975 vinfos[3].maxsolutions = _nj12;
00976 vinfos[4].jointtype = 1;
00977 vinfos[4].foffset = j13;
00978 vinfos[4].indices[0] = _ij13[0];
00979 vinfos[4].indices[1] = _ij13[1];
00980 vinfos[4].maxsolutions = _nj13;
00981 vinfos[5].jointtype = 1;
00982 vinfos[5].foffset = j14;
00983 vinfos[5].indices[0] = _ij14[0];
00984 vinfos[5].indices[1] = _ij14[1];
00985 vinfos[5].maxsolutions = _nj14;
00986 std::vector<int> vfree(0);
00987 solutions.AddSolution(vinfos,vfree);
00988 }
00989 }
00990 }
00991 
00992 }
00993 
00994 }
00995 }
00996 }
00997 
00998 }
00999 
01000 }
01001 
01002 } else
01003 {
01004 {
01005 IkReal j10array[1], cj10array[1], sj10array[1];
01006 bool j10valid[1]={false};
01007 _nj10 = 1;
01008 IkReal x245=((cj13)*(sj11));
01009 IkReal x246=((r21)*(sj14));
01010 IkReal x247=((cj11)*(cj13));
01011 IkReal x248=((cj11)*(sj13));
01012 IkReal x249=((sj11)*(sj13));
01013 IkReal x250=((IkReal(1.00000000000000))*(cj14)*(r20));
01014 if( IKabs(((gconst68)*(((((r22)*(x247)))+(((IkReal(-1.00000000000000))*(x248)*(x250)))+(((IkReal(-1.00000000000000))*(x245)*(x250)))+(((x245)*(x246)))+(((x246)*(x248)))+(((IkReal(-1.00000000000000))*(r22)*(x249))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst68)*(((((r22)*(x248)))+(((r22)*(x245)))+(((IkReal(-1.00000000000000))*(x249)*(x250)))+(((IkReal(-1.00000000000000))*(x246)*(x247)))+(((x246)*(x249)))+(((cj14)*(r20)*(x247))))))) < IKFAST_ATAN2_MAGTHRESH )
01015     continue;
01016 j10array[0]=IKatan2(((gconst68)*(((((r22)*(x247)))+(((IkReal(-1.00000000000000))*(x248)*(x250)))+(((IkReal(-1.00000000000000))*(x245)*(x250)))+(((x245)*(x246)))+(((x246)*(x248)))+(((IkReal(-1.00000000000000))*(r22)*(x249)))))), ((gconst68)*(((((r22)*(x248)))+(((r22)*(x245)))+(((IkReal(-1.00000000000000))*(x249)*(x250)))+(((IkReal(-1.00000000000000))*(x246)*(x247)))+(((x246)*(x249)))+(((cj14)*(r20)*(x247)))))));
01017 sj10array[0]=IKsin(j10array[0]);
01018 cj10array[0]=IKcos(j10array[0]);
01019 if( j10array[0] > IKPI )
01020 {
01021     j10array[0]-=IK2PI;
01022 }
01023 else if( j10array[0] < -IKPI )
01024 {    j10array[0]+=IK2PI;
01025 }
01026 j10valid[0] = true;
01027 for(int ij10 = 0; ij10 < 1; ++ij10)
01028 {
01029 if( !j10valid[ij10] )
01030 {
01031     continue;
01032 }
01033 _ij10[0] = ij10; _ij10[1] = -1;
01034 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
01035 {
01036 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
01037 {
01038     j10valid[iij10]=false; _ij10[1] = iij10; break; 
01039 }
01040 }
01041 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
01042 {
01043 IkReal evalcond[2];
01044 IkReal x251=IKsin(j10);
01045 IkReal x252=IKcos(j10);
01046 IkReal x253=((IkReal(1.00000000000000))*(sj13));
01047 IkReal x254=((cj14)*(r20));
01048 IkReal x255=((r21)*(sj14));
01049 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x253)))+(((cj13)*(x255)))+(((sj11)*(x251)))+(((IkReal(-1.00000000000000))*(cj13)*(x254)))+(((IkReal(-1.00000000000000))*(cj11)*(x252))));
01050 evalcond[1]=((((sj13)*(x255)))+(((cj11)*(x251)))+(((sj11)*(x252)))+(((IkReal(-1.00000000000000))*(x253)*(x254)))+(((cj13)*(r22))));
01051 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
01052 {
01053 continue;
01054 }
01055 }
01056 
01057 {
01058 IkReal dummyeval[1];
01059 IkReal gconst71;
01060 IkReal x256=(sj14)*(sj14);
01061 IkReal x257=(cj14)*(cj14);
01062 IkReal x258=((IkReal(2.00000000000000))*(cj14)*(sj14));
01063 gconst71=IKsign(((((r10)*(r11)*(x258)))+(((x256)*((r10)*(r10))))+(((x257)*((r11)*(r11))))+(((r00)*(r01)*(x258)))+(((x257)*((r01)*(r01))))+(((x256)*((r00)*(r00))))));
01064 IkReal x259=(sj14)*(sj14);
01065 IkReal x260=(cj14)*(cj14);
01066 IkReal x261=((IkReal(2.00000000000000))*(cj14)*(sj14));
01067 dummyeval[0]=((((r00)*(r01)*(x261)))+(((x260)*((r01)*(r01))))+(((x260)*((r11)*(r11))))+(((x259)*((r10)*(r10))))+(((x259)*((r00)*(r00))))+(((r10)*(r11)*(x261))));
01068 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01069 {
01070 {
01071 IkReal dummyeval[1];
01072 IkReal gconst72;
01073 IkReal x262=(cj14)*(cj14);
01074 IkReal x263=(sj14)*(sj14);
01075 IkReal x264=((IkReal(1.00000000000000))*(r01));
01076 IkReal x265=((sj13)*(sj14));
01077 IkReal x266=((cj14)*(sj13));
01078 IkReal x267=((r00)*(r11));
01079 IkReal x268=((cj13)*(x262));
01080 IkReal x269=((cj13)*(x263));
01081 gconst72=IKsign(((((x267)*(x268)))+(((x267)*(x269)))+(((r02)*(r10)*(x265)))+(((r02)*(r11)*(x266)))+(((IkReal(-1.00000000000000))*(r10)*(x264)*(x269)))+(((IkReal(-1.00000000000000))*(r10)*(x264)*(x268)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x265)))+(((IkReal(-1.00000000000000))*(r12)*(x264)*(x266)))));
01082 IkReal x270=(cj14)*(cj14);
01083 IkReal x271=(sj14)*(sj14);
01084 IkReal x272=((IkReal(1.00000000000000))*(r01));
01085 IkReal x273=((sj13)*(sj14));
01086 IkReal x274=((cj14)*(sj13));
01087 IkReal x275=((r00)*(r11));
01088 IkReal x276=((cj13)*(x270));
01089 IkReal x277=((cj13)*(x271));
01090 dummyeval[0]=((((x275)*(x277)))+(((x275)*(x276)))+(((IkReal(-1.00000000000000))*(r12)*(x272)*(x274)))+(((r02)*(r11)*(x274)))+(((r02)*(r10)*(x273)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x273)))+(((IkReal(-1.00000000000000))*(r10)*(x272)*(x277)))+(((IkReal(-1.00000000000000))*(r10)*(x272)*(x276))));
01091 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01092 {
01093 continue;
01094 
01095 } else
01096 {
01097 {
01098 IkReal j9array[1], cj9array[1], sj9array[1];
01099 bool j9valid[1]={false};
01100 _nj9 = 1;
01101 IkReal x278=((cj13)*(cj14));
01102 IkReal x279=((IkReal(1.00000000000000))*(cj13)*(sj14));
01103 if( IKabs(((gconst72)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x279)))+(((r10)*(x278))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst72)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x279)))+(((r00)*(x278))))))) < IKFAST_ATAN2_MAGTHRESH )
01104     continue;
01105 j9array[0]=IKatan2(((gconst72)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x279)))+(((r10)*(x278)))))), ((gconst72)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x279)))+(((r00)*(x278)))))));
01106 sj9array[0]=IKsin(j9array[0]);
01107 cj9array[0]=IKcos(j9array[0]);
01108 if( j9array[0] > IKPI )
01109 {
01110     j9array[0]-=IK2PI;
01111 }
01112 else if( j9array[0] < -IKPI )
01113 {    j9array[0]+=IK2PI;
01114 }
01115 j9valid[0] = true;
01116 for(int ij9 = 0; ij9 < 1; ++ij9)
01117 {
01118 if( !j9valid[ij9] )
01119 {
01120     continue;
01121 }
01122 _ij9[0] = ij9; _ij9[1] = -1;
01123 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
01124 {
01125 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
01126 {
01127     j9valid[iij9]=false; _ij9[1] = iij9; break; 
01128 }
01129 }
01130 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
01131 {
01132 IkReal evalcond[6];
01133 IkReal x280=IKsin(j9);
01134 IkReal x281=IKcos(j9);
01135 IkReal x282=((IkReal(1.00000000000000))*(cj14));
01136 IkReal x283=((IkReal(1.00000000000000))*(sj14));
01137 IkReal x284=((cj13)*(cj14));
01138 IkReal x285=((cj14)*(r10));
01139 IkReal x286=((r01)*(sj14));
01140 IkReal x287=((IkReal(1.00000000000000))*(r12));
01141 IkReal x288=((sj13)*(x281));
01142 IkReal x289=((r02)*(x280));
01143 IkReal x290=((r11)*(x280));
01144 IkReal x291=((r10)*(x281));
01145 IkReal x292=((r01)*(x281));
01146 IkReal x293=((sj13)*(x280));
01147 IkReal x294=((r11)*(x281));
01148 IkReal x295=((cj13)*(x280));
01149 IkReal x296=((r10)*(x280));
01150 IkReal x297=((r00)*(x281));
01151 IkReal x298=((cj13)*(x281));
01152 evalcond[0]=((IkReal(1.00000000000000))+(((r00)*(sj14)*(x280)))+(((IkReal(-1.00000000000000))*(x283)*(x291)))+(((cj14)*(r01)*(x280)))+(((IkReal(-1.00000000000000))*(x282)*(x294))));
01153 evalcond[1]=((((IkReal(-1.00000000000000))*(x283)*(x297)))+(((IkReal(-1.00000000000000))*(x283)*(x296)))+(((IkReal(-1.00000000000000))*(x282)*(x290)))+(((IkReal(-1.00000000000000))*(x282)*(x292))));
01154 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x283)*(x294)))+(((IkReal(-1.00000000000000))*(sj13)*(x289)))+(((x284)*(x291)))+(((r12)*(x288)))+(((x286)*(x295)))+(((IkReal(-1.00000000000000))*(r00)*(x282)*(x295))));
01155 evalcond[3]=((((x285)*(x288)))+(((cj13)*(x289)))+(((IkReal(-1.00000000000000))*(r11)*(x283)*(x288)))+(((x286)*(x293)))+(((IkReal(-1.00000000000000))*(x287)*(x298)))+(((IkReal(-1.00000000000000))*(r00)*(x282)*(x293))));
01156 evalcond[4]=((((r12)*(x293)))+(((IkReal(-1.00000000000000))*(cj13)*(x283)*(x290)))+(((IkReal(-1.00000000000000))*(cj13)*(x283)*(x292)))+(((r02)*(x288)))+(((cj10)*(sj11)))+(((x284)*(x296)))+(((x284)*(x297)))+(((cj11)*(sj10))));
01157 evalcond[5]=((((cj14)*(r00)*(x288)))+(((IkReal(-1.00000000000000))*(r01)*(x283)*(x288)))+(((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(r02)*(x298)))+(((x285)*(x293)))+(((IkReal(-1.00000000000000))*(x287)*(x295)))+(((cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(sj13)*(x283)*(x290))));
01158 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  || IKabs(evalcond[4]) > 0.000001  || IKabs(evalcond[5]) > 0.000001  )
01159 {
01160 continue;
01161 }
01162 }
01163 
01164 {
01165 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01166 vinfos[0].jointtype = 1;
01167 vinfos[0].foffset = j9;
01168 vinfos[0].indices[0] = _ij9[0];
01169 vinfos[0].indices[1] = _ij9[1];
01170 vinfos[0].maxsolutions = _nj9;
01171 vinfos[1].jointtype = 1;
01172 vinfos[1].foffset = j10;
01173 vinfos[1].indices[0] = _ij10[0];
01174 vinfos[1].indices[1] = _ij10[1];
01175 vinfos[1].maxsolutions = _nj10;
01176 vinfos[2].jointtype = 1;
01177 vinfos[2].foffset = j11;
01178 vinfos[2].indices[0] = _ij11[0];
01179 vinfos[2].indices[1] = _ij11[1];
01180 vinfos[2].maxsolutions = _nj11;
01181 vinfos[3].jointtype = 1;
01182 vinfos[3].foffset = j12;
01183 vinfos[3].indices[0] = _ij12[0];
01184 vinfos[3].indices[1] = _ij12[1];
01185 vinfos[3].maxsolutions = _nj12;
01186 vinfos[4].jointtype = 1;
01187 vinfos[4].foffset = j13;
01188 vinfos[4].indices[0] = _ij13[0];
01189 vinfos[4].indices[1] = _ij13[1];
01190 vinfos[4].maxsolutions = _nj13;
01191 vinfos[5].jointtype = 1;
01192 vinfos[5].foffset = j14;
01193 vinfos[5].indices[0] = _ij14[0];
01194 vinfos[5].indices[1] = _ij14[1];
01195 vinfos[5].maxsolutions = _nj14;
01196 std::vector<int> vfree(0);
01197 solutions.AddSolution(vinfos,vfree);
01198 }
01199 }
01200 }
01201 
01202 }
01203 
01204 }
01205 
01206 } else
01207 {
01208 {
01209 IkReal j9array[1], cj9array[1], sj9array[1];
01210 bool j9valid[1]={false};
01211 _nj9 = 1;
01212 if( IKabs(((gconst71)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst71)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
01213     continue;
01214 j9array[0]=IKatan2(((gconst71)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst71)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
01215 sj9array[0]=IKsin(j9array[0]);
01216 cj9array[0]=IKcos(j9array[0]);
01217 if( j9array[0] > IKPI )
01218 {
01219     j9array[0]-=IK2PI;
01220 }
01221 else if( j9array[0] < -IKPI )
01222 {    j9array[0]+=IK2PI;
01223 }
01224 j9valid[0] = true;
01225 for(int ij9 = 0; ij9 < 1; ++ij9)
01226 {
01227 if( !j9valid[ij9] )
01228 {
01229     continue;
01230 }
01231 _ij9[0] = ij9; _ij9[1] = -1;
01232 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
01233 {
01234 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
01235 {
01236     j9valid[iij9]=false; _ij9[1] = iij9; break; 
01237 }
01238 }
01239 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
01240 {
01241 IkReal evalcond[6];
01242 IkReal x299=IKsin(j9);
01243 IkReal x300=IKcos(j9);
01244 IkReal x301=((IkReal(1.00000000000000))*(cj14));
01245 IkReal x302=((IkReal(1.00000000000000))*(sj14));
01246 IkReal x303=((cj13)*(cj14));
01247 IkReal x304=((cj14)*(r10));
01248 IkReal x305=((r01)*(sj14));
01249 IkReal x306=((IkReal(1.00000000000000))*(r12));
01250 IkReal x307=((sj13)*(x300));
01251 IkReal x308=((r02)*(x299));
01252 IkReal x309=((r11)*(x299));
01253 IkReal x310=((r10)*(x300));
01254 IkReal x311=((r01)*(x300));
01255 IkReal x312=((sj13)*(x299));
01256 IkReal x313=((r11)*(x300));
01257 IkReal x314=((cj13)*(x299));
01258 IkReal x315=((r10)*(x299));
01259 IkReal x316=((r00)*(x300));
01260 IkReal x317=((cj13)*(x300));
01261 evalcond[0]=((IkReal(1.00000000000000))+(((cj14)*(r01)*(x299)))+(((IkReal(-1.00000000000000))*(x302)*(x310)))+(((r00)*(sj14)*(x299)))+(((IkReal(-1.00000000000000))*(x301)*(x313))));
01262 evalcond[1]=((((IkReal(-1.00000000000000))*(x301)*(x309)))+(((IkReal(-1.00000000000000))*(x302)*(x316)))+(((IkReal(-1.00000000000000))*(x302)*(x315)))+(((IkReal(-1.00000000000000))*(x301)*(x311))));
01263 evalcond[2]=((((x305)*(x314)))+(((IkReal(-1.00000000000000))*(r00)*(x301)*(x314)))+(((IkReal(-1.00000000000000))*(cj13)*(x302)*(x313)))+(((IkReal(-1.00000000000000))*(sj13)*(x308)))+(((x303)*(x310)))+(((r12)*(x307))));
01264 evalcond[3]=((((x305)*(x312)))+(((IkReal(-1.00000000000000))*(r00)*(x301)*(x312)))+(((IkReal(-1.00000000000000))*(r11)*(x302)*(x307)))+(((IkReal(-1.00000000000000))*(x306)*(x317)))+(((x304)*(x307)))+(((cj13)*(x308))));
01265 evalcond[4]=((((IkReal(-1.00000000000000))*(cj13)*(x302)*(x309)))+(((r02)*(x307)))+(((cj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x302)*(x311)))+(((x303)*(x315)))+(((x303)*(x316)))+(((r12)*(x312)))+(((cj11)*(sj10))));
01266 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x317)))+(((x304)*(x312)))+(((IkReal(-1.00000000000000))*(r01)*(x302)*(x307)))+(((IkReal(-1.00000000000000))*(sj13)*(x302)*(x309)))+(((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(x306)*(x314)))+(((cj10)*(cj11)))+(((cj14)*(r00)*(x307))));
01267 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  )
01268 {
01269 continue;
01270 }
01271 }
01272 
01273 {
01274 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01275 vinfos[0].jointtype = 1;
01276 vinfos[0].foffset = j9;
01277 vinfos[0].indices[0] = _ij9[0];
01278 vinfos[0].indices[1] = _ij9[1];
01279 vinfos[0].maxsolutions = _nj9;
01280 vinfos[1].jointtype = 1;
01281 vinfos[1].foffset = j10;
01282 vinfos[1].indices[0] = _ij10[0];
01283 vinfos[1].indices[1] = _ij10[1];
01284 vinfos[1].maxsolutions = _nj10;
01285 vinfos[2].jointtype = 1;
01286 vinfos[2].foffset = j11;
01287 vinfos[2].indices[0] = _ij11[0];
01288 vinfos[2].indices[1] = _ij11[1];
01289 vinfos[2].maxsolutions = _nj11;
01290 vinfos[3].jointtype = 1;
01291 vinfos[3].foffset = j12;
01292 vinfos[3].indices[0] = _ij12[0];
01293 vinfos[3].indices[1] = _ij12[1];
01294 vinfos[3].maxsolutions = _nj12;
01295 vinfos[4].jointtype = 1;
01296 vinfos[4].foffset = j13;
01297 vinfos[4].indices[0] = _ij13[0];
01298 vinfos[4].indices[1] = _ij13[1];
01299 vinfos[4].maxsolutions = _nj13;
01300 vinfos[5].jointtype = 1;
01301 vinfos[5].foffset = j14;
01302 vinfos[5].indices[0] = _ij14[0];
01303 vinfos[5].indices[1] = _ij14[1];
01304 vinfos[5].maxsolutions = _nj14;
01305 std::vector<int> vfree(0);
01306 solutions.AddSolution(vinfos,vfree);
01307 }
01308 }
01309 }
01310 
01311 }
01312 
01313 }
01314 }
01315 }
01316 
01317 }
01318 
01319 }
01320 
01321 } else
01322 {
01323 {
01324 IkReal j9array[1], cj9array[1], sj9array[1];
01325 bool j9valid[1]={false};
01326 _nj9 = 1;
01327 if( IKabs(((gconst66)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst66)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
01328     continue;
01329 j9array[0]=IKatan2(((gconst66)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst66)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
01330 sj9array[0]=IKsin(j9array[0]);
01331 cj9array[0]=IKcos(j9array[0]);
01332 if( j9array[0] > IKPI )
01333 {
01334     j9array[0]-=IK2PI;
01335 }
01336 else if( j9array[0] < -IKPI )
01337 {    j9array[0]+=IK2PI;
01338 }
01339 j9valid[0] = true;
01340 for(int ij9 = 0; ij9 < 1; ++ij9)
01341 {
01342 if( !j9valid[ij9] )
01343 {
01344     continue;
01345 }
01346 _ij9[0] = ij9; _ij9[1] = -1;
01347 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
01348 {
01349 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
01350 {
01351     j9valid[iij9]=false; _ij9[1] = iij9; break; 
01352 }
01353 }
01354 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
01355 {
01356 IkReal evalcond[4];
01357 IkReal x318=IKsin(j9);
01358 IkReal x319=IKcos(j9);
01359 IkReal x320=((r10)*(sj14));
01360 IkReal x321=((cj14)*(r11));
01361 IkReal x322=((cj14)*(r10));
01362 IkReal x323=((cj14)*(r00));
01363 IkReal x324=((r11)*(sj14));
01364 IkReal x325=((r00)*(sj14));
01365 IkReal x326=((IkReal(1.00000000000000))*(x318));
01366 IkReal x327=((cj13)*(x318));
01367 IkReal x328=((sj13)*(x319));
01368 IkReal x329=((r01)*(x318));
01369 IkReal x330=((IkReal(1.00000000000000))*(x319));
01370 evalcond[0]=((IkReal(1.00000000000000))+(((x318)*(x325)))+(((IkReal(-1.00000000000000))*(x321)*(x330)))+(((IkReal(-1.00000000000000))*(x320)*(x330)))+(((cj14)*(x329))));
01371 evalcond[1]=((((IkReal(-1.00000000000000))*(cj14)*(r01)*(x330)))+(((IkReal(-1.00000000000000))*(x321)*(x326)))+(((IkReal(-1.00000000000000))*(x320)*(x326)))+(((IkReal(-1.00000000000000))*(x325)*(x330))));
01372 evalcond[2]=((((r12)*(x328)))+(((IkReal(-1.00000000000000))*(cj13)*(x324)*(x330)))+(((cj13)*(x319)*(x322)))+(((r01)*(sj14)*(x327)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x326)))+(((IkReal(-1.00000000000000))*(cj13)*(x323)*(x326))));
01373 evalcond[3]=((((r02)*(x327)))+(((x322)*(x328)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x330)))+(((IkReal(-1.00000000000000))*(x324)*(x328)))+(((sj13)*(sj14)*(x329)))+(((IkReal(-1.00000000000000))*(sj13)*(x323)*(x326))));
01374 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01375 {
01376 continue;
01377 }
01378 }
01379 
01380 {
01381 IkReal dummyeval[1];
01382 IkReal gconst69;
01383 gconst69=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
01384 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
01385 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01386 {
01387 {
01388 IkReal dummyeval[1];
01389 IkReal gconst70;
01390 gconst70=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
01391 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
01392 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01393 {
01394 continue;
01395 
01396 } else
01397 {
01398 {
01399 IkReal j10array[1], cj10array[1], sj10array[1];
01400 bool j10valid[1]={false};
01401 _nj10 = 1;
01402 IkReal x331=((cj13)*(sj14));
01403 IkReal x332=((IkReal(1.00000000000000))*(cj11));
01404 IkReal x333=((r11)*(sj9));
01405 IkReal x334=((IkReal(1.00000000000000))*(sj11));
01406 IkReal x335=((cj13)*(cj14));
01407 IkReal x336=((cj11)*(sj13));
01408 IkReal x337=((r12)*(sj9));
01409 IkReal x338=((cj9)*(r01));
01410 IkReal x339=((sj11)*(sj13));
01411 IkReal x340=((r10)*(sj9));
01412 IkReal x341=((cj9)*(r00));
01413 IkReal x342=((cj9)*(r02));
01414 if( IKabs(((gconst70)*(((((x336)*(x342)))+(((x336)*(x337)))+(((IkReal(-1.00000000000000))*(x331)*(x332)*(x333)))+(((IkReal(-1.00000000000000))*(x331)*(x332)*(x338)))+(((r21)*(sj11)*(x331)))+(((IkReal(-1.00000000000000))*(r20)*(x334)*(x335)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x334)))+(((cj11)*(x335)*(x340)))+(((cj11)*(x335)*(x341))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst70)*(((((r22)*(x336)))+(((x337)*(x339)))+(((sj11)*(x335)*(x340)))+(((sj11)*(x335)*(x341)))+(((IkReal(-1.00000000000000))*(x331)*(x333)*(x334)))+(((cj11)*(r20)*(x335)))+(((IkReal(-1.00000000000000))*(r21)*(x331)*(x332)))+(((x339)*(x342)))+(((IkReal(-1.00000000000000))*(x331)*(x334)*(x338))))))) < IKFAST_ATAN2_MAGTHRESH )
01415     continue;
01416 j10array[0]=IKatan2(((gconst70)*(((((x336)*(x342)))+(((x336)*(x337)))+(((IkReal(-1.00000000000000))*(x331)*(x332)*(x333)))+(((IkReal(-1.00000000000000))*(x331)*(x332)*(x338)))+(((r21)*(sj11)*(x331)))+(((IkReal(-1.00000000000000))*(r20)*(x334)*(x335)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x334)))+(((cj11)*(x335)*(x340)))+(((cj11)*(x335)*(x341)))))), ((gconst70)*(((((r22)*(x336)))+(((x337)*(x339)))+(((sj11)*(x335)*(x340)))+(((sj11)*(x335)*(x341)))+(((IkReal(-1.00000000000000))*(x331)*(x333)*(x334)))+(((cj11)*(r20)*(x335)))+(((IkReal(-1.00000000000000))*(r21)*(x331)*(x332)))+(((x339)*(x342)))+(((IkReal(-1.00000000000000))*(x331)*(x334)*(x338)))))));
01417 sj10array[0]=IKsin(j10array[0]);
01418 cj10array[0]=IKcos(j10array[0]);
01419 if( j10array[0] > IKPI )
01420 {
01421     j10array[0]-=IK2PI;
01422 }
01423 else if( j10array[0] < -IKPI )
01424 {    j10array[0]+=IK2PI;
01425 }
01426 j10valid[0] = true;
01427 for(int ij10 = 0; ij10 < 1; ++ij10)
01428 {
01429 if( !j10valid[ij10] )
01430 {
01431     continue;
01432 }
01433 _ij10[0] = ij10; _ij10[1] = -1;
01434 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
01435 {
01436 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
01437 {
01438     j10valid[iij10]=false; _ij10[1] = iij10; break; 
01439 }
01440 }
01441 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
01442 {
01443 IkReal evalcond[4];
01444 IkReal x343=IKsin(j10);
01445 IkReal x344=IKcos(j10);
01446 IkReal x345=((IkReal(1.00000000000000))*(sj13));
01447 IkReal x346=((r11)*(sj9));
01448 IkReal x347=((cj9)*(r01));
01449 IkReal x348=((r21)*(sj14));
01450 IkReal x349=((cj9)*(r02));
01451 IkReal x350=((sj13)*(sj9));
01452 IkReal x351=((cj14)*(r10));
01453 IkReal x352=((IkReal(1.00000000000000))*(cj13));
01454 IkReal x353=((cj14)*(r20));
01455 IkReal x354=((cj11)*(x343));
01456 IkReal x355=((sj11)*(x344));
01457 IkReal x356=((sj14)*(x352));
01458 IkReal x357=((sj11)*(x343));
01459 IkReal x358=((cj11)*(x344));
01460 IkReal x359=((cj14)*(cj9)*(r00));
01461 IkReal x360=((x355)+(x354));
01462 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x345)))+(((cj13)*(x348)))+(((IkReal(-1.00000000000000))*(x358)))+(x357)+(((IkReal(-1.00000000000000))*(x352)*(x353))));
01463 evalcond[1]=((((sj13)*(x348)))+(((IkReal(-1.00000000000000))*(x345)*(x353)))+(x360)+(((cj13)*(r22))));
01464 evalcond[2]=((((cj13)*(sj9)*(x351)))+(((sj13)*(x349)))+(((r12)*(x350)))+(((cj13)*(x359)))+(((IkReal(-1.00000000000000))*(x346)*(x356)))+(x360)+(((IkReal(-1.00000000000000))*(x347)*(x356))));
01465 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x345)*(x347)))+(((IkReal(-1.00000000000000))*(sj14)*(x345)*(x346)))+(((IkReal(-1.00000000000000))*(x349)*(x352)))+(((IkReal(-1.00000000000000))*(x357)))+(x358)+(((sj13)*(x359)))+(((x350)*(x351)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x352))));
01466 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01467 {
01468 continue;
01469 }
01470 }
01471 
01472 {
01473 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01474 vinfos[0].jointtype = 1;
01475 vinfos[0].foffset = j9;
01476 vinfos[0].indices[0] = _ij9[0];
01477 vinfos[0].indices[1] = _ij9[1];
01478 vinfos[0].maxsolutions = _nj9;
01479 vinfos[1].jointtype = 1;
01480 vinfos[1].foffset = j10;
01481 vinfos[1].indices[0] = _ij10[0];
01482 vinfos[1].indices[1] = _ij10[1];
01483 vinfos[1].maxsolutions = _nj10;
01484 vinfos[2].jointtype = 1;
01485 vinfos[2].foffset = j11;
01486 vinfos[2].indices[0] = _ij11[0];
01487 vinfos[2].indices[1] = _ij11[1];
01488 vinfos[2].maxsolutions = _nj11;
01489 vinfos[3].jointtype = 1;
01490 vinfos[3].foffset = j12;
01491 vinfos[3].indices[0] = _ij12[0];
01492 vinfos[3].indices[1] = _ij12[1];
01493 vinfos[3].maxsolutions = _nj12;
01494 vinfos[4].jointtype = 1;
01495 vinfos[4].foffset = j13;
01496 vinfos[4].indices[0] = _ij13[0];
01497 vinfos[4].indices[1] = _ij13[1];
01498 vinfos[4].maxsolutions = _nj13;
01499 vinfos[5].jointtype = 1;
01500 vinfos[5].foffset = j14;
01501 vinfos[5].indices[0] = _ij14[0];
01502 vinfos[5].indices[1] = _ij14[1];
01503 vinfos[5].maxsolutions = _nj14;
01504 std::vector<int> vfree(0);
01505 solutions.AddSolution(vinfos,vfree);
01506 }
01507 }
01508 }
01509 
01510 }
01511 
01512 }
01513 
01514 } else
01515 {
01516 {
01517 IkReal j10array[1], cj10array[1], sj10array[1];
01518 bool j10valid[1]={false};
01519 _nj10 = 1;
01520 IkReal x361=((cj13)*(sj11));
01521 IkReal x362=((r21)*(sj14));
01522 IkReal x363=((cj11)*(cj13));
01523 IkReal x364=((r22)*(sj13));
01524 IkReal x365=((sj11)*(sj13));
01525 IkReal x366=((cj11)*(sj13));
01526 IkReal x367=((IkReal(1.00000000000000))*(cj14)*(r20));
01527 if( IKabs(((gconst69)*(((((x361)*(x362)))+(((IkReal(-1.00000000000000))*(x361)*(x367)))+(((IkReal(-1.00000000000000))*(sj11)*(x364)))+(((IkReal(-1.00000000000000))*(x366)*(x367)))+(((r22)*(x363)))+(((x362)*(x366))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst69)*(((((cj14)*(r20)*(x363)))+(((cj11)*(x364)))+(((IkReal(-1.00000000000000))*(x362)*(x363)))+(((r22)*(x361)))+(((IkReal(-1.00000000000000))*(x365)*(x367)))+(((x362)*(x365))))))) < IKFAST_ATAN2_MAGTHRESH )
01528     continue;
01529 j10array[0]=IKatan2(((gconst69)*(((((x361)*(x362)))+(((IkReal(-1.00000000000000))*(x361)*(x367)))+(((IkReal(-1.00000000000000))*(sj11)*(x364)))+(((IkReal(-1.00000000000000))*(x366)*(x367)))+(((r22)*(x363)))+(((x362)*(x366)))))), ((gconst69)*(((((cj14)*(r20)*(x363)))+(((cj11)*(x364)))+(((IkReal(-1.00000000000000))*(x362)*(x363)))+(((r22)*(x361)))+(((IkReal(-1.00000000000000))*(x365)*(x367)))+(((x362)*(x365)))))));
01530 sj10array[0]=IKsin(j10array[0]);
01531 cj10array[0]=IKcos(j10array[0]);
01532 if( j10array[0] > IKPI )
01533 {
01534     j10array[0]-=IK2PI;
01535 }
01536 else if( j10array[0] < -IKPI )
01537 {    j10array[0]+=IK2PI;
01538 }
01539 j10valid[0] = true;
01540 for(int ij10 = 0; ij10 < 1; ++ij10)
01541 {
01542 if( !j10valid[ij10] )
01543 {
01544     continue;
01545 }
01546 _ij10[0] = ij10; _ij10[1] = -1;
01547 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
01548 {
01549 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
01550 {
01551     j10valid[iij10]=false; _ij10[1] = iij10; break; 
01552 }
01553 }
01554 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
01555 {
01556 IkReal evalcond[4];
01557 IkReal x368=IKsin(j10);
01558 IkReal x369=IKcos(j10);
01559 IkReal x370=((IkReal(1.00000000000000))*(sj13));
01560 IkReal x371=((r11)*(sj9));
01561 IkReal x372=((cj9)*(r01));
01562 IkReal x373=((r21)*(sj14));
01563 IkReal x374=((cj9)*(r02));
01564 IkReal x375=((sj13)*(sj9));
01565 IkReal x376=((cj14)*(r10));
01566 IkReal x377=((IkReal(1.00000000000000))*(cj13));
01567 IkReal x378=((cj14)*(r20));
01568 IkReal x379=((cj11)*(x368));
01569 IkReal x380=((sj11)*(x369));
01570 IkReal x381=((sj14)*(x377));
01571 IkReal x382=((sj11)*(x368));
01572 IkReal x383=((cj11)*(x369));
01573 IkReal x384=((cj14)*(cj9)*(r00));
01574 IkReal x385=((x380)+(x379));
01575 evalcond[0]=((((IkReal(-1.00000000000000))*(x377)*(x378)))+(x382)+(((cj13)*(x373)))+(((IkReal(-1.00000000000000))*(x383)))+(((IkReal(-1.00000000000000))*(r22)*(x370))));
01576 evalcond[1]=((((IkReal(-1.00000000000000))*(x370)*(x378)))+(((sj13)*(x373)))+(x385)+(((cj13)*(r22))));
01577 evalcond[2]=((((cj13)*(x384)))+(((sj13)*(x374)))+(x385)+(((r12)*(x375)))+(((IkReal(-1.00000000000000))*(x371)*(x381)))+(((cj13)*(sj9)*(x376)))+(((IkReal(-1.00000000000000))*(x372)*(x381))));
01578 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x370)*(x371)))+(((IkReal(-1.00000000000000))*(sj14)*(x370)*(x372)))+(((x375)*(x376)))+(x383)+(((IkReal(-1.00000000000000))*(x374)*(x377)))+(((IkReal(-1.00000000000000))*(x382)))+(((sj13)*(x384)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x377))));
01579 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01580 {
01581 continue;
01582 }
01583 }
01584 
01585 {
01586 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01587 vinfos[0].jointtype = 1;
01588 vinfos[0].foffset = j9;
01589 vinfos[0].indices[0] = _ij9[0];
01590 vinfos[0].indices[1] = _ij9[1];
01591 vinfos[0].maxsolutions = _nj9;
01592 vinfos[1].jointtype = 1;
01593 vinfos[1].foffset = j10;
01594 vinfos[1].indices[0] = _ij10[0];
01595 vinfos[1].indices[1] = _ij10[1];
01596 vinfos[1].maxsolutions = _nj10;
01597 vinfos[2].jointtype = 1;
01598 vinfos[2].foffset = j11;
01599 vinfos[2].indices[0] = _ij11[0];
01600 vinfos[2].indices[1] = _ij11[1];
01601 vinfos[2].maxsolutions = _nj11;
01602 vinfos[3].jointtype = 1;
01603 vinfos[3].foffset = j12;
01604 vinfos[3].indices[0] = _ij12[0];
01605 vinfos[3].indices[1] = _ij12[1];
01606 vinfos[3].maxsolutions = _nj12;
01607 vinfos[4].jointtype = 1;
01608 vinfos[4].foffset = j13;
01609 vinfos[4].indices[0] = _ij13[0];
01610 vinfos[4].indices[1] = _ij13[1];
01611 vinfos[4].maxsolutions = _nj13;
01612 vinfos[5].jointtype = 1;
01613 vinfos[5].foffset = j14;
01614 vinfos[5].indices[0] = _ij14[0];
01615 vinfos[5].indices[1] = _ij14[1];
01616 vinfos[5].maxsolutions = _nj14;
01617 std::vector<int> vfree(0);
01618 solutions.AddSolution(vinfos,vfree);
01619 }
01620 }
01621 }
01622 
01623 }
01624 
01625 }
01626 }
01627 }
01628 
01629 }
01630 
01631 }
01632 }
01633 }
01634 
01635 } else
01636 {
01637 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
01638 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
01639 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
01640 if( IKabs(evalcond[0]) < 0.0000010000000000  && IKabs(evalcond[1]) < 0.0000010000000000  && IKabs(evalcond[2]) < 0.0000010000000000  )
01641 {
01642 {
01643 IkReal j11array[1], cj11array[1], sj11array[1];
01644 bool j11valid[1]={false};
01645 _nj11 = 1;
01646 IkReal x386=((IkReal(4.00000000000000))*(cj13));
01647 IkReal x387=((npy)*(sj14));
01648 IkReal x388=((cj14)*(npx));
01649 IkReal x389=((IkReal(4.00000000000000))*(sj13));
01650 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x386)))+(((x388)*(x389)))+(((IkReal(-1.00000000000000))*(x387)*(x389)))+(((IkReal(-0.360000000000000))*(sj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((x386)*(x388)))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x389)))+(((IkReal(-1.00000000000000))*(x386)*(x387))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x386)))+(((x388)*(x389)))+(((IkReal(-1.00000000000000))*(x387)*(x389)))+(((IkReal(-0.360000000000000))*(sj13)))))+IKsqr(((IkReal(-0.940000000000000))+(((x386)*(x388)))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x389)))+(((IkReal(-1.00000000000000))*(x386)*(x387)))))-1) <= IKFAST_SINCOS_THRESH )
01651     continue;
01652 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x386)))+(((x388)*(x389)))+(((IkReal(-1.00000000000000))*(x387)*(x389)))+(((IkReal(-0.360000000000000))*(sj13)))), ((IkReal(-0.940000000000000))+(((x386)*(x388)))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x389)))+(((IkReal(-1.00000000000000))*(x386)*(x387)))));
01653 sj11array[0]=IKsin(j11array[0]);
01654 cj11array[0]=IKcos(j11array[0]);
01655 if( j11array[0] > IKPI )
01656 {
01657     j11array[0]-=IK2PI;
01658 }
01659 else if( j11array[0] < -IKPI )
01660 {    j11array[0]+=IK2PI;
01661 }
01662 j11valid[0] = true;
01663 for(int ij11 = 0; ij11 < 1; ++ij11)
01664 {
01665 if( !j11valid[ij11] )
01666 {
01667     continue;
01668 }
01669 _ij11[0] = ij11; _ij11[1] = -1;
01670 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
01671 {
01672 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
01673 {
01674     j11valid[iij11]=false; _ij11[1] = iij11; break; 
01675 }
01676 }
01677 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
01678 {
01679 IkReal evalcond[2];
01680 IkReal x390=((IkReal(1.00000000000000))*(sj13));
01681 IkReal x391=((cj14)*(npx));
01682 IkReal x392=((npy)*(sj14));
01683 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(cj13)*(x391)))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x392)))+(((IkReal(-1.00000000000000))*(npz)*(x390))));
01684 evalcond[1]=((IkReal(-0.0300000000000000))+(((sj13)*(x392)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x390)*(x391)))+(((IkReal(0.250000000000000))*(IKsin(j11)))));
01685 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
01686 {
01687 continue;
01688 }
01689 }
01690 
01691 {
01692 IkReal dummyeval[1];
01693 IkReal gconst75;
01694 IkReal x393=(sj14)*(sj14);
01695 IkReal x394=(cj14)*(cj14);
01696 IkReal x395=((IkReal(1.00000000000000))*(x393));
01697 IkReal x396=((IkReal(2.00000000000000))*(cj14)*(sj14));
01698 IkReal x397=((IkReal(1.00000000000000))*(x394));
01699 gconst75=IKsign(((((IkReal(-1.00000000000000))*(r00)*(r01)*(x396)))+(((IkReal(-1.00000000000000))*(x397)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x396)))+(((IkReal(-1.00000000000000))*(x397)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x395)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x395)*((r00)*(r00))))));
01700 IkReal x398=(sj14)*(sj14);
01701 IkReal x399=(cj14)*(cj14);
01702 IkReal x400=((IkReal(1.00000000000000))*(x398));
01703 IkReal x401=((IkReal(2.00000000000000))*(cj14)*(sj14));
01704 IkReal x402=((IkReal(1.00000000000000))*(x399));
01705 dummyeval[0]=((((IkReal(-1.00000000000000))*(x400)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x400)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x402)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x401)))+(((IkReal(-1.00000000000000))*(x402)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x401))));
01706 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01707 {
01708 {
01709 IkReal dummyeval[1];
01710 IkReal gconst77;
01711 gconst77=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
01712 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
01713 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01714 {
01715 {
01716 IkReal dummyeval[1];
01717 IkReal gconst76;
01718 IkReal x403=(sj14)*(sj14);
01719 IkReal x404=(cj14)*(cj14);
01720 IkReal x405=((cj14)*(sj13));
01721 IkReal x406=((IkReal(1.00000000000000))*(r11));
01722 IkReal x407=((cj13)*(r00));
01723 IkReal x408=((sj13)*(sj14));
01724 IkReal x409=((cj13)*(r01)*(r10));
01725 gconst76=IKsign(((((r01)*(r12)*(x405)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x408)))+(((IkReal(-1.00000000000000))*(x404)*(x406)*(x407)))+(((x404)*(x409)))+(((IkReal(-1.00000000000000))*(x403)*(x406)*(x407)))+(((IkReal(-1.00000000000000))*(r02)*(x405)*(x406)))+(((x403)*(x409)))+(((r00)*(r12)*(x408)))));
01726 IkReal x410=(sj14)*(sj14);
01727 IkReal x411=(cj14)*(cj14);
01728 IkReal x412=((cj14)*(sj13));
01729 IkReal x413=((IkReal(1.00000000000000))*(r11));
01730 IkReal x414=((cj13)*(r00));
01731 IkReal x415=((sj13)*(sj14));
01732 IkReal x416=((cj13)*(r01)*(r10));
01733 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(r10)*(x415)))+(((IkReal(-1.00000000000000))*(x411)*(x413)*(x414)))+(((r01)*(r12)*(x412)))+(((x411)*(x416)))+(((x410)*(x416)))+(((IkReal(-1.00000000000000))*(r02)*(x412)*(x413)))+(((IkReal(-1.00000000000000))*(x410)*(x413)*(x414)))+(((r00)*(r12)*(x415))));
01734 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01735 {
01736 continue;
01737 
01738 } else
01739 {
01740 {
01741 IkReal j9array[1], cj9array[1], sj9array[1];
01742 bool j9valid[1]={false};
01743 _nj9 = 1;
01744 IkReal x417=((cj13)*(cj14));
01745 IkReal x418=((IkReal(1.00000000000000))*(cj13)*(sj14));
01746 if( IKabs(((gconst76)*(((((r12)*(sj13)))+(((r10)*(x417)))+(((IkReal(-1.00000000000000))*(r11)*(x418))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst76)*(((((r02)*(sj13)))+(((r00)*(x417)))+(((IkReal(-1.00000000000000))*(r01)*(x418))))))) < IKFAST_ATAN2_MAGTHRESH )
01747     continue;
01748 j9array[0]=IKatan2(((gconst76)*(((((r12)*(sj13)))+(((r10)*(x417)))+(((IkReal(-1.00000000000000))*(r11)*(x418)))))), ((gconst76)*(((((r02)*(sj13)))+(((r00)*(x417)))+(((IkReal(-1.00000000000000))*(r01)*(x418)))))));
01749 sj9array[0]=IKsin(j9array[0]);
01750 cj9array[0]=IKcos(j9array[0]);
01751 if( j9array[0] > IKPI )
01752 {
01753     j9array[0]-=IK2PI;
01754 }
01755 else if( j9array[0] < -IKPI )
01756 {    j9array[0]+=IK2PI;
01757 }
01758 j9valid[0] = true;
01759 for(int ij9 = 0; ij9 < 1; ++ij9)
01760 {
01761 if( !j9valid[ij9] )
01762 {
01763     continue;
01764 }
01765 _ij9[0] = ij9; _ij9[1] = -1;
01766 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
01767 {
01768 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
01769 {
01770     j9valid[iij9]=false; _ij9[1] = iij9; break; 
01771 }
01772 }
01773 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
01774 {
01775 IkReal evalcond[4];
01776 IkReal x419=IKsin(j9);
01777 IkReal x420=IKcos(j9);
01778 IkReal x421=((r10)*(sj14));
01779 IkReal x422=((cj14)*(r11));
01780 IkReal x423=((cj14)*(r10));
01781 IkReal x424=((cj14)*(r00));
01782 IkReal x425=((r11)*(sj14));
01783 IkReal x426=((r00)*(sj14));
01784 IkReal x427=((IkReal(1.00000000000000))*(x419));
01785 IkReal x428=((cj13)*(x419));
01786 IkReal x429=((sj13)*(x420));
01787 IkReal x430=((r01)*(x419));
01788 IkReal x431=((IkReal(1.00000000000000))*(x420));
01789 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x421)*(x431)))+(((x419)*(x426)))+(((IkReal(-1.00000000000000))*(x422)*(x431)))+(((cj14)*(x430))));
01790 evalcond[1]=((((IkReal(-1.00000000000000))*(x422)*(x427)))+(((IkReal(-1.00000000000000))*(x421)*(x427)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x431)))+(((IkReal(-1.00000000000000))*(x426)*(x431))));
01791 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x424)*(x427)))+(((cj13)*(x420)*(x423)))+(((IkReal(-1.00000000000000))*(cj13)*(x425)*(x431)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x427)))+(((r12)*(x429)))+(((r01)*(sj14)*(x428))));
01792 evalcond[3]=((((IkReal(-1.00000000000000))*(x425)*(x429)))+(((IkReal(-1.00000000000000))*(sj13)*(x424)*(x427)))+(((r02)*(x428)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x431)))+(((sj13)*(sj14)*(x430)))+(((x423)*(x429))));
01793 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01794 {
01795 continue;
01796 }
01797 }
01798 
01799 {
01800 IkReal dummyeval[1];
01801 IkReal gconst78;
01802 gconst78=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
01803 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
01804 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01805 {
01806 {
01807 IkReal dummyeval[1];
01808 IkReal gconst79;
01809 gconst79=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
01810 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
01811 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01812 {
01813 continue;
01814 
01815 } else
01816 {
01817 {
01818 IkReal j10array[1], cj10array[1], sj10array[1];
01819 bool j10valid[1]={false};
01820 _nj10 = 1;
01821 IkReal x432=((cj13)*(sj14));
01822 IkReal x433=((IkReal(1.00000000000000))*(cj11));
01823 IkReal x434=((r11)*(sj9));
01824 IkReal x435=((IkReal(1.00000000000000))*(sj11));
01825 IkReal x436=((cj13)*(cj14));
01826 IkReal x437=((cj11)*(sj13));
01827 IkReal x438=((r12)*(sj9));
01828 IkReal x439=((cj9)*(r01));
01829 IkReal x440=((sj11)*(sj13));
01830 IkReal x441=((cj9)*(r02));
01831 IkReal x442=((r10)*(sj9));
01832 IkReal x443=((cj9)*(r00));
01833 if( IKabs(((gconst79)*(((((IkReal(-1.00000000000000))*(x432)*(x433)*(x434)))+(((IkReal(-1.00000000000000))*(x432)*(x433)*(x439)))+(((IkReal(-1.00000000000000))*(r20)*(x435)*(x436)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x435)))+(((x437)*(x438)))+(((x437)*(x441)))+(((r21)*(sj11)*(x432)))+(((cj11)*(x436)*(x443)))+(((cj11)*(x436)*(x442))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((IkReal(-1.00000000000000))*(x432)*(x434)*(x435)))+(((cj11)*(r20)*(x436)))+(((x440)*(x441)))+(((r22)*(x437)))+(((x438)*(x440)))+(((IkReal(-1.00000000000000))*(r21)*(x432)*(x433)))+(((IkReal(-1.00000000000000))*(x432)*(x435)*(x439)))+(((sj11)*(x436)*(x442)))+(((sj11)*(x436)*(x443))))))) < IKFAST_ATAN2_MAGTHRESH )
01834     continue;
01835 j10array[0]=IKatan2(((gconst79)*(((((IkReal(-1.00000000000000))*(x432)*(x433)*(x434)))+(((IkReal(-1.00000000000000))*(x432)*(x433)*(x439)))+(((IkReal(-1.00000000000000))*(r20)*(x435)*(x436)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x435)))+(((x437)*(x438)))+(((x437)*(x441)))+(((r21)*(sj11)*(x432)))+(((cj11)*(x436)*(x443)))+(((cj11)*(x436)*(x442)))))), ((gconst79)*(((((IkReal(-1.00000000000000))*(x432)*(x434)*(x435)))+(((cj11)*(r20)*(x436)))+(((x440)*(x441)))+(((r22)*(x437)))+(((x438)*(x440)))+(((IkReal(-1.00000000000000))*(r21)*(x432)*(x433)))+(((IkReal(-1.00000000000000))*(x432)*(x435)*(x439)))+(((sj11)*(x436)*(x442)))+(((sj11)*(x436)*(x443)))))));
01836 sj10array[0]=IKsin(j10array[0]);
01837 cj10array[0]=IKcos(j10array[0]);
01838 if( j10array[0] > IKPI )
01839 {
01840     j10array[0]-=IK2PI;
01841 }
01842 else if( j10array[0] < -IKPI )
01843 {    j10array[0]+=IK2PI;
01844 }
01845 j10valid[0] = true;
01846 for(int ij10 = 0; ij10 < 1; ++ij10)
01847 {
01848 if( !j10valid[ij10] )
01849 {
01850     continue;
01851 }
01852 _ij10[0] = ij10; _ij10[1] = -1;
01853 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
01854 {
01855 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
01856 {
01857     j10valid[iij10]=false; _ij10[1] = iij10; break; 
01858 }
01859 }
01860 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
01861 {
01862 IkReal evalcond[4];
01863 IkReal x444=IKsin(j10);
01864 IkReal x445=IKcos(j10);
01865 IkReal x446=((IkReal(1.00000000000000))*(sj13));
01866 IkReal x447=((r11)*(sj9));
01867 IkReal x448=((cj9)*(r01));
01868 IkReal x449=((IkReal(1.00000000000000))*(cj11));
01869 IkReal x450=((r21)*(sj14));
01870 IkReal x451=((cj9)*(r02));
01871 IkReal x452=((sj13)*(sj9));
01872 IkReal x453=((cj14)*(r10));
01873 IkReal x454=((IkReal(1.00000000000000))*(cj13));
01874 IkReal x455=((cj14)*(r20));
01875 IkReal x456=((sj11)*(x444));
01876 IkReal x457=((sj14)*(x454));
01877 IkReal x458=((sj11)*(x445));
01878 IkReal x459=((cj14)*(cj9)*(r00));
01879 IkReal x460=((x445)*(x449));
01880 evalcond[0]=((((cj13)*(x450)))+(((IkReal(-1.00000000000000))*(x460)))+(((IkReal(-1.00000000000000))*(x454)*(x455)))+(x456)+(((IkReal(-1.00000000000000))*(r22)*(x446))));
01881 evalcond[1]=((((IkReal(-1.00000000000000))*(x446)*(x455)))+(((IkReal(-1.00000000000000))*(x444)*(x449)))+(((IkReal(-1.00000000000000))*(x458)))+(((sj13)*(x450)))+(((cj13)*(r22))));
01882 evalcond[2]=((((cj11)*(x444)))+(((cj13)*(x459)))+(((IkReal(-1.00000000000000))*(x447)*(x457)))+(x458)+(((r12)*(x452)))+(((sj13)*(x451)))+(((cj13)*(sj9)*(x453)))+(((IkReal(-1.00000000000000))*(x448)*(x457))));
01883 evalcond[3]=((((x452)*(x453)))+(((IkReal(-1.00000000000000))*(sj14)*(x446)*(x448)))+(((IkReal(-1.00000000000000))*(sj14)*(x446)*(x447)))+(((IkReal(-1.00000000000000))*(x460)))+(x456)+(((sj13)*(x459)))+(((IkReal(-1.00000000000000))*(x451)*(x454)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x454))));
01884 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01885 {
01886 continue;
01887 }
01888 }
01889 
01890 {
01891 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
01892 vinfos[0].jointtype = 1;
01893 vinfos[0].foffset = j9;
01894 vinfos[0].indices[0] = _ij9[0];
01895 vinfos[0].indices[1] = _ij9[1];
01896 vinfos[0].maxsolutions = _nj9;
01897 vinfos[1].jointtype = 1;
01898 vinfos[1].foffset = j10;
01899 vinfos[1].indices[0] = _ij10[0];
01900 vinfos[1].indices[1] = _ij10[1];
01901 vinfos[1].maxsolutions = _nj10;
01902 vinfos[2].jointtype = 1;
01903 vinfos[2].foffset = j11;
01904 vinfos[2].indices[0] = _ij11[0];
01905 vinfos[2].indices[1] = _ij11[1];
01906 vinfos[2].maxsolutions = _nj11;
01907 vinfos[3].jointtype = 1;
01908 vinfos[3].foffset = j12;
01909 vinfos[3].indices[0] = _ij12[0];
01910 vinfos[3].indices[1] = _ij12[1];
01911 vinfos[3].maxsolutions = _nj12;
01912 vinfos[4].jointtype = 1;
01913 vinfos[4].foffset = j13;
01914 vinfos[4].indices[0] = _ij13[0];
01915 vinfos[4].indices[1] = _ij13[1];
01916 vinfos[4].maxsolutions = _nj13;
01917 vinfos[5].jointtype = 1;
01918 vinfos[5].foffset = j14;
01919 vinfos[5].indices[0] = _ij14[0];
01920 vinfos[5].indices[1] = _ij14[1];
01921 vinfos[5].maxsolutions = _nj14;
01922 std::vector<int> vfree(0);
01923 solutions.AddSolution(vinfos,vfree);
01924 }
01925 }
01926 }
01927 
01928 }
01929 
01930 }
01931 
01932 } else
01933 {
01934 {
01935 IkReal j10array[1], cj10array[1], sj10array[1];
01936 bool j10valid[1]={false};
01937 _nj10 = 1;
01938 IkReal x461=((r22)*(sj11));
01939 IkReal x462=((IkReal(1.00000000000000))*(cj13));
01940 IkReal x463=((cj14)*(r20));
01941 IkReal x464=((r21)*(sj14));
01942 IkReal x465=((cj11)*(cj13));
01943 IkReal x466=((IkReal(1.00000000000000))*(sj13));
01944 if( IKabs(((gconst78)*(((((r22)*(x465)))+(((IkReal(-1.00000000000000))*(sj11)*(x462)*(x464)))+(((cj11)*(sj13)*(x464)))+(((cj13)*(sj11)*(x463)))+(((IkReal(-1.00000000000000))*(cj11)*(x463)*(x466)))+(((sj13)*(x461))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(cj11)*(r22)*(x466)))+(((cj13)*(x461)))+(((sj11)*(sj13)*(x464)))+(((IkReal(-1.00000000000000))*(cj11)*(x462)*(x463)))+(((x464)*(x465)))+(((IkReal(-1.00000000000000))*(sj11)*(x463)*(x466))))))) < IKFAST_ATAN2_MAGTHRESH )
01945     continue;
01946 j10array[0]=IKatan2(((gconst78)*(((((r22)*(x465)))+(((IkReal(-1.00000000000000))*(sj11)*(x462)*(x464)))+(((cj11)*(sj13)*(x464)))+(((cj13)*(sj11)*(x463)))+(((IkReal(-1.00000000000000))*(cj11)*(x463)*(x466)))+(((sj13)*(x461)))))), ((gconst78)*(((((IkReal(-1.00000000000000))*(cj11)*(r22)*(x466)))+(((cj13)*(x461)))+(((sj11)*(sj13)*(x464)))+(((IkReal(-1.00000000000000))*(cj11)*(x462)*(x463)))+(((x464)*(x465)))+(((IkReal(-1.00000000000000))*(sj11)*(x463)*(x466)))))));
01947 sj10array[0]=IKsin(j10array[0]);
01948 cj10array[0]=IKcos(j10array[0]);
01949 if( j10array[0] > IKPI )
01950 {
01951     j10array[0]-=IK2PI;
01952 }
01953 else if( j10array[0] < -IKPI )
01954 {    j10array[0]+=IK2PI;
01955 }
01956 j10valid[0] = true;
01957 for(int ij10 = 0; ij10 < 1; ++ij10)
01958 {
01959 if( !j10valid[ij10] )
01960 {
01961     continue;
01962 }
01963 _ij10[0] = ij10; _ij10[1] = -1;
01964 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
01965 {
01966 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
01967 {
01968     j10valid[iij10]=false; _ij10[1] = iij10; break; 
01969 }
01970 }
01971 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
01972 {
01973 IkReal evalcond[4];
01974 IkReal x467=IKsin(j10);
01975 IkReal x468=IKcos(j10);
01976 IkReal x469=((IkReal(1.00000000000000))*(sj13));
01977 IkReal x470=((r11)*(sj9));
01978 IkReal x471=((cj9)*(r01));
01979 IkReal x472=((IkReal(1.00000000000000))*(cj11));
01980 IkReal x473=((r21)*(sj14));
01981 IkReal x474=((cj9)*(r02));
01982 IkReal x475=((sj13)*(sj9));
01983 IkReal x476=((cj14)*(r10));
01984 IkReal x477=((IkReal(1.00000000000000))*(cj13));
01985 IkReal x478=((cj14)*(r20));
01986 IkReal x479=((sj11)*(x467));
01987 IkReal x480=((sj14)*(x477));
01988 IkReal x481=((sj11)*(x468));
01989 IkReal x482=((cj14)*(cj9)*(r00));
01990 IkReal x483=((x468)*(x472));
01991 evalcond[0]=((((IkReal(-1.00000000000000))*(x477)*(x478)))+(((IkReal(-1.00000000000000))*(x483)))+(((cj13)*(x473)))+(x479)+(((IkReal(-1.00000000000000))*(r22)*(x469))));
01992 evalcond[1]=((((IkReal(-1.00000000000000))*(x467)*(x472)))+(((IkReal(-1.00000000000000))*(x469)*(x478)))+(((IkReal(-1.00000000000000))*(x481)))+(((sj13)*(x473)))+(((cj13)*(r22))));
01993 evalcond[2]=((((cj11)*(x467)))+(((cj13)*(sj9)*(x476)))+(((IkReal(-1.00000000000000))*(x470)*(x480)))+(((sj13)*(x474)))+(x481)+(((r12)*(x475)))+(((IkReal(-1.00000000000000))*(x471)*(x480)))+(((cj13)*(x482))));
01994 evalcond[3]=((((IkReal(-1.00000000000000))*(x483)))+(((sj13)*(x482)))+(((IkReal(-1.00000000000000))*(sj14)*(x469)*(x471)))+(((IkReal(-1.00000000000000))*(sj14)*(x469)*(x470)))+(x479)+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x477)))+(((x475)*(x476)))+(((IkReal(-1.00000000000000))*(x474)*(x477))));
01995 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01996 {
01997 continue;
01998 }
01999 }
02000 
02001 {
02002 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02003 vinfos[0].jointtype = 1;
02004 vinfos[0].foffset = j9;
02005 vinfos[0].indices[0] = _ij9[0];
02006 vinfos[0].indices[1] = _ij9[1];
02007 vinfos[0].maxsolutions = _nj9;
02008 vinfos[1].jointtype = 1;
02009 vinfos[1].foffset = j10;
02010 vinfos[1].indices[0] = _ij10[0];
02011 vinfos[1].indices[1] = _ij10[1];
02012 vinfos[1].maxsolutions = _nj10;
02013 vinfos[2].jointtype = 1;
02014 vinfos[2].foffset = j11;
02015 vinfos[2].indices[0] = _ij11[0];
02016 vinfos[2].indices[1] = _ij11[1];
02017 vinfos[2].maxsolutions = _nj11;
02018 vinfos[3].jointtype = 1;
02019 vinfos[3].foffset = j12;
02020 vinfos[3].indices[0] = _ij12[0];
02021 vinfos[3].indices[1] = _ij12[1];
02022 vinfos[3].maxsolutions = _nj12;
02023 vinfos[4].jointtype = 1;
02024 vinfos[4].foffset = j13;
02025 vinfos[4].indices[0] = _ij13[0];
02026 vinfos[4].indices[1] = _ij13[1];
02027 vinfos[4].maxsolutions = _nj13;
02028 vinfos[5].jointtype = 1;
02029 vinfos[5].foffset = j14;
02030 vinfos[5].indices[0] = _ij14[0];
02031 vinfos[5].indices[1] = _ij14[1];
02032 vinfos[5].maxsolutions = _nj14;
02033 std::vector<int> vfree(0);
02034 solutions.AddSolution(vinfos,vfree);
02035 }
02036 }
02037 }
02038 
02039 }
02040 
02041 }
02042 }
02043 }
02044 
02045 }
02046 
02047 }
02048 
02049 } else
02050 {
02051 {
02052 IkReal j10array[1], cj10array[1], sj10array[1];
02053 bool j10valid[1]={false};
02054 _nj10 = 1;
02055 IkReal x484=((cj13)*(sj11));
02056 IkReal x485=((r21)*(sj14));
02057 IkReal x486=((cj11)*(cj13));
02058 IkReal x487=((IkReal(1.00000000000000))*(sj13));
02059 IkReal x488=((sj11)*(sj13));
02060 IkReal x489=((cj14)*(r20));
02061 if( IKabs(((gconst77)*(((((IkReal(-1.00000000000000))*(cj11)*(x487)*(x489)))+(((x484)*(x489)))+(((IkReal(-1.00000000000000))*(x484)*(x485)))+(((r22)*(x488)))+(((r22)*(x486)))+(((cj11)*(sj13)*(x485))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst77)*(((((IkReal(-1.00000000000000))*(x486)*(x489)))+(((x485)*(x486)))+(((x485)*(x488)))+(((IkReal(-1.00000000000000))*(cj11)*(r22)*(x487)))+(((r22)*(x484)))+(((IkReal(-1.00000000000000))*(sj11)*(x487)*(x489))))))) < IKFAST_ATAN2_MAGTHRESH )
02062     continue;
02063 j10array[0]=IKatan2(((gconst77)*(((((IkReal(-1.00000000000000))*(cj11)*(x487)*(x489)))+(((x484)*(x489)))+(((IkReal(-1.00000000000000))*(x484)*(x485)))+(((r22)*(x488)))+(((r22)*(x486)))+(((cj11)*(sj13)*(x485)))))), ((gconst77)*(((((IkReal(-1.00000000000000))*(x486)*(x489)))+(((x485)*(x486)))+(((x485)*(x488)))+(((IkReal(-1.00000000000000))*(cj11)*(r22)*(x487)))+(((r22)*(x484)))+(((IkReal(-1.00000000000000))*(sj11)*(x487)*(x489)))))));
02064 sj10array[0]=IKsin(j10array[0]);
02065 cj10array[0]=IKcos(j10array[0]);
02066 if( j10array[0] > IKPI )
02067 {
02068     j10array[0]-=IK2PI;
02069 }
02070 else if( j10array[0] < -IKPI )
02071 {    j10array[0]+=IK2PI;
02072 }
02073 j10valid[0] = true;
02074 for(int ij10 = 0; ij10 < 1; ++ij10)
02075 {
02076 if( !j10valid[ij10] )
02077 {
02078     continue;
02079 }
02080 _ij10[0] = ij10; _ij10[1] = -1;
02081 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
02082 {
02083 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
02084 {
02085     j10valid[iij10]=false; _ij10[1] = iij10; break; 
02086 }
02087 }
02088 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
02089 {
02090 IkReal evalcond[2];
02091 IkReal x490=IKsin(j10);
02092 IkReal x491=IKcos(j10);
02093 IkReal x492=((IkReal(1.00000000000000))*(sj13));
02094 IkReal x493=((cj14)*(r20));
02095 IkReal x494=((r21)*(sj14));
02096 IkReal x495=((IkReal(1.00000000000000))*(x491));
02097 evalcond[0]=((((cj13)*(x494)))+(((IkReal(-1.00000000000000))*(cj11)*(x495)))+(((IkReal(-1.00000000000000))*(cj13)*(x493)))+(((IkReal(-1.00000000000000))*(r22)*(x492)))+(((sj11)*(x490))));
02098 evalcond[1]=((((IkReal(-1.00000000000000))*(sj11)*(x495)))+(((IkReal(-1.00000000000000))*(cj11)*(x490)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x492)*(x493)))+(((sj13)*(x494))));
02099 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
02100 {
02101 continue;
02102 }
02103 }
02104 
02105 {
02106 IkReal dummyeval[1];
02107 IkReal gconst80;
02108 IkReal x496=(sj14)*(sj14);
02109 IkReal x497=(cj14)*(cj14);
02110 IkReal x498=((IkReal(1.00000000000000))*(x496));
02111 IkReal x499=((IkReal(2.00000000000000))*(cj14)*(sj14));
02112 IkReal x500=((IkReal(1.00000000000000))*(x497));
02113 gconst80=IKsign(((((IkReal(-1.00000000000000))*(x498)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x499)))+(((IkReal(-1.00000000000000))*(x498)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x500)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x499)))+(((IkReal(-1.00000000000000))*(x500)*((r01)*(r01))))));
02114 IkReal x501=(sj14)*(sj14);
02115 IkReal x502=(cj14)*(cj14);
02116 IkReal x503=((IkReal(1.00000000000000))*(x501));
02117 IkReal x504=((IkReal(2.00000000000000))*(cj14)*(sj14));
02118 IkReal x505=((IkReal(1.00000000000000))*(x502));
02119 dummyeval[0]=((((IkReal(-1.00000000000000))*(x505)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x505)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x504)))+(((IkReal(-1.00000000000000))*(x503)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x504)))+(((IkReal(-1.00000000000000))*(x503)*((r10)*(r10)))));
02120 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02121 {
02122 {
02123 IkReal dummyeval[1];
02124 IkReal gconst81;
02125 IkReal x506=(sj14)*(sj14);
02126 IkReal x507=(cj14)*(cj14);
02127 IkReal x508=((cj14)*(sj13));
02128 IkReal x509=((IkReal(1.00000000000000))*(r11));
02129 IkReal x510=((cj13)*(r00));
02130 IkReal x511=((sj13)*(sj14));
02131 IkReal x512=((cj13)*(r01)*(r10));
02132 gconst81=IKsign(((((x507)*(x512)))+(((IkReal(-1.00000000000000))*(x506)*(x509)*(x510)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x511)))+(((r00)*(r12)*(x511)))+(((IkReal(-1.00000000000000))*(r02)*(x508)*(x509)))+(((IkReal(-1.00000000000000))*(x507)*(x509)*(x510)))+(((r01)*(r12)*(x508)))+(((x506)*(x512)))));
02133 IkReal x513=(sj14)*(sj14);
02134 IkReal x514=(cj14)*(cj14);
02135 IkReal x515=((cj14)*(sj13));
02136 IkReal x516=((IkReal(1.00000000000000))*(r11));
02137 IkReal x517=((cj13)*(r00));
02138 IkReal x518=((sj13)*(sj14));
02139 IkReal x519=((cj13)*(r01)*(r10));
02140 dummyeval[0]=((((r01)*(r12)*(x515)))+(((IkReal(-1.00000000000000))*(x514)*(x516)*(x517)))+(((x514)*(x519)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x518)))+(((x513)*(x519)))+(((r00)*(r12)*(x518)))+(((IkReal(-1.00000000000000))*(r02)*(x515)*(x516)))+(((IkReal(-1.00000000000000))*(x513)*(x516)*(x517))));
02141 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02142 {
02143 continue;
02144 
02145 } else
02146 {
02147 {
02148 IkReal j9array[1], cj9array[1], sj9array[1];
02149 bool j9valid[1]={false};
02150 _nj9 = 1;
02151 IkReal x520=((cj13)*(cj14));
02152 IkReal x521=((IkReal(1.00000000000000))*(cj13)*(sj14));
02153 if( IKabs(((gconst81)*(((((r12)*(sj13)))+(((r10)*(x520)))+(((IkReal(-1.00000000000000))*(r11)*(x521))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst81)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x521)))+(((r00)*(x520))))))) < IKFAST_ATAN2_MAGTHRESH )
02154     continue;
02155 j9array[0]=IKatan2(((gconst81)*(((((r12)*(sj13)))+(((r10)*(x520)))+(((IkReal(-1.00000000000000))*(r11)*(x521)))))), ((gconst81)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x521)))+(((r00)*(x520)))))));
02156 sj9array[0]=IKsin(j9array[0]);
02157 cj9array[0]=IKcos(j9array[0]);
02158 if( j9array[0] > IKPI )
02159 {
02160     j9array[0]-=IK2PI;
02161 }
02162 else if( j9array[0] < -IKPI )
02163 {    j9array[0]+=IK2PI;
02164 }
02165 j9valid[0] = true;
02166 for(int ij9 = 0; ij9 < 1; ++ij9)
02167 {
02168 if( !j9valid[ij9] )
02169 {
02170     continue;
02171 }
02172 _ij9[0] = ij9; _ij9[1] = -1;
02173 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
02174 {
02175 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
02176 {
02177     j9valid[iij9]=false; _ij9[1] = iij9; break; 
02178 }
02179 }
02180 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
02181 {
02182 IkReal evalcond[6];
02183 IkReal x522=IKsin(j9);
02184 IkReal x523=IKcos(j9);
02185 IkReal x524=((IkReal(1.00000000000000))*(cj14));
02186 IkReal x525=((IkReal(1.00000000000000))*(sj14));
02187 IkReal x526=((cj13)*(cj14));
02188 IkReal x527=((cj14)*(r10));
02189 IkReal x528=((r01)*(sj14));
02190 IkReal x529=((IkReal(1.00000000000000))*(r12));
02191 IkReal x530=((sj13)*(x523));
02192 IkReal x531=((r02)*(x522));
02193 IkReal x532=((r11)*(x522));
02194 IkReal x533=((r10)*(x523));
02195 IkReal x534=((r01)*(x523));
02196 IkReal x535=((sj13)*(x522));
02197 IkReal x536=((r11)*(x523));
02198 IkReal x537=((cj13)*(x522));
02199 IkReal x538=((r10)*(x522));
02200 IkReal x539=((r00)*(x523));
02201 IkReal x540=((cj13)*(x523));
02202 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x524)*(x536)))+(((IkReal(-1.00000000000000))*(x525)*(x533)))+(((cj14)*(r01)*(x522)))+(((r00)*(sj14)*(x522))));
02203 evalcond[1]=((((IkReal(-1.00000000000000))*(x524)*(x532)))+(((IkReal(-1.00000000000000))*(x524)*(x534)))+(((IkReal(-1.00000000000000))*(x525)*(x539)))+(((IkReal(-1.00000000000000))*(x525)*(x538))));
02204 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x525)*(x536)))+(((x526)*(x533)))+(((r12)*(x530)))+(((IkReal(-1.00000000000000))*(sj13)*(x531)))+(((x528)*(x537)))+(((IkReal(-1.00000000000000))*(r00)*(x524)*(x537))));
02205 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x525)*(x530)))+(((cj13)*(x531)))+(((IkReal(-1.00000000000000))*(x529)*(x540)))+(((x528)*(x535)))+(((x527)*(x530)))+(((IkReal(-1.00000000000000))*(r00)*(x524)*(x535))));
02206 evalcond[4]=((((r02)*(x530)))+(((IkReal(-1.00000000000000))*(cj13)*(x525)*(x534)))+(((IkReal(-1.00000000000000))*(cj13)*(x525)*(x532)))+(((x526)*(x538)))+(((x526)*(x539)))+(((r12)*(x535)))+(((cj10)*(sj11)))+(((cj11)*(sj10))));
02207 evalcond[5]=((((IkReal(-1.00000000000000))*(x529)*(x537)))+(((cj14)*(r00)*(x530)))+(((sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(r01)*(x525)*(x530)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11)))+(((x527)*(x535)))+(((IkReal(-1.00000000000000))*(sj13)*(x525)*(x532)))+(((IkReal(-1.00000000000000))*(r02)*(x540))));
02208 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  )
02209 {
02210 continue;
02211 }
02212 }
02213 
02214 {
02215 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02216 vinfos[0].jointtype = 1;
02217 vinfos[0].foffset = j9;
02218 vinfos[0].indices[0] = _ij9[0];
02219 vinfos[0].indices[1] = _ij9[1];
02220 vinfos[0].maxsolutions = _nj9;
02221 vinfos[1].jointtype = 1;
02222 vinfos[1].foffset = j10;
02223 vinfos[1].indices[0] = _ij10[0];
02224 vinfos[1].indices[1] = _ij10[1];
02225 vinfos[1].maxsolutions = _nj10;
02226 vinfos[2].jointtype = 1;
02227 vinfos[2].foffset = j11;
02228 vinfos[2].indices[0] = _ij11[0];
02229 vinfos[2].indices[1] = _ij11[1];
02230 vinfos[2].maxsolutions = _nj11;
02231 vinfos[3].jointtype = 1;
02232 vinfos[3].foffset = j12;
02233 vinfos[3].indices[0] = _ij12[0];
02234 vinfos[3].indices[1] = _ij12[1];
02235 vinfos[3].maxsolutions = _nj12;
02236 vinfos[4].jointtype = 1;
02237 vinfos[4].foffset = j13;
02238 vinfos[4].indices[0] = _ij13[0];
02239 vinfos[4].indices[1] = _ij13[1];
02240 vinfos[4].maxsolutions = _nj13;
02241 vinfos[5].jointtype = 1;
02242 vinfos[5].foffset = j14;
02243 vinfos[5].indices[0] = _ij14[0];
02244 vinfos[5].indices[1] = _ij14[1];
02245 vinfos[5].maxsolutions = _nj14;
02246 std::vector<int> vfree(0);
02247 solutions.AddSolution(vinfos,vfree);
02248 }
02249 }
02250 }
02251 
02252 }
02253 
02254 }
02255 
02256 } else
02257 {
02258 {
02259 IkReal j9array[1], cj9array[1], sj9array[1];
02260 bool j9valid[1]={false};
02261 _nj9 = 1;
02262 if( IKabs(((gconst80)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst80)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
02263     continue;
02264 j9array[0]=IKatan2(((gconst80)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst80)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
02265 sj9array[0]=IKsin(j9array[0]);
02266 cj9array[0]=IKcos(j9array[0]);
02267 if( j9array[0] > IKPI )
02268 {
02269     j9array[0]-=IK2PI;
02270 }
02271 else if( j9array[0] < -IKPI )
02272 {    j9array[0]+=IK2PI;
02273 }
02274 j9valid[0] = true;
02275 for(int ij9 = 0; ij9 < 1; ++ij9)
02276 {
02277 if( !j9valid[ij9] )
02278 {
02279     continue;
02280 }
02281 _ij9[0] = ij9; _ij9[1] = -1;
02282 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
02283 {
02284 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
02285 {
02286     j9valid[iij9]=false; _ij9[1] = iij9; break; 
02287 }
02288 }
02289 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
02290 {
02291 IkReal evalcond[6];
02292 IkReal x541=IKsin(j9);
02293 IkReal x542=IKcos(j9);
02294 IkReal x543=((IkReal(1.00000000000000))*(cj14));
02295 IkReal x544=((IkReal(1.00000000000000))*(sj14));
02296 IkReal x545=((cj13)*(cj14));
02297 IkReal x546=((cj14)*(r10));
02298 IkReal x547=((r01)*(sj14));
02299 IkReal x548=((IkReal(1.00000000000000))*(r12));
02300 IkReal x549=((sj13)*(x542));
02301 IkReal x550=((r02)*(x541));
02302 IkReal x551=((r11)*(x541));
02303 IkReal x552=((r10)*(x542));
02304 IkReal x553=((r01)*(x542));
02305 IkReal x554=((sj13)*(x541));
02306 IkReal x555=((r11)*(x542));
02307 IkReal x556=((cj13)*(x541));
02308 IkReal x557=((r10)*(x541));
02309 IkReal x558=((r00)*(x542));
02310 IkReal x559=((cj13)*(x542));
02311 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x544)*(x552)))+(((cj14)*(r01)*(x541)))+(((r00)*(sj14)*(x541)))+(((IkReal(-1.00000000000000))*(x543)*(x555))));
02312 evalcond[1]=((((IkReal(-1.00000000000000))*(x544)*(x558)))+(((IkReal(-1.00000000000000))*(x544)*(x557)))+(((IkReal(-1.00000000000000))*(x543)*(x553)))+(((IkReal(-1.00000000000000))*(x543)*(x551))));
02313 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x543)*(x556)))+(((IkReal(-1.00000000000000))*(sj13)*(x550)))+(((r12)*(x549)))+(((IkReal(-1.00000000000000))*(cj13)*(x544)*(x555)))+(((x547)*(x556)))+(((x545)*(x552))));
02314 evalcond[3]=((((IkReal(-1.00000000000000))*(r00)*(x543)*(x554)))+(((cj13)*(x550)))+(((IkReal(-1.00000000000000))*(r11)*(x544)*(x549)))+(((IkReal(-1.00000000000000))*(x548)*(x559)))+(((x547)*(x554)))+(((x546)*(x549))));
02315 evalcond[4]=((((r02)*(x549)))+(((r12)*(x554)))+(((cj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x544)*(x553)))+(((IkReal(-1.00000000000000))*(cj13)*(x544)*(x551)))+(((x545)*(x558)))+(((x545)*(x557)))+(((cj11)*(sj10))));
02316 evalcond[5]=((((IkReal(-1.00000000000000))*(sj13)*(x544)*(x551)))+(((IkReal(-1.00000000000000))*(r02)*(x559)))+(((cj14)*(r00)*(x549)))+(((IkReal(-1.00000000000000))*(r01)*(x544)*(x549)))+(((IkReal(-1.00000000000000))*(x548)*(x556)))+(((sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11)))+(((x546)*(x554))));
02317 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  )
02318 {
02319 continue;
02320 }
02321 }
02322 
02323 {
02324 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02325 vinfos[0].jointtype = 1;
02326 vinfos[0].foffset = j9;
02327 vinfos[0].indices[0] = _ij9[0];
02328 vinfos[0].indices[1] = _ij9[1];
02329 vinfos[0].maxsolutions = _nj9;
02330 vinfos[1].jointtype = 1;
02331 vinfos[1].foffset = j10;
02332 vinfos[1].indices[0] = _ij10[0];
02333 vinfos[1].indices[1] = _ij10[1];
02334 vinfos[1].maxsolutions = _nj10;
02335 vinfos[2].jointtype = 1;
02336 vinfos[2].foffset = j11;
02337 vinfos[2].indices[0] = _ij11[0];
02338 vinfos[2].indices[1] = _ij11[1];
02339 vinfos[2].maxsolutions = _nj11;
02340 vinfos[3].jointtype = 1;
02341 vinfos[3].foffset = j12;
02342 vinfos[3].indices[0] = _ij12[0];
02343 vinfos[3].indices[1] = _ij12[1];
02344 vinfos[3].maxsolutions = _nj12;
02345 vinfos[4].jointtype = 1;
02346 vinfos[4].foffset = j13;
02347 vinfos[4].indices[0] = _ij13[0];
02348 vinfos[4].indices[1] = _ij13[1];
02349 vinfos[4].maxsolutions = _nj13;
02350 vinfos[5].jointtype = 1;
02351 vinfos[5].foffset = j14;
02352 vinfos[5].indices[0] = _ij14[0];
02353 vinfos[5].indices[1] = _ij14[1];
02354 vinfos[5].maxsolutions = _nj14;
02355 std::vector<int> vfree(0);
02356 solutions.AddSolution(vinfos,vfree);
02357 }
02358 }
02359 }
02360 
02361 }
02362 
02363 }
02364 }
02365 }
02366 
02367 }
02368 
02369 }
02370 
02371 } else
02372 {
02373 {
02374 IkReal j9array[1], cj9array[1], sj9array[1];
02375 bool j9valid[1]={false};
02376 _nj9 = 1;
02377 if( IKabs(((gconst75)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst75)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
02378     continue;
02379 j9array[0]=IKatan2(((gconst75)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst75)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
02380 sj9array[0]=IKsin(j9array[0]);
02381 cj9array[0]=IKcos(j9array[0]);
02382 if( j9array[0] > IKPI )
02383 {
02384     j9array[0]-=IK2PI;
02385 }
02386 else if( j9array[0] < -IKPI )
02387 {    j9array[0]+=IK2PI;
02388 }
02389 j9valid[0] = true;
02390 for(int ij9 = 0; ij9 < 1; ++ij9)
02391 {
02392 if( !j9valid[ij9] )
02393 {
02394     continue;
02395 }
02396 _ij9[0] = ij9; _ij9[1] = -1;
02397 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
02398 {
02399 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
02400 {
02401     j9valid[iij9]=false; _ij9[1] = iij9; break; 
02402 }
02403 }
02404 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
02405 {
02406 IkReal evalcond[4];
02407 IkReal x560=IKsin(j9);
02408 IkReal x561=IKcos(j9);
02409 IkReal x562=((r10)*(sj14));
02410 IkReal x563=((cj14)*(r11));
02411 IkReal x564=((cj14)*(r10));
02412 IkReal x565=((cj14)*(r00));
02413 IkReal x566=((r11)*(sj14));
02414 IkReal x567=((r00)*(sj14));
02415 IkReal x568=((IkReal(1.00000000000000))*(x560));
02416 IkReal x569=((cj13)*(x560));
02417 IkReal x570=((sj13)*(x561));
02418 IkReal x571=((r01)*(x560));
02419 IkReal x572=((IkReal(1.00000000000000))*(x561));
02420 evalcond[0]=((IkReal(-1.00000000000000))+(((cj14)*(x571)))+(((x560)*(x567)))+(((IkReal(-1.00000000000000))*(x563)*(x572)))+(((IkReal(-1.00000000000000))*(x562)*(x572))));
02421 evalcond[1]=((((IkReal(-1.00000000000000))*(x562)*(x568)))+(((IkReal(-1.00000000000000))*(x567)*(x572)))+(((IkReal(-1.00000000000000))*(x563)*(x568)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x572))));
02422 evalcond[2]=((((r12)*(x570)))+(((IkReal(-1.00000000000000))*(cj13)*(x565)*(x568)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x568)))+(((IkReal(-1.00000000000000))*(cj13)*(x566)*(x572)))+(((r01)*(sj14)*(x569)))+(((cj13)*(x561)*(x564))));
02423 evalcond[3]=((((sj13)*(sj14)*(x571)))+(((IkReal(-1.00000000000000))*(x566)*(x570)))+(((IkReal(-1.00000000000000))*(sj13)*(x565)*(x568)))+(((x564)*(x570)))+(((r02)*(x569)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x572))));
02424 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02425 {
02426 continue;
02427 }
02428 }
02429 
02430 {
02431 IkReal dummyeval[1];
02432 IkReal gconst78;
02433 gconst78=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
02434 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
02435 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02436 {
02437 {
02438 IkReal dummyeval[1];
02439 IkReal gconst79;
02440 gconst79=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
02441 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
02442 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02443 {
02444 continue;
02445 
02446 } else
02447 {
02448 {
02449 IkReal j10array[1], cj10array[1], sj10array[1];
02450 bool j10valid[1]={false};
02451 _nj10 = 1;
02452 IkReal x573=((cj13)*(sj14));
02453 IkReal x574=((IkReal(1.00000000000000))*(cj11));
02454 IkReal x575=((r11)*(sj9));
02455 IkReal x576=((IkReal(1.00000000000000))*(sj11));
02456 IkReal x577=((cj13)*(cj14));
02457 IkReal x578=((cj11)*(sj13));
02458 IkReal x579=((r12)*(sj9));
02459 IkReal x580=((cj9)*(r01));
02460 IkReal x581=((sj11)*(sj13));
02461 IkReal x582=((cj9)*(r02));
02462 IkReal x583=((r10)*(sj9));
02463 IkReal x584=((cj9)*(r00));
02464 if( IKabs(((gconst79)*(((((x578)*(x582)))+(((x578)*(x579)))+(((cj11)*(x577)*(x584)))+(((cj11)*(x577)*(x583)))+(((IkReal(-1.00000000000000))*(x573)*(x574)*(x580)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x576)))+(((IkReal(-1.00000000000000))*(r20)*(x576)*(x577)))+(((IkReal(-1.00000000000000))*(x573)*(x574)*(x575)))+(((r21)*(sj11)*(x573))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst79)*(((((IkReal(-1.00000000000000))*(x573)*(x576)*(x580)))+(((x581)*(x582)))+(((x579)*(x581)))+(((sj11)*(x577)*(x584)))+(((sj11)*(x577)*(x583)))+(((cj11)*(r20)*(x577)))+(((IkReal(-1.00000000000000))*(x573)*(x575)*(x576)))+(((IkReal(-1.00000000000000))*(r21)*(x573)*(x574)))+(((r22)*(x578))))))) < IKFAST_ATAN2_MAGTHRESH )
02465     continue;
02466 j10array[0]=IKatan2(((gconst79)*(((((x578)*(x582)))+(((x578)*(x579)))+(((cj11)*(x577)*(x584)))+(((cj11)*(x577)*(x583)))+(((IkReal(-1.00000000000000))*(x573)*(x574)*(x580)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x576)))+(((IkReal(-1.00000000000000))*(r20)*(x576)*(x577)))+(((IkReal(-1.00000000000000))*(x573)*(x574)*(x575)))+(((r21)*(sj11)*(x573)))))), ((gconst79)*(((((IkReal(-1.00000000000000))*(x573)*(x576)*(x580)))+(((x581)*(x582)))+(((x579)*(x581)))+(((sj11)*(x577)*(x584)))+(((sj11)*(x577)*(x583)))+(((cj11)*(r20)*(x577)))+(((IkReal(-1.00000000000000))*(x573)*(x575)*(x576)))+(((IkReal(-1.00000000000000))*(r21)*(x573)*(x574)))+(((r22)*(x578)))))));
02467 sj10array[0]=IKsin(j10array[0]);
02468 cj10array[0]=IKcos(j10array[0]);
02469 if( j10array[0] > IKPI )
02470 {
02471     j10array[0]-=IK2PI;
02472 }
02473 else if( j10array[0] < -IKPI )
02474 {    j10array[0]+=IK2PI;
02475 }
02476 j10valid[0] = true;
02477 for(int ij10 = 0; ij10 < 1; ++ij10)
02478 {
02479 if( !j10valid[ij10] )
02480 {
02481     continue;
02482 }
02483 _ij10[0] = ij10; _ij10[1] = -1;
02484 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
02485 {
02486 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
02487 {
02488     j10valid[iij10]=false; _ij10[1] = iij10; break; 
02489 }
02490 }
02491 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
02492 {
02493 IkReal evalcond[4];
02494 IkReal x585=IKsin(j10);
02495 IkReal x586=IKcos(j10);
02496 IkReal x587=((IkReal(1.00000000000000))*(sj13));
02497 IkReal x588=((r11)*(sj9));
02498 IkReal x589=((cj9)*(r01));
02499 IkReal x590=((IkReal(1.00000000000000))*(cj11));
02500 IkReal x591=((r21)*(sj14));
02501 IkReal x592=((cj9)*(r02));
02502 IkReal x593=((sj13)*(sj9));
02503 IkReal x594=((cj14)*(r10));
02504 IkReal x595=((IkReal(1.00000000000000))*(cj13));
02505 IkReal x596=((cj14)*(r20));
02506 IkReal x597=((sj11)*(x585));
02507 IkReal x598=((sj14)*(x595));
02508 IkReal x599=((sj11)*(x586));
02509 IkReal x600=((cj14)*(cj9)*(r00));
02510 IkReal x601=((x586)*(x590));
02511 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x587)))+(((cj13)*(x591)))+(x597)+(((IkReal(-1.00000000000000))*(x595)*(x596)))+(((IkReal(-1.00000000000000))*(x601))));
02512 evalcond[1]=((((sj13)*(x591)))+(((IkReal(-1.00000000000000))*(x587)*(x596)))+(((IkReal(-1.00000000000000))*(x585)*(x590)))+(((IkReal(-1.00000000000000))*(x599)))+(((cj13)*(r22))));
02513 evalcond[2]=((((IkReal(-1.00000000000000))*(x588)*(x598)))+(((sj13)*(x592)))+(((IkReal(-1.00000000000000))*(x589)*(x598)))+(((cj13)*(sj9)*(x594)))+(((cj11)*(x585)))+(x599)+(((r12)*(x593)))+(((cj13)*(x600))));
02514 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x587)*(x589)))+(((IkReal(-1.00000000000000))*(sj14)*(x587)*(x588)))+(((sj13)*(x600)))+(((IkReal(-1.00000000000000))*(x592)*(x595)))+(x597)+(((IkReal(-1.00000000000000))*(x601)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x595)))+(((x593)*(x594))));
02515 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02516 {
02517 continue;
02518 }
02519 }
02520 
02521 {
02522 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02523 vinfos[0].jointtype = 1;
02524 vinfos[0].foffset = j9;
02525 vinfos[0].indices[0] = _ij9[0];
02526 vinfos[0].indices[1] = _ij9[1];
02527 vinfos[0].maxsolutions = _nj9;
02528 vinfos[1].jointtype = 1;
02529 vinfos[1].foffset = j10;
02530 vinfos[1].indices[0] = _ij10[0];
02531 vinfos[1].indices[1] = _ij10[1];
02532 vinfos[1].maxsolutions = _nj10;
02533 vinfos[2].jointtype = 1;
02534 vinfos[2].foffset = j11;
02535 vinfos[2].indices[0] = _ij11[0];
02536 vinfos[2].indices[1] = _ij11[1];
02537 vinfos[2].maxsolutions = _nj11;
02538 vinfos[3].jointtype = 1;
02539 vinfos[3].foffset = j12;
02540 vinfos[3].indices[0] = _ij12[0];
02541 vinfos[3].indices[1] = _ij12[1];
02542 vinfos[3].maxsolutions = _nj12;
02543 vinfos[4].jointtype = 1;
02544 vinfos[4].foffset = j13;
02545 vinfos[4].indices[0] = _ij13[0];
02546 vinfos[4].indices[1] = _ij13[1];
02547 vinfos[4].maxsolutions = _nj13;
02548 vinfos[5].jointtype = 1;
02549 vinfos[5].foffset = j14;
02550 vinfos[5].indices[0] = _ij14[0];
02551 vinfos[5].indices[1] = _ij14[1];
02552 vinfos[5].maxsolutions = _nj14;
02553 std::vector<int> vfree(0);
02554 solutions.AddSolution(vinfos,vfree);
02555 }
02556 }
02557 }
02558 
02559 }
02560 
02561 }
02562 
02563 } else
02564 {
02565 {
02566 IkReal j10array[1], cj10array[1], sj10array[1];
02567 bool j10valid[1]={false};
02568 _nj10 = 1;
02569 IkReal x602=((r22)*(sj11));
02570 IkReal x603=((IkReal(1.00000000000000))*(cj13));
02571 IkReal x604=((cj14)*(r20));
02572 IkReal x605=((r21)*(sj14));
02573 IkReal x606=((cj11)*(cj13));
02574 IkReal x607=((IkReal(1.00000000000000))*(sj13));
02575 if( IKabs(((gconst78)*(((((IkReal(-1.00000000000000))*(sj11)*(x603)*(x605)))+(((sj13)*(x602)))+(((cj13)*(sj11)*(x604)))+(((cj11)*(sj13)*(x605)))+(((IkReal(-1.00000000000000))*(cj11)*(x604)*(x607)))+(((r22)*(x606))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst78)*(((((x605)*(x606)))+(((IkReal(-1.00000000000000))*(cj11)*(r22)*(x607)))+(((sj11)*(sj13)*(x605)))+(((IkReal(-1.00000000000000))*(cj11)*(x603)*(x604)))+(((cj13)*(x602)))+(((IkReal(-1.00000000000000))*(sj11)*(x604)*(x607))))))) < IKFAST_ATAN2_MAGTHRESH )
02576     continue;
02577 j10array[0]=IKatan2(((gconst78)*(((((IkReal(-1.00000000000000))*(sj11)*(x603)*(x605)))+(((sj13)*(x602)))+(((cj13)*(sj11)*(x604)))+(((cj11)*(sj13)*(x605)))+(((IkReal(-1.00000000000000))*(cj11)*(x604)*(x607)))+(((r22)*(x606)))))), ((gconst78)*(((((x605)*(x606)))+(((IkReal(-1.00000000000000))*(cj11)*(r22)*(x607)))+(((sj11)*(sj13)*(x605)))+(((IkReal(-1.00000000000000))*(cj11)*(x603)*(x604)))+(((cj13)*(x602)))+(((IkReal(-1.00000000000000))*(sj11)*(x604)*(x607)))))));
02578 sj10array[0]=IKsin(j10array[0]);
02579 cj10array[0]=IKcos(j10array[0]);
02580 if( j10array[0] > IKPI )
02581 {
02582     j10array[0]-=IK2PI;
02583 }
02584 else if( j10array[0] < -IKPI )
02585 {    j10array[0]+=IK2PI;
02586 }
02587 j10valid[0] = true;
02588 for(int ij10 = 0; ij10 < 1; ++ij10)
02589 {
02590 if( !j10valid[ij10] )
02591 {
02592     continue;
02593 }
02594 _ij10[0] = ij10; _ij10[1] = -1;
02595 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
02596 {
02597 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
02598 {
02599     j10valid[iij10]=false; _ij10[1] = iij10; break; 
02600 }
02601 }
02602 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
02603 {
02604 IkReal evalcond[4];
02605 IkReal x608=IKsin(j10);
02606 IkReal x609=IKcos(j10);
02607 IkReal x610=((IkReal(1.00000000000000))*(sj13));
02608 IkReal x611=((r11)*(sj9));
02609 IkReal x612=((cj9)*(r01));
02610 IkReal x613=((IkReal(1.00000000000000))*(cj11));
02611 IkReal x614=((r21)*(sj14));
02612 IkReal x615=((cj9)*(r02));
02613 IkReal x616=((sj13)*(sj9));
02614 IkReal x617=((cj14)*(r10));
02615 IkReal x618=((IkReal(1.00000000000000))*(cj13));
02616 IkReal x619=((cj14)*(r20));
02617 IkReal x620=((sj11)*(x608));
02618 IkReal x621=((sj14)*(x618));
02619 IkReal x622=((sj11)*(x609));
02620 IkReal x623=((cj14)*(cj9)*(r00));
02621 IkReal x624=((x609)*(x613));
02622 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x610)))+(((IkReal(-1.00000000000000))*(x618)*(x619)))+(((IkReal(-1.00000000000000))*(x624)))+(x620)+(((cj13)*(x614))));
02623 evalcond[1]=((((IkReal(-1.00000000000000))*(x610)*(x619)))+(((sj13)*(x614)))+(((IkReal(-1.00000000000000))*(x622)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x608)*(x613))));
02624 evalcond[2]=((((cj13)*(x623)))+(((sj13)*(x615)))+(((cj11)*(x608)))+(((IkReal(-1.00000000000000))*(x611)*(x621)))+(((cj13)*(sj9)*(x617)))+(((r12)*(x616)))+(((IkReal(-1.00000000000000))*(x612)*(x621)))+(x622));
02625 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x610)*(x612)))+(((IkReal(-1.00000000000000))*(sj14)*(x610)*(x611)))+(((IkReal(-1.00000000000000))*(x624)))+(((x616)*(x617)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x618)))+(x620)+(((IkReal(-1.00000000000000))*(x615)*(x618)))+(((sj13)*(x623))));
02626 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02627 {
02628 continue;
02629 }
02630 }
02631 
02632 {
02633 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
02634 vinfos[0].jointtype = 1;
02635 vinfos[0].foffset = j9;
02636 vinfos[0].indices[0] = _ij9[0];
02637 vinfos[0].indices[1] = _ij9[1];
02638 vinfos[0].maxsolutions = _nj9;
02639 vinfos[1].jointtype = 1;
02640 vinfos[1].foffset = j10;
02641 vinfos[1].indices[0] = _ij10[0];
02642 vinfos[1].indices[1] = _ij10[1];
02643 vinfos[1].maxsolutions = _nj10;
02644 vinfos[2].jointtype = 1;
02645 vinfos[2].foffset = j11;
02646 vinfos[2].indices[0] = _ij11[0];
02647 vinfos[2].indices[1] = _ij11[1];
02648 vinfos[2].maxsolutions = _nj11;
02649 vinfos[3].jointtype = 1;
02650 vinfos[3].foffset = j12;
02651 vinfos[3].indices[0] = _ij12[0];
02652 vinfos[3].indices[1] = _ij12[1];
02653 vinfos[3].maxsolutions = _nj12;
02654 vinfos[4].jointtype = 1;
02655 vinfos[4].foffset = j13;
02656 vinfos[4].indices[0] = _ij13[0];
02657 vinfos[4].indices[1] = _ij13[1];
02658 vinfos[4].maxsolutions = _nj13;
02659 vinfos[5].jointtype = 1;
02660 vinfos[5].foffset = j14;
02661 vinfos[5].indices[0] = _ij14[0];
02662 vinfos[5].indices[1] = _ij14[1];
02663 vinfos[5].maxsolutions = _nj14;
02664 std::vector<int> vfree(0);
02665 solutions.AddSolution(vinfos,vfree);
02666 }
02667 }
02668 }
02669 
02670 }
02671 
02672 }
02673 }
02674 }
02675 
02676 }
02677 
02678 }
02679 }
02680 }
02681 
02682 } else
02683 {
02684 if( 1 )
02685 {
02686 continue;
02687 
02688 } else
02689 {
02690 }
02691 }
02692 }
02693 }
02694 
02695 } else
02696 {
02697 {
02698 IkReal j11array[1], cj11array[1], sj11array[1];
02699 bool j11valid[1]={false};
02700 _nj11 = 1;
02701 IkReal x625=((IkReal(4.00000000000000))*(sj14));
02702 IkReal x626=((IkReal(4.00000000000000))*(cj14));
02703 if( IKabs(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x626)))+(((IkReal(-1.00000000000000))*(npx)*(x625))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x626)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x625))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x626)))+(((IkReal(-1.00000000000000))*(npx)*(x625)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x626)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x625)))))-1) <= IKFAST_SINCOS_THRESH )
02704     continue;
02705 j11array[0]=IKatan2(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x626)))+(((IkReal(-1.00000000000000))*(npx)*(x625)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x626)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x625)))));
02706 sj11array[0]=IKsin(j11array[0]);
02707 cj11array[0]=IKcos(j11array[0]);
02708 if( j11array[0] > IKPI )
02709 {
02710     j11array[0]-=IK2PI;
02711 }
02712 else if( j11array[0] < -IKPI )
02713 {    j11array[0]+=IK2PI;
02714 }
02715 j11valid[0] = true;
02716 for(int ij11 = 0; ij11 < 1; ++ij11)
02717 {
02718 if( !j11valid[ij11] )
02719 {
02720     continue;
02721 }
02722 _ij11[0] = ij11; _ij11[1] = -1;
02723 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
02724 {
02725 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
02726 {
02727     j11valid[iij11]=false; _ij11[1] = iij11; break; 
02728 }
02729 }
02730 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
02731 {
02732 IkReal evalcond[3];
02733 IkReal x627=IKsin(j11);
02734 IkReal x628=((IkReal(1.00000000000000))*(sj13));
02735 IkReal x629=((cj14)*(npx));
02736 IkReal x630=((npy)*(sj14));
02737 IkReal x631=((IkReal(0.250000000000000))*(x627));
02738 evalcond[0]=((((IkReal(0.0950000000000000))*(cj12)))+(((cj14)*(npy)))+(((IkReal(-0.0300000000000000))*(sj12)))+(((npx)*(sj14)))+(((sj12)*(x631))));
02739 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(cj13)*(x629)))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x630)))+(((IkReal(-1.00000000000000))*(npz)*(x628))));
02740 evalcond[2]=((((IkReal(0.0950000000000000))*(sj12)))+(((IkReal(-1.00000000000000))*(x628)*(x629)))+(((cj13)*(npz)))+(((IkReal(0.0300000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(cj12)*(x631)))+(((IkReal(0.0900000000000000))*(sj13)))+(((sj13)*(x630))));
02741 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
02742 {
02743 continue;
02744 }
02745 }
02746 
02747 {
02748 IkReal dummyeval[1];
02749 IkReal gconst4;
02750 gconst4=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
02751 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
02752 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02753 {
02754 {
02755 IkReal dummyeval[1];
02756 IkReal gconst5;
02757 gconst5=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
02758 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
02759 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02760 {
02761 {
02762 IkReal dummyeval[1];
02763 IkReal gconst2;
02764 IkReal x632=(cj14)*(cj14);
02765 IkReal x633=(sj14)*(sj14);
02766 IkReal x634=((IkReal(1.00000000000000))*(r01));
02767 IkReal x635=((sj13)*(sj14));
02768 IkReal x636=((cj14)*(sj13));
02769 IkReal x637=((r00)*(r11));
02770 IkReal x638=((cj13)*(x632));
02771 IkReal x639=((cj13)*(x633));
02772 gconst2=IKsign(((((r02)*(r11)*(x636)))+(((r02)*(r10)*(x635)))+(((IkReal(-1.00000000000000))*(r12)*(x634)*(x636)))+(((IkReal(-1.00000000000000))*(r10)*(x634)*(x639)))+(((IkReal(-1.00000000000000))*(r10)*(x634)*(x638)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x635)))+(((x637)*(x639)))+(((x637)*(x638)))));
02773 IkReal x640=(cj14)*(cj14);
02774 IkReal x641=(sj14)*(sj14);
02775 IkReal x642=((IkReal(1.00000000000000))*(r01));
02776 IkReal x643=((sj13)*(sj14));
02777 IkReal x644=((cj14)*(sj13));
02778 IkReal x645=((r00)*(r11));
02779 IkReal x646=((cj13)*(x640));
02780 IkReal x647=((cj13)*(x641));
02781 dummyeval[0]=((((r02)*(r10)*(x643)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x643)))+(((IkReal(-1.00000000000000))*(r12)*(x642)*(x644)))+(((x645)*(x647)))+(((x645)*(x646)))+(((IkReal(-1.00000000000000))*(r10)*(x642)*(x647)))+(((IkReal(-1.00000000000000))*(r10)*(x642)*(x646)))+(((r02)*(r11)*(x644))));
02782 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02783 {
02784 {
02785 IkReal evalcond[5];
02786 IkReal x648=((IkReal(1.00000000000000))*(sj13));
02787 IkReal x649=((npy)*(sj14));
02788 IkReal x650=((IkReal(1.00000000000000))*(cj14)*(npx));
02789 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
02790 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
02791 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x648)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x650)))+(((cj13)*(x649))));
02792 evalcond[3]=((((r21)*(sj13)*(sj14)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x648)))+(((cj13)*(r22))));
02793 evalcond[4]=((IkReal(0.0950000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x648)))+(((sj13)*(x649)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
02794 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  )
02795 {
02796 {
02797 IkReal dummyeval[1];
02798 IkReal gconst20;
02799 gconst20=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
02800 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
02801 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02802 {
02803 {
02804 IkReal dummyeval[1];
02805 IkReal gconst18;
02806 IkReal x651=(sj14)*(sj14);
02807 IkReal x652=(cj14)*(cj14);
02808 IkReal x653=((r01)*(r10));
02809 IkReal x654=((cj13)*(cj14));
02810 IkReal x655=((IkReal(1.00000000000000))*(r12));
02811 IkReal x656=((cj13)*(sj14));
02812 IkReal x657=((sj13)*(x651));
02813 IkReal x658=((IkReal(1.00000000000000))*(r00)*(r11));
02814 IkReal x659=((sj13)*(x652));
02815 gconst18=IKsign(((((IkReal(-1.00000000000000))*(r00)*(x655)*(x656)))+(((IkReal(-1.00000000000000))*(x657)*(x658)))+(((x653)*(x657)))+(((x653)*(x659)))+(((r02)*(r10)*(x656)))+(((IkReal(-1.00000000000000))*(r01)*(x654)*(x655)))+(((IkReal(-1.00000000000000))*(x658)*(x659)))+(((r02)*(r11)*(x654)))));
02816 IkReal x660=(sj14)*(sj14);
02817 IkReal x661=(cj14)*(cj14);
02818 IkReal x662=((r01)*(r10));
02819 IkReal x663=((cj13)*(cj14));
02820 IkReal x664=((IkReal(1.00000000000000))*(r12));
02821 IkReal x665=((cj13)*(sj14));
02822 IkReal x666=((sj13)*(x660));
02823 IkReal x667=((IkReal(1.00000000000000))*(r00)*(r11));
02824 IkReal x668=((sj13)*(x661));
02825 dummyeval[0]=((((x662)*(x668)))+(((x662)*(x666)))+(((IkReal(-1.00000000000000))*(r01)*(x663)*(x664)))+(((IkReal(-1.00000000000000))*(r00)*(x664)*(x665)))+(((r02)*(r11)*(x663)))+(((IkReal(-1.00000000000000))*(x666)*(x667)))+(((IkReal(-1.00000000000000))*(x667)*(x668)))+(((r02)*(r10)*(x665))));
02826 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02827 {
02828 {
02829 IkReal dummyeval[1];
02830 IkReal gconst19;
02831 IkReal x669=(sj13)*(sj13);
02832 IkReal x670=(cj13)*(cj13);
02833 IkReal x671=((cj14)*(r00));
02834 IkReal x672=((r11)*(sj14));
02835 IkReal x673=((r12)*(x670));
02836 IkReal x674=((IkReal(1.00000000000000))*(r01)*(sj14));
02837 IkReal x675=((r02)*(x669));
02838 IkReal x676=((IkReal(1.00000000000000))*(cj14)*(r10));
02839 IkReal x677=((r12)*(x669));
02840 IkReal x678=((r02)*(x670));
02841 gconst19=IKsign(((((x672)*(x675)))+(((x672)*(x678)))+(((IkReal(-1.00000000000000))*(x675)*(x676)))+(((x671)*(x673)))+(((x671)*(x677)))+(((IkReal(-1.00000000000000))*(x676)*(x678)))+(((IkReal(-1.00000000000000))*(x674)*(x677)))+(((IkReal(-1.00000000000000))*(x673)*(x674)))));
02842 IkReal x679=(sj13)*(sj13);
02843 IkReal x680=(cj13)*(cj13);
02844 IkReal x681=((cj14)*(r00));
02845 IkReal x682=((r11)*(sj14));
02846 IkReal x683=((r12)*(x680));
02847 IkReal x684=((IkReal(1.00000000000000))*(r01)*(sj14));
02848 IkReal x685=((r02)*(x679));
02849 IkReal x686=((IkReal(1.00000000000000))*(cj14)*(r10));
02850 IkReal x687=((r12)*(x679));
02851 IkReal x688=((r02)*(x680));
02852 dummyeval[0]=((((IkReal(-1.00000000000000))*(x685)*(x686)))+(((x682)*(x688)))+(((x682)*(x685)))+(((IkReal(-1.00000000000000))*(x686)*(x688)))+(((IkReal(-1.00000000000000))*(x684)*(x687)))+(((x681)*(x683)))+(((x681)*(x687)))+(((IkReal(-1.00000000000000))*(x683)*(x684))));
02853 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02854 {
02855 continue;
02856 
02857 } else
02858 {
02859 {
02860 IkReal j9array[1], cj9array[1], sj9array[1];
02861 bool j9valid[1]={false};
02862 _nj9 = 1;
02863 IkReal x689=((cj13)*(cj14));
02864 IkReal x690=((IkReal(1.00000000000000))*(cj13)*(sj14));
02865 if( IKabs(((gconst19)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x690)))+(((r10)*(x689))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst19)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x690)))+(((r00)*(x689))))))) < IKFAST_ATAN2_MAGTHRESH )
02866     continue;
02867 j9array[0]=IKatan2(((gconst19)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x690)))+(((r10)*(x689)))))), ((gconst19)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x690)))+(((r00)*(x689)))))));
02868 sj9array[0]=IKsin(j9array[0]);
02869 cj9array[0]=IKcos(j9array[0]);
02870 if( j9array[0] > IKPI )
02871 {
02872     j9array[0]-=IK2PI;
02873 }
02874 else if( j9array[0] < -IKPI )
02875 {    j9array[0]+=IK2PI;
02876 }
02877 j9valid[0] = true;
02878 for(int ij9 = 0; ij9 < 1; ++ij9)
02879 {
02880 if( !j9valid[ij9] )
02881 {
02882     continue;
02883 }
02884 _ij9[0] = ij9; _ij9[1] = -1;
02885 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
02886 {
02887 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
02888 {
02889     j9valid[iij9]=false; _ij9[1] = iij9; break; 
02890 }
02891 }
02892 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
02893 {
02894 IkReal evalcond[4];
02895 IkReal x691=IKsin(j9);
02896 IkReal x692=IKcos(j9);
02897 IkReal x693=((IkReal(1.00000000000000))*(sj14));
02898 IkReal x694=((cj13)*(cj14));
02899 IkReal x695=((IkReal(1.00000000000000))*(r00));
02900 IkReal x696=((r01)*(sj14));
02901 IkReal x697=((IkReal(1.00000000000000))*(cj13));
02902 IkReal x698=((sj13)*(x692));
02903 IkReal x699=((r02)*(x691));
02904 IkReal x700=((r10)*(x692));
02905 IkReal x701=((r11)*(x692));
02906 IkReal x702=((sj13)*(x691));
02907 IkReal x703=((cj14)*(x702));
02908 evalcond[0]=((((IkReal(-1.00000000000000))*(x693)*(x700)))+(((r00)*(sj14)*(x691)))+(((cj14)*(r01)*(x691)))+(((IkReal(-1.00000000000000))*(cj14)*(x701))));
02909 evalcond[1]=((((IkReal(-1.00000000000000))*(x691)*(x694)*(x695)))+(((x694)*(x700)))+(((IkReal(-1.00000000000000))*(sj13)*(x699)))+(((r12)*(x698)))+(((cj13)*(x691)*(x696)))+(((IkReal(-1.00000000000000))*(cj13)*(x693)*(x701))));
02910 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x693)*(x698)))+(((IkReal(-1.00000000000000))*(x695)*(x703)))+(((cj13)*(x699)))+(((cj14)*(r10)*(x698)))+(((IkReal(-1.00000000000000))*(r12)*(x692)*(x697)))+(((x696)*(x702))));
02911 evalcond[3]=((((cj14)*(r00)*(x698)))+(((IkReal(-1.00000000000000))*(r02)*(x692)*(x697)))+(((IkReal(-1.00000000000000))*(r01)*(x693)*(x698)))+(((IkReal(-1.00000000000000))*(r12)*(x691)*(x697)))+(((IkReal(-1.00000000000000))*(r11)*(x693)*(x702)))+(((r10)*(x703))));
02912 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02913 {
02914 continue;
02915 }
02916 }
02917 
02918 {
02919 IkReal dummyeval[1];
02920 IkReal gconst21;
02921 gconst21=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
02922 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
02923 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02924 {
02925 {
02926 IkReal dummyeval[1];
02927 IkReal gconst22;
02928 gconst22=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
02929 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
02930 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02931 {
02932 continue;
02933 
02934 } else
02935 {
02936 {
02937 IkReal j10array[1], cj10array[1], sj10array[1];
02938 bool j10valid[1]={false};
02939 _nj10 = 1;
02940 IkReal x704=((IkReal(1.00000000000000))*(cj11));
02941 IkReal x705=((r20)*(sj14));
02942 IkReal x706=((cj14)*(r21));
02943 IkReal x707=((cj14)*(cj9)*(r01));
02944 IkReal x708=((r10)*(sj14)*(sj9));
02945 IkReal x709=((cj9)*(r00)*(sj14));
02946 IkReal x710=((cj14)*(r11)*(sj9));
02947 if( IKabs(((gconst22)*(((((sj11)*(x708)))+(((sj11)*(x709)))+(((sj11)*(x707)))+(((sj11)*(x710)))+(((cj11)*(x706)))+(((cj11)*(x705))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst22)*(((((sj11)*(x705)))+(((sj11)*(x706)))+(((IkReal(-1.00000000000000))*(x704)*(x710)))+(((IkReal(-1.00000000000000))*(x704)*(x707)))+(((IkReal(-1.00000000000000))*(x704)*(x709)))+(((IkReal(-1.00000000000000))*(x704)*(x708))))))) < IKFAST_ATAN2_MAGTHRESH )
02948     continue;
02949 j10array[0]=IKatan2(((gconst22)*(((((sj11)*(x708)))+(((sj11)*(x709)))+(((sj11)*(x707)))+(((sj11)*(x710)))+(((cj11)*(x706)))+(((cj11)*(x705)))))), ((gconst22)*(((((sj11)*(x705)))+(((sj11)*(x706)))+(((IkReal(-1.00000000000000))*(x704)*(x710)))+(((IkReal(-1.00000000000000))*(x704)*(x707)))+(((IkReal(-1.00000000000000))*(x704)*(x709)))+(((IkReal(-1.00000000000000))*(x704)*(x708)))))));
02950 sj10array[0]=IKsin(j10array[0]);
02951 cj10array[0]=IKcos(j10array[0]);
02952 if( j10array[0] > IKPI )
02953 {
02954     j10array[0]-=IK2PI;
02955 }
02956 else if( j10array[0] < -IKPI )
02957 {    j10array[0]+=IK2PI;
02958 }
02959 j10valid[0] = true;
02960 for(int ij10 = 0; ij10 < 1; ++ij10)
02961 {
02962 if( !j10valid[ij10] )
02963 {
02964     continue;
02965 }
02966 _ij10[0] = ij10; _ij10[1] = -1;
02967 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
02968 {
02969 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
02970 {
02971     j10valid[iij10]=false; _ij10[1] = iij10; break; 
02972 }
02973 }
02974 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
02975 {
02976 IkReal evalcond[4];
02977 IkReal x711=IKsin(j10);
02978 IkReal x712=IKcos(j10);
02979 IkReal x713=((cj13)*(sj14));
02980 IkReal x714=((cj13)*(cj14));
02981 IkReal x715=((r10)*(sj9));
02982 IkReal x716=((IkReal(1.00000000000000))*(cj9));
02983 IkReal x717=((sj11)*(x711));
02984 IkReal x718=((IkReal(1.00000000000000))*(x712));
02985 IkReal x719=((cj11)*(x711));
02986 IkReal x720=((IkReal(1.00000000000000))*(r11)*(sj9));
02987 IkReal x721=((cj11)*(x718));
02988 evalcond[0]=((((IkReal(-1.00000000000000))*(sj11)*(x718)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x719))));
02989 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x714)))+(((IkReal(-1.00000000000000))*(x721)))+(((r21)*(x713)))+(x717));
02990 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x720)))+(((IkReal(-1.00000000000000))*(x721)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x716)))+(((IkReal(-1.00000000000000))*(sj14)*(x715)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x716)))+(x717));
02991 evalcond[3]=((((IkReal(-1.00000000000000))*(x713)*(x720)))+(((x714)*(x715)))+(((sj11)*(x712)))+(((IkReal(-1.00000000000000))*(r01)*(x713)*(x716)))+(((cj9)*(r00)*(x714)))+(((cj9)*(r02)*(sj13)))+(x719)+(((r12)*(sj13)*(sj9))));
02992 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02993 {
02994 continue;
02995 }
02996 }
02997 
02998 {
02999 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03000 vinfos[0].jointtype = 1;
03001 vinfos[0].foffset = j9;
03002 vinfos[0].indices[0] = _ij9[0];
03003 vinfos[0].indices[1] = _ij9[1];
03004 vinfos[0].maxsolutions = _nj9;
03005 vinfos[1].jointtype = 1;
03006 vinfos[1].foffset = j10;
03007 vinfos[1].indices[0] = _ij10[0];
03008 vinfos[1].indices[1] = _ij10[1];
03009 vinfos[1].maxsolutions = _nj10;
03010 vinfos[2].jointtype = 1;
03011 vinfos[2].foffset = j11;
03012 vinfos[2].indices[0] = _ij11[0];
03013 vinfos[2].indices[1] = _ij11[1];
03014 vinfos[2].maxsolutions = _nj11;
03015 vinfos[3].jointtype = 1;
03016 vinfos[3].foffset = j12;
03017 vinfos[3].indices[0] = _ij12[0];
03018 vinfos[3].indices[1] = _ij12[1];
03019 vinfos[3].maxsolutions = _nj12;
03020 vinfos[4].jointtype = 1;
03021 vinfos[4].foffset = j13;
03022 vinfos[4].indices[0] = _ij13[0];
03023 vinfos[4].indices[1] = _ij13[1];
03024 vinfos[4].maxsolutions = _nj13;
03025 vinfos[5].jointtype = 1;
03026 vinfos[5].foffset = j14;
03027 vinfos[5].indices[0] = _ij14[0];
03028 vinfos[5].indices[1] = _ij14[1];
03029 vinfos[5].maxsolutions = _nj14;
03030 std::vector<int> vfree(0);
03031 solutions.AddSolution(vinfos,vfree);
03032 }
03033 }
03034 }
03035 
03036 }
03037 
03038 }
03039 
03040 } else
03041 {
03042 {
03043 IkReal j10array[1], cj10array[1], sj10array[1];
03044 bool j10valid[1]={false};
03045 _nj10 = 1;
03046 IkReal x722=((cj11)*(r20));
03047 IkReal x723=((IkReal(1.00000000000000))*(cj13));
03048 IkReal x724=((r21)*(sj14));
03049 IkReal x725=((r22)*(sj13));
03050 IkReal x726=((cj14)*(sj11));
03051 if( IKabs(((gconst21)*(((((sj14)*(x722)))+(((cj11)*(cj14)*(r21)))+(((cj13)*(r20)*(x726)))+(((IkReal(-1.00000000000000))*(sj11)*(x723)*(x724)))+(((sj11)*(x725))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(cj11)*(x725)))+(((cj11)*(cj13)*(x724)))+(((r20)*(sj11)*(sj14)))+(((r21)*(x726)))+(((IkReal(-1.00000000000000))*(cj14)*(x722)*(x723))))))) < IKFAST_ATAN2_MAGTHRESH )
03052     continue;
03053 j10array[0]=IKatan2(((gconst21)*(((((sj14)*(x722)))+(((cj11)*(cj14)*(r21)))+(((cj13)*(r20)*(x726)))+(((IkReal(-1.00000000000000))*(sj11)*(x723)*(x724)))+(((sj11)*(x725)))))), ((gconst21)*(((((IkReal(-1.00000000000000))*(cj11)*(x725)))+(((cj11)*(cj13)*(x724)))+(((r20)*(sj11)*(sj14)))+(((r21)*(x726)))+(((IkReal(-1.00000000000000))*(cj14)*(x722)*(x723)))))));
03054 sj10array[0]=IKsin(j10array[0]);
03055 cj10array[0]=IKcos(j10array[0]);
03056 if( j10array[0] > IKPI )
03057 {
03058     j10array[0]-=IK2PI;
03059 }
03060 else if( j10array[0] < -IKPI )
03061 {    j10array[0]+=IK2PI;
03062 }
03063 j10valid[0] = true;
03064 for(int ij10 = 0; ij10 < 1; ++ij10)
03065 {
03066 if( !j10valid[ij10] )
03067 {
03068     continue;
03069 }
03070 _ij10[0] = ij10; _ij10[1] = -1;
03071 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
03072 {
03073 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
03074 {
03075     j10valid[iij10]=false; _ij10[1] = iij10; break; 
03076 }
03077 }
03078 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
03079 {
03080 IkReal evalcond[4];
03081 IkReal x727=IKsin(j10);
03082 IkReal x728=IKcos(j10);
03083 IkReal x729=((cj13)*(sj14));
03084 IkReal x730=((cj13)*(cj14));
03085 IkReal x731=((r10)*(sj9));
03086 IkReal x732=((IkReal(1.00000000000000))*(cj9));
03087 IkReal x733=((sj11)*(x727));
03088 IkReal x734=((IkReal(1.00000000000000))*(x728));
03089 IkReal x735=((cj11)*(x727));
03090 IkReal x736=((IkReal(1.00000000000000))*(r11)*(sj9));
03091 IkReal x737=((cj11)*(x734));
03092 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x734)))+(((IkReal(-1.00000000000000))*(x735))));
03093 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x730)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x737)))+(x733)+(((r21)*(x729))));
03094 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x736)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x732)))+(((IkReal(-1.00000000000000))*(sj14)*(x731)))+(((IkReal(-1.00000000000000))*(x737)))+(x733)+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x732))));
03095 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x729)*(x732)))+(((cj9)*(r00)*(x730)))+(((cj9)*(r02)*(sj13)))+(x735)+(((r12)*(sj13)*(sj9)))+(((sj11)*(x728)))+(((IkReal(-1.00000000000000))*(x729)*(x736)))+(((x730)*(x731))));
03096 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03097 {
03098 continue;
03099 }
03100 }
03101 
03102 {
03103 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03104 vinfos[0].jointtype = 1;
03105 vinfos[0].foffset = j9;
03106 vinfos[0].indices[0] = _ij9[0];
03107 vinfos[0].indices[1] = _ij9[1];
03108 vinfos[0].maxsolutions = _nj9;
03109 vinfos[1].jointtype = 1;
03110 vinfos[1].foffset = j10;
03111 vinfos[1].indices[0] = _ij10[0];
03112 vinfos[1].indices[1] = _ij10[1];
03113 vinfos[1].maxsolutions = _nj10;
03114 vinfos[2].jointtype = 1;
03115 vinfos[2].foffset = j11;
03116 vinfos[2].indices[0] = _ij11[0];
03117 vinfos[2].indices[1] = _ij11[1];
03118 vinfos[2].maxsolutions = _nj11;
03119 vinfos[3].jointtype = 1;
03120 vinfos[3].foffset = j12;
03121 vinfos[3].indices[0] = _ij12[0];
03122 vinfos[3].indices[1] = _ij12[1];
03123 vinfos[3].maxsolutions = _nj12;
03124 vinfos[4].jointtype = 1;
03125 vinfos[4].foffset = j13;
03126 vinfos[4].indices[0] = _ij13[0];
03127 vinfos[4].indices[1] = _ij13[1];
03128 vinfos[4].maxsolutions = _nj13;
03129 vinfos[5].jointtype = 1;
03130 vinfos[5].foffset = j14;
03131 vinfos[5].indices[0] = _ij14[0];
03132 vinfos[5].indices[1] = _ij14[1];
03133 vinfos[5].maxsolutions = _nj14;
03134 std::vector<int> vfree(0);
03135 solutions.AddSolution(vinfos,vfree);
03136 }
03137 }
03138 }
03139 
03140 }
03141 
03142 }
03143 }
03144 }
03145 
03146 }
03147 
03148 }
03149 
03150 } else
03151 {
03152 {
03153 IkReal j9array[1], cj9array[1], sj9array[1];
03154 bool j9valid[1]={false};
03155 _nj9 = 1;
03156 IkReal x738=((IkReal(1.00000000000000))*(cj14));
03157 IkReal x739=((IkReal(1.00000000000000))*(sj14));
03158 if( IKabs(((gconst18)*(((((IkReal(-1.00000000000000))*(r10)*(x739)))+(((IkReal(-1.00000000000000))*(r11)*(x738))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst18)*(((((IkReal(-1.00000000000000))*(r01)*(x738)))+(((IkReal(-1.00000000000000))*(r00)*(x739))))))) < IKFAST_ATAN2_MAGTHRESH )
03159     continue;
03160 j9array[0]=IKatan2(((gconst18)*(((((IkReal(-1.00000000000000))*(r10)*(x739)))+(((IkReal(-1.00000000000000))*(r11)*(x738)))))), ((gconst18)*(((((IkReal(-1.00000000000000))*(r01)*(x738)))+(((IkReal(-1.00000000000000))*(r00)*(x739)))))));
03161 sj9array[0]=IKsin(j9array[0]);
03162 cj9array[0]=IKcos(j9array[0]);
03163 if( j9array[0] > IKPI )
03164 {
03165     j9array[0]-=IK2PI;
03166 }
03167 else if( j9array[0] < -IKPI )
03168 {    j9array[0]+=IK2PI;
03169 }
03170 j9valid[0] = true;
03171 for(int ij9 = 0; ij9 < 1; ++ij9)
03172 {
03173 if( !j9valid[ij9] )
03174 {
03175     continue;
03176 }
03177 _ij9[0] = ij9; _ij9[1] = -1;
03178 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
03179 {
03180 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
03181 {
03182     j9valid[iij9]=false; _ij9[1] = iij9; break; 
03183 }
03184 }
03185 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
03186 {
03187 IkReal evalcond[4];
03188 IkReal x740=IKsin(j9);
03189 IkReal x741=IKcos(j9);
03190 IkReal x742=((IkReal(1.00000000000000))*(sj14));
03191 IkReal x743=((cj13)*(cj14));
03192 IkReal x744=((IkReal(1.00000000000000))*(r00));
03193 IkReal x745=((r01)*(sj14));
03194 IkReal x746=((IkReal(1.00000000000000))*(cj13));
03195 IkReal x747=((sj13)*(x741));
03196 IkReal x748=((r02)*(x740));
03197 IkReal x749=((r10)*(x741));
03198 IkReal x750=((r11)*(x741));
03199 IkReal x751=((sj13)*(x740));
03200 IkReal x752=((cj14)*(x751));
03201 evalcond[0]=((((cj14)*(r01)*(x740)))+(((r00)*(sj14)*(x740)))+(((IkReal(-1.00000000000000))*(x742)*(x749)))+(((IkReal(-1.00000000000000))*(cj14)*(x750))));
03202 evalcond[1]=((((IkReal(-1.00000000000000))*(x740)*(x743)*(x744)))+(((cj13)*(x740)*(x745)))+(((IkReal(-1.00000000000000))*(sj13)*(x748)))+(((x743)*(x749)))+(((r12)*(x747)))+(((IkReal(-1.00000000000000))*(cj13)*(x742)*(x750))));
03203 evalcond[2]=((IkReal(1.00000000000000))+(((x745)*(x751)))+(((IkReal(-1.00000000000000))*(r11)*(x742)*(x747)))+(((cj13)*(x748)))+(((cj14)*(r10)*(x747)))+(((IkReal(-1.00000000000000))*(r12)*(x741)*(x746)))+(((IkReal(-1.00000000000000))*(x744)*(x752))));
03204 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x742)*(x747)))+(((IkReal(-1.00000000000000))*(r12)*(x740)*(x746)))+(((r10)*(x752)))+(((IkReal(-1.00000000000000))*(r11)*(x742)*(x751)))+(((IkReal(-1.00000000000000))*(r02)*(x741)*(x746)))+(((cj14)*(r00)*(x747))));
03205 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03206 {
03207 continue;
03208 }
03209 }
03210 
03211 {
03212 IkReal dummyeval[1];
03213 IkReal gconst21;
03214 gconst21=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
03215 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
03216 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03217 {
03218 {
03219 IkReal dummyeval[1];
03220 IkReal gconst22;
03221 gconst22=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
03222 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
03223 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03224 {
03225 continue;
03226 
03227 } else
03228 {
03229 {
03230 IkReal j10array[1], cj10array[1], sj10array[1];
03231 bool j10valid[1]={false};
03232 _nj10 = 1;
03233 IkReal x753=((IkReal(1.00000000000000))*(cj11));
03234 IkReal x754=((r20)*(sj14));
03235 IkReal x755=((cj14)*(r21));
03236 IkReal x756=((cj14)*(cj9)*(r01));
03237 IkReal x757=((r10)*(sj14)*(sj9));
03238 IkReal x758=((cj9)*(r00)*(sj14));
03239 IkReal x759=((cj14)*(r11)*(sj9));
03240 if( IKabs(((gconst22)*(((((cj11)*(x755)))+(((cj11)*(x754)))+(((sj11)*(x756)))+(((sj11)*(x757)))+(((sj11)*(x758)))+(((sj11)*(x759))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst22)*(((((IkReal(-1.00000000000000))*(x753)*(x757)))+(((IkReal(-1.00000000000000))*(x753)*(x756)))+(((IkReal(-1.00000000000000))*(x753)*(x758)))+(((IkReal(-1.00000000000000))*(x753)*(x759)))+(((sj11)*(x754)))+(((sj11)*(x755))))))) < IKFAST_ATAN2_MAGTHRESH )
03241     continue;
03242 j10array[0]=IKatan2(((gconst22)*(((((cj11)*(x755)))+(((cj11)*(x754)))+(((sj11)*(x756)))+(((sj11)*(x757)))+(((sj11)*(x758)))+(((sj11)*(x759)))))), ((gconst22)*(((((IkReal(-1.00000000000000))*(x753)*(x757)))+(((IkReal(-1.00000000000000))*(x753)*(x756)))+(((IkReal(-1.00000000000000))*(x753)*(x758)))+(((IkReal(-1.00000000000000))*(x753)*(x759)))+(((sj11)*(x754)))+(((sj11)*(x755)))))));
03243 sj10array[0]=IKsin(j10array[0]);
03244 cj10array[0]=IKcos(j10array[0]);
03245 if( j10array[0] > IKPI )
03246 {
03247     j10array[0]-=IK2PI;
03248 }
03249 else if( j10array[0] < -IKPI )
03250 {    j10array[0]+=IK2PI;
03251 }
03252 j10valid[0] = true;
03253 for(int ij10 = 0; ij10 < 1; ++ij10)
03254 {
03255 if( !j10valid[ij10] )
03256 {
03257     continue;
03258 }
03259 _ij10[0] = ij10; _ij10[1] = -1;
03260 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
03261 {
03262 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
03263 {
03264     j10valid[iij10]=false; _ij10[1] = iij10; break; 
03265 }
03266 }
03267 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
03268 {
03269 IkReal evalcond[4];
03270 IkReal x760=IKsin(j10);
03271 IkReal x761=IKcos(j10);
03272 IkReal x762=((cj13)*(sj14));
03273 IkReal x763=((cj13)*(cj14));
03274 IkReal x764=((r10)*(sj9));
03275 IkReal x765=((IkReal(1.00000000000000))*(cj9));
03276 IkReal x766=((sj11)*(x760));
03277 IkReal x767=((IkReal(1.00000000000000))*(x761));
03278 IkReal x768=((cj11)*(x760));
03279 IkReal x769=((IkReal(1.00000000000000))*(r11)*(sj9));
03280 IkReal x770=((cj11)*(x767));
03281 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x768)))+(((IkReal(-1.00000000000000))*(sj11)*(x767))));
03282 evalcond[1]=((((r21)*(x762)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x763)))+(x766)+(((IkReal(-1.00000000000000))*(x770))));
03283 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj14)*(x765)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x765)))+(((IkReal(-1.00000000000000))*(cj14)*(x769)))+(x766)+(((IkReal(-1.00000000000000))*(x770)))+(((IkReal(-1.00000000000000))*(sj14)*(x764))));
03284 evalcond[3]=((((sj11)*(x761)))+(((cj9)*(r00)*(x763)))+(((IkReal(-1.00000000000000))*(x762)*(x769)))+(((cj9)*(r02)*(sj13)))+(((x763)*(x764)))+(((IkReal(-1.00000000000000))*(r01)*(x762)*(x765)))+(x768)+(((r12)*(sj13)*(sj9))));
03285 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03286 {
03287 continue;
03288 }
03289 }
03290 
03291 {
03292 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03293 vinfos[0].jointtype = 1;
03294 vinfos[0].foffset = j9;
03295 vinfos[0].indices[0] = _ij9[0];
03296 vinfos[0].indices[1] = _ij9[1];
03297 vinfos[0].maxsolutions = _nj9;
03298 vinfos[1].jointtype = 1;
03299 vinfos[1].foffset = j10;
03300 vinfos[1].indices[0] = _ij10[0];
03301 vinfos[1].indices[1] = _ij10[1];
03302 vinfos[1].maxsolutions = _nj10;
03303 vinfos[2].jointtype = 1;
03304 vinfos[2].foffset = j11;
03305 vinfos[2].indices[0] = _ij11[0];
03306 vinfos[2].indices[1] = _ij11[1];
03307 vinfos[2].maxsolutions = _nj11;
03308 vinfos[3].jointtype = 1;
03309 vinfos[3].foffset = j12;
03310 vinfos[3].indices[0] = _ij12[0];
03311 vinfos[3].indices[1] = _ij12[1];
03312 vinfos[3].maxsolutions = _nj12;
03313 vinfos[4].jointtype = 1;
03314 vinfos[4].foffset = j13;
03315 vinfos[4].indices[0] = _ij13[0];
03316 vinfos[4].indices[1] = _ij13[1];
03317 vinfos[4].maxsolutions = _nj13;
03318 vinfos[5].jointtype = 1;
03319 vinfos[5].foffset = j14;
03320 vinfos[5].indices[0] = _ij14[0];
03321 vinfos[5].indices[1] = _ij14[1];
03322 vinfos[5].maxsolutions = _nj14;
03323 std::vector<int> vfree(0);
03324 solutions.AddSolution(vinfos,vfree);
03325 }
03326 }
03327 }
03328 
03329 }
03330 
03331 }
03332 
03333 } else
03334 {
03335 {
03336 IkReal j10array[1], cj10array[1], sj10array[1];
03337 bool j10valid[1]={false};
03338 _nj10 = 1;
03339 IkReal x771=((cj11)*(r20));
03340 IkReal x772=((IkReal(1.00000000000000))*(cj13));
03341 IkReal x773=((r21)*(sj14));
03342 IkReal x774=((r22)*(sj13));
03343 IkReal x775=((cj14)*(sj11));
03344 if( IKabs(((gconst21)*(((((cj11)*(cj14)*(r21)))+(((cj13)*(r20)*(x775)))+(((sj11)*(x774)))+(((IkReal(-1.00000000000000))*(sj11)*(x772)*(x773)))+(((sj14)*(x771))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst21)*(((((IkReal(-1.00000000000000))*(cj11)*(x774)))+(((cj11)*(cj13)*(x773)))+(((r21)*(x775)))+(((r20)*(sj11)*(sj14)))+(((IkReal(-1.00000000000000))*(cj14)*(x771)*(x772))))))) < IKFAST_ATAN2_MAGTHRESH )
03345     continue;
03346 j10array[0]=IKatan2(((gconst21)*(((((cj11)*(cj14)*(r21)))+(((cj13)*(r20)*(x775)))+(((sj11)*(x774)))+(((IkReal(-1.00000000000000))*(sj11)*(x772)*(x773)))+(((sj14)*(x771)))))), ((gconst21)*(((((IkReal(-1.00000000000000))*(cj11)*(x774)))+(((cj11)*(cj13)*(x773)))+(((r21)*(x775)))+(((r20)*(sj11)*(sj14)))+(((IkReal(-1.00000000000000))*(cj14)*(x771)*(x772)))))));
03347 sj10array[0]=IKsin(j10array[0]);
03348 cj10array[0]=IKcos(j10array[0]);
03349 if( j10array[0] > IKPI )
03350 {
03351     j10array[0]-=IK2PI;
03352 }
03353 else if( j10array[0] < -IKPI )
03354 {    j10array[0]+=IK2PI;
03355 }
03356 j10valid[0] = true;
03357 for(int ij10 = 0; ij10 < 1; ++ij10)
03358 {
03359 if( !j10valid[ij10] )
03360 {
03361     continue;
03362 }
03363 _ij10[0] = ij10; _ij10[1] = -1;
03364 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
03365 {
03366 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
03367 {
03368     j10valid[iij10]=false; _ij10[1] = iij10; break; 
03369 }
03370 }
03371 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
03372 {
03373 IkReal evalcond[4];
03374 IkReal x776=IKsin(j10);
03375 IkReal x777=IKcos(j10);
03376 IkReal x778=((cj13)*(sj14));
03377 IkReal x779=((cj13)*(cj14));
03378 IkReal x780=((r10)*(sj9));
03379 IkReal x781=((IkReal(1.00000000000000))*(cj9));
03380 IkReal x782=((sj11)*(x776));
03381 IkReal x783=((IkReal(1.00000000000000))*(x777));
03382 IkReal x784=((cj11)*(x776));
03383 IkReal x785=((IkReal(1.00000000000000))*(r11)*(sj9));
03384 IkReal x786=((cj11)*(x783));
03385 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x784)))+(((IkReal(-1.00000000000000))*(sj11)*(x783))));
03386 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x779)))+(((IkReal(-1.00000000000000))*(x786)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x778)))+(x782));
03387 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj14)*(x781)))+(((IkReal(-1.00000000000000))*(x786)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x781)))+(((IkReal(-1.00000000000000))*(cj14)*(x785)))+(x782)+(((IkReal(-1.00000000000000))*(sj14)*(x780))));
03388 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x778)*(x781)))+(((cj9)*(r02)*(sj13)))+(((x779)*(x780)))+(((cj9)*(r00)*(x779)))+(((sj11)*(x777)))+(x784)+(((IkReal(-1.00000000000000))*(x778)*(x785)))+(((r12)*(sj13)*(sj9))));
03389 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03390 {
03391 continue;
03392 }
03393 }
03394 
03395 {
03396 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03397 vinfos[0].jointtype = 1;
03398 vinfos[0].foffset = j9;
03399 vinfos[0].indices[0] = _ij9[0];
03400 vinfos[0].indices[1] = _ij9[1];
03401 vinfos[0].maxsolutions = _nj9;
03402 vinfos[1].jointtype = 1;
03403 vinfos[1].foffset = j10;
03404 vinfos[1].indices[0] = _ij10[0];
03405 vinfos[1].indices[1] = _ij10[1];
03406 vinfos[1].maxsolutions = _nj10;
03407 vinfos[2].jointtype = 1;
03408 vinfos[2].foffset = j11;
03409 vinfos[2].indices[0] = _ij11[0];
03410 vinfos[2].indices[1] = _ij11[1];
03411 vinfos[2].maxsolutions = _nj11;
03412 vinfos[3].jointtype = 1;
03413 vinfos[3].foffset = j12;
03414 vinfos[3].indices[0] = _ij12[0];
03415 vinfos[3].indices[1] = _ij12[1];
03416 vinfos[3].maxsolutions = _nj12;
03417 vinfos[4].jointtype = 1;
03418 vinfos[4].foffset = j13;
03419 vinfos[4].indices[0] = _ij13[0];
03420 vinfos[4].indices[1] = _ij13[1];
03421 vinfos[4].maxsolutions = _nj13;
03422 vinfos[5].jointtype = 1;
03423 vinfos[5].foffset = j14;
03424 vinfos[5].indices[0] = _ij14[0];
03425 vinfos[5].indices[1] = _ij14[1];
03426 vinfos[5].maxsolutions = _nj14;
03427 std::vector<int> vfree(0);
03428 solutions.AddSolution(vinfos,vfree);
03429 }
03430 }
03431 }
03432 
03433 }
03434 
03435 }
03436 }
03437 }
03438 
03439 }
03440 
03441 }
03442 
03443 } else
03444 {
03445 {
03446 IkReal j10array[1], cj10array[1], sj10array[1];
03447 bool j10valid[1]={false};
03448 _nj10 = 1;
03449 IkReal x787=((cj11)*(r20));
03450 IkReal x788=((IkReal(1.00000000000000))*(cj13));
03451 IkReal x789=((r21)*(sj14));
03452 IkReal x790=((r22)*(sj13));
03453 IkReal x791=((r20)*(sj11));
03454 IkReal x792=((cj14)*(r21));
03455 if( IKabs(((gconst20)*(((((cj11)*(x792)))+(((IkReal(-1.00000000000000))*(sj11)*(x788)*(x789)))+(((cj13)*(cj14)*(x791)))+(((sj11)*(x790)))+(((sj14)*(x787))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst20)*(((((IkReal(-1.00000000000000))*(cj11)*(x790)))+(((cj11)*(cj13)*(x789)))+(((IkReal(-1.00000000000000))*(cj14)*(x787)*(x788)))+(((sj11)*(x792)))+(((sj14)*(x791))))))) < IKFAST_ATAN2_MAGTHRESH )
03456     continue;
03457 j10array[0]=IKatan2(((gconst20)*(((((cj11)*(x792)))+(((IkReal(-1.00000000000000))*(sj11)*(x788)*(x789)))+(((cj13)*(cj14)*(x791)))+(((sj11)*(x790)))+(((sj14)*(x787)))))), ((gconst20)*(((((IkReal(-1.00000000000000))*(cj11)*(x790)))+(((cj11)*(cj13)*(x789)))+(((IkReal(-1.00000000000000))*(cj14)*(x787)*(x788)))+(((sj11)*(x792)))+(((sj14)*(x791)))))));
03458 sj10array[0]=IKsin(j10array[0]);
03459 cj10array[0]=IKcos(j10array[0]);
03460 if( j10array[0] > IKPI )
03461 {
03462     j10array[0]-=IK2PI;
03463 }
03464 else if( j10array[0] < -IKPI )
03465 {    j10array[0]+=IK2PI;
03466 }
03467 j10valid[0] = true;
03468 for(int ij10 = 0; ij10 < 1; ++ij10)
03469 {
03470 if( !j10valid[ij10] )
03471 {
03472     continue;
03473 }
03474 _ij10[0] = ij10; _ij10[1] = -1;
03475 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
03476 {
03477 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
03478 {
03479     j10valid[iij10]=false; _ij10[1] = iij10; break; 
03480 }
03481 }
03482 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
03483 {
03484 IkReal evalcond[2];
03485 IkReal x793=IKsin(j10);
03486 IkReal x794=IKcos(j10);
03487 IkReal x795=((IkReal(1.00000000000000))*(x794));
03488 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(cj11)*(x793)))+(((IkReal(-1.00000000000000))*(sj11)*(x795))));
03489 evalcond[1]=((((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)))+(((IkReal(-1.00000000000000))*(cj11)*(x795)))+(((cj13)*(r21)*(sj14)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((sj11)*(x793))));
03490 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
03491 {
03492 continue;
03493 }
03494 }
03495 
03496 {
03497 IkReal dummyeval[1];
03498 IkReal gconst24;
03499 IkReal x796=(sj14)*(sj14);
03500 IkReal x797=(cj14)*(cj14);
03501 IkReal x798=((r01)*(r10));
03502 IkReal x799=((cj13)*(cj14));
03503 IkReal x800=((IkReal(1.00000000000000))*(r12));
03504 IkReal x801=((cj13)*(sj14));
03505 IkReal x802=((sj13)*(x796));
03506 IkReal x803=((IkReal(1.00000000000000))*(r00)*(r11));
03507 IkReal x804=((sj13)*(x797));
03508 gconst24=IKsign(((((r02)*(r10)*(x801)))+(((r02)*(r11)*(x799)))+(((IkReal(-1.00000000000000))*(r00)*(x800)*(x801)))+(((x798)*(x802)))+(((x798)*(x804)))+(((IkReal(-1.00000000000000))*(r01)*(x799)*(x800)))+(((IkReal(-1.00000000000000))*(x803)*(x804)))+(((IkReal(-1.00000000000000))*(x802)*(x803)))));
03509 IkReal x805=(sj14)*(sj14);
03510 IkReal x806=(cj14)*(cj14);
03511 IkReal x807=((r01)*(r10));
03512 IkReal x808=((cj13)*(cj14));
03513 IkReal x809=((IkReal(1.00000000000000))*(r12));
03514 IkReal x810=((cj13)*(sj14));
03515 IkReal x811=((sj13)*(x805));
03516 IkReal x812=((IkReal(1.00000000000000))*(r00)*(r11));
03517 IkReal x813=((sj13)*(x806));
03518 dummyeval[0]=((((IkReal(-1.00000000000000))*(x812)*(x813)))+(((r02)*(r11)*(x808)))+(((IkReal(-1.00000000000000))*(r00)*(x809)*(x810)))+(((IkReal(-1.00000000000000))*(x811)*(x812)))+(((x807)*(x813)))+(((x807)*(x811)))+(((r02)*(r10)*(x810)))+(((IkReal(-1.00000000000000))*(r01)*(x808)*(x809))));
03519 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03520 {
03521 {
03522 IkReal dummyeval[1];
03523 IkReal gconst23;
03524 IkReal x814=(sj14)*(sj14);
03525 IkReal x815=(cj14)*(cj14);
03526 IkReal x816=((IkReal(1.00000000000000))*(x814));
03527 IkReal x817=((IkReal(2.00000000000000))*(cj14)*(sj14));
03528 IkReal x818=((IkReal(1.00000000000000))*(x815));
03529 gconst23=IKsign(((((IkReal(-1.00000000000000))*(x818)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x817)))+(((IkReal(-1.00000000000000))*(x816)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x816)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x818)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x817)))));
03530 IkReal x819=(sj14)*(sj14);
03531 IkReal x820=(cj14)*(cj14);
03532 IkReal x821=((IkReal(1.00000000000000))*(x819));
03533 IkReal x822=((IkReal(2.00000000000000))*(cj14)*(sj14));
03534 IkReal x823=((IkReal(1.00000000000000))*(x820));
03535 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(r01)*(x822)))+(((IkReal(-1.00000000000000))*(x821)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x822)))+(((IkReal(-1.00000000000000))*(x821)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x823)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x823)*((r01)*(r01)))));
03536 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03537 {
03538 continue;
03539 
03540 } else
03541 {
03542 {
03543 IkReal j9array[1], cj9array[1], sj9array[1];
03544 bool j9valid[1]={false};
03545 _nj9 = 1;
03546 IkReal x824=((cj14)*(r11));
03547 IkReal x825=((cj10)*(cj11));
03548 IkReal x826=((cj14)*(r01));
03549 IkReal x827=((sj14)*(x825));
03550 IkReal x828=((IkReal(1.00000000000000))*(sj10)*(sj11));
03551 if( IKabs(((gconst23)*(((((x824)*(x825)))+(((r10)*(x827)))+(((IkReal(-1.00000000000000))*(x824)*(x828)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(x828))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst23)*(((((x825)*(x826)))+(((r00)*(x827)))+(((IkReal(-1.00000000000000))*(x826)*(x828)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x828))))))) < IKFAST_ATAN2_MAGTHRESH )
03552     continue;
03553 j9array[0]=IKatan2(((gconst23)*(((((x824)*(x825)))+(((r10)*(x827)))+(((IkReal(-1.00000000000000))*(x824)*(x828)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(x828)))))), ((gconst23)*(((((x825)*(x826)))+(((r00)*(x827)))+(((IkReal(-1.00000000000000))*(x826)*(x828)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x828)))))));
03554 sj9array[0]=IKsin(j9array[0]);
03555 cj9array[0]=IKcos(j9array[0]);
03556 if( j9array[0] > IKPI )
03557 {
03558     j9array[0]-=IK2PI;
03559 }
03560 else if( j9array[0] < -IKPI )
03561 {    j9array[0]+=IK2PI;
03562 }
03563 j9valid[0] = true;
03564 for(int ij9 = 0; ij9 < 1; ++ij9)
03565 {
03566 if( !j9valid[ij9] )
03567 {
03568     continue;
03569 }
03570 _ij9[0] = ij9; _ij9[1] = -1;
03571 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
03572 {
03573 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
03574 {
03575     j9valid[iij9]=false; _ij9[1] = iij9; break; 
03576 }
03577 }
03578 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
03579 {
03580 IkReal evalcond[6];
03581 IkReal x829=IKsin(j9);
03582 IkReal x830=IKcos(j9);
03583 IkReal x831=((IkReal(1.00000000000000))*(cj14));
03584 IkReal x832=((IkReal(1.00000000000000))*(sj14));
03585 IkReal x833=((cj13)*(cj14));
03586 IkReal x834=((cj14)*(r10));
03587 IkReal x835=((r01)*(sj14));
03588 IkReal x836=((IkReal(1.00000000000000))*(r12));
03589 IkReal x837=((sj13)*(x830));
03590 IkReal x838=((r02)*(x829));
03591 IkReal x839=((r11)*(x829));
03592 IkReal x840=((r10)*(x830));
03593 IkReal x841=((r01)*(x830));
03594 IkReal x842=((sj13)*(x829));
03595 IkReal x843=((r11)*(x830));
03596 IkReal x844=((cj13)*(x829));
03597 IkReal x845=((r10)*(x829));
03598 IkReal x846=((r00)*(x830));
03599 IkReal x847=((cj13)*(x830));
03600 evalcond[0]=((((IkReal(-1.00000000000000))*(x831)*(x843)))+(((r00)*(sj14)*(x829)))+(((cj14)*(r01)*(x829)))+(((IkReal(-1.00000000000000))*(x832)*(x840))));
03601 evalcond[1]=((((IkReal(-1.00000000000000))*(x831)*(x841)))+(((sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(x832)*(x846)))+(((IkReal(-1.00000000000000))*(x832)*(x845)))+(((IkReal(-1.00000000000000))*(x831)*(x839))));
03602 evalcond[2]=((((IkReal(-1.00000000000000))*(sj13)*(x838)))+(((x833)*(x840)))+(((x835)*(x844)))+(((IkReal(-1.00000000000000))*(r00)*(x831)*(x844)))+(((IkReal(-1.00000000000000))*(cj13)*(x832)*(x843)))+(((r12)*(x837))));
03603 evalcond[3]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x836)*(x847)))+(((x835)*(x842)))+(((IkReal(-1.00000000000000))*(r00)*(x831)*(x842)))+(((IkReal(-1.00000000000000))*(r11)*(x832)*(x837)))+(((x834)*(x837)))+(((cj13)*(x838))));
03604 evalcond[4]=((((x833)*(x845)))+(((x833)*(x846)))+(((r02)*(x837)))+(((cj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x832)*(x839)))+(((IkReal(-1.00000000000000))*(cj13)*(x832)*(x841)))+(((r12)*(x842)))+(((cj11)*(sj10))));
03605 evalcond[5]=((((IkReal(-1.00000000000000))*(sj13)*(x832)*(x839)))+(((IkReal(-1.00000000000000))*(x836)*(x844)))+(((IkReal(-1.00000000000000))*(r02)*(x847)))+(((cj14)*(r00)*(x837)))+(((x834)*(x842)))+(((IkReal(-1.00000000000000))*(r01)*(x832)*(x837))));
03606 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  )
03607 {
03608 continue;
03609 }
03610 }
03611 
03612 {
03613 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03614 vinfos[0].jointtype = 1;
03615 vinfos[0].foffset = j9;
03616 vinfos[0].indices[0] = _ij9[0];
03617 vinfos[0].indices[1] = _ij9[1];
03618 vinfos[0].maxsolutions = _nj9;
03619 vinfos[1].jointtype = 1;
03620 vinfos[1].foffset = j10;
03621 vinfos[1].indices[0] = _ij10[0];
03622 vinfos[1].indices[1] = _ij10[1];
03623 vinfos[1].maxsolutions = _nj10;
03624 vinfos[2].jointtype = 1;
03625 vinfos[2].foffset = j11;
03626 vinfos[2].indices[0] = _ij11[0];
03627 vinfos[2].indices[1] = _ij11[1];
03628 vinfos[2].maxsolutions = _nj11;
03629 vinfos[3].jointtype = 1;
03630 vinfos[3].foffset = j12;
03631 vinfos[3].indices[0] = _ij12[0];
03632 vinfos[3].indices[1] = _ij12[1];
03633 vinfos[3].maxsolutions = _nj12;
03634 vinfos[4].jointtype = 1;
03635 vinfos[4].foffset = j13;
03636 vinfos[4].indices[0] = _ij13[0];
03637 vinfos[4].indices[1] = _ij13[1];
03638 vinfos[4].maxsolutions = _nj13;
03639 vinfos[5].jointtype = 1;
03640 vinfos[5].foffset = j14;
03641 vinfos[5].indices[0] = _ij14[0];
03642 vinfos[5].indices[1] = _ij14[1];
03643 vinfos[5].maxsolutions = _nj14;
03644 std::vector<int> vfree(0);
03645 solutions.AddSolution(vinfos,vfree);
03646 }
03647 }
03648 }
03649 
03650 }
03651 
03652 }
03653 
03654 } else
03655 {
03656 {
03657 IkReal j9array[1], cj9array[1], sj9array[1];
03658 bool j9valid[1]={false};
03659 _nj9 = 1;
03660 IkReal x848=((IkReal(1.00000000000000))*(sj14));
03661 IkReal x849=((IkReal(1.00000000000000))*(cj14));
03662 if( IKabs(((gconst24)*(((((IkReal(-1.00000000000000))*(r10)*(x848)))+(((IkReal(-1.00000000000000))*(r11)*(x849))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst24)*(((((IkReal(-1.00000000000000))*(r01)*(x849)))+(((IkReal(-1.00000000000000))*(r00)*(x848))))))) < IKFAST_ATAN2_MAGTHRESH )
03663     continue;
03664 j9array[0]=IKatan2(((gconst24)*(((((IkReal(-1.00000000000000))*(r10)*(x848)))+(((IkReal(-1.00000000000000))*(r11)*(x849)))))), ((gconst24)*(((((IkReal(-1.00000000000000))*(r01)*(x849)))+(((IkReal(-1.00000000000000))*(r00)*(x848)))))));
03665 sj9array[0]=IKsin(j9array[0]);
03666 cj9array[0]=IKcos(j9array[0]);
03667 if( j9array[0] > IKPI )
03668 {
03669     j9array[0]-=IK2PI;
03670 }
03671 else if( j9array[0] < -IKPI )
03672 {    j9array[0]+=IK2PI;
03673 }
03674 j9valid[0] = true;
03675 for(int ij9 = 0; ij9 < 1; ++ij9)
03676 {
03677 if( !j9valid[ij9] )
03678 {
03679     continue;
03680 }
03681 _ij9[0] = ij9; _ij9[1] = -1;
03682 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
03683 {
03684 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
03685 {
03686     j9valid[iij9]=false; _ij9[1] = iij9; break; 
03687 }
03688 }
03689 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
03690 {
03691 IkReal evalcond[6];
03692 IkReal x850=IKsin(j9);
03693 IkReal x851=IKcos(j9);
03694 IkReal x852=((IkReal(1.00000000000000))*(cj14));
03695 IkReal x853=((IkReal(1.00000000000000))*(sj14));
03696 IkReal x854=((cj13)*(cj14));
03697 IkReal x855=((cj14)*(r10));
03698 IkReal x856=((r01)*(sj14));
03699 IkReal x857=((IkReal(1.00000000000000))*(r12));
03700 IkReal x858=((sj13)*(x851));
03701 IkReal x859=((r02)*(x850));
03702 IkReal x860=((r11)*(x850));
03703 IkReal x861=((r10)*(x851));
03704 IkReal x862=((r01)*(x851));
03705 IkReal x863=((sj13)*(x850));
03706 IkReal x864=((r11)*(x851));
03707 IkReal x865=((cj13)*(x850));
03708 IkReal x866=((r10)*(x850));
03709 IkReal x867=((r00)*(x851));
03710 IkReal x868=((cj13)*(x851));
03711 evalcond[0]=((((r00)*(sj14)*(x850)))+(((cj14)*(r01)*(x850)))+(((IkReal(-1.00000000000000))*(x852)*(x864)))+(((IkReal(-1.00000000000000))*(x853)*(x861))));
03712 evalcond[1]=((((IkReal(-1.00000000000000))*(x852)*(x860)))+(((IkReal(-1.00000000000000))*(x852)*(x862)))+(((IkReal(-1.00000000000000))*(x853)*(x867)))+(((IkReal(-1.00000000000000))*(x853)*(x866)))+(((sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11))));
03713 evalcond[2]=((((r12)*(x858)))+(((x856)*(x865)))+(((IkReal(-1.00000000000000))*(r00)*(x852)*(x865)))+(((IkReal(-1.00000000000000))*(sj13)*(x859)))+(((IkReal(-1.00000000000000))*(cj13)*(x853)*(x864)))+(((x854)*(x861))));
03714 evalcond[3]=((IkReal(1.00000000000000))+(((x855)*(x858)))+(((cj13)*(x859)))+(((x856)*(x863)))+(((IkReal(-1.00000000000000))*(r00)*(x852)*(x863)))+(((IkReal(-1.00000000000000))*(r11)*(x853)*(x858)))+(((IkReal(-1.00000000000000))*(x857)*(x868))));
03715 evalcond[4]=((((r12)*(x863)))+(((cj10)*(sj11)))+(((r02)*(x858)))+(((IkReal(-1.00000000000000))*(cj13)*(x853)*(x860)))+(((IkReal(-1.00000000000000))*(cj13)*(x853)*(x862)))+(((x854)*(x866)))+(((x854)*(x867)))+(((cj11)*(sj10))));
03716 evalcond[5]=((((cj14)*(r00)*(x858)))+(((IkReal(-1.00000000000000))*(sj13)*(x853)*(x860)))+(((x855)*(x863)))+(((IkReal(-1.00000000000000))*(r02)*(x868)))+(((IkReal(-1.00000000000000))*(r01)*(x853)*(x858)))+(((IkReal(-1.00000000000000))*(x857)*(x865))));
03717 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  )
03718 {
03719 continue;
03720 }
03721 }
03722 
03723 {
03724 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03725 vinfos[0].jointtype = 1;
03726 vinfos[0].foffset = j9;
03727 vinfos[0].indices[0] = _ij9[0];
03728 vinfos[0].indices[1] = _ij9[1];
03729 vinfos[0].maxsolutions = _nj9;
03730 vinfos[1].jointtype = 1;
03731 vinfos[1].foffset = j10;
03732 vinfos[1].indices[0] = _ij10[0];
03733 vinfos[1].indices[1] = _ij10[1];
03734 vinfos[1].maxsolutions = _nj10;
03735 vinfos[2].jointtype = 1;
03736 vinfos[2].foffset = j11;
03737 vinfos[2].indices[0] = _ij11[0];
03738 vinfos[2].indices[1] = _ij11[1];
03739 vinfos[2].maxsolutions = _nj11;
03740 vinfos[3].jointtype = 1;
03741 vinfos[3].foffset = j12;
03742 vinfos[3].indices[0] = _ij12[0];
03743 vinfos[3].indices[1] = _ij12[1];
03744 vinfos[3].maxsolutions = _nj12;
03745 vinfos[4].jointtype = 1;
03746 vinfos[4].foffset = j13;
03747 vinfos[4].indices[0] = _ij13[0];
03748 vinfos[4].indices[1] = _ij13[1];
03749 vinfos[4].maxsolutions = _nj13;
03750 vinfos[5].jointtype = 1;
03751 vinfos[5].foffset = j14;
03752 vinfos[5].indices[0] = _ij14[0];
03753 vinfos[5].indices[1] = _ij14[1];
03754 vinfos[5].maxsolutions = _nj14;
03755 std::vector<int> vfree(0);
03756 solutions.AddSolution(vinfos,vfree);
03757 }
03758 }
03759 }
03760 
03761 }
03762 
03763 }
03764 }
03765 }
03766 
03767 }
03768 
03769 }
03770 
03771 } else
03772 {
03773 IkReal x869=((IkReal(1.00000000000000))*(sj13));
03774 IkReal x870=((npy)*(sj14));
03775 IkReal x871=((IkReal(1.00000000000000))*(cj14)*(npx));
03776 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
03777 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
03778 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(x871)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x870)))+(((IkReal(-1.00000000000000))*(npz)*(x869))));
03779 evalcond[3]=((((r21)*(sj13)*(sj14)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x869)))+(((cj13)*(r22))));
03780 evalcond[4]=((IkReal(-0.0950000000000000))+(((sj13)*(x870)))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x869)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
03781 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  )
03782 {
03783 {
03784 IkReal dummyeval[1];
03785 IkReal gconst27;
03786 gconst27=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
03787 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
03788 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03789 {
03790 {
03791 IkReal dummyeval[1];
03792 IkReal gconst25;
03793 IkReal x872=(sj14)*(sj14);
03794 IkReal x873=(cj14)*(cj14);
03795 IkReal x874=((cj13)*(r12));
03796 IkReal x875=((IkReal(1.00000000000000))*(r10));
03797 IkReal x876=((cj13)*(r02));
03798 IkReal x877=((r01)*(sj13));
03799 IkReal x878=((r00)*(r11)*(sj13));
03800 gconst25=IKsign(((((x872)*(x878)))+(((IkReal(-1.00000000000000))*(x872)*(x875)*(x877)))+(((IkReal(-1.00000000000000))*(x873)*(x875)*(x877)))+(((IkReal(-1.00000000000000))*(sj14)*(x875)*(x876)))+(((x873)*(x878)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x876)))+(((r00)*(sj14)*(x874)))+(((cj14)*(r01)*(x874)))));
03801 IkReal x879=(sj14)*(sj14);
03802 IkReal x880=(cj14)*(cj14);
03803 IkReal x881=((cj13)*(r12));
03804 IkReal x882=((IkReal(1.00000000000000))*(r10));
03805 IkReal x883=((cj13)*(r02));
03806 IkReal x884=((r01)*(sj13));
03807 IkReal x885=((r00)*(r11)*(sj13));
03808 dummyeval[0]=((((IkReal(-1.00000000000000))*(x880)*(x882)*(x884)))+(((x879)*(x885)))+(((IkReal(-1.00000000000000))*(sj14)*(x882)*(x883)))+(((x880)*(x885)))+(((cj14)*(r01)*(x881)))+(((r00)*(sj14)*(x881)))+(((IkReal(-1.00000000000000))*(x879)*(x882)*(x884)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x883))));
03809 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03810 {
03811 {
03812 IkReal dummyeval[1];
03813 IkReal gconst26;
03814 IkReal x886=(cj13)*(cj13);
03815 IkReal x887=(sj13)*(sj13);
03816 IkReal x888=((r01)*(sj14));
03817 IkReal x889=((r12)*(x887));
03818 IkReal x890=((IkReal(1.00000000000000))*(cj14)*(r00));
03819 IkReal x891=((cj14)*(r02)*(r10));
03820 IkReal x892=((r12)*(x886));
03821 IkReal x893=((IkReal(1.00000000000000))*(r02)*(r11)*(sj14));
03822 gconst26=IKsign(((((x886)*(x891)))+(((IkReal(-1.00000000000000))*(x889)*(x890)))+(((x888)*(x889)))+(((x888)*(x892)))+(((IkReal(-1.00000000000000))*(x890)*(x892)))+(((x887)*(x891)))+(((IkReal(-1.00000000000000))*(x886)*(x893)))+(((IkReal(-1.00000000000000))*(x887)*(x893)))));
03823 IkReal x894=(cj13)*(cj13);
03824 IkReal x895=(sj13)*(sj13);
03825 IkReal x896=((r01)*(sj14));
03826 IkReal x897=((r12)*(x895));
03827 IkReal x898=((IkReal(1.00000000000000))*(cj14)*(r00));
03828 IkReal x899=((cj14)*(r02)*(r10));
03829 IkReal x900=((r12)*(x894));
03830 IkReal x901=x893;
03831 dummyeval[0]=((((x894)*(x899)))+(((IkReal(-1.00000000000000))*(x895)*(x901)))+(((x896)*(x897)))+(((IkReal(-1.00000000000000))*(x894)*(x901)))+(((x895)*(x899)))+(((IkReal(-1.00000000000000))*(x898)*(x900)))+(((x896)*(x900)))+(((IkReal(-1.00000000000000))*(x897)*(x898))));
03832 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03833 {
03834 continue;
03835 
03836 } else
03837 {
03838 {
03839 IkReal j9array[1], cj9array[1], sj9array[1];
03840 bool j9valid[1]={false};
03841 _nj9 = 1;
03842 IkReal x902=((cj13)*(cj14));
03843 IkReal x903=((IkReal(1.00000000000000))*(cj13)*(sj14));
03844 if( IKabs(((gconst26)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x903)))+(((r10)*(x902))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst26)*(((((r00)*(x902)))+(((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x903))))))) < IKFAST_ATAN2_MAGTHRESH )
03845     continue;
03846 j9array[0]=IKatan2(((gconst26)*(((((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x903)))+(((r10)*(x902)))))), ((gconst26)*(((((r00)*(x902)))+(((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x903)))))));
03847 sj9array[0]=IKsin(j9array[0]);
03848 cj9array[0]=IKcos(j9array[0]);
03849 if( j9array[0] > IKPI )
03850 {
03851     j9array[0]-=IK2PI;
03852 }
03853 else if( j9array[0] < -IKPI )
03854 {    j9array[0]+=IK2PI;
03855 }
03856 j9valid[0] = true;
03857 for(int ij9 = 0; ij9 < 1; ++ij9)
03858 {
03859 if( !j9valid[ij9] )
03860 {
03861     continue;
03862 }
03863 _ij9[0] = ij9; _ij9[1] = -1;
03864 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
03865 {
03866 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
03867 {
03868     j9valid[iij9]=false; _ij9[1] = iij9; break; 
03869 }
03870 }
03871 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
03872 {
03873 IkReal evalcond[4];
03874 IkReal x904=IKsin(j9);
03875 IkReal x905=IKcos(j9);
03876 IkReal x906=((IkReal(1.00000000000000))*(sj14));
03877 IkReal x907=((cj13)*(cj14));
03878 IkReal x908=((IkReal(1.00000000000000))*(r00));
03879 IkReal x909=((r01)*(sj14));
03880 IkReal x910=((IkReal(1.00000000000000))*(cj13));
03881 IkReal x911=((sj13)*(x905));
03882 IkReal x912=((r02)*(x904));
03883 IkReal x913=((r10)*(x905));
03884 IkReal x914=((r11)*(x905));
03885 IkReal x915=((sj13)*(x904));
03886 IkReal x916=((cj14)*(x915));
03887 evalcond[0]=((((IkReal(-1.00000000000000))*(x906)*(x913)))+(((cj14)*(r01)*(x904)))+(((r00)*(sj14)*(x904)))+(((IkReal(-1.00000000000000))*(cj14)*(x914))));
03888 evalcond[1]=((((IkReal(-1.00000000000000))*(sj13)*(x912)))+(((cj13)*(x904)*(x909)))+(((IkReal(-1.00000000000000))*(x904)*(x907)*(x908)))+(((r12)*(x911)))+(((x907)*(x913)))+(((IkReal(-1.00000000000000))*(cj13)*(x906)*(x914))));
03889 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x906)*(x911)))+(((x909)*(x915)))+(((IkReal(-1.00000000000000))*(x908)*(x916)))+(((IkReal(-1.00000000000000))*(r12)*(x905)*(x910)))+(((cj14)*(r10)*(x911)))+(((cj13)*(x912))));
03890 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x906)*(x915)))+(((cj14)*(r00)*(x911)))+(((IkReal(-1.00000000000000))*(r01)*(x906)*(x911)))+(((r10)*(x916)))+(((IkReal(-1.00000000000000))*(r12)*(x904)*(x910)))+(((IkReal(-1.00000000000000))*(r02)*(x905)*(x910))));
03891 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03892 {
03893 continue;
03894 }
03895 }
03896 
03897 {
03898 IkReal dummyeval[1];
03899 IkReal gconst28;
03900 gconst28=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
03901 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
03902 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03903 {
03904 {
03905 IkReal dummyeval[1];
03906 IkReal gconst29;
03907 gconst29=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
03908 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
03909 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03910 {
03911 continue;
03912 
03913 } else
03914 {
03915 {
03916 IkReal j10array[1], cj10array[1], sj10array[1];
03917 bool j10valid[1]={false};
03918 _nj10 = 1;
03919 IkReal x917=((IkReal(1.00000000000000))*(sj11));
03920 IkReal x918=((cj14)*(r21));
03921 IkReal x919=((IkReal(1.00000000000000))*(cj11));
03922 IkReal x920=((r20)*(sj14));
03923 IkReal x921=((cj9)*(r00)*(sj14));
03924 IkReal x922=((cj14)*(r11)*(sj9));
03925 IkReal x923=((cj14)*(cj9)*(r01));
03926 IkReal x924=((r10)*(sj14)*(sj9));
03927 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(x918)*(x919)))+(((IkReal(-1.00000000000000))*(x919)*(x920)))+(((IkReal(-1.00000000000000))*(x917)*(x924)))+(((IkReal(-1.00000000000000))*(x917)*(x921)))+(((IkReal(-1.00000000000000))*(x917)*(x923)))+(((IkReal(-1.00000000000000))*(x917)*(x922))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((cj11)*(x924)))+(((cj11)*(x922)))+(((cj11)*(x923)))+(((cj11)*(x921)))+(((IkReal(-1.00000000000000))*(x917)*(x920)))+(((IkReal(-1.00000000000000))*(x917)*(x918))))))) < IKFAST_ATAN2_MAGTHRESH )
03928     continue;
03929 j10array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(x918)*(x919)))+(((IkReal(-1.00000000000000))*(x919)*(x920)))+(((IkReal(-1.00000000000000))*(x917)*(x924)))+(((IkReal(-1.00000000000000))*(x917)*(x921)))+(((IkReal(-1.00000000000000))*(x917)*(x923)))+(((IkReal(-1.00000000000000))*(x917)*(x922)))))), ((gconst29)*(((((cj11)*(x924)))+(((cj11)*(x922)))+(((cj11)*(x923)))+(((cj11)*(x921)))+(((IkReal(-1.00000000000000))*(x917)*(x920)))+(((IkReal(-1.00000000000000))*(x917)*(x918)))))));
03930 sj10array[0]=IKsin(j10array[0]);
03931 cj10array[0]=IKcos(j10array[0]);
03932 if( j10array[0] > IKPI )
03933 {
03934     j10array[0]-=IK2PI;
03935 }
03936 else if( j10array[0] < -IKPI )
03937 {    j10array[0]+=IK2PI;
03938 }
03939 j10valid[0] = true;
03940 for(int ij10 = 0; ij10 < 1; ++ij10)
03941 {
03942 if( !j10valid[ij10] )
03943 {
03944     continue;
03945 }
03946 _ij10[0] = ij10; _ij10[1] = -1;
03947 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
03948 {
03949 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
03950 {
03951     j10valid[iij10]=false; _ij10[1] = iij10; break; 
03952 }
03953 }
03954 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
03955 {
03956 IkReal evalcond[4];
03957 IkReal x925=IKsin(j10);
03958 IkReal x926=IKcos(j10);
03959 IkReal x927=((cj14)*(sj9));
03960 IkReal x928=((IkReal(1.00000000000000))*(r11));
03961 IkReal x929=((cj13)*(sj14));
03962 IkReal x930=((IkReal(1.00000000000000))*(cj9));
03963 IkReal x931=((cj13)*(cj14));
03964 IkReal x932=((cj11)*(x925));
03965 IkReal x933=((sj11)*(x926));
03966 IkReal x934=((cj11)*(x926));
03967 IkReal x935=((sj11)*(x925));
03968 IkReal x936=((x933)+(x932));
03969 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x936));
03970 evalcond[1]=((((r21)*(x929)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x931)))+(((IkReal(-1.00000000000000))*(x934)))+(x935));
03971 evalcond[2]=((((IkReal(-1.00000000000000))*(x927)*(x928)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x935)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x930)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x930)))+(x934));
03972 evalcond[3]=((((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x929)*(x930)))+(((cj9)*(r00)*(x931)))+(((IkReal(-1.00000000000000))*(sj9)*(x928)*(x929)))+(((cj13)*(r10)*(x927)))+(x936)+(((r12)*(sj13)*(sj9))));
03973 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03974 {
03975 continue;
03976 }
03977 }
03978 
03979 {
03980 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
03981 vinfos[0].jointtype = 1;
03982 vinfos[0].foffset = j9;
03983 vinfos[0].indices[0] = _ij9[0];
03984 vinfos[0].indices[1] = _ij9[1];
03985 vinfos[0].maxsolutions = _nj9;
03986 vinfos[1].jointtype = 1;
03987 vinfos[1].foffset = j10;
03988 vinfos[1].indices[0] = _ij10[0];
03989 vinfos[1].indices[1] = _ij10[1];
03990 vinfos[1].maxsolutions = _nj10;
03991 vinfos[2].jointtype = 1;
03992 vinfos[2].foffset = j11;
03993 vinfos[2].indices[0] = _ij11[0];
03994 vinfos[2].indices[1] = _ij11[1];
03995 vinfos[2].maxsolutions = _nj11;
03996 vinfos[3].jointtype = 1;
03997 vinfos[3].foffset = j12;
03998 vinfos[3].indices[0] = _ij12[0];
03999 vinfos[3].indices[1] = _ij12[1];
04000 vinfos[3].maxsolutions = _nj12;
04001 vinfos[4].jointtype = 1;
04002 vinfos[4].foffset = j13;
04003 vinfos[4].indices[0] = _ij13[0];
04004 vinfos[4].indices[1] = _ij13[1];
04005 vinfos[4].maxsolutions = _nj13;
04006 vinfos[5].jointtype = 1;
04007 vinfos[5].foffset = j14;
04008 vinfos[5].indices[0] = _ij14[0];
04009 vinfos[5].indices[1] = _ij14[1];
04010 vinfos[5].maxsolutions = _nj14;
04011 std::vector<int> vfree(0);
04012 solutions.AddSolution(vinfos,vfree);
04013 }
04014 }
04015 }
04016 
04017 }
04018 
04019 }
04020 
04021 } else
04022 {
04023 {
04024 IkReal j10array[1], cj10array[1], sj10array[1];
04025 bool j10valid[1]={false};
04026 _nj10 = 1;
04027 IkReal x937=((cj13)*(sj11));
04028 IkReal x938=((r21)*(sj14));
04029 IkReal x939=((cj14)*(r20));
04030 IkReal x940=((cj11)*(cj13));
04031 IkReal x941=((r22)*(sj13));
04032 IkReal x942=((r20)*(sj14));
04033 IkReal x943=((cj14)*(r21));
04034 if( IKabs(((gconst28)*(((((IkReal(-1.00000000000000))*(sj11)*(x941)))+(((x937)*(x938)))+(((cj11)*(x942)))+(((cj11)*(x943)))+(((IkReal(-1.00000000000000))*(x937)*(x939))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((cj11)*(x941)))+(((x939)*(x940)))+(((IkReal(-1.00000000000000))*(x938)*(x940)))+(((sj11)*(x943)))+(((sj11)*(x942))))))) < IKFAST_ATAN2_MAGTHRESH )
04035     continue;
04036 j10array[0]=IKatan2(((gconst28)*(((((IkReal(-1.00000000000000))*(sj11)*(x941)))+(((x937)*(x938)))+(((cj11)*(x942)))+(((cj11)*(x943)))+(((IkReal(-1.00000000000000))*(x937)*(x939)))))), ((gconst28)*(((((cj11)*(x941)))+(((x939)*(x940)))+(((IkReal(-1.00000000000000))*(x938)*(x940)))+(((sj11)*(x943)))+(((sj11)*(x942)))))));
04037 sj10array[0]=IKsin(j10array[0]);
04038 cj10array[0]=IKcos(j10array[0]);
04039 if( j10array[0] > IKPI )
04040 {
04041     j10array[0]-=IK2PI;
04042 }
04043 else if( j10array[0] < -IKPI )
04044 {    j10array[0]+=IK2PI;
04045 }
04046 j10valid[0] = true;
04047 for(int ij10 = 0; ij10 < 1; ++ij10)
04048 {
04049 if( !j10valid[ij10] )
04050 {
04051     continue;
04052 }
04053 _ij10[0] = ij10; _ij10[1] = -1;
04054 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
04055 {
04056 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
04057 {
04058     j10valid[iij10]=false; _ij10[1] = iij10; break; 
04059 }
04060 }
04061 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
04062 {
04063 IkReal evalcond[4];
04064 IkReal x944=IKsin(j10);
04065 IkReal x945=IKcos(j10);
04066 IkReal x946=((cj14)*(sj9));
04067 IkReal x947=((IkReal(1.00000000000000))*(r11));
04068 IkReal x948=((cj13)*(sj14));
04069 IkReal x949=((IkReal(1.00000000000000))*(cj9));
04070 IkReal x950=((cj13)*(cj14));
04071 IkReal x951=((cj11)*(x944));
04072 IkReal x952=((sj11)*(x945));
04073 IkReal x953=((cj11)*(x945));
04074 IkReal x954=((sj11)*(x944));
04075 IkReal x955=((x952)+(x951));
04076 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x955));
04077 evalcond[1]=((((r21)*(x948)))+(((IkReal(-1.00000000000000))*(x953)))+(((IkReal(-1.00000000000000))*(r20)*(x950)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(x954));
04078 evalcond[2]=((((IkReal(-1.00000000000000))*(x946)*(x947)))+(((IkReal(-1.00000000000000))*(x954)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x949)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x949)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(x953));
04079 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x948)*(x949)))+(((cj13)*(r10)*(x946)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(sj9)*(x947)*(x948)))+(((cj9)*(r00)*(x950)))+(x955)+(((r12)*(sj13)*(sj9))));
04080 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04081 {
04082 continue;
04083 }
04084 }
04085 
04086 {
04087 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04088 vinfos[0].jointtype = 1;
04089 vinfos[0].foffset = j9;
04090 vinfos[0].indices[0] = _ij9[0];
04091 vinfos[0].indices[1] = _ij9[1];
04092 vinfos[0].maxsolutions = _nj9;
04093 vinfos[1].jointtype = 1;
04094 vinfos[1].foffset = j10;
04095 vinfos[1].indices[0] = _ij10[0];
04096 vinfos[1].indices[1] = _ij10[1];
04097 vinfos[1].maxsolutions = _nj10;
04098 vinfos[2].jointtype = 1;
04099 vinfos[2].foffset = j11;
04100 vinfos[2].indices[0] = _ij11[0];
04101 vinfos[2].indices[1] = _ij11[1];
04102 vinfos[2].maxsolutions = _nj11;
04103 vinfos[3].jointtype = 1;
04104 vinfos[3].foffset = j12;
04105 vinfos[3].indices[0] = _ij12[0];
04106 vinfos[3].indices[1] = _ij12[1];
04107 vinfos[3].maxsolutions = _nj12;
04108 vinfos[4].jointtype = 1;
04109 vinfos[4].foffset = j13;
04110 vinfos[4].indices[0] = _ij13[0];
04111 vinfos[4].indices[1] = _ij13[1];
04112 vinfos[4].maxsolutions = _nj13;
04113 vinfos[5].jointtype = 1;
04114 vinfos[5].foffset = j14;
04115 vinfos[5].indices[0] = _ij14[0];
04116 vinfos[5].indices[1] = _ij14[1];
04117 vinfos[5].maxsolutions = _nj14;
04118 std::vector<int> vfree(0);
04119 solutions.AddSolution(vinfos,vfree);
04120 }
04121 }
04122 }
04123 
04124 }
04125 
04126 }
04127 }
04128 }
04129 
04130 }
04131 
04132 }
04133 
04134 } else
04135 {
04136 {
04137 IkReal j9array[1], cj9array[1], sj9array[1];
04138 bool j9valid[1]={false};
04139 _nj9 = 1;
04140 IkReal x956=((IkReal(1.00000000000000))*(sj14));
04141 IkReal x957=((IkReal(1.00000000000000))*(cj14));
04142 if( IKabs(((gconst25)*(((((IkReal(-1.00000000000000))*(r10)*(x956)))+(((IkReal(-1.00000000000000))*(r11)*(x957))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst25)*(((((IkReal(-1.00000000000000))*(r01)*(x957)))+(((IkReal(-1.00000000000000))*(r00)*(x956))))))) < IKFAST_ATAN2_MAGTHRESH )
04143     continue;
04144 j9array[0]=IKatan2(((gconst25)*(((((IkReal(-1.00000000000000))*(r10)*(x956)))+(((IkReal(-1.00000000000000))*(r11)*(x957)))))), ((gconst25)*(((((IkReal(-1.00000000000000))*(r01)*(x957)))+(((IkReal(-1.00000000000000))*(r00)*(x956)))))));
04145 sj9array[0]=IKsin(j9array[0]);
04146 cj9array[0]=IKcos(j9array[0]);
04147 if( j9array[0] > IKPI )
04148 {
04149     j9array[0]-=IK2PI;
04150 }
04151 else if( j9array[0] < -IKPI )
04152 {    j9array[0]+=IK2PI;
04153 }
04154 j9valid[0] = true;
04155 for(int ij9 = 0; ij9 < 1; ++ij9)
04156 {
04157 if( !j9valid[ij9] )
04158 {
04159     continue;
04160 }
04161 _ij9[0] = ij9; _ij9[1] = -1;
04162 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
04163 {
04164 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
04165 {
04166     j9valid[iij9]=false; _ij9[1] = iij9; break; 
04167 }
04168 }
04169 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
04170 {
04171 IkReal evalcond[4];
04172 IkReal x958=IKsin(j9);
04173 IkReal x959=IKcos(j9);
04174 IkReal x960=((IkReal(1.00000000000000))*(sj14));
04175 IkReal x961=((cj13)*(cj14));
04176 IkReal x962=((IkReal(1.00000000000000))*(r00));
04177 IkReal x963=((r01)*(sj14));
04178 IkReal x964=((IkReal(1.00000000000000))*(cj13));
04179 IkReal x965=((sj13)*(x959));
04180 IkReal x966=((r02)*(x958));
04181 IkReal x967=((r10)*(x959));
04182 IkReal x968=((r11)*(x959));
04183 IkReal x969=((sj13)*(x958));
04184 IkReal x970=((cj14)*(x969));
04185 evalcond[0]=((((cj14)*(r01)*(x958)))+(((IkReal(-1.00000000000000))*(cj14)*(x968)))+(((IkReal(-1.00000000000000))*(x960)*(x967)))+(((r00)*(sj14)*(x958))));
04186 evalcond[1]=((((cj13)*(x958)*(x963)))+(((x961)*(x967)))+(((IkReal(-1.00000000000000))*(x958)*(x961)*(x962)))+(((r12)*(x965)))+(((IkReal(-1.00000000000000))*(cj13)*(x960)*(x968)))+(((IkReal(-1.00000000000000))*(sj13)*(x966))));
04187 evalcond[2]=((IkReal(-1.00000000000000))+(((cj14)*(r10)*(x965)))+(((IkReal(-1.00000000000000))*(x962)*(x970)))+(((IkReal(-1.00000000000000))*(r11)*(x960)*(x965)))+(((x963)*(x969)))+(((cj13)*(x966)))+(((IkReal(-1.00000000000000))*(r12)*(x959)*(x964))));
04188 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x960)*(x969)))+(((IkReal(-1.00000000000000))*(r01)*(x960)*(x965)))+(((IkReal(-1.00000000000000))*(r12)*(x958)*(x964)))+(((IkReal(-1.00000000000000))*(r02)*(x959)*(x964)))+(((r10)*(x970)))+(((cj14)*(r00)*(x965))));
04189 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04190 {
04191 continue;
04192 }
04193 }
04194 
04195 {
04196 IkReal dummyeval[1];
04197 IkReal gconst28;
04198 gconst28=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
04199 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
04200 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04201 {
04202 {
04203 IkReal dummyeval[1];
04204 IkReal gconst29;
04205 gconst29=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
04206 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
04207 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04208 {
04209 continue;
04210 
04211 } else
04212 {
04213 {
04214 IkReal j10array[1], cj10array[1], sj10array[1];
04215 bool j10valid[1]={false};
04216 _nj10 = 1;
04217 IkReal x971=((IkReal(1.00000000000000))*(sj11));
04218 IkReal x972=((cj14)*(r21));
04219 IkReal x973=((IkReal(1.00000000000000))*(cj11));
04220 IkReal x974=((r20)*(sj14));
04221 IkReal x975=((cj9)*(r00)*(sj14));
04222 IkReal x976=((cj14)*(r11)*(sj9));
04223 IkReal x977=((cj14)*(cj9)*(r01));
04224 IkReal x978=((r10)*(sj14)*(sj9));
04225 if( IKabs(((gconst29)*(((((IkReal(-1.00000000000000))*(x971)*(x976)))+(((IkReal(-1.00000000000000))*(x971)*(x977)))+(((IkReal(-1.00000000000000))*(x971)*(x978)))+(((IkReal(-1.00000000000000))*(x971)*(x975)))+(((IkReal(-1.00000000000000))*(x972)*(x973)))+(((IkReal(-1.00000000000000))*(x973)*(x974))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst29)*(((((cj11)*(x975)))+(((cj11)*(x977)))+(((cj11)*(x976)))+(((cj11)*(x978)))+(((IkReal(-1.00000000000000))*(x971)*(x972)))+(((IkReal(-1.00000000000000))*(x971)*(x974))))))) < IKFAST_ATAN2_MAGTHRESH )
04226     continue;
04227 j10array[0]=IKatan2(((gconst29)*(((((IkReal(-1.00000000000000))*(x971)*(x976)))+(((IkReal(-1.00000000000000))*(x971)*(x977)))+(((IkReal(-1.00000000000000))*(x971)*(x978)))+(((IkReal(-1.00000000000000))*(x971)*(x975)))+(((IkReal(-1.00000000000000))*(x972)*(x973)))+(((IkReal(-1.00000000000000))*(x973)*(x974)))))), ((gconst29)*(((((cj11)*(x975)))+(((cj11)*(x977)))+(((cj11)*(x976)))+(((cj11)*(x978)))+(((IkReal(-1.00000000000000))*(x971)*(x972)))+(((IkReal(-1.00000000000000))*(x971)*(x974)))))));
04228 sj10array[0]=IKsin(j10array[0]);
04229 cj10array[0]=IKcos(j10array[0]);
04230 if( j10array[0] > IKPI )
04231 {
04232     j10array[0]-=IK2PI;
04233 }
04234 else if( j10array[0] < -IKPI )
04235 {    j10array[0]+=IK2PI;
04236 }
04237 j10valid[0] = true;
04238 for(int ij10 = 0; ij10 < 1; ++ij10)
04239 {
04240 if( !j10valid[ij10] )
04241 {
04242     continue;
04243 }
04244 _ij10[0] = ij10; _ij10[1] = -1;
04245 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
04246 {
04247 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
04248 {
04249     j10valid[iij10]=false; _ij10[1] = iij10; break; 
04250 }
04251 }
04252 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
04253 {
04254 IkReal evalcond[4];
04255 IkReal x979=IKsin(j10);
04256 IkReal x980=IKcos(j10);
04257 IkReal x981=((cj14)*(sj9));
04258 IkReal x982=((IkReal(1.00000000000000))*(r11));
04259 IkReal x983=((cj13)*(sj14));
04260 IkReal x984=((IkReal(1.00000000000000))*(cj9));
04261 IkReal x985=((cj13)*(cj14));
04262 IkReal x986=((cj11)*(x979));
04263 IkReal x987=((sj11)*(x980));
04264 IkReal x988=((cj11)*(x980));
04265 IkReal x989=((sj11)*(x979));
04266 IkReal x990=((x986)+(x987));
04267 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x990));
04268 evalcond[1]=((((IkReal(-1.00000000000000))*(x988)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x983)))+(((IkReal(-1.00000000000000))*(r20)*(x985)))+(x989));
04269 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj14)*(x984)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x984)))+(((IkReal(-1.00000000000000))*(x989)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x981)*(x982)))+(x988));
04270 evalcond[3]=((((IkReal(-1.00000000000000))*(sj9)*(x982)*(x983)))+(((cj9)*(r02)*(sj13)))+(((cj13)*(r10)*(x981)))+(((cj9)*(r00)*(x985)))+(x990)+(((IkReal(-1.00000000000000))*(r01)*(x983)*(x984)))+(((r12)*(sj13)*(sj9))));
04271 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04272 {
04273 continue;
04274 }
04275 }
04276 
04277 {
04278 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04279 vinfos[0].jointtype = 1;
04280 vinfos[0].foffset = j9;
04281 vinfos[0].indices[0] = _ij9[0];
04282 vinfos[0].indices[1] = _ij9[1];
04283 vinfos[0].maxsolutions = _nj9;
04284 vinfos[1].jointtype = 1;
04285 vinfos[1].foffset = j10;
04286 vinfos[1].indices[0] = _ij10[0];
04287 vinfos[1].indices[1] = _ij10[1];
04288 vinfos[1].maxsolutions = _nj10;
04289 vinfos[2].jointtype = 1;
04290 vinfos[2].foffset = j11;
04291 vinfos[2].indices[0] = _ij11[0];
04292 vinfos[2].indices[1] = _ij11[1];
04293 vinfos[2].maxsolutions = _nj11;
04294 vinfos[3].jointtype = 1;
04295 vinfos[3].foffset = j12;
04296 vinfos[3].indices[0] = _ij12[0];
04297 vinfos[3].indices[1] = _ij12[1];
04298 vinfos[3].maxsolutions = _nj12;
04299 vinfos[4].jointtype = 1;
04300 vinfos[4].foffset = j13;
04301 vinfos[4].indices[0] = _ij13[0];
04302 vinfos[4].indices[1] = _ij13[1];
04303 vinfos[4].maxsolutions = _nj13;
04304 vinfos[5].jointtype = 1;
04305 vinfos[5].foffset = j14;
04306 vinfos[5].indices[0] = _ij14[0];
04307 vinfos[5].indices[1] = _ij14[1];
04308 vinfos[5].maxsolutions = _nj14;
04309 std::vector<int> vfree(0);
04310 solutions.AddSolution(vinfos,vfree);
04311 }
04312 }
04313 }
04314 
04315 }
04316 
04317 }
04318 
04319 } else
04320 {
04321 {
04322 IkReal j10array[1], cj10array[1], sj10array[1];
04323 bool j10valid[1]={false};
04324 _nj10 = 1;
04325 IkReal x991=((cj13)*(sj11));
04326 IkReal x992=((r21)*(sj14));
04327 IkReal x993=((cj14)*(r20));
04328 IkReal x994=((cj11)*(cj13));
04329 IkReal x995=((r22)*(sj13));
04330 IkReal x996=((r20)*(sj14));
04331 IkReal x997=((cj14)*(r21));
04332 if( IKabs(((gconst28)*(((((x991)*(x992)))+(((IkReal(-1.00000000000000))*(x991)*(x993)))+(((cj11)*(x997)))+(((cj11)*(x996)))+(((IkReal(-1.00000000000000))*(sj11)*(x995))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst28)*(((((x993)*(x994)))+(((IkReal(-1.00000000000000))*(x992)*(x994)))+(((sj11)*(x996)))+(((sj11)*(x997)))+(((cj11)*(x995))))))) < IKFAST_ATAN2_MAGTHRESH )
04333     continue;
04334 j10array[0]=IKatan2(((gconst28)*(((((x991)*(x992)))+(((IkReal(-1.00000000000000))*(x991)*(x993)))+(((cj11)*(x997)))+(((cj11)*(x996)))+(((IkReal(-1.00000000000000))*(sj11)*(x995)))))), ((gconst28)*(((((x993)*(x994)))+(((IkReal(-1.00000000000000))*(x992)*(x994)))+(((sj11)*(x996)))+(((sj11)*(x997)))+(((cj11)*(x995)))))));
04335 sj10array[0]=IKsin(j10array[0]);
04336 cj10array[0]=IKcos(j10array[0]);
04337 if( j10array[0] > IKPI )
04338 {
04339     j10array[0]-=IK2PI;
04340 }
04341 else if( j10array[0] < -IKPI )
04342 {    j10array[0]+=IK2PI;
04343 }
04344 j10valid[0] = true;
04345 for(int ij10 = 0; ij10 < 1; ++ij10)
04346 {
04347 if( !j10valid[ij10] )
04348 {
04349     continue;
04350 }
04351 _ij10[0] = ij10; _ij10[1] = -1;
04352 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
04353 {
04354 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
04355 {
04356     j10valid[iij10]=false; _ij10[1] = iij10; break; 
04357 }
04358 }
04359 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
04360 {
04361 IkReal evalcond[4];
04362 IkReal x998=IKsin(j10);
04363 IkReal x999=IKcos(j10);
04364 IkReal x1000=((cj14)*(sj9));
04365 IkReal x1001=((IkReal(1.00000000000000))*(r11));
04366 IkReal x1002=((cj13)*(sj14));
04367 IkReal x1003=((IkReal(1.00000000000000))*(cj9));
04368 IkReal x1004=((cj13)*(cj14));
04369 IkReal x1005=((cj11)*(x998));
04370 IkReal x1006=((sj11)*(x999));
04371 IkReal x1007=((cj11)*(x999));
04372 IkReal x1008=((sj11)*(x998));
04373 IkReal x1009=((x1006)+(x1005));
04374 evalcond[0]=((x1009)+(((cj14)*(r21)))+(((r20)*(sj14))));
04375 evalcond[1]=((((IkReal(-1.00000000000000))*(x1007)))+(x1008)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x1004)))+(((r21)*(x1002))));
04376 evalcond[2]=((((IkReal(-1.00000000000000))*(x1008)))+(x1007)+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1003)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x1003)))+(((IkReal(-1.00000000000000))*(x1000)*(x1001))));
04377 evalcond[3]=((x1009)+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(sj9)*(x1001)*(x1002)))+(((cj13)*(r10)*(x1000)))+(((IkReal(-1.00000000000000))*(r01)*(x1002)*(x1003)))+(((cj9)*(r00)*(x1004)))+(((r12)*(sj13)*(sj9))));
04378 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04379 {
04380 continue;
04381 }
04382 }
04383 
04384 {
04385 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04386 vinfos[0].jointtype = 1;
04387 vinfos[0].foffset = j9;
04388 vinfos[0].indices[0] = _ij9[0];
04389 vinfos[0].indices[1] = _ij9[1];
04390 vinfos[0].maxsolutions = _nj9;
04391 vinfos[1].jointtype = 1;
04392 vinfos[1].foffset = j10;
04393 vinfos[1].indices[0] = _ij10[0];
04394 vinfos[1].indices[1] = _ij10[1];
04395 vinfos[1].maxsolutions = _nj10;
04396 vinfos[2].jointtype = 1;
04397 vinfos[2].foffset = j11;
04398 vinfos[2].indices[0] = _ij11[0];
04399 vinfos[2].indices[1] = _ij11[1];
04400 vinfos[2].maxsolutions = _nj11;
04401 vinfos[3].jointtype = 1;
04402 vinfos[3].foffset = j12;
04403 vinfos[3].indices[0] = _ij12[0];
04404 vinfos[3].indices[1] = _ij12[1];
04405 vinfos[3].maxsolutions = _nj12;
04406 vinfos[4].jointtype = 1;
04407 vinfos[4].foffset = j13;
04408 vinfos[4].indices[0] = _ij13[0];
04409 vinfos[4].indices[1] = _ij13[1];
04410 vinfos[4].maxsolutions = _nj13;
04411 vinfos[5].jointtype = 1;
04412 vinfos[5].foffset = j14;
04413 vinfos[5].indices[0] = _ij14[0];
04414 vinfos[5].indices[1] = _ij14[1];
04415 vinfos[5].maxsolutions = _nj14;
04416 std::vector<int> vfree(0);
04417 solutions.AddSolution(vinfos,vfree);
04418 }
04419 }
04420 }
04421 
04422 }
04423 
04424 }
04425 }
04426 }
04427 
04428 }
04429 
04430 }
04431 
04432 } else
04433 {
04434 {
04435 IkReal j10array[1], cj10array[1], sj10array[1];
04436 bool j10valid[1]={false};
04437 _nj10 = 1;
04438 IkReal x1010=((cj13)*(sj11));
04439 IkReal x1011=((r21)*(sj14));
04440 IkReal x1012=((cj14)*(r20));
04441 IkReal x1013=((cj11)*(cj13));
04442 IkReal x1014=((r22)*(sj13));
04443 IkReal x1015=((r20)*(sj14));
04444 IkReal x1016=((cj14)*(r21));
04445 if( IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(x1010)*(x1012)))+(((IkReal(-1.00000000000000))*(sj11)*(x1014)))+(((cj11)*(x1015)))+(((cj11)*(x1016)))+(((x1010)*(x1011))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst27)*(((((IkReal(-1.00000000000000))*(x1011)*(x1013)))+(((x1012)*(x1013)))+(((sj11)*(x1016)))+(((sj11)*(x1015)))+(((cj11)*(x1014))))))) < IKFAST_ATAN2_MAGTHRESH )
04446     continue;
04447 j10array[0]=IKatan2(((gconst27)*(((((IkReal(-1.00000000000000))*(x1010)*(x1012)))+(((IkReal(-1.00000000000000))*(sj11)*(x1014)))+(((cj11)*(x1015)))+(((cj11)*(x1016)))+(((x1010)*(x1011)))))), ((gconst27)*(((((IkReal(-1.00000000000000))*(x1011)*(x1013)))+(((x1012)*(x1013)))+(((sj11)*(x1016)))+(((sj11)*(x1015)))+(((cj11)*(x1014)))))));
04448 sj10array[0]=IKsin(j10array[0]);
04449 cj10array[0]=IKcos(j10array[0]);
04450 if( j10array[0] > IKPI )
04451 {
04452     j10array[0]-=IK2PI;
04453 }
04454 else if( j10array[0] < -IKPI )
04455 {    j10array[0]+=IK2PI;
04456 }
04457 j10valid[0] = true;
04458 for(int ij10 = 0; ij10 < 1; ++ij10)
04459 {
04460 if( !j10valid[ij10] )
04461 {
04462     continue;
04463 }
04464 _ij10[0] = ij10; _ij10[1] = -1;
04465 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
04466 {
04467 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
04468 {
04469     j10valid[iij10]=false; _ij10[1] = iij10; break; 
04470 }
04471 }
04472 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
04473 {
04474 IkReal evalcond[2];
04475 IkReal x1017=IKsin(j10);
04476 IkReal x1018=IKcos(j10);
04477 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((sj11)*(x1018)))+(((cj11)*(x1017))));
04478 evalcond[1]=((((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)))+(((cj13)*(r21)*(sj14)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((sj11)*(x1017)))+(((IkReal(-1.00000000000000))*(cj11)*(x1018))));
04479 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
04480 {
04481 continue;
04482 }
04483 }
04484 
04485 {
04486 IkReal dummyeval[1];
04487 IkReal gconst31;
04488 IkReal x1019=(sj14)*(sj14);
04489 IkReal x1020=(cj14)*(cj14);
04490 IkReal x1021=((cj13)*(r12));
04491 IkReal x1022=((IkReal(1.00000000000000))*(r10));
04492 IkReal x1023=((cj13)*(r02));
04493 IkReal x1024=((r01)*(sj13));
04494 IkReal x1025=((r00)*(r11)*(sj13));
04495 gconst31=IKsign(((((IkReal(-1.00000000000000))*(sj14)*(x1022)*(x1023)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1023)))+(((x1019)*(x1025)))+(((r00)*(sj14)*(x1021)))+(((IkReal(-1.00000000000000))*(x1019)*(x1022)*(x1024)))+(((x1020)*(x1025)))+(((cj14)*(r01)*(x1021)))+(((IkReal(-1.00000000000000))*(x1020)*(x1022)*(x1024)))));
04496 IkReal x1026=(sj14)*(sj14);
04497 IkReal x1027=(cj14)*(cj14);
04498 IkReal x1028=((cj13)*(r12));
04499 IkReal x1029=((IkReal(1.00000000000000))*(r10));
04500 IkReal x1030=((cj13)*(r02));
04501 IkReal x1031=((r01)*(sj13));
04502 IkReal x1032=((r00)*(r11)*(sj13));
04503 dummyeval[0]=((((x1026)*(x1032)))+(((IkReal(-1.00000000000000))*(x1026)*(x1029)*(x1031)))+(((IkReal(-1.00000000000000))*(sj14)*(x1029)*(x1030)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1030)))+(((IkReal(-1.00000000000000))*(x1027)*(x1029)*(x1031)))+(((r00)*(sj14)*(x1028)))+(((x1027)*(x1032)))+(((cj14)*(r01)*(x1028))));
04504 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04505 {
04506 {
04507 IkReal dummyeval[1];
04508 IkReal gconst30;
04509 IkReal x1033=(sj14)*(sj14);
04510 IkReal x1034=(cj14)*(cj14);
04511 IkReal x1035=((IkReal(1.00000000000000))*(x1033));
04512 IkReal x1036=((IkReal(2.00000000000000))*(cj14)*(sj14));
04513 IkReal x1037=((IkReal(1.00000000000000))*(x1034));
04514 gconst30=IKsign(((((IkReal(-1.00000000000000))*(x1037)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1037)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1036)))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1036)))+(((IkReal(-1.00000000000000))*(x1035)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1035)*((r00)*(r00))))));
04515 IkReal x1038=(sj14)*(sj14);
04516 IkReal x1039=(cj14)*(cj14);
04517 IkReal x1040=((IkReal(1.00000000000000))*(x1038));
04518 IkReal x1041=((IkReal(2.00000000000000))*(cj14)*(sj14));
04519 IkReal x1042=((IkReal(1.00000000000000))*(x1039));
04520 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1041)))+(((IkReal(-1.00000000000000))*(x1042)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1040)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(x1040)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1041)))+(((IkReal(-1.00000000000000))*(x1042)*((r11)*(r11)))));
04521 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04522 {
04523 continue;
04524 
04525 } else
04526 {
04527 {
04528 IkReal j9array[1], cj9array[1], sj9array[1];
04529 bool j9valid[1]={false};
04530 _nj9 = 1;
04531 IkReal x1043=((sj10)*(sj11));
04532 IkReal x1044=((r00)*(sj14));
04533 IkReal x1045=((cj14)*(r11));
04534 IkReal x1046=((r10)*(sj14));
04535 IkReal x1047=((cj14)*(r01));
04536 IkReal x1048=((IkReal(1.00000000000000))*(cj10)*(cj11));
04537 if( IKabs(((gconst30)*(((((IkReal(-1.00000000000000))*(x1046)*(x1048)))+(((x1043)*(x1045)))+(((x1043)*(x1046)))+(((IkReal(-1.00000000000000))*(x1045)*(x1048))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst30)*(((((x1043)*(x1044)))+(((x1043)*(x1047)))+(((IkReal(-1.00000000000000))*(x1044)*(x1048)))+(((IkReal(-1.00000000000000))*(x1047)*(x1048))))))) < IKFAST_ATAN2_MAGTHRESH )
04538     continue;
04539 j9array[0]=IKatan2(((gconst30)*(((((IkReal(-1.00000000000000))*(x1046)*(x1048)))+(((x1043)*(x1045)))+(((x1043)*(x1046)))+(((IkReal(-1.00000000000000))*(x1045)*(x1048)))))), ((gconst30)*(((((x1043)*(x1044)))+(((x1043)*(x1047)))+(((IkReal(-1.00000000000000))*(x1044)*(x1048)))+(((IkReal(-1.00000000000000))*(x1047)*(x1048)))))));
04540 sj9array[0]=IKsin(j9array[0]);
04541 cj9array[0]=IKcos(j9array[0]);
04542 if( j9array[0] > IKPI )
04543 {
04544     j9array[0]-=IK2PI;
04545 }
04546 else if( j9array[0] < -IKPI )
04547 {    j9array[0]+=IK2PI;
04548 }
04549 j9valid[0] = true;
04550 for(int ij9 = 0; ij9 < 1; ++ij9)
04551 {
04552 if( !j9valid[ij9] )
04553 {
04554     continue;
04555 }
04556 _ij9[0] = ij9; _ij9[1] = -1;
04557 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
04558 {
04559 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
04560 {
04561     j9valid[iij9]=false; _ij9[1] = iij9; break; 
04562 }
04563 }
04564 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
04565 {
04566 IkReal evalcond[6];
04567 IkReal x1049=IKsin(j9);
04568 IkReal x1050=IKcos(j9);
04569 IkReal x1051=((IkReal(1.00000000000000))*(cj14));
04570 IkReal x1052=((IkReal(1.00000000000000))*(sj14));
04571 IkReal x1053=((cj13)*(cj14));
04572 IkReal x1054=((cj14)*(r10));
04573 IkReal x1055=((r01)*(sj14));
04574 IkReal x1056=((IkReal(1.00000000000000))*(r12));
04575 IkReal x1057=((sj13)*(x1050));
04576 IkReal x1058=((r02)*(x1049));
04577 IkReal x1059=((r11)*(x1049));
04578 IkReal x1060=((r10)*(x1050));
04579 IkReal x1061=((r01)*(x1050));
04580 IkReal x1062=((sj13)*(x1049));
04581 IkReal x1063=((r11)*(x1050));
04582 IkReal x1064=((cj13)*(x1049));
04583 IkReal x1065=((r10)*(x1049));
04584 IkReal x1066=((r00)*(x1050));
04585 IkReal x1067=((cj13)*(x1050));
04586 evalcond[0]=((((cj14)*(r01)*(x1049)))+(((IkReal(-1.00000000000000))*(x1052)*(x1060)))+(((IkReal(-1.00000000000000))*(x1051)*(x1063)))+(((r00)*(sj14)*(x1049))));
04587 evalcond[1]=((((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(x1052)*(x1066)))+(((IkReal(-1.00000000000000))*(x1052)*(x1065)))+(((IkReal(-1.00000000000000))*(x1051)*(x1061)))+(((cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(x1051)*(x1059))));
04588 evalcond[2]=((((r12)*(x1057)))+(((x1055)*(x1064)))+(((IkReal(-1.00000000000000))*(cj13)*(x1052)*(x1063)))+(((IkReal(-1.00000000000000))*(r00)*(x1051)*(x1064)))+(((x1053)*(x1060)))+(((IkReal(-1.00000000000000))*(sj13)*(x1058))));
04589 evalcond[3]=((IkReal(-1.00000000000000))+(((x1054)*(x1057)))+(((x1055)*(x1062)))+(((IkReal(-1.00000000000000))*(r11)*(x1052)*(x1057)))+(((IkReal(-1.00000000000000))*(r00)*(x1051)*(x1062)))+(((IkReal(-1.00000000000000))*(x1056)*(x1067)))+(((cj13)*(x1058))));
04590 evalcond[4]=((((IkReal(-1.00000000000000))*(cj13)*(x1052)*(x1059)))+(((r12)*(x1062)))+(((r02)*(x1057)))+(((IkReal(-1.00000000000000))*(cj13)*(x1052)*(x1061)))+(((cj10)*(sj11)))+(((x1053)*(x1065)))+(((x1053)*(x1066)))+(((cj11)*(sj10))));
04591 evalcond[5]=((((IkReal(-1.00000000000000))*(sj13)*(x1052)*(x1059)))+(((x1054)*(x1062)))+(((IkReal(-1.00000000000000))*(r02)*(x1067)))+(((cj14)*(r00)*(x1057)))+(((IkReal(-1.00000000000000))*(x1056)*(x1064)))+(((IkReal(-1.00000000000000))*(r01)*(x1052)*(x1057))));
04592 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  )
04593 {
04594 continue;
04595 }
04596 }
04597 
04598 {
04599 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04600 vinfos[0].jointtype = 1;
04601 vinfos[0].foffset = j9;
04602 vinfos[0].indices[0] = _ij9[0];
04603 vinfos[0].indices[1] = _ij9[1];
04604 vinfos[0].maxsolutions = _nj9;
04605 vinfos[1].jointtype = 1;
04606 vinfos[1].foffset = j10;
04607 vinfos[1].indices[0] = _ij10[0];
04608 vinfos[1].indices[1] = _ij10[1];
04609 vinfos[1].maxsolutions = _nj10;
04610 vinfos[2].jointtype = 1;
04611 vinfos[2].foffset = j11;
04612 vinfos[2].indices[0] = _ij11[0];
04613 vinfos[2].indices[1] = _ij11[1];
04614 vinfos[2].maxsolutions = _nj11;
04615 vinfos[3].jointtype = 1;
04616 vinfos[3].foffset = j12;
04617 vinfos[3].indices[0] = _ij12[0];
04618 vinfos[3].indices[1] = _ij12[1];
04619 vinfos[3].maxsolutions = _nj12;
04620 vinfos[4].jointtype = 1;
04621 vinfos[4].foffset = j13;
04622 vinfos[4].indices[0] = _ij13[0];
04623 vinfos[4].indices[1] = _ij13[1];
04624 vinfos[4].maxsolutions = _nj13;
04625 vinfos[5].jointtype = 1;
04626 vinfos[5].foffset = j14;
04627 vinfos[5].indices[0] = _ij14[0];
04628 vinfos[5].indices[1] = _ij14[1];
04629 vinfos[5].maxsolutions = _nj14;
04630 std::vector<int> vfree(0);
04631 solutions.AddSolution(vinfos,vfree);
04632 }
04633 }
04634 }
04635 
04636 }
04637 
04638 }
04639 
04640 } else
04641 {
04642 {
04643 IkReal j9array[1], cj9array[1], sj9array[1];
04644 bool j9valid[1]={false};
04645 _nj9 = 1;
04646 IkReal x1068=((IkReal(1.00000000000000))*(sj14));
04647 IkReal x1069=((IkReal(1.00000000000000))*(cj14));
04648 if( IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r11)*(x1069)))+(((IkReal(-1.00000000000000))*(r10)*(x1068))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst31)*(((((IkReal(-1.00000000000000))*(r01)*(x1069)))+(((IkReal(-1.00000000000000))*(r00)*(x1068))))))) < IKFAST_ATAN2_MAGTHRESH )
04649     continue;
04650 j9array[0]=IKatan2(((gconst31)*(((((IkReal(-1.00000000000000))*(r11)*(x1069)))+(((IkReal(-1.00000000000000))*(r10)*(x1068)))))), ((gconst31)*(((((IkReal(-1.00000000000000))*(r01)*(x1069)))+(((IkReal(-1.00000000000000))*(r00)*(x1068)))))));
04651 sj9array[0]=IKsin(j9array[0]);
04652 cj9array[0]=IKcos(j9array[0]);
04653 if( j9array[0] > IKPI )
04654 {
04655     j9array[0]-=IK2PI;
04656 }
04657 else if( j9array[0] < -IKPI )
04658 {    j9array[0]+=IK2PI;
04659 }
04660 j9valid[0] = true;
04661 for(int ij9 = 0; ij9 < 1; ++ij9)
04662 {
04663 if( !j9valid[ij9] )
04664 {
04665     continue;
04666 }
04667 _ij9[0] = ij9; _ij9[1] = -1;
04668 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
04669 {
04670 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
04671 {
04672     j9valid[iij9]=false; _ij9[1] = iij9; break; 
04673 }
04674 }
04675 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
04676 {
04677 IkReal evalcond[6];
04678 IkReal x1070=IKsin(j9);
04679 IkReal x1071=IKcos(j9);
04680 IkReal x1072=((IkReal(1.00000000000000))*(cj14));
04681 IkReal x1073=((IkReal(1.00000000000000))*(sj14));
04682 IkReal x1074=((cj13)*(cj14));
04683 IkReal x1075=((cj14)*(r10));
04684 IkReal x1076=((r01)*(sj14));
04685 IkReal x1077=((IkReal(1.00000000000000))*(r12));
04686 IkReal x1078=((sj13)*(x1071));
04687 IkReal x1079=((r02)*(x1070));
04688 IkReal x1080=((r11)*(x1070));
04689 IkReal x1081=((r10)*(x1071));
04690 IkReal x1082=((r01)*(x1071));
04691 IkReal x1083=((sj13)*(x1070));
04692 IkReal x1084=((r11)*(x1071));
04693 IkReal x1085=((cj13)*(x1070));
04694 IkReal x1086=((r10)*(x1070));
04695 IkReal x1087=((r00)*(x1071));
04696 IkReal x1088=((cj13)*(x1071));
04697 evalcond[0]=((((cj14)*(r01)*(x1070)))+(((IkReal(-1.00000000000000))*(x1073)*(x1081)))+(((r00)*(sj14)*(x1070)))+(((IkReal(-1.00000000000000))*(x1072)*(x1084))));
04698 evalcond[1]=((((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(x1073)*(x1086)))+(((IkReal(-1.00000000000000))*(x1073)*(x1087)))+(((cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(x1072)*(x1082)))+(((IkReal(-1.00000000000000))*(x1072)*(x1080))));
04699 evalcond[2]=((((IkReal(-1.00000000000000))*(sj13)*(x1079)))+(((x1076)*(x1085)))+(((r12)*(x1078)))+(((IkReal(-1.00000000000000))*(r00)*(x1072)*(x1085)))+(((IkReal(-1.00000000000000))*(cj13)*(x1073)*(x1084)))+(((x1074)*(x1081))));
04700 evalcond[3]=((IkReal(-1.00000000000000))+(((x1076)*(x1083)))+(((IkReal(-1.00000000000000))*(r00)*(x1072)*(x1083)))+(((IkReal(-1.00000000000000))*(r11)*(x1073)*(x1078)))+(((x1075)*(x1078)))+(((IkReal(-1.00000000000000))*(x1077)*(x1088)))+(((cj13)*(x1079))));
04701 evalcond[4]=((((IkReal(-1.00000000000000))*(cj13)*(x1073)*(x1082)))+(((IkReal(-1.00000000000000))*(cj13)*(x1073)*(x1080)))+(((r12)*(x1083)))+(((cj10)*(sj11)))+(((x1074)*(x1087)))+(((x1074)*(x1086)))+(((cj11)*(sj10)))+(((r02)*(x1078))));
04702 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x1088)))+(((x1075)*(x1083)))+(((IkReal(-1.00000000000000))*(r01)*(x1073)*(x1078)))+(((IkReal(-1.00000000000000))*(sj13)*(x1073)*(x1080)))+(((cj14)*(r00)*(x1078)))+(((IkReal(-1.00000000000000))*(x1077)*(x1085))));
04703 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  )
04704 {
04705 continue;
04706 }
04707 }
04708 
04709 {
04710 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04711 vinfos[0].jointtype = 1;
04712 vinfos[0].foffset = j9;
04713 vinfos[0].indices[0] = _ij9[0];
04714 vinfos[0].indices[1] = _ij9[1];
04715 vinfos[0].maxsolutions = _nj9;
04716 vinfos[1].jointtype = 1;
04717 vinfos[1].foffset = j10;
04718 vinfos[1].indices[0] = _ij10[0];
04719 vinfos[1].indices[1] = _ij10[1];
04720 vinfos[1].maxsolutions = _nj10;
04721 vinfos[2].jointtype = 1;
04722 vinfos[2].foffset = j11;
04723 vinfos[2].indices[0] = _ij11[0];
04724 vinfos[2].indices[1] = _ij11[1];
04725 vinfos[2].maxsolutions = _nj11;
04726 vinfos[3].jointtype = 1;
04727 vinfos[3].foffset = j12;
04728 vinfos[3].indices[0] = _ij12[0];
04729 vinfos[3].indices[1] = _ij12[1];
04730 vinfos[3].maxsolutions = _nj12;
04731 vinfos[4].jointtype = 1;
04732 vinfos[4].foffset = j13;
04733 vinfos[4].indices[0] = _ij13[0];
04734 vinfos[4].indices[1] = _ij13[1];
04735 vinfos[4].maxsolutions = _nj13;
04736 vinfos[5].jointtype = 1;
04737 vinfos[5].foffset = j14;
04738 vinfos[5].indices[0] = _ij14[0];
04739 vinfos[5].indices[1] = _ij14[1];
04740 vinfos[5].maxsolutions = _nj14;
04741 std::vector<int> vfree(0);
04742 solutions.AddSolution(vinfos,vfree);
04743 }
04744 }
04745 }
04746 
04747 }
04748 
04749 }
04750 }
04751 }
04752 
04753 }
04754 
04755 }
04756 
04757 } else
04758 {
04759 IkReal x1089=((IkReal(1.00000000000000))*(sj13));
04760 IkReal x1090=((cj14)*(npx));
04761 IkReal x1091=((npy)*(sj14));
04762 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
04763 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
04764 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
04765 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x1091)))+(((IkReal(-1.00000000000000))*(cj13)*(x1090)))+(((IkReal(-1.00000000000000))*(npz)*(x1089))));
04766 evalcond[4]=((IkReal(0.0300000000000000))+(((sj13)*(x1091)))+(((IkReal(-0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x1089)*(x1090)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
04767 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  )
04768 {
04769 {
04770 IkReal dummyeval[1];
04771 IkReal gconst32;
04772 IkReal x1092=(sj14)*(sj14);
04773 IkReal x1093=(cj14)*(cj14);
04774 IkReal x1094=((IkReal(2.00000000000000))*(cj14)*(sj14));
04775 gconst32=IKsign(((((x1092)*((r10)*(r10))))+(((r00)*(r01)*(x1094)))+(((x1093)*((r01)*(r01))))+(((r10)*(r11)*(x1094)))+(((x1092)*((r00)*(r00))))+(((x1093)*((r11)*(r11))))));
04776 IkReal x1095=(sj14)*(sj14);
04777 IkReal x1096=(cj14)*(cj14);
04778 IkReal x1097=((IkReal(2.00000000000000))*(cj14)*(sj14));
04779 dummyeval[0]=((((x1096)*((r01)*(r01))))+(((x1095)*((r10)*(r10))))+(((x1095)*((r00)*(r00))))+(((x1096)*((r11)*(r11))))+(((r00)*(r01)*(x1097)))+(((r10)*(r11)*(x1097))));
04780 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04781 {
04782 {
04783 IkReal dummyeval[1];
04784 IkReal gconst34;
04785 gconst34=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
04786 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
04787 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04788 {
04789 {
04790 IkReal dummyeval[1];
04791 IkReal gconst33;
04792 IkReal x1098=(cj14)*(cj14);
04793 IkReal x1099=(sj14)*(sj14);
04794 IkReal x1100=((IkReal(1.00000000000000))*(r01));
04795 IkReal x1101=((sj13)*(sj14));
04796 IkReal x1102=((cj14)*(sj13));
04797 IkReal x1103=((r00)*(r11));
04798 IkReal x1104=((cj13)*(x1098));
04799 IkReal x1105=((cj13)*(x1099));
04800 gconst33=IKsign(((((IkReal(-1.00000000000000))*(r10)*(x1100)*(x1104)))+(((IkReal(-1.00000000000000))*(r10)*(x1100)*(x1105)))+(((IkReal(-1.00000000000000))*(r12)*(x1100)*(x1102)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x1101)))+(((r02)*(r11)*(x1102)))+(((r02)*(r10)*(x1101)))+(((x1103)*(x1105)))+(((x1103)*(x1104)))));
04801 IkReal x1106=(cj14)*(cj14);
04802 IkReal x1107=(sj14)*(sj14);
04803 IkReal x1108=((IkReal(1.00000000000000))*(r01));
04804 IkReal x1109=((sj13)*(sj14));
04805 IkReal x1110=((cj14)*(sj13));
04806 IkReal x1111=((r00)*(r11));
04807 IkReal x1112=((cj13)*(x1106));
04808 IkReal x1113=((cj13)*(x1107));
04809 dummyeval[0]=((((x1111)*(x1112)))+(((x1111)*(x1113)))+(((IkReal(-1.00000000000000))*(r12)*(x1108)*(x1110)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x1109)))+(((r02)*(r11)*(x1110)))+(((r02)*(r10)*(x1109)))+(((IkReal(-1.00000000000000))*(r10)*(x1108)*(x1113)))+(((IkReal(-1.00000000000000))*(r10)*(x1108)*(x1112))));
04810 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04811 {
04812 continue;
04813 
04814 } else
04815 {
04816 {
04817 IkReal j9array[1], cj9array[1], sj9array[1];
04818 bool j9valid[1]={false};
04819 _nj9 = 1;
04820 IkReal x1114=((cj13)*(cj14));
04821 IkReal x1115=((IkReal(1.00000000000000))*(cj13)*(sj14));
04822 if( IKabs(((gconst33)*(((((IkReal(-1.00000000000000))*(r11)*(x1115)))+(((r12)*(sj13)))+(((r10)*(x1114))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst33)*(((((IkReal(-1.00000000000000))*(r01)*(x1115)))+(((r02)*(sj13)))+(((r00)*(x1114))))))) < IKFAST_ATAN2_MAGTHRESH )
04823     continue;
04824 j9array[0]=IKatan2(((gconst33)*(((((IkReal(-1.00000000000000))*(r11)*(x1115)))+(((r12)*(sj13)))+(((r10)*(x1114)))))), ((gconst33)*(((((IkReal(-1.00000000000000))*(r01)*(x1115)))+(((r02)*(sj13)))+(((r00)*(x1114)))))));
04825 sj9array[0]=IKsin(j9array[0]);
04826 cj9array[0]=IKcos(j9array[0]);
04827 if( j9array[0] > IKPI )
04828 {
04829     j9array[0]-=IK2PI;
04830 }
04831 else if( j9array[0] < -IKPI )
04832 {    j9array[0]+=IK2PI;
04833 }
04834 j9valid[0] = true;
04835 for(int ij9 = 0; ij9 < 1; ++ij9)
04836 {
04837 if( !j9valid[ij9] )
04838 {
04839     continue;
04840 }
04841 _ij9[0] = ij9; _ij9[1] = -1;
04842 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
04843 {
04844 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
04845 {
04846     j9valid[iij9]=false; _ij9[1] = iij9; break; 
04847 }
04848 }
04849 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
04850 {
04851 IkReal evalcond[4];
04852 IkReal x1116=IKsin(j9);
04853 IkReal x1117=IKcos(j9);
04854 IkReal x1118=((r10)*(sj14));
04855 IkReal x1119=((cj14)*(r11));
04856 IkReal x1120=((cj14)*(r10));
04857 IkReal x1121=((cj14)*(r00));
04858 IkReal x1122=((r11)*(sj14));
04859 IkReal x1123=((r00)*(sj14));
04860 IkReal x1124=((IkReal(1.00000000000000))*(x1116));
04861 IkReal x1125=((cj13)*(x1116));
04862 IkReal x1126=((sj13)*(x1117));
04863 IkReal x1127=((r01)*(x1116));
04864 IkReal x1128=((IkReal(1.00000000000000))*(x1117));
04865 evalcond[0]=((IkReal(1.00000000000000))+(((cj14)*(x1127)))+(((IkReal(-1.00000000000000))*(x1119)*(x1128)))+(((x1116)*(x1123)))+(((IkReal(-1.00000000000000))*(x1118)*(x1128))));
04866 evalcond[1]=((((IkReal(-1.00000000000000))*(x1123)*(x1128)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1128)))+(((IkReal(-1.00000000000000))*(x1119)*(x1124)))+(((IkReal(-1.00000000000000))*(x1118)*(x1124))));
04867 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x1122)*(x1128)))+(((cj13)*(x1117)*(x1120)))+(((r01)*(sj14)*(x1125)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x1124)))+(((r12)*(x1126)))+(((IkReal(-1.00000000000000))*(cj13)*(x1121)*(x1124))));
04868 evalcond[3]=((((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1128)))+(((x1120)*(x1126)))+(((sj13)*(sj14)*(x1127)))+(((IkReal(-1.00000000000000))*(x1122)*(x1126)))+(((IkReal(-1.00000000000000))*(sj13)*(x1121)*(x1124)))+(((r02)*(x1125))));
04869 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04870 {
04871 continue;
04872 }
04873 }
04874 
04875 {
04876 IkReal dummyeval[1];
04877 IkReal gconst35;
04878 gconst35=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
04879 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
04880 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04881 {
04882 {
04883 IkReal dummyeval[1];
04884 IkReal gconst36;
04885 gconst36=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
04886 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
04887 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04888 {
04889 continue;
04890 
04891 } else
04892 {
04893 {
04894 IkReal j10array[1], cj10array[1], sj10array[1];
04895 bool j10valid[1]={false};
04896 _nj10 = 1;
04897 IkReal x1129=((cj13)*(sj14));
04898 IkReal x1130=((IkReal(1.00000000000000))*(cj11));
04899 IkReal x1131=((r11)*(sj9));
04900 IkReal x1132=((cj13)*(cj14));
04901 IkReal x1133=((IkReal(1.00000000000000))*(sj11));
04902 IkReal x1134=((cj11)*(sj13));
04903 IkReal x1135=((r10)*(sj9));
04904 IkReal x1136=((sj11)*(sj13));
04905 IkReal x1137=((cj9)*(r02));
04906 IkReal x1138=((r12)*(sj9));
04907 IkReal x1139=((cj9)*(r00));
04908 IkReal x1140=((cj9)*(r01));
04909 if( IKabs(((gconst36)*(((((r21)*(sj11)*(x1129)))+(((IkReal(-1.00000000000000))*(x1129)*(x1130)*(x1140)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1133)))+(((x1134)*(x1137)))+(((x1134)*(x1138)))+(((cj11)*(x1132)*(x1139)))+(((cj11)*(x1132)*(x1135)))+(((IkReal(-1.00000000000000))*(x1129)*(x1130)*(x1131)))+(((IkReal(-1.00000000000000))*(r20)*(x1132)*(x1133))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((cj11)*(r20)*(x1132)))+(((sj11)*(x1132)*(x1139)))+(((sj11)*(x1132)*(x1135)))+(((IkReal(-1.00000000000000))*(x1129)*(x1131)*(x1133)))+(((x1136)*(x1137)))+(((x1136)*(x1138)))+(((IkReal(-1.00000000000000))*(r21)*(x1129)*(x1130)))+(((IkReal(-1.00000000000000))*(x1129)*(x1133)*(x1140)))+(((r22)*(x1134))))))) < IKFAST_ATAN2_MAGTHRESH )
04910     continue;
04911 j10array[0]=IKatan2(((gconst36)*(((((r21)*(sj11)*(x1129)))+(((IkReal(-1.00000000000000))*(x1129)*(x1130)*(x1140)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1133)))+(((x1134)*(x1137)))+(((x1134)*(x1138)))+(((cj11)*(x1132)*(x1139)))+(((cj11)*(x1132)*(x1135)))+(((IkReal(-1.00000000000000))*(x1129)*(x1130)*(x1131)))+(((IkReal(-1.00000000000000))*(r20)*(x1132)*(x1133)))))), ((gconst36)*(((((cj11)*(r20)*(x1132)))+(((sj11)*(x1132)*(x1139)))+(((sj11)*(x1132)*(x1135)))+(((IkReal(-1.00000000000000))*(x1129)*(x1131)*(x1133)))+(((x1136)*(x1137)))+(((x1136)*(x1138)))+(((IkReal(-1.00000000000000))*(r21)*(x1129)*(x1130)))+(((IkReal(-1.00000000000000))*(x1129)*(x1133)*(x1140)))+(((r22)*(x1134)))))));
04912 sj10array[0]=IKsin(j10array[0]);
04913 cj10array[0]=IKcos(j10array[0]);
04914 if( j10array[0] > IKPI )
04915 {
04916     j10array[0]-=IK2PI;
04917 }
04918 else if( j10array[0] < -IKPI )
04919 {    j10array[0]+=IK2PI;
04920 }
04921 j10valid[0] = true;
04922 for(int ij10 = 0; ij10 < 1; ++ij10)
04923 {
04924 if( !j10valid[ij10] )
04925 {
04926     continue;
04927 }
04928 _ij10[0] = ij10; _ij10[1] = -1;
04929 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
04930 {
04931 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
04932 {
04933     j10valid[iij10]=false; _ij10[1] = iij10; break; 
04934 }
04935 }
04936 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
04937 {
04938 IkReal evalcond[4];
04939 IkReal x1141=IKsin(j10);
04940 IkReal x1142=IKcos(j10);
04941 IkReal x1143=((IkReal(1.00000000000000))*(sj13));
04942 IkReal x1144=((r11)*(sj9));
04943 IkReal x1145=((cj9)*(r01));
04944 IkReal x1146=((r21)*(sj14));
04945 IkReal x1147=((cj9)*(r02));
04946 IkReal x1148=((sj13)*(sj9));
04947 IkReal x1149=((cj14)*(r10));
04948 IkReal x1150=((IkReal(1.00000000000000))*(cj13));
04949 IkReal x1151=((cj14)*(r20));
04950 IkReal x1152=((cj11)*(x1141));
04951 IkReal x1153=((sj11)*(x1142));
04952 IkReal x1154=((sj14)*(x1150));
04953 IkReal x1155=((sj11)*(x1141));
04954 IkReal x1156=((cj11)*(x1142));
04955 IkReal x1157=((cj14)*(cj9)*(r00));
04956 IkReal x1158=((x1153)+(x1152));
04957 evalcond[0]=((x1155)+(((cj13)*(x1146)))+(((IkReal(-1.00000000000000))*(x1156)))+(((IkReal(-1.00000000000000))*(r22)*(x1143)))+(((IkReal(-1.00000000000000))*(x1150)*(x1151))));
04958 evalcond[1]=((x1158)+(((IkReal(-1.00000000000000))*(x1143)*(x1151)))+(((sj13)*(x1146)))+(((cj13)*(r22))));
04959 evalcond[2]=((((IkReal(-1.00000000000000))*(x1144)*(x1154)))+(x1158)+(((cj13)*(sj9)*(x1149)))+(((cj13)*(x1157)))+(((sj13)*(x1147)))+(((IkReal(-1.00000000000000))*(x1145)*(x1154)))+(((r12)*(x1148))));
04960 evalcond[3]=((x1156)+(((IkReal(-1.00000000000000))*(x1147)*(x1150)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1150)))+(((IkReal(-1.00000000000000))*(x1155)))+(((sj13)*(x1157)))+(((IkReal(-1.00000000000000))*(sj14)*(x1143)*(x1144)))+(((IkReal(-1.00000000000000))*(sj14)*(x1143)*(x1145)))+(((x1148)*(x1149))));
04961 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04962 {
04963 continue;
04964 }
04965 }
04966 
04967 {
04968 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
04969 vinfos[0].jointtype = 1;
04970 vinfos[0].foffset = j9;
04971 vinfos[0].indices[0] = _ij9[0];
04972 vinfos[0].indices[1] = _ij9[1];
04973 vinfos[0].maxsolutions = _nj9;
04974 vinfos[1].jointtype = 1;
04975 vinfos[1].foffset = j10;
04976 vinfos[1].indices[0] = _ij10[0];
04977 vinfos[1].indices[1] = _ij10[1];
04978 vinfos[1].maxsolutions = _nj10;
04979 vinfos[2].jointtype = 1;
04980 vinfos[2].foffset = j11;
04981 vinfos[2].indices[0] = _ij11[0];
04982 vinfos[2].indices[1] = _ij11[1];
04983 vinfos[2].maxsolutions = _nj11;
04984 vinfos[3].jointtype = 1;
04985 vinfos[3].foffset = j12;
04986 vinfos[3].indices[0] = _ij12[0];
04987 vinfos[3].indices[1] = _ij12[1];
04988 vinfos[3].maxsolutions = _nj12;
04989 vinfos[4].jointtype = 1;
04990 vinfos[4].foffset = j13;
04991 vinfos[4].indices[0] = _ij13[0];
04992 vinfos[4].indices[1] = _ij13[1];
04993 vinfos[4].maxsolutions = _nj13;
04994 vinfos[5].jointtype = 1;
04995 vinfos[5].foffset = j14;
04996 vinfos[5].indices[0] = _ij14[0];
04997 vinfos[5].indices[1] = _ij14[1];
04998 vinfos[5].maxsolutions = _nj14;
04999 std::vector<int> vfree(0);
05000 solutions.AddSolution(vinfos,vfree);
05001 }
05002 }
05003 }
05004 
05005 }
05006 
05007 }
05008 
05009 } else
05010 {
05011 {
05012 IkReal j10array[1], cj10array[1], sj10array[1];
05013 bool j10valid[1]={false};
05014 _nj10 = 1;
05015 IkReal x1159=((cj13)*(sj11));
05016 IkReal x1160=((r21)*(sj14));
05017 IkReal x1161=((cj11)*(cj13));
05018 IkReal x1162=((cj11)*(sj13));
05019 IkReal x1163=((sj11)*(sj13));
05020 IkReal x1164=((IkReal(1.00000000000000))*(cj14)*(r20));
05021 if( IKabs(((gconst35)*(((((x1159)*(x1160)))+(((IkReal(-1.00000000000000))*(x1159)*(x1164)))+(((IkReal(-1.00000000000000))*(x1162)*(x1164)))+(((IkReal(-1.00000000000000))*(r22)*(x1163)))+(((r22)*(x1161)))+(((x1160)*(x1162))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((cj14)*(r20)*(x1161)))+(((r22)*(x1159)))+(((IkReal(-1.00000000000000))*(x1163)*(x1164)))+(((r22)*(x1162)))+(((IkReal(-1.00000000000000))*(x1160)*(x1161)))+(((x1160)*(x1163))))))) < IKFAST_ATAN2_MAGTHRESH )
05022     continue;
05023 j10array[0]=IKatan2(((gconst35)*(((((x1159)*(x1160)))+(((IkReal(-1.00000000000000))*(x1159)*(x1164)))+(((IkReal(-1.00000000000000))*(x1162)*(x1164)))+(((IkReal(-1.00000000000000))*(r22)*(x1163)))+(((r22)*(x1161)))+(((x1160)*(x1162)))))), ((gconst35)*(((((cj14)*(r20)*(x1161)))+(((r22)*(x1159)))+(((IkReal(-1.00000000000000))*(x1163)*(x1164)))+(((r22)*(x1162)))+(((IkReal(-1.00000000000000))*(x1160)*(x1161)))+(((x1160)*(x1163)))))));
05024 sj10array[0]=IKsin(j10array[0]);
05025 cj10array[0]=IKcos(j10array[0]);
05026 if( j10array[0] > IKPI )
05027 {
05028     j10array[0]-=IK2PI;
05029 }
05030 else if( j10array[0] < -IKPI )
05031 {    j10array[0]+=IK2PI;
05032 }
05033 j10valid[0] = true;
05034 for(int ij10 = 0; ij10 < 1; ++ij10)
05035 {
05036 if( !j10valid[ij10] )
05037 {
05038     continue;
05039 }
05040 _ij10[0] = ij10; _ij10[1] = -1;
05041 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
05042 {
05043 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
05044 {
05045     j10valid[iij10]=false; _ij10[1] = iij10; break; 
05046 }
05047 }
05048 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
05049 {
05050 IkReal evalcond[4];
05051 IkReal x1165=IKsin(j10);
05052 IkReal x1166=IKcos(j10);
05053 IkReal x1167=((IkReal(1.00000000000000))*(sj13));
05054 IkReal x1168=((r11)*(sj9));
05055 IkReal x1169=((cj9)*(r01));
05056 IkReal x1170=((r21)*(sj14));
05057 IkReal x1171=((cj9)*(r02));
05058 IkReal x1172=((sj13)*(sj9));
05059 IkReal x1173=((cj14)*(r10));
05060 IkReal x1174=((IkReal(1.00000000000000))*(cj13));
05061 IkReal x1175=((cj14)*(r20));
05062 IkReal x1176=((cj11)*(x1165));
05063 IkReal x1177=((sj11)*(x1166));
05064 IkReal x1178=((sj14)*(x1174));
05065 IkReal x1179=((sj11)*(x1165));
05066 IkReal x1180=((cj11)*(x1166));
05067 IkReal x1181=((cj14)*(cj9)*(r00));
05068 IkReal x1182=((x1177)+(x1176));
05069 evalcond[0]=((((cj13)*(x1170)))+(x1179)+(((IkReal(-1.00000000000000))*(r22)*(x1167)))+(((IkReal(-1.00000000000000))*(x1180)))+(((IkReal(-1.00000000000000))*(x1174)*(x1175))));
05070 evalcond[1]=((x1182)+(((sj13)*(x1170)))+(((IkReal(-1.00000000000000))*(x1167)*(x1175)))+(((cj13)*(r22))));
05071 evalcond[2]=((x1182)+(((cj13)*(sj9)*(x1173)))+(((sj13)*(x1171)))+(((IkReal(-1.00000000000000))*(x1168)*(x1178)))+(((r12)*(x1172)))+(((IkReal(-1.00000000000000))*(x1169)*(x1178)))+(((cj13)*(x1181))));
05072 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1174)))+(x1180)+(((IkReal(-1.00000000000000))*(x1171)*(x1174)))+(((IkReal(-1.00000000000000))*(sj14)*(x1167)*(x1168)))+(((IkReal(-1.00000000000000))*(sj14)*(x1167)*(x1169)))+(((x1172)*(x1173)))+(((sj13)*(x1181)))+(((IkReal(-1.00000000000000))*(x1179))));
05073 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05074 {
05075 continue;
05076 }
05077 }
05078 
05079 {
05080 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05081 vinfos[0].jointtype = 1;
05082 vinfos[0].foffset = j9;
05083 vinfos[0].indices[0] = _ij9[0];
05084 vinfos[0].indices[1] = _ij9[1];
05085 vinfos[0].maxsolutions = _nj9;
05086 vinfos[1].jointtype = 1;
05087 vinfos[1].foffset = j10;
05088 vinfos[1].indices[0] = _ij10[0];
05089 vinfos[1].indices[1] = _ij10[1];
05090 vinfos[1].maxsolutions = _nj10;
05091 vinfos[2].jointtype = 1;
05092 vinfos[2].foffset = j11;
05093 vinfos[2].indices[0] = _ij11[0];
05094 vinfos[2].indices[1] = _ij11[1];
05095 vinfos[2].maxsolutions = _nj11;
05096 vinfos[3].jointtype = 1;
05097 vinfos[3].foffset = j12;
05098 vinfos[3].indices[0] = _ij12[0];
05099 vinfos[3].indices[1] = _ij12[1];
05100 vinfos[3].maxsolutions = _nj12;
05101 vinfos[4].jointtype = 1;
05102 vinfos[4].foffset = j13;
05103 vinfos[4].indices[0] = _ij13[0];
05104 vinfos[4].indices[1] = _ij13[1];
05105 vinfos[4].maxsolutions = _nj13;
05106 vinfos[5].jointtype = 1;
05107 vinfos[5].foffset = j14;
05108 vinfos[5].indices[0] = _ij14[0];
05109 vinfos[5].indices[1] = _ij14[1];
05110 vinfos[5].maxsolutions = _nj14;
05111 std::vector<int> vfree(0);
05112 solutions.AddSolution(vinfos,vfree);
05113 }
05114 }
05115 }
05116 
05117 }
05118 
05119 }
05120 }
05121 }
05122 
05123 }
05124 
05125 }
05126 
05127 } else
05128 {
05129 {
05130 IkReal j10array[1], cj10array[1], sj10array[1];
05131 bool j10valid[1]={false};
05132 _nj10 = 1;
05133 IkReal x1183=((cj13)*(sj11));
05134 IkReal x1184=((r21)*(sj14));
05135 IkReal x1185=((cj11)*(cj13));
05136 IkReal x1186=((cj11)*(sj13));
05137 IkReal x1187=((sj11)*(sj13));
05138 IkReal x1188=((IkReal(1.00000000000000))*(cj14)*(r20));
05139 if( IKabs(((gconst34)*(((((x1184)*(x1186)))+(((x1183)*(x1184)))+(((r22)*(x1185)))+(((IkReal(-1.00000000000000))*(x1186)*(x1188)))+(((IkReal(-1.00000000000000))*(x1183)*(x1188)))+(((IkReal(-1.00000000000000))*(r22)*(x1187))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst34)*(((((cj14)*(r20)*(x1185)))+(((x1184)*(x1187)))+(((r22)*(x1186)))+(((r22)*(x1183)))+(((IkReal(-1.00000000000000))*(x1187)*(x1188)))+(((IkReal(-1.00000000000000))*(x1184)*(x1185))))))) < IKFAST_ATAN2_MAGTHRESH )
05140     continue;
05141 j10array[0]=IKatan2(((gconst34)*(((((x1184)*(x1186)))+(((x1183)*(x1184)))+(((r22)*(x1185)))+(((IkReal(-1.00000000000000))*(x1186)*(x1188)))+(((IkReal(-1.00000000000000))*(x1183)*(x1188)))+(((IkReal(-1.00000000000000))*(r22)*(x1187)))))), ((gconst34)*(((((cj14)*(r20)*(x1185)))+(((x1184)*(x1187)))+(((r22)*(x1186)))+(((r22)*(x1183)))+(((IkReal(-1.00000000000000))*(x1187)*(x1188)))+(((IkReal(-1.00000000000000))*(x1184)*(x1185)))))));
05142 sj10array[0]=IKsin(j10array[0]);
05143 cj10array[0]=IKcos(j10array[0]);
05144 if( j10array[0] > IKPI )
05145 {
05146     j10array[0]-=IK2PI;
05147 }
05148 else if( j10array[0] < -IKPI )
05149 {    j10array[0]+=IK2PI;
05150 }
05151 j10valid[0] = true;
05152 for(int ij10 = 0; ij10 < 1; ++ij10)
05153 {
05154 if( !j10valid[ij10] )
05155 {
05156     continue;
05157 }
05158 _ij10[0] = ij10; _ij10[1] = -1;
05159 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
05160 {
05161 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
05162 {
05163     j10valid[iij10]=false; _ij10[1] = iij10; break; 
05164 }
05165 }
05166 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
05167 {
05168 IkReal evalcond[2];
05169 IkReal x1189=IKsin(j10);
05170 IkReal x1190=IKcos(j10);
05171 IkReal x1191=((IkReal(1.00000000000000))*(sj13));
05172 IkReal x1192=((cj14)*(r20));
05173 IkReal x1193=((r21)*(sj14));
05174 evalcond[0]=((((IkReal(-1.00000000000000))*(cj11)*(x1190)))+(((IkReal(-1.00000000000000))*(r22)*(x1191)))+(((sj11)*(x1189)))+(((IkReal(-1.00000000000000))*(cj13)*(x1192)))+(((cj13)*(x1193))));
05175 evalcond[1]=((((IkReal(-1.00000000000000))*(x1191)*(x1192)))+(((sj11)*(x1190)))+(((cj11)*(x1189)))+(((sj13)*(x1193)))+(((cj13)*(r22))));
05176 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
05177 {
05178 continue;
05179 }
05180 }
05181 
05182 {
05183 IkReal dummyeval[1];
05184 IkReal gconst37;
05185 IkReal x1194=(sj14)*(sj14);
05186 IkReal x1195=(cj14)*(cj14);
05187 IkReal x1196=((IkReal(2.00000000000000))*(cj14)*(sj14));
05188 gconst37=IKsign(((((x1194)*((r10)*(r10))))+(((x1195)*((r01)*(r01))))+(((r10)*(r11)*(x1196)))+(((x1195)*((r11)*(r11))))+(((x1194)*((r00)*(r00))))+(((r00)*(r01)*(x1196)))));
05189 IkReal x1197=(sj14)*(sj14);
05190 IkReal x1198=(cj14)*(cj14);
05191 IkReal x1199=((IkReal(2.00000000000000))*(cj14)*(sj14));
05192 dummyeval[0]=((((x1197)*((r00)*(r00))))+(((r10)*(r11)*(x1199)))+(((x1198)*((r01)*(r01))))+(((x1197)*((r10)*(r10))))+(((r00)*(r01)*(x1199)))+(((x1198)*((r11)*(r11)))));
05193 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05194 {
05195 {
05196 IkReal dummyeval[1];
05197 IkReal gconst38;
05198 IkReal x1200=(cj14)*(cj14);
05199 IkReal x1201=(sj14)*(sj14);
05200 IkReal x1202=((IkReal(1.00000000000000))*(r01));
05201 IkReal x1203=((sj13)*(sj14));
05202 IkReal x1204=((cj14)*(sj13));
05203 IkReal x1205=((r00)*(r11));
05204 IkReal x1206=((cj13)*(x1200));
05205 IkReal x1207=((cj13)*(x1201));
05206 gconst38=IKsign(((((IkReal(-1.00000000000000))*(r12)*(x1202)*(x1204)))+(((x1205)*(x1206)))+(((x1205)*(x1207)))+(((IkReal(-1.00000000000000))*(r10)*(x1202)*(x1207)))+(((IkReal(-1.00000000000000))*(r10)*(x1202)*(x1206)))+(((r02)*(r11)*(x1204)))+(((r02)*(r10)*(x1203)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x1203)))));
05207 IkReal x1208=(cj14)*(cj14);
05208 IkReal x1209=(sj14)*(sj14);
05209 IkReal x1210=((IkReal(1.00000000000000))*(r01));
05210 IkReal x1211=((sj13)*(sj14));
05211 IkReal x1212=((cj14)*(sj13));
05212 IkReal x1213=((r00)*(r11));
05213 IkReal x1214=((cj13)*(x1208));
05214 IkReal x1215=((cj13)*(x1209));
05215 dummyeval[0]=((((x1213)*(x1215)))+(((x1213)*(x1214)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x1211)))+(((IkReal(-1.00000000000000))*(r10)*(x1210)*(x1215)))+(((IkReal(-1.00000000000000))*(r10)*(x1210)*(x1214)))+(((IkReal(-1.00000000000000))*(r12)*(x1210)*(x1212)))+(((r02)*(r10)*(x1211)))+(((r02)*(r11)*(x1212))));
05216 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05217 {
05218 continue;
05219 
05220 } else
05221 {
05222 {
05223 IkReal j9array[1], cj9array[1], sj9array[1];
05224 bool j9valid[1]={false};
05225 _nj9 = 1;
05226 IkReal x1216=((cj13)*(cj14));
05227 IkReal x1217=((IkReal(1.00000000000000))*(cj13)*(sj14));
05228 if( IKabs(((gconst38)*(((((r12)*(sj13)))+(((r10)*(x1216)))+(((IkReal(-1.00000000000000))*(r11)*(x1217))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst38)*(((((r02)*(sj13)))+(((r00)*(x1216)))+(((IkReal(-1.00000000000000))*(r01)*(x1217))))))) < IKFAST_ATAN2_MAGTHRESH )
05229     continue;
05230 j9array[0]=IKatan2(((gconst38)*(((((r12)*(sj13)))+(((r10)*(x1216)))+(((IkReal(-1.00000000000000))*(r11)*(x1217)))))), ((gconst38)*(((((r02)*(sj13)))+(((r00)*(x1216)))+(((IkReal(-1.00000000000000))*(r01)*(x1217)))))));
05231 sj9array[0]=IKsin(j9array[0]);
05232 cj9array[0]=IKcos(j9array[0]);
05233 if( j9array[0] > IKPI )
05234 {
05235     j9array[0]-=IK2PI;
05236 }
05237 else if( j9array[0] < -IKPI )
05238 {    j9array[0]+=IK2PI;
05239 }
05240 j9valid[0] = true;
05241 for(int ij9 = 0; ij9 < 1; ++ij9)
05242 {
05243 if( !j9valid[ij9] )
05244 {
05245     continue;
05246 }
05247 _ij9[0] = ij9; _ij9[1] = -1;
05248 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
05249 {
05250 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
05251 {
05252     j9valid[iij9]=false; _ij9[1] = iij9; break; 
05253 }
05254 }
05255 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
05256 {
05257 IkReal evalcond[6];
05258 IkReal x1218=IKsin(j9);
05259 IkReal x1219=IKcos(j9);
05260 IkReal x1220=((IkReal(1.00000000000000))*(cj14));
05261 IkReal x1221=((IkReal(1.00000000000000))*(sj14));
05262 IkReal x1222=((cj13)*(cj14));
05263 IkReal x1223=((cj14)*(r10));
05264 IkReal x1224=((r01)*(sj14));
05265 IkReal x1225=((IkReal(1.00000000000000))*(r12));
05266 IkReal x1226=((sj13)*(x1219));
05267 IkReal x1227=((r02)*(x1218));
05268 IkReal x1228=((r11)*(x1218));
05269 IkReal x1229=((r10)*(x1219));
05270 IkReal x1230=((r01)*(x1219));
05271 IkReal x1231=((sj13)*(x1218));
05272 IkReal x1232=((r11)*(x1219));
05273 IkReal x1233=((cj13)*(x1218));
05274 IkReal x1234=((r10)*(x1218));
05275 IkReal x1235=((r00)*(x1219));
05276 IkReal x1236=((cj13)*(x1219));
05277 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1220)*(x1232)))+(((IkReal(-1.00000000000000))*(x1221)*(x1229)))+(((cj14)*(r01)*(x1218)))+(((r00)*(sj14)*(x1218))));
05278 evalcond[1]=((((IkReal(-1.00000000000000))*(x1220)*(x1230)))+(((IkReal(-1.00000000000000))*(x1220)*(x1228)))+(((IkReal(-1.00000000000000))*(x1221)*(x1234)))+(((IkReal(-1.00000000000000))*(x1221)*(x1235))));
05279 evalcond[2]=((((x1224)*(x1233)))+(((x1222)*(x1229)))+(((IkReal(-1.00000000000000))*(r00)*(x1220)*(x1233)))+(((IkReal(-1.00000000000000))*(sj13)*(x1227)))+(((r12)*(x1226)))+(((IkReal(-1.00000000000000))*(cj13)*(x1221)*(x1232))));
05280 evalcond[3]=((((IkReal(-1.00000000000000))*(r11)*(x1221)*(x1226)))+(((IkReal(-1.00000000000000))*(x1225)*(x1236)))+(((x1223)*(x1226)))+(((x1224)*(x1231)))+(((cj13)*(x1227)))+(((IkReal(-1.00000000000000))*(r00)*(x1220)*(x1231))));
05281 evalcond[4]=((((cj10)*(sj11)))+(((r02)*(x1226)))+(((x1222)*(x1235)))+(((x1222)*(x1234)))+(((IkReal(-1.00000000000000))*(cj13)*(x1221)*(x1228)))+(((cj11)*(sj10)))+(((IkReal(-1.00000000000000))*(cj13)*(x1221)*(x1230)))+(((r12)*(x1231))));
05282 evalcond[5]=((((IkReal(-1.00000000000000))*(x1225)*(x1233)))+(((IkReal(-1.00000000000000))*(r01)*(x1221)*(x1226)))+(((x1223)*(x1231)))+(((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(sj13)*(x1221)*(x1228)))+(((IkReal(-1.00000000000000))*(r02)*(x1236)))+(((cj14)*(r00)*(x1226)))+(((cj10)*(cj11))));
05283 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  )
05284 {
05285 continue;
05286 }
05287 }
05288 
05289 {
05290 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05291 vinfos[0].jointtype = 1;
05292 vinfos[0].foffset = j9;
05293 vinfos[0].indices[0] = _ij9[0];
05294 vinfos[0].indices[1] = _ij9[1];
05295 vinfos[0].maxsolutions = _nj9;
05296 vinfos[1].jointtype = 1;
05297 vinfos[1].foffset = j10;
05298 vinfos[1].indices[0] = _ij10[0];
05299 vinfos[1].indices[1] = _ij10[1];
05300 vinfos[1].maxsolutions = _nj10;
05301 vinfos[2].jointtype = 1;
05302 vinfos[2].foffset = j11;
05303 vinfos[2].indices[0] = _ij11[0];
05304 vinfos[2].indices[1] = _ij11[1];
05305 vinfos[2].maxsolutions = _nj11;
05306 vinfos[3].jointtype = 1;
05307 vinfos[3].foffset = j12;
05308 vinfos[3].indices[0] = _ij12[0];
05309 vinfos[3].indices[1] = _ij12[1];
05310 vinfos[3].maxsolutions = _nj12;
05311 vinfos[4].jointtype = 1;
05312 vinfos[4].foffset = j13;
05313 vinfos[4].indices[0] = _ij13[0];
05314 vinfos[4].indices[1] = _ij13[1];
05315 vinfos[4].maxsolutions = _nj13;
05316 vinfos[5].jointtype = 1;
05317 vinfos[5].foffset = j14;
05318 vinfos[5].indices[0] = _ij14[0];
05319 vinfos[5].indices[1] = _ij14[1];
05320 vinfos[5].maxsolutions = _nj14;
05321 std::vector<int> vfree(0);
05322 solutions.AddSolution(vinfos,vfree);
05323 }
05324 }
05325 }
05326 
05327 }
05328 
05329 }
05330 
05331 } else
05332 {
05333 {
05334 IkReal j9array[1], cj9array[1], sj9array[1];
05335 bool j9valid[1]={false};
05336 _nj9 = 1;
05337 if( IKabs(((gconst37)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst37)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
05338     continue;
05339 j9array[0]=IKatan2(((gconst37)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst37)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
05340 sj9array[0]=IKsin(j9array[0]);
05341 cj9array[0]=IKcos(j9array[0]);
05342 if( j9array[0] > IKPI )
05343 {
05344     j9array[0]-=IK2PI;
05345 }
05346 else if( j9array[0] < -IKPI )
05347 {    j9array[0]+=IK2PI;
05348 }
05349 j9valid[0] = true;
05350 for(int ij9 = 0; ij9 < 1; ++ij9)
05351 {
05352 if( !j9valid[ij9] )
05353 {
05354     continue;
05355 }
05356 _ij9[0] = ij9; _ij9[1] = -1;
05357 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
05358 {
05359 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
05360 {
05361     j9valid[iij9]=false; _ij9[1] = iij9; break; 
05362 }
05363 }
05364 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
05365 {
05366 IkReal evalcond[6];
05367 IkReal x1237=IKsin(j9);
05368 IkReal x1238=IKcos(j9);
05369 IkReal x1239=((IkReal(1.00000000000000))*(cj14));
05370 IkReal x1240=((IkReal(1.00000000000000))*(sj14));
05371 IkReal x1241=((cj13)*(cj14));
05372 IkReal x1242=((cj14)*(r10));
05373 IkReal x1243=((r01)*(sj14));
05374 IkReal x1244=((IkReal(1.00000000000000))*(r12));
05375 IkReal x1245=((sj13)*(x1238));
05376 IkReal x1246=((r02)*(x1237));
05377 IkReal x1247=((r11)*(x1237));
05378 IkReal x1248=((r10)*(x1238));
05379 IkReal x1249=((r01)*(x1238));
05380 IkReal x1250=((sj13)*(x1237));
05381 IkReal x1251=((r11)*(x1238));
05382 IkReal x1252=((cj13)*(x1237));
05383 IkReal x1253=((r10)*(x1237));
05384 IkReal x1254=((r00)*(x1238));
05385 IkReal x1255=((cj13)*(x1238));
05386 evalcond[0]=((IkReal(1.00000000000000))+(((cj14)*(r01)*(x1237)))+(((r00)*(sj14)*(x1237)))+(((IkReal(-1.00000000000000))*(x1239)*(x1251)))+(((IkReal(-1.00000000000000))*(x1240)*(x1248))));
05387 evalcond[1]=((((IkReal(-1.00000000000000))*(x1239)*(x1247)))+(((IkReal(-1.00000000000000))*(x1239)*(x1249)))+(((IkReal(-1.00000000000000))*(x1240)*(x1253)))+(((IkReal(-1.00000000000000))*(x1240)*(x1254))));
05388 evalcond[2]=((((x1243)*(x1252)))+(((IkReal(-1.00000000000000))*(r00)*(x1239)*(x1252)))+(((IkReal(-1.00000000000000))*(cj13)*(x1240)*(x1251)))+(((IkReal(-1.00000000000000))*(sj13)*(x1246)))+(((x1241)*(x1248)))+(((r12)*(x1245))));
05389 evalcond[3]=((((x1243)*(x1250)))+(((IkReal(-1.00000000000000))*(r00)*(x1239)*(x1250)))+(((IkReal(-1.00000000000000))*(x1244)*(x1255)))+(((x1242)*(x1245)))+(((IkReal(-1.00000000000000))*(r11)*(x1240)*(x1245)))+(((cj13)*(x1246))));
05390 evalcond[4]=((((IkReal(-1.00000000000000))*(cj13)*(x1240)*(x1249)))+(((IkReal(-1.00000000000000))*(cj13)*(x1240)*(x1247)))+(((x1241)*(x1254)))+(((x1241)*(x1253)))+(((r12)*(x1250)))+(((cj10)*(sj11)))+(((r02)*(x1245)))+(((cj11)*(sj10))));
05391 evalcond[5]=((((IkReal(-1.00000000000000))*(r01)*(x1240)*(x1245)))+(((IkReal(-1.00000000000000))*(sj13)*(x1240)*(x1247)))+(((IkReal(-1.00000000000000))*(r02)*(x1255)))+(((IkReal(-1.00000000000000))*(sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(x1244)*(x1252)))+(((cj14)*(r00)*(x1245)))+(((cj10)*(cj11)))+(((x1242)*(x1250))));
05392 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  )
05393 {
05394 continue;
05395 }
05396 }
05397 
05398 {
05399 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05400 vinfos[0].jointtype = 1;
05401 vinfos[0].foffset = j9;
05402 vinfos[0].indices[0] = _ij9[0];
05403 vinfos[0].indices[1] = _ij9[1];
05404 vinfos[0].maxsolutions = _nj9;
05405 vinfos[1].jointtype = 1;
05406 vinfos[1].foffset = j10;
05407 vinfos[1].indices[0] = _ij10[0];
05408 vinfos[1].indices[1] = _ij10[1];
05409 vinfos[1].maxsolutions = _nj10;
05410 vinfos[2].jointtype = 1;
05411 vinfos[2].foffset = j11;
05412 vinfos[2].indices[0] = _ij11[0];
05413 vinfos[2].indices[1] = _ij11[1];
05414 vinfos[2].maxsolutions = _nj11;
05415 vinfos[3].jointtype = 1;
05416 vinfos[3].foffset = j12;
05417 vinfos[3].indices[0] = _ij12[0];
05418 vinfos[3].indices[1] = _ij12[1];
05419 vinfos[3].maxsolutions = _nj12;
05420 vinfos[4].jointtype = 1;
05421 vinfos[4].foffset = j13;
05422 vinfos[4].indices[0] = _ij13[0];
05423 vinfos[4].indices[1] = _ij13[1];
05424 vinfos[4].maxsolutions = _nj13;
05425 vinfos[5].jointtype = 1;
05426 vinfos[5].foffset = j14;
05427 vinfos[5].indices[0] = _ij14[0];
05428 vinfos[5].indices[1] = _ij14[1];
05429 vinfos[5].maxsolutions = _nj14;
05430 std::vector<int> vfree(0);
05431 solutions.AddSolution(vinfos,vfree);
05432 }
05433 }
05434 }
05435 
05436 }
05437 
05438 }
05439 }
05440 }
05441 
05442 }
05443 
05444 }
05445 
05446 } else
05447 {
05448 {
05449 IkReal j9array[1], cj9array[1], sj9array[1];
05450 bool j9valid[1]={false};
05451 _nj9 = 1;
05452 if( IKabs(((gconst32)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst32)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
05453     continue;
05454 j9array[0]=IKatan2(((gconst32)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst32)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
05455 sj9array[0]=IKsin(j9array[0]);
05456 cj9array[0]=IKcos(j9array[0]);
05457 if( j9array[0] > IKPI )
05458 {
05459     j9array[0]-=IK2PI;
05460 }
05461 else if( j9array[0] < -IKPI )
05462 {    j9array[0]+=IK2PI;
05463 }
05464 j9valid[0] = true;
05465 for(int ij9 = 0; ij9 < 1; ++ij9)
05466 {
05467 if( !j9valid[ij9] )
05468 {
05469     continue;
05470 }
05471 _ij9[0] = ij9; _ij9[1] = -1;
05472 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
05473 {
05474 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
05475 {
05476     j9valid[iij9]=false; _ij9[1] = iij9; break; 
05477 }
05478 }
05479 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
05480 {
05481 IkReal evalcond[4];
05482 IkReal x1256=IKsin(j9);
05483 IkReal x1257=IKcos(j9);
05484 IkReal x1258=((r10)*(sj14));
05485 IkReal x1259=((cj14)*(r11));
05486 IkReal x1260=((cj14)*(r10));
05487 IkReal x1261=((cj14)*(r00));
05488 IkReal x1262=((r11)*(sj14));
05489 IkReal x1263=((r00)*(sj14));
05490 IkReal x1264=((IkReal(1.00000000000000))*(x1256));
05491 IkReal x1265=((cj13)*(x1256));
05492 IkReal x1266=((sj13)*(x1257));
05493 IkReal x1267=((r01)*(x1256));
05494 IkReal x1268=((IkReal(1.00000000000000))*(x1257));
05495 evalcond[0]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x1258)*(x1268)))+(((cj14)*(x1267)))+(((x1256)*(x1263)))+(((IkReal(-1.00000000000000))*(x1259)*(x1268))));
05496 evalcond[1]=((((IkReal(-1.00000000000000))*(x1258)*(x1264)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1268)))+(((IkReal(-1.00000000000000))*(x1263)*(x1268)))+(((IkReal(-1.00000000000000))*(x1259)*(x1264))));
05497 evalcond[2]=((((r01)*(sj14)*(x1265)))+(((cj13)*(x1257)*(x1260)))+(((IkReal(-1.00000000000000))*(cj13)*(x1262)*(x1268)))+(((r12)*(x1266)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x1264)))+(((IkReal(-1.00000000000000))*(cj13)*(x1261)*(x1264))));
05498 evalcond[3]=((((r02)*(x1265)))+(((IkReal(-1.00000000000000))*(x1262)*(x1266)))+(((x1260)*(x1266)))+(((sj13)*(sj14)*(x1267)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1268)))+(((IkReal(-1.00000000000000))*(sj13)*(x1261)*(x1264))));
05499 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05500 {
05501 continue;
05502 }
05503 }
05504 
05505 {
05506 IkReal dummyeval[1];
05507 IkReal gconst35;
05508 gconst35=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
05509 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
05510 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05511 {
05512 {
05513 IkReal dummyeval[1];
05514 IkReal gconst36;
05515 gconst36=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
05516 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
05517 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05518 {
05519 continue;
05520 
05521 } else
05522 {
05523 {
05524 IkReal j10array[1], cj10array[1], sj10array[1];
05525 bool j10valid[1]={false};
05526 _nj10 = 1;
05527 IkReal x1269=((cj13)*(sj14));
05528 IkReal x1270=((IkReal(1.00000000000000))*(cj11));
05529 IkReal x1271=((r11)*(sj9));
05530 IkReal x1272=((cj13)*(cj14));
05531 IkReal x1273=((IkReal(1.00000000000000))*(sj11));
05532 IkReal x1274=((cj11)*(sj13));
05533 IkReal x1275=((r10)*(sj9));
05534 IkReal x1276=((sj11)*(sj13));
05535 IkReal x1277=((cj9)*(r02));
05536 IkReal x1278=((r12)*(sj9));
05537 IkReal x1279=((cj9)*(r00));
05538 IkReal x1280=((cj9)*(r01));
05539 if( IKabs(((gconst36)*(((((cj11)*(x1272)*(x1279)))+(((cj11)*(x1272)*(x1275)))+(((x1274)*(x1278)))+(((x1274)*(x1277)))+(((IkReal(-1.00000000000000))*(x1269)*(x1270)*(x1280)))+(((IkReal(-1.00000000000000))*(r20)*(x1272)*(x1273)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1273)))+(((r21)*(sj11)*(x1269)))+(((IkReal(-1.00000000000000))*(x1269)*(x1270)*(x1271))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst36)*(((((IkReal(-1.00000000000000))*(x1269)*(x1273)*(x1280)))+(((x1276)*(x1277)))+(((x1276)*(x1278)))+(((IkReal(-1.00000000000000))*(r21)*(x1269)*(x1270)))+(((sj11)*(x1272)*(x1275)))+(((sj11)*(x1272)*(x1279)))+(((r22)*(x1274)))+(((cj11)*(r20)*(x1272)))+(((IkReal(-1.00000000000000))*(x1269)*(x1271)*(x1273))))))) < IKFAST_ATAN2_MAGTHRESH )
05540     continue;
05541 j10array[0]=IKatan2(((gconst36)*(((((cj11)*(x1272)*(x1279)))+(((cj11)*(x1272)*(x1275)))+(((x1274)*(x1278)))+(((x1274)*(x1277)))+(((IkReal(-1.00000000000000))*(x1269)*(x1270)*(x1280)))+(((IkReal(-1.00000000000000))*(r20)*(x1272)*(x1273)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1273)))+(((r21)*(sj11)*(x1269)))+(((IkReal(-1.00000000000000))*(x1269)*(x1270)*(x1271)))))), ((gconst36)*(((((IkReal(-1.00000000000000))*(x1269)*(x1273)*(x1280)))+(((x1276)*(x1277)))+(((x1276)*(x1278)))+(((IkReal(-1.00000000000000))*(r21)*(x1269)*(x1270)))+(((sj11)*(x1272)*(x1275)))+(((sj11)*(x1272)*(x1279)))+(((r22)*(x1274)))+(((cj11)*(r20)*(x1272)))+(((IkReal(-1.00000000000000))*(x1269)*(x1271)*(x1273)))))));
05542 sj10array[0]=IKsin(j10array[0]);
05543 cj10array[0]=IKcos(j10array[0]);
05544 if( j10array[0] > IKPI )
05545 {
05546     j10array[0]-=IK2PI;
05547 }
05548 else if( j10array[0] < -IKPI )
05549 {    j10array[0]+=IK2PI;
05550 }
05551 j10valid[0] = true;
05552 for(int ij10 = 0; ij10 < 1; ++ij10)
05553 {
05554 if( !j10valid[ij10] )
05555 {
05556     continue;
05557 }
05558 _ij10[0] = ij10; _ij10[1] = -1;
05559 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
05560 {
05561 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
05562 {
05563     j10valid[iij10]=false; _ij10[1] = iij10; break; 
05564 }
05565 }
05566 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
05567 {
05568 IkReal evalcond[4];
05569 IkReal x1281=IKsin(j10);
05570 IkReal x1282=IKcos(j10);
05571 IkReal x1283=((IkReal(1.00000000000000))*(sj13));
05572 IkReal x1284=((r11)*(sj9));
05573 IkReal x1285=((cj9)*(r01));
05574 IkReal x1286=((r21)*(sj14));
05575 IkReal x1287=((cj9)*(r02));
05576 IkReal x1288=((sj13)*(sj9));
05577 IkReal x1289=((cj14)*(r10));
05578 IkReal x1290=((IkReal(1.00000000000000))*(cj13));
05579 IkReal x1291=((cj14)*(r20));
05580 IkReal x1292=((cj11)*(x1281));
05581 IkReal x1293=((sj11)*(x1282));
05582 IkReal x1294=((sj14)*(x1290));
05583 IkReal x1295=((sj11)*(x1281));
05584 IkReal x1296=((cj11)*(x1282));
05585 IkReal x1297=((cj14)*(cj9)*(r00));
05586 IkReal x1298=((x1292)+(x1293));
05587 evalcond[0]=((x1295)+(((IkReal(-1.00000000000000))*(r22)*(x1283)))+(((IkReal(-1.00000000000000))*(x1290)*(x1291)))+(((IkReal(-1.00000000000000))*(x1296)))+(((cj13)*(x1286))));
05588 evalcond[1]=((x1298)+(((IkReal(-1.00000000000000))*(x1283)*(x1291)))+(((sj13)*(x1286)))+(((cj13)*(r22))));
05589 evalcond[2]=((((IkReal(-1.00000000000000))*(x1284)*(x1294)))+(x1298)+(((cj13)*(x1297)))+(((sj13)*(x1287)))+(((IkReal(-1.00000000000000))*(x1285)*(x1294)))+(((r12)*(x1288)))+(((cj13)*(sj9)*(x1289))));
05590 evalcond[3]=((((x1288)*(x1289)))+(x1296)+(((sj13)*(x1297)))+(((IkReal(-1.00000000000000))*(x1287)*(x1290)))+(((IkReal(-1.00000000000000))*(sj14)*(x1283)*(x1284)))+(((IkReal(-1.00000000000000))*(sj14)*(x1283)*(x1285)))+(((IkReal(-1.00000000000000))*(x1295)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1290))));
05591 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05592 {
05593 continue;
05594 }
05595 }
05596 
05597 {
05598 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05599 vinfos[0].jointtype = 1;
05600 vinfos[0].foffset = j9;
05601 vinfos[0].indices[0] = _ij9[0];
05602 vinfos[0].indices[1] = _ij9[1];
05603 vinfos[0].maxsolutions = _nj9;
05604 vinfos[1].jointtype = 1;
05605 vinfos[1].foffset = j10;
05606 vinfos[1].indices[0] = _ij10[0];
05607 vinfos[1].indices[1] = _ij10[1];
05608 vinfos[1].maxsolutions = _nj10;
05609 vinfos[2].jointtype = 1;
05610 vinfos[2].foffset = j11;
05611 vinfos[2].indices[0] = _ij11[0];
05612 vinfos[2].indices[1] = _ij11[1];
05613 vinfos[2].maxsolutions = _nj11;
05614 vinfos[3].jointtype = 1;
05615 vinfos[3].foffset = j12;
05616 vinfos[3].indices[0] = _ij12[0];
05617 vinfos[3].indices[1] = _ij12[1];
05618 vinfos[3].maxsolutions = _nj12;
05619 vinfos[4].jointtype = 1;
05620 vinfos[4].foffset = j13;
05621 vinfos[4].indices[0] = _ij13[0];
05622 vinfos[4].indices[1] = _ij13[1];
05623 vinfos[4].maxsolutions = _nj13;
05624 vinfos[5].jointtype = 1;
05625 vinfos[5].foffset = j14;
05626 vinfos[5].indices[0] = _ij14[0];
05627 vinfos[5].indices[1] = _ij14[1];
05628 vinfos[5].maxsolutions = _nj14;
05629 std::vector<int> vfree(0);
05630 solutions.AddSolution(vinfos,vfree);
05631 }
05632 }
05633 }
05634 
05635 }
05636 
05637 }
05638 
05639 } else
05640 {
05641 {
05642 IkReal j10array[1], cj10array[1], sj10array[1];
05643 bool j10valid[1]={false};
05644 _nj10 = 1;
05645 IkReal x1299=((cj13)*(sj11));
05646 IkReal x1300=((r21)*(sj14));
05647 IkReal x1301=((cj11)*(cj13));
05648 IkReal x1302=((cj11)*(sj13));
05649 IkReal x1303=((sj11)*(sj13));
05650 IkReal x1304=((IkReal(1.00000000000000))*(cj14)*(r20));
05651 if( IKabs(((gconst35)*(((((x1299)*(x1300)))+(((IkReal(-1.00000000000000))*(x1299)*(x1304)))+(((x1300)*(x1302)))+(((IkReal(-1.00000000000000))*(r22)*(x1303)))+(((r22)*(x1301)))+(((IkReal(-1.00000000000000))*(x1302)*(x1304))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst35)*(((((x1300)*(x1303)))+(((IkReal(-1.00000000000000))*(x1303)*(x1304)))+(((r22)*(x1302)))+(((IkReal(-1.00000000000000))*(x1300)*(x1301)))+(((r22)*(x1299)))+(((cj14)*(r20)*(x1301))))))) < IKFAST_ATAN2_MAGTHRESH )
05652     continue;
05653 j10array[0]=IKatan2(((gconst35)*(((((x1299)*(x1300)))+(((IkReal(-1.00000000000000))*(x1299)*(x1304)))+(((x1300)*(x1302)))+(((IkReal(-1.00000000000000))*(r22)*(x1303)))+(((r22)*(x1301)))+(((IkReal(-1.00000000000000))*(x1302)*(x1304)))))), ((gconst35)*(((((x1300)*(x1303)))+(((IkReal(-1.00000000000000))*(x1303)*(x1304)))+(((r22)*(x1302)))+(((IkReal(-1.00000000000000))*(x1300)*(x1301)))+(((r22)*(x1299)))+(((cj14)*(r20)*(x1301)))))));
05654 sj10array[0]=IKsin(j10array[0]);
05655 cj10array[0]=IKcos(j10array[0]);
05656 if( j10array[0] > IKPI )
05657 {
05658     j10array[0]-=IK2PI;
05659 }
05660 else if( j10array[0] < -IKPI )
05661 {    j10array[0]+=IK2PI;
05662 }
05663 j10valid[0] = true;
05664 for(int ij10 = 0; ij10 < 1; ++ij10)
05665 {
05666 if( !j10valid[ij10] )
05667 {
05668     continue;
05669 }
05670 _ij10[0] = ij10; _ij10[1] = -1;
05671 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
05672 {
05673 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
05674 {
05675     j10valid[iij10]=false; _ij10[1] = iij10; break; 
05676 }
05677 }
05678 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
05679 {
05680 IkReal evalcond[4];
05681 IkReal x1305=IKsin(j10);
05682 IkReal x1306=IKcos(j10);
05683 IkReal x1307=((IkReal(1.00000000000000))*(sj13));
05684 IkReal x1308=((r11)*(sj9));
05685 IkReal x1309=((cj9)*(r01));
05686 IkReal x1310=((r21)*(sj14));
05687 IkReal x1311=((cj9)*(r02));
05688 IkReal x1312=((sj13)*(sj9));
05689 IkReal x1313=((cj14)*(r10));
05690 IkReal x1314=((IkReal(1.00000000000000))*(cj13));
05691 IkReal x1315=((cj14)*(r20));
05692 IkReal x1316=((cj11)*(x1305));
05693 IkReal x1317=((sj11)*(x1306));
05694 IkReal x1318=((sj14)*(x1314));
05695 IkReal x1319=((sj11)*(x1305));
05696 IkReal x1320=((cj11)*(x1306));
05697 IkReal x1321=((cj14)*(cj9)*(r00));
05698 IkReal x1322=((x1317)+(x1316));
05699 evalcond[0]=((x1319)+(((cj13)*(x1310)))+(((IkReal(-1.00000000000000))*(r22)*(x1307)))+(((IkReal(-1.00000000000000))*(x1314)*(x1315)))+(((IkReal(-1.00000000000000))*(x1320))));
05700 evalcond[1]=((x1322)+(((sj13)*(x1310)))+(((IkReal(-1.00000000000000))*(x1307)*(x1315)))+(((cj13)*(r22))));
05701 evalcond[2]=((x1322)+(((sj13)*(x1311)))+(((cj13)*(x1321)))+(((IkReal(-1.00000000000000))*(x1308)*(x1318)))+(((r12)*(x1312)))+(((cj13)*(sj9)*(x1313)))+(((IkReal(-1.00000000000000))*(x1309)*(x1318))));
05702 evalcond[3]=((x1320)+(((IkReal(-1.00000000000000))*(x1311)*(x1314)))+(((sj13)*(x1321)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1314)))+(((IkReal(-1.00000000000000))*(x1319)))+(((IkReal(-1.00000000000000))*(sj14)*(x1307)*(x1308)))+(((IkReal(-1.00000000000000))*(sj14)*(x1307)*(x1309)))+(((x1312)*(x1313))));
05703 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05704 {
05705 continue;
05706 }
05707 }
05708 
05709 {
05710 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05711 vinfos[0].jointtype = 1;
05712 vinfos[0].foffset = j9;
05713 vinfos[0].indices[0] = _ij9[0];
05714 vinfos[0].indices[1] = _ij9[1];
05715 vinfos[0].maxsolutions = _nj9;
05716 vinfos[1].jointtype = 1;
05717 vinfos[1].foffset = j10;
05718 vinfos[1].indices[0] = _ij10[0];
05719 vinfos[1].indices[1] = _ij10[1];
05720 vinfos[1].maxsolutions = _nj10;
05721 vinfos[2].jointtype = 1;
05722 vinfos[2].foffset = j11;
05723 vinfos[2].indices[0] = _ij11[0];
05724 vinfos[2].indices[1] = _ij11[1];
05725 vinfos[2].maxsolutions = _nj11;
05726 vinfos[3].jointtype = 1;
05727 vinfos[3].foffset = j12;
05728 vinfos[3].indices[0] = _ij12[0];
05729 vinfos[3].indices[1] = _ij12[1];
05730 vinfos[3].maxsolutions = _nj12;
05731 vinfos[4].jointtype = 1;
05732 vinfos[4].foffset = j13;
05733 vinfos[4].indices[0] = _ij13[0];
05734 vinfos[4].indices[1] = _ij13[1];
05735 vinfos[4].maxsolutions = _nj13;
05736 vinfos[5].jointtype = 1;
05737 vinfos[5].foffset = j14;
05738 vinfos[5].indices[0] = _ij14[0];
05739 vinfos[5].indices[1] = _ij14[1];
05740 vinfos[5].maxsolutions = _nj14;
05741 std::vector<int> vfree(0);
05742 solutions.AddSolution(vinfos,vfree);
05743 }
05744 }
05745 }
05746 
05747 }
05748 
05749 }
05750 }
05751 }
05752 
05753 }
05754 
05755 }
05756 
05757 } else
05758 {
05759 IkReal x1323=((IkReal(1.00000000000000))*(sj13));
05760 IkReal x1324=((cj14)*(npx));
05761 IkReal x1325=((npy)*(sj14));
05762 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
05763 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
05764 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
05765 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x1325)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x1323)))+(((IkReal(-1.00000000000000))*(cj13)*(x1324))));
05766 evalcond[4]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x1323)*(x1324)))+(((sj13)*(x1325)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(0.250000000000000))*(sj11))));
05767 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  )
05768 {
05769 {
05770 IkReal dummyeval[1];
05771 IkReal gconst39;
05772 IkReal x1326=(sj14)*(sj14);
05773 IkReal x1327=(cj14)*(cj14);
05774 IkReal x1328=((IkReal(1.00000000000000))*(x1326));
05775 IkReal x1329=((IkReal(2.00000000000000))*(cj14)*(sj14));
05776 IkReal x1330=((IkReal(1.00000000000000))*(x1327));
05777 gconst39=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1329)))+(((IkReal(-1.00000000000000))*(x1328)*((r00)*(r00))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1329)))+(((IkReal(-1.00000000000000))*(x1328)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1330)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1330)*((r01)*(r01))))));
05778 IkReal x1331=(sj14)*(sj14);
05779 IkReal x1332=(cj14)*(cj14);
05780 IkReal x1333=((IkReal(1.00000000000000))*(x1331));
05781 IkReal x1334=((IkReal(2.00000000000000))*(cj14)*(sj14));
05782 IkReal x1335=((IkReal(1.00000000000000))*(x1332));
05783 dummyeval[0]=((((IkReal(-1.00000000000000))*(x1333)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(r10)*(r11)*(x1334)))+(((IkReal(-1.00000000000000))*(x1335)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1335)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1334)))+(((IkReal(-1.00000000000000))*(x1333)*((r00)*(r00)))));
05784 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05785 {
05786 {
05787 IkReal dummyeval[1];
05788 IkReal gconst41;
05789 gconst41=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
05790 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
05791 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05792 {
05793 {
05794 IkReal dummyeval[1];
05795 IkReal gconst40;
05796 IkReal x1336=(sj14)*(sj14);
05797 IkReal x1337=(cj14)*(cj14);
05798 IkReal x1338=((cj14)*(sj13));
05799 IkReal x1339=((IkReal(1.00000000000000))*(r11));
05800 IkReal x1340=((cj13)*(r00));
05801 IkReal x1341=((sj13)*(sj14));
05802 IkReal x1342=((cj13)*(r01)*(r10));
05803 gconst40=IKsign(((((IkReal(-1.00000000000000))*(r02)*(r10)*(x1341)))+(((r01)*(r12)*(x1338)))+(((IkReal(-1.00000000000000))*(x1336)*(x1339)*(x1340)))+(((x1337)*(x1342)))+(((x1336)*(x1342)))+(((IkReal(-1.00000000000000))*(r02)*(x1338)*(x1339)))+(((IkReal(-1.00000000000000))*(x1337)*(x1339)*(x1340)))+(((r00)*(r12)*(x1341)))));
05804 IkReal x1343=(sj14)*(sj14);
05805 IkReal x1344=(cj14)*(cj14);
05806 IkReal x1345=((cj14)*(sj13));
05807 IkReal x1346=((IkReal(1.00000000000000))*(r11));
05808 IkReal x1347=((cj13)*(r00));
05809 IkReal x1348=((sj13)*(sj14));
05810 IkReal x1349=((cj13)*(r01)*(r10));
05811 dummyeval[0]=((((IkReal(-1.00000000000000))*(r02)*(x1345)*(x1346)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x1348)))+(((IkReal(-1.00000000000000))*(x1344)*(x1346)*(x1347)))+(((x1344)*(x1349)))+(((r00)*(r12)*(x1348)))+(((r01)*(r12)*(x1345)))+(((IkReal(-1.00000000000000))*(x1343)*(x1346)*(x1347)))+(((x1343)*(x1349))));
05812 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05813 {
05814 continue;
05815 
05816 } else
05817 {
05818 {
05819 IkReal j9array[1], cj9array[1], sj9array[1];
05820 bool j9valid[1]={false};
05821 _nj9 = 1;
05822 IkReal x1350=((cj13)*(cj14));
05823 IkReal x1351=((IkReal(1.00000000000000))*(cj13)*(sj14));
05824 if( IKabs(((gconst40)*(((((r10)*(x1350)))+(((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x1351))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst40)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x1351)))+(((r00)*(x1350))))))) < IKFAST_ATAN2_MAGTHRESH )
05825     continue;
05826 j9array[0]=IKatan2(((gconst40)*(((((r10)*(x1350)))+(((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x1351)))))), ((gconst40)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x1351)))+(((r00)*(x1350)))))));
05827 sj9array[0]=IKsin(j9array[0]);
05828 cj9array[0]=IKcos(j9array[0]);
05829 if( j9array[0] > IKPI )
05830 {
05831     j9array[0]-=IK2PI;
05832 }
05833 else if( j9array[0] < -IKPI )
05834 {    j9array[0]+=IK2PI;
05835 }
05836 j9valid[0] = true;
05837 for(int ij9 = 0; ij9 < 1; ++ij9)
05838 {
05839 if( !j9valid[ij9] )
05840 {
05841     continue;
05842 }
05843 _ij9[0] = ij9; _ij9[1] = -1;
05844 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
05845 {
05846 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
05847 {
05848     j9valid[iij9]=false; _ij9[1] = iij9; break; 
05849 }
05850 }
05851 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
05852 {
05853 IkReal evalcond[4];
05854 IkReal x1352=IKsin(j9);
05855 IkReal x1353=IKcos(j9);
05856 IkReal x1354=((r10)*(sj14));
05857 IkReal x1355=((cj14)*(r11));
05858 IkReal x1356=((cj14)*(r10));
05859 IkReal x1357=((cj14)*(r00));
05860 IkReal x1358=((r11)*(sj14));
05861 IkReal x1359=((r00)*(sj14));
05862 IkReal x1360=((IkReal(1.00000000000000))*(x1352));
05863 IkReal x1361=((cj13)*(x1352));
05864 IkReal x1362=((sj13)*(x1353));
05865 IkReal x1363=((r01)*(x1352));
05866 IkReal x1364=((IkReal(1.00000000000000))*(x1353));
05867 evalcond[0]=((IkReal(-1.00000000000000))+(((cj14)*(x1363)))+(((IkReal(-1.00000000000000))*(x1354)*(x1364)))+(((IkReal(-1.00000000000000))*(x1355)*(x1364)))+(((x1352)*(x1359))));
05868 evalcond[1]=((((IkReal(-1.00000000000000))*(x1354)*(x1360)))+(((IkReal(-1.00000000000000))*(x1359)*(x1364)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1364)))+(((IkReal(-1.00000000000000))*(x1355)*(x1360))));
05869 evalcond[2]=((((IkReal(-1.00000000000000))*(cj13)*(x1357)*(x1360)))+(((IkReal(-1.00000000000000))*(cj13)*(x1358)*(x1364)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x1360)))+(((cj13)*(x1353)*(x1356)))+(((r01)*(sj14)*(x1361)))+(((r12)*(x1362))));
05870 evalcond[3]=((((x1356)*(x1362)))+(((IkReal(-1.00000000000000))*(sj13)*(x1357)*(x1360)))+(((r02)*(x1361)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1364)))+(((IkReal(-1.00000000000000))*(x1358)*(x1362)))+(((sj13)*(sj14)*(x1363))));
05871 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05872 {
05873 continue;
05874 }
05875 }
05876 
05877 {
05878 IkReal dummyeval[1];
05879 IkReal gconst42;
05880 gconst42=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
05881 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
05882 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05883 {
05884 {
05885 IkReal dummyeval[1];
05886 IkReal gconst43;
05887 gconst43=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
05888 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
05889 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
05890 {
05891 continue;
05892 
05893 } else
05894 {
05895 {
05896 IkReal j10array[1], cj10array[1], sj10array[1];
05897 bool j10valid[1]={false};
05898 _nj10 = 1;
05899 IkReal x1365=((cj13)*(sj14));
05900 IkReal x1366=((IkReal(1.00000000000000))*(cj11));
05901 IkReal x1367=((r11)*(sj9));
05902 IkReal x1368=((IkReal(1.00000000000000))*(sj11));
05903 IkReal x1369=((cj13)*(cj14));
05904 IkReal x1370=((cj11)*(sj13));
05905 IkReal x1371=((r12)*(sj9));
05906 IkReal x1372=((cj9)*(r01));
05907 IkReal x1373=((sj11)*(sj13));
05908 IkReal x1374=((cj9)*(r02));
05909 IkReal x1375=((r10)*(sj9));
05910 IkReal x1376=((cj9)*(r00));
05911 if( IKabs(((gconst43)*(((((r21)*(sj11)*(x1365)))+(((IkReal(-1.00000000000000))*(r20)*(x1368)*(x1369)))+(((cj11)*(x1369)*(x1376)))+(((cj11)*(x1369)*(x1375)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)*(x1372)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)*(x1367)))+(((x1370)*(x1371)))+(((x1370)*(x1374)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1368))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((IkReal(-1.00000000000000))*(x1365)*(x1368)*(x1372)))+(((r22)*(x1370)))+(((x1371)*(x1373)))+(((cj11)*(r20)*(x1369)))+(((IkReal(-1.00000000000000))*(x1365)*(x1367)*(x1368)))+(((sj11)*(x1369)*(x1376)))+(((sj11)*(x1369)*(x1375)))+(((IkReal(-1.00000000000000))*(r21)*(x1365)*(x1366)))+(((x1373)*(x1374))))))) < IKFAST_ATAN2_MAGTHRESH )
05912     continue;
05913 j10array[0]=IKatan2(((gconst43)*(((((r21)*(sj11)*(x1365)))+(((IkReal(-1.00000000000000))*(r20)*(x1368)*(x1369)))+(((cj11)*(x1369)*(x1376)))+(((cj11)*(x1369)*(x1375)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)*(x1372)))+(((IkReal(-1.00000000000000))*(x1365)*(x1366)*(x1367)))+(((x1370)*(x1371)))+(((x1370)*(x1374)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1368)))))), ((gconst43)*(((((IkReal(-1.00000000000000))*(x1365)*(x1368)*(x1372)))+(((r22)*(x1370)))+(((x1371)*(x1373)))+(((cj11)*(r20)*(x1369)))+(((IkReal(-1.00000000000000))*(x1365)*(x1367)*(x1368)))+(((sj11)*(x1369)*(x1376)))+(((sj11)*(x1369)*(x1375)))+(((IkReal(-1.00000000000000))*(r21)*(x1365)*(x1366)))+(((x1373)*(x1374)))))));
05914 sj10array[0]=IKsin(j10array[0]);
05915 cj10array[0]=IKcos(j10array[0]);
05916 if( j10array[0] > IKPI )
05917 {
05918     j10array[0]-=IK2PI;
05919 }
05920 else if( j10array[0] < -IKPI )
05921 {    j10array[0]+=IK2PI;
05922 }
05923 j10valid[0] = true;
05924 for(int ij10 = 0; ij10 < 1; ++ij10)
05925 {
05926 if( !j10valid[ij10] )
05927 {
05928     continue;
05929 }
05930 _ij10[0] = ij10; _ij10[1] = -1;
05931 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
05932 {
05933 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
05934 {
05935     j10valid[iij10]=false; _ij10[1] = iij10; break; 
05936 }
05937 }
05938 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
05939 {
05940 IkReal evalcond[4];
05941 IkReal x1377=IKsin(j10);
05942 IkReal x1378=IKcos(j10);
05943 IkReal x1379=((IkReal(1.00000000000000))*(sj13));
05944 IkReal x1380=((r11)*(sj9));
05945 IkReal x1381=((cj9)*(r01));
05946 IkReal x1382=((IkReal(1.00000000000000))*(cj11));
05947 IkReal x1383=((r21)*(sj14));
05948 IkReal x1384=((cj9)*(r02));
05949 IkReal x1385=((sj13)*(sj9));
05950 IkReal x1386=((cj14)*(r10));
05951 IkReal x1387=((IkReal(1.00000000000000))*(cj13));
05952 IkReal x1388=((cj14)*(r20));
05953 IkReal x1389=((sj11)*(x1377));
05954 IkReal x1390=((sj14)*(x1387));
05955 IkReal x1391=((sj11)*(x1378));
05956 IkReal x1392=((cj14)*(cj9)*(r00));
05957 IkReal x1393=((x1378)*(x1382));
05958 evalcond[0]=((x1389)+(((IkReal(-1.00000000000000))*(r22)*(x1379)))+(((cj13)*(x1383)))+(((IkReal(-1.00000000000000))*(x1387)*(x1388)))+(((IkReal(-1.00000000000000))*(x1393))));
05959 evalcond[1]=((((IkReal(-1.00000000000000))*(x1377)*(x1382)))+(((sj13)*(x1383)))+(((IkReal(-1.00000000000000))*(x1391)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x1379)*(x1388))));
05960 evalcond[2]=((x1391)+(((cj13)*(x1392)))+(((sj13)*(x1384)))+(((IkReal(-1.00000000000000))*(x1381)*(x1390)))+(((IkReal(-1.00000000000000))*(x1380)*(x1390)))+(((cj11)*(x1377)))+(((r12)*(x1385)))+(((cj13)*(sj9)*(x1386))));
05961 evalcond[3]=((x1389)+(((IkReal(-1.00000000000000))*(x1384)*(x1387)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1387)))+(((IkReal(-1.00000000000000))*(sj14)*(x1379)*(x1380)))+(((IkReal(-1.00000000000000))*(sj14)*(x1379)*(x1381)))+(((sj13)*(x1392)))+(((x1385)*(x1386)))+(((IkReal(-1.00000000000000))*(x1393))));
05962 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
05963 {
05964 continue;
05965 }
05966 }
05967 
05968 {
05969 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
05970 vinfos[0].jointtype = 1;
05971 vinfos[0].foffset = j9;
05972 vinfos[0].indices[0] = _ij9[0];
05973 vinfos[0].indices[1] = _ij9[1];
05974 vinfos[0].maxsolutions = _nj9;
05975 vinfos[1].jointtype = 1;
05976 vinfos[1].foffset = j10;
05977 vinfos[1].indices[0] = _ij10[0];
05978 vinfos[1].indices[1] = _ij10[1];
05979 vinfos[1].maxsolutions = _nj10;
05980 vinfos[2].jointtype = 1;
05981 vinfos[2].foffset = j11;
05982 vinfos[2].indices[0] = _ij11[0];
05983 vinfos[2].indices[1] = _ij11[1];
05984 vinfos[2].maxsolutions = _nj11;
05985 vinfos[3].jointtype = 1;
05986 vinfos[3].foffset = j12;
05987 vinfos[3].indices[0] = _ij12[0];
05988 vinfos[3].indices[1] = _ij12[1];
05989 vinfos[3].maxsolutions = _nj12;
05990 vinfos[4].jointtype = 1;
05991 vinfos[4].foffset = j13;
05992 vinfos[4].indices[0] = _ij13[0];
05993 vinfos[4].indices[1] = _ij13[1];
05994 vinfos[4].maxsolutions = _nj13;
05995 vinfos[5].jointtype = 1;
05996 vinfos[5].foffset = j14;
05997 vinfos[5].indices[0] = _ij14[0];
05998 vinfos[5].indices[1] = _ij14[1];
05999 vinfos[5].maxsolutions = _nj14;
06000 std::vector<int> vfree(0);
06001 solutions.AddSolution(vinfos,vfree);
06002 }
06003 }
06004 }
06005 
06006 }
06007 
06008 }
06009 
06010 } else
06011 {
06012 {
06013 IkReal j10array[1], cj10array[1], sj10array[1];
06014 bool j10valid[1]={false};
06015 _nj10 = 1;
06016 IkReal x1394=((cj11)*(r22));
06017 IkReal x1395=((IkReal(1.00000000000000))*(sj13));
06018 IkReal x1396=((cj13)*(sj11));
06019 IkReal x1397=((r21)*(sj14));
06020 IkReal x1398=((cj11)*(cj13));
06021 IkReal x1399=((sj11)*(sj13));
06022 IkReal x1400=((cj14)*(r20));
06023 if( IKabs(((gconst42)*(((((cj11)*(sj13)*(x1397)))+(((x1396)*(x1400)))+(((cj13)*(x1394)))+(((r22)*(x1399)))+(((IkReal(-1.00000000000000))*(x1396)*(x1397)))+(((IkReal(-1.00000000000000))*(cj11)*(x1395)*(x1400))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1398)*(x1400)))+(((IkReal(-1.00000000000000))*(x1394)*(x1395)))+(((IkReal(-1.00000000000000))*(sj11)*(x1395)*(x1400)))+(((x1397)*(x1399)))+(((x1397)*(x1398)))+(((r22)*(x1396))))))) < IKFAST_ATAN2_MAGTHRESH )
06024     continue;
06025 j10array[0]=IKatan2(((gconst42)*(((((cj11)*(sj13)*(x1397)))+(((x1396)*(x1400)))+(((cj13)*(x1394)))+(((r22)*(x1399)))+(((IkReal(-1.00000000000000))*(x1396)*(x1397)))+(((IkReal(-1.00000000000000))*(cj11)*(x1395)*(x1400)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(x1398)*(x1400)))+(((IkReal(-1.00000000000000))*(x1394)*(x1395)))+(((IkReal(-1.00000000000000))*(sj11)*(x1395)*(x1400)))+(((x1397)*(x1399)))+(((x1397)*(x1398)))+(((r22)*(x1396)))))));
06026 sj10array[0]=IKsin(j10array[0]);
06027 cj10array[0]=IKcos(j10array[0]);
06028 if( j10array[0] > IKPI )
06029 {
06030     j10array[0]-=IK2PI;
06031 }
06032 else if( j10array[0] < -IKPI )
06033 {    j10array[0]+=IK2PI;
06034 }
06035 j10valid[0] = true;
06036 for(int ij10 = 0; ij10 < 1; ++ij10)
06037 {
06038 if( !j10valid[ij10] )
06039 {
06040     continue;
06041 }
06042 _ij10[0] = ij10; _ij10[1] = -1;
06043 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
06044 {
06045 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
06046 {
06047     j10valid[iij10]=false; _ij10[1] = iij10; break; 
06048 }
06049 }
06050 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
06051 {
06052 IkReal evalcond[4];
06053 IkReal x1401=IKsin(j10);
06054 IkReal x1402=IKcos(j10);
06055 IkReal x1403=((IkReal(1.00000000000000))*(sj13));
06056 IkReal x1404=((r11)*(sj9));
06057 IkReal x1405=((cj9)*(r01));
06058 IkReal x1406=((IkReal(1.00000000000000))*(cj11));
06059 IkReal x1407=((r21)*(sj14));
06060 IkReal x1408=((cj9)*(r02));
06061 IkReal x1409=((sj13)*(sj9));
06062 IkReal x1410=((cj14)*(r10));
06063 IkReal x1411=((IkReal(1.00000000000000))*(cj13));
06064 IkReal x1412=((cj14)*(r20));
06065 IkReal x1413=((sj11)*(x1401));
06066 IkReal x1414=((sj14)*(x1411));
06067 IkReal x1415=((sj11)*(x1402));
06068 IkReal x1416=((cj14)*(cj9)*(r00));
06069 IkReal x1417=((x1402)*(x1406));
06070 evalcond[0]=((((IkReal(-1.00000000000000))*(x1417)))+(((IkReal(-1.00000000000000))*(r22)*(x1403)))+(((cj13)*(x1407)))+(((IkReal(-1.00000000000000))*(x1411)*(x1412)))+(x1413));
06071 evalcond[1]=((((IkReal(-1.00000000000000))*(x1403)*(x1412)))+(((IkReal(-1.00000000000000))*(x1401)*(x1406)))+(((cj13)*(r22)))+(((sj13)*(x1407)))+(((IkReal(-1.00000000000000))*(x1415))));
06072 evalcond[2]=((((cj13)*(sj9)*(x1410)))+(((cj13)*(x1416)))+(((r12)*(x1409)))+(((IkReal(-1.00000000000000))*(x1404)*(x1414)))+(x1415)+(((IkReal(-1.00000000000000))*(x1405)*(x1414)))+(((cj11)*(x1401)))+(((sj13)*(x1408))));
06073 evalcond[3]=((((IkReal(-1.00000000000000))*(x1417)))+(((IkReal(-1.00000000000000))*(sj14)*(x1403)*(x1405)))+(((IkReal(-1.00000000000000))*(sj14)*(x1403)*(x1404)))+(((IkReal(-1.00000000000000))*(x1408)*(x1411)))+(((sj13)*(x1416)))+(x1413)+(((x1409)*(x1410)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1411))));
06074 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06075 {
06076 continue;
06077 }
06078 }
06079 
06080 {
06081 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06082 vinfos[0].jointtype = 1;
06083 vinfos[0].foffset = j9;
06084 vinfos[0].indices[0] = _ij9[0];
06085 vinfos[0].indices[1] = _ij9[1];
06086 vinfos[0].maxsolutions = _nj9;
06087 vinfos[1].jointtype = 1;
06088 vinfos[1].foffset = j10;
06089 vinfos[1].indices[0] = _ij10[0];
06090 vinfos[1].indices[1] = _ij10[1];
06091 vinfos[1].maxsolutions = _nj10;
06092 vinfos[2].jointtype = 1;
06093 vinfos[2].foffset = j11;
06094 vinfos[2].indices[0] = _ij11[0];
06095 vinfos[2].indices[1] = _ij11[1];
06096 vinfos[2].maxsolutions = _nj11;
06097 vinfos[3].jointtype = 1;
06098 vinfos[3].foffset = j12;
06099 vinfos[3].indices[0] = _ij12[0];
06100 vinfos[3].indices[1] = _ij12[1];
06101 vinfos[3].maxsolutions = _nj12;
06102 vinfos[4].jointtype = 1;
06103 vinfos[4].foffset = j13;
06104 vinfos[4].indices[0] = _ij13[0];
06105 vinfos[4].indices[1] = _ij13[1];
06106 vinfos[4].maxsolutions = _nj13;
06107 vinfos[5].jointtype = 1;
06108 vinfos[5].foffset = j14;
06109 vinfos[5].indices[0] = _ij14[0];
06110 vinfos[5].indices[1] = _ij14[1];
06111 vinfos[5].maxsolutions = _nj14;
06112 std::vector<int> vfree(0);
06113 solutions.AddSolution(vinfos,vfree);
06114 }
06115 }
06116 }
06117 
06118 }
06119 
06120 }
06121 }
06122 }
06123 
06124 }
06125 
06126 }
06127 
06128 } else
06129 {
06130 {
06131 IkReal j10array[1], cj10array[1], sj10array[1];
06132 bool j10valid[1]={false};
06133 _nj10 = 1;
06134 IkReal x1418=((r22)*(sj13));
06135 IkReal x1419=((IkReal(1.00000000000000))*(cj11));
06136 IkReal x1420=((cj13)*(sj11));
06137 IkReal x1421=((cj14)*(r20));
06138 IkReal x1422=((r21)*(sj14));
06139 IkReal x1423=((cj11)*(cj13));
06140 IkReal x1424=((sj11)*(sj13));
06141 if( IKabs(((gconst41)*(((((IkReal(-1.00000000000000))*(sj13)*(x1419)*(x1421)))+(((x1420)*(x1421)))+(((IkReal(-1.00000000000000))*(x1420)*(x1422)))+(((r22)*(x1423)))+(((sj11)*(x1418)))+(((cj11)*(sj13)*(x1422))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst41)*(((((x1422)*(x1423)))+(((x1422)*(x1424)))+(((r22)*(x1420)))+(((IkReal(-1.00000000000000))*(cj13)*(x1419)*(x1421)))+(((IkReal(-1.00000000000000))*(x1418)*(x1419)))+(((IkReal(-1.00000000000000))*(x1421)*(x1424))))))) < IKFAST_ATAN2_MAGTHRESH )
06142     continue;
06143 j10array[0]=IKatan2(((gconst41)*(((((IkReal(-1.00000000000000))*(sj13)*(x1419)*(x1421)))+(((x1420)*(x1421)))+(((IkReal(-1.00000000000000))*(x1420)*(x1422)))+(((r22)*(x1423)))+(((sj11)*(x1418)))+(((cj11)*(sj13)*(x1422)))))), ((gconst41)*(((((x1422)*(x1423)))+(((x1422)*(x1424)))+(((r22)*(x1420)))+(((IkReal(-1.00000000000000))*(cj13)*(x1419)*(x1421)))+(((IkReal(-1.00000000000000))*(x1418)*(x1419)))+(((IkReal(-1.00000000000000))*(x1421)*(x1424)))))));
06144 sj10array[0]=IKsin(j10array[0]);
06145 cj10array[0]=IKcos(j10array[0]);
06146 if( j10array[0] > IKPI )
06147 {
06148     j10array[0]-=IK2PI;
06149 }
06150 else if( j10array[0] < -IKPI )
06151 {    j10array[0]+=IK2PI;
06152 }
06153 j10valid[0] = true;
06154 for(int ij10 = 0; ij10 < 1; ++ij10)
06155 {
06156 if( !j10valid[ij10] )
06157 {
06158     continue;
06159 }
06160 _ij10[0] = ij10; _ij10[1] = -1;
06161 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
06162 {
06163 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
06164 {
06165     j10valid[iij10]=false; _ij10[1] = iij10; break; 
06166 }
06167 }
06168 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
06169 {
06170 IkReal evalcond[2];
06171 IkReal x1425=IKsin(j10);
06172 IkReal x1426=IKcos(j10);
06173 IkReal x1427=((IkReal(1.00000000000000))*(sj13));
06174 IkReal x1428=((cj14)*(r20));
06175 IkReal x1429=((r21)*(sj14));
06176 IkReal x1430=((IkReal(1.00000000000000))*(x1426));
06177 evalcond[0]=((((IkReal(-1.00000000000000))*(cj11)*(x1430)))+(((IkReal(-1.00000000000000))*(r22)*(x1427)))+(((IkReal(-1.00000000000000))*(cj13)*(x1428)))+(((cj13)*(x1429)))+(((sj11)*(x1425))));
06178 evalcond[1]=((((IkReal(-1.00000000000000))*(x1427)*(x1428)))+(((IkReal(-1.00000000000000))*(sj11)*(x1430)))+(((sj13)*(x1429)))+(((IkReal(-1.00000000000000))*(cj11)*(x1425)))+(((cj13)*(r22))));
06179 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
06180 {
06181 continue;
06182 }
06183 }
06184 
06185 {
06186 IkReal dummyeval[1];
06187 IkReal gconst44;
06188 IkReal x1431=(sj14)*(sj14);
06189 IkReal x1432=(cj14)*(cj14);
06190 IkReal x1433=((IkReal(1.00000000000000))*(x1431));
06191 IkReal x1434=((IkReal(2.00000000000000))*(cj14)*(sj14));
06192 IkReal x1435=((IkReal(1.00000000000000))*(x1432));
06193 gconst44=IKsign(((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1434)))+(((IkReal(-1.00000000000000))*(x1433)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1435)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(x1435)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1434)))+(((IkReal(-1.00000000000000))*(x1433)*((r00)*(r00))))));
06194 IkReal x1436=(sj14)*(sj14);
06195 IkReal x1437=(cj14)*(cj14);
06196 IkReal x1438=((IkReal(1.00000000000000))*(x1436));
06197 IkReal x1439=((IkReal(2.00000000000000))*(cj14)*(sj14));
06198 IkReal x1440=((IkReal(1.00000000000000))*(x1437));
06199 dummyeval[0]=((((IkReal(-1.00000000000000))*(r10)*(r11)*(x1439)))+(((IkReal(-1.00000000000000))*(x1438)*((r10)*(r10))))+(((IkReal(-1.00000000000000))*(x1440)*((r01)*(r01))))+(((IkReal(-1.00000000000000))*(x1440)*((r11)*(r11))))+(((IkReal(-1.00000000000000))*(r00)*(r01)*(x1439)))+(((IkReal(-1.00000000000000))*(x1438)*((r00)*(r00)))));
06200 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06201 {
06202 {
06203 IkReal dummyeval[1];
06204 IkReal gconst45;
06205 IkReal x1441=(sj14)*(sj14);
06206 IkReal x1442=(cj14)*(cj14);
06207 IkReal x1443=((cj14)*(sj13));
06208 IkReal x1444=((IkReal(1.00000000000000))*(r11));
06209 IkReal x1445=((cj13)*(r00));
06210 IkReal x1446=((sj13)*(sj14));
06211 IkReal x1447=((cj13)*(r01)*(r10));
06212 gconst45=IKsign(((((x1442)*(x1447)))+(((x1441)*(x1447)))+(((r01)*(r12)*(x1443)))+(((IkReal(-1.00000000000000))*(x1442)*(x1444)*(x1445)))+(((IkReal(-1.00000000000000))*(r02)*(x1443)*(x1444)))+(((r00)*(r12)*(x1446)))+(((IkReal(-1.00000000000000))*(x1441)*(x1444)*(x1445)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x1446)))));
06213 IkReal x1448=(sj14)*(sj14);
06214 IkReal x1449=(cj14)*(cj14);
06215 IkReal x1450=((cj14)*(sj13));
06216 IkReal x1451=((IkReal(1.00000000000000))*(r11));
06217 IkReal x1452=((cj13)*(r00));
06218 IkReal x1453=((sj13)*(sj14));
06219 IkReal x1454=((cj13)*(r01)*(r10));
06220 dummyeval[0]=((((r00)*(r12)*(x1453)))+(((IkReal(-1.00000000000000))*(x1449)*(x1451)*(x1452)))+(((IkReal(-1.00000000000000))*(r02)*(r10)*(x1453)))+(((x1448)*(x1454)))+(((IkReal(-1.00000000000000))*(x1448)*(x1451)*(x1452)))+(((r01)*(r12)*(x1450)))+(((IkReal(-1.00000000000000))*(r02)*(x1450)*(x1451)))+(((x1449)*(x1454))));
06221 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06222 {
06223 continue;
06224 
06225 } else
06226 {
06227 {
06228 IkReal j9array[1], cj9array[1], sj9array[1];
06229 bool j9valid[1]={false};
06230 _nj9 = 1;
06231 IkReal x1455=((cj13)*(cj14));
06232 IkReal x1456=((IkReal(1.00000000000000))*(cj13)*(sj14));
06233 if( IKabs(((gconst45)*(((((r10)*(x1455)))+(((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x1456))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst45)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x1456)))+(((r00)*(x1455))))))) < IKFAST_ATAN2_MAGTHRESH )
06234     continue;
06235 j9array[0]=IKatan2(((gconst45)*(((((r10)*(x1455)))+(((r12)*(sj13)))+(((IkReal(-1.00000000000000))*(r11)*(x1456)))))), ((gconst45)*(((((r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x1456)))+(((r00)*(x1455)))))));
06236 sj9array[0]=IKsin(j9array[0]);
06237 cj9array[0]=IKcos(j9array[0]);
06238 if( j9array[0] > IKPI )
06239 {
06240     j9array[0]-=IK2PI;
06241 }
06242 else if( j9array[0] < -IKPI )
06243 {    j9array[0]+=IK2PI;
06244 }
06245 j9valid[0] = true;
06246 for(int ij9 = 0; ij9 < 1; ++ij9)
06247 {
06248 if( !j9valid[ij9] )
06249 {
06250     continue;
06251 }
06252 _ij9[0] = ij9; _ij9[1] = -1;
06253 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
06254 {
06255 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
06256 {
06257     j9valid[iij9]=false; _ij9[1] = iij9; break; 
06258 }
06259 }
06260 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
06261 {
06262 IkReal evalcond[6];
06263 IkReal x1457=IKsin(j9);
06264 IkReal x1458=IKcos(j9);
06265 IkReal x1459=((IkReal(1.00000000000000))*(cj14));
06266 IkReal x1460=((IkReal(1.00000000000000))*(sj14));
06267 IkReal x1461=((cj13)*(cj14));
06268 IkReal x1462=((cj14)*(r10));
06269 IkReal x1463=((r01)*(sj14));
06270 IkReal x1464=((IkReal(1.00000000000000))*(r12));
06271 IkReal x1465=((sj13)*(x1458));
06272 IkReal x1466=((r02)*(x1457));
06273 IkReal x1467=((r11)*(x1457));
06274 IkReal x1468=((r10)*(x1458));
06275 IkReal x1469=((r01)*(x1458));
06276 IkReal x1470=((sj13)*(x1457));
06277 IkReal x1471=((r11)*(x1458));
06278 IkReal x1472=((cj13)*(x1457));
06279 IkReal x1473=((r10)*(x1457));
06280 IkReal x1474=((r00)*(x1458));
06281 IkReal x1475=((cj13)*(x1458));
06282 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1460)*(x1468)))+(((r00)*(sj14)*(x1457)))+(((cj14)*(r01)*(x1457)))+(((IkReal(-1.00000000000000))*(x1459)*(x1471))));
06283 evalcond[1]=((((IkReal(-1.00000000000000))*(x1459)*(x1467)))+(((IkReal(-1.00000000000000))*(x1459)*(x1469)))+(((IkReal(-1.00000000000000))*(x1460)*(x1474)))+(((IkReal(-1.00000000000000))*(x1460)*(x1473))));
06284 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x1459)*(x1472)))+(((x1461)*(x1468)))+(((IkReal(-1.00000000000000))*(cj13)*(x1460)*(x1471)))+(((IkReal(-1.00000000000000))*(sj13)*(x1466)))+(((x1463)*(x1472)))+(((r12)*(x1465))));
06285 evalcond[3]=((((IkReal(-1.00000000000000))*(r00)*(x1459)*(x1470)))+(((cj13)*(x1466)))+(((IkReal(-1.00000000000000))*(r11)*(x1460)*(x1465)))+(((x1463)*(x1470)))+(((x1462)*(x1465)))+(((IkReal(-1.00000000000000))*(x1464)*(x1475))));
06286 evalcond[4]=((((r12)*(x1470)))+(((cj10)*(sj11)))+(((r02)*(x1465)))+(((IkReal(-1.00000000000000))*(cj13)*(x1460)*(x1469)))+(((IkReal(-1.00000000000000))*(cj13)*(x1460)*(x1467)))+(((cj11)*(sj10)))+(((x1461)*(x1474)))+(((x1461)*(x1473))));
06287 evalcond[5]=((((IkReal(-1.00000000000000))*(r01)*(x1460)*(x1465)))+(((IkReal(-1.00000000000000))*(sj13)*(x1460)*(x1467)))+(((x1462)*(x1470)))+(((IkReal(-1.00000000000000))*(r02)*(x1475)))+(((sj10)*(sj11)))+(((cj14)*(r00)*(x1465)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(x1464)*(x1472))));
06288 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  )
06289 {
06290 continue;
06291 }
06292 }
06293 
06294 {
06295 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06296 vinfos[0].jointtype = 1;
06297 vinfos[0].foffset = j9;
06298 vinfos[0].indices[0] = _ij9[0];
06299 vinfos[0].indices[1] = _ij9[1];
06300 vinfos[0].maxsolutions = _nj9;
06301 vinfos[1].jointtype = 1;
06302 vinfos[1].foffset = j10;
06303 vinfos[1].indices[0] = _ij10[0];
06304 vinfos[1].indices[1] = _ij10[1];
06305 vinfos[1].maxsolutions = _nj10;
06306 vinfos[2].jointtype = 1;
06307 vinfos[2].foffset = j11;
06308 vinfos[2].indices[0] = _ij11[0];
06309 vinfos[2].indices[1] = _ij11[1];
06310 vinfos[2].maxsolutions = _nj11;
06311 vinfos[3].jointtype = 1;
06312 vinfos[3].foffset = j12;
06313 vinfos[3].indices[0] = _ij12[0];
06314 vinfos[3].indices[1] = _ij12[1];
06315 vinfos[3].maxsolutions = _nj12;
06316 vinfos[4].jointtype = 1;
06317 vinfos[4].foffset = j13;
06318 vinfos[4].indices[0] = _ij13[0];
06319 vinfos[4].indices[1] = _ij13[1];
06320 vinfos[4].maxsolutions = _nj13;
06321 vinfos[5].jointtype = 1;
06322 vinfos[5].foffset = j14;
06323 vinfos[5].indices[0] = _ij14[0];
06324 vinfos[5].indices[1] = _ij14[1];
06325 vinfos[5].maxsolutions = _nj14;
06326 std::vector<int> vfree(0);
06327 solutions.AddSolution(vinfos,vfree);
06328 }
06329 }
06330 }
06331 
06332 }
06333 
06334 }
06335 
06336 } else
06337 {
06338 {
06339 IkReal j9array[1], cj9array[1], sj9array[1];
06340 bool j9valid[1]={false};
06341 _nj9 = 1;
06342 if( IKabs(((gconst44)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst44)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
06343     continue;
06344 j9array[0]=IKatan2(((gconst44)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst44)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
06345 sj9array[0]=IKsin(j9array[0]);
06346 cj9array[0]=IKcos(j9array[0]);
06347 if( j9array[0] > IKPI )
06348 {
06349     j9array[0]-=IK2PI;
06350 }
06351 else if( j9array[0] < -IKPI )
06352 {    j9array[0]+=IK2PI;
06353 }
06354 j9valid[0] = true;
06355 for(int ij9 = 0; ij9 < 1; ++ij9)
06356 {
06357 if( !j9valid[ij9] )
06358 {
06359     continue;
06360 }
06361 _ij9[0] = ij9; _ij9[1] = -1;
06362 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
06363 {
06364 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
06365 {
06366     j9valid[iij9]=false; _ij9[1] = iij9; break; 
06367 }
06368 }
06369 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
06370 {
06371 IkReal evalcond[6];
06372 IkReal x1476=IKsin(j9);
06373 IkReal x1477=IKcos(j9);
06374 IkReal x1478=((IkReal(1.00000000000000))*(cj14));
06375 IkReal x1479=((IkReal(1.00000000000000))*(sj14));
06376 IkReal x1480=((cj13)*(cj14));
06377 IkReal x1481=((cj14)*(r10));
06378 IkReal x1482=((r01)*(sj14));
06379 IkReal x1483=((IkReal(1.00000000000000))*(r12));
06380 IkReal x1484=((sj13)*(x1477));
06381 IkReal x1485=((r02)*(x1476));
06382 IkReal x1486=((r11)*(x1476));
06383 IkReal x1487=((r10)*(x1477));
06384 IkReal x1488=((r01)*(x1477));
06385 IkReal x1489=((sj13)*(x1476));
06386 IkReal x1490=((r11)*(x1477));
06387 IkReal x1491=((cj13)*(x1476));
06388 IkReal x1492=((r10)*(x1476));
06389 IkReal x1493=((r00)*(x1477));
06390 IkReal x1494=((cj13)*(x1477));
06391 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1479)*(x1487)))+(((r00)*(sj14)*(x1476)))+(((cj14)*(r01)*(x1476)))+(((IkReal(-1.00000000000000))*(x1478)*(x1490))));
06392 evalcond[1]=((((IkReal(-1.00000000000000))*(x1479)*(x1493)))+(((IkReal(-1.00000000000000))*(x1479)*(x1492)))+(((IkReal(-1.00000000000000))*(x1478)*(x1486)))+(((IkReal(-1.00000000000000))*(x1478)*(x1488))));
06393 evalcond[2]=((((x1482)*(x1491)))+(((IkReal(-1.00000000000000))*(sj13)*(x1485)))+(((x1480)*(x1487)))+(((IkReal(-1.00000000000000))*(r00)*(x1478)*(x1491)))+(((r12)*(x1484)))+(((IkReal(-1.00000000000000))*(cj13)*(x1479)*(x1490))));
06394 evalcond[3]=((((IkReal(-1.00000000000000))*(r00)*(x1478)*(x1489)))+(((x1482)*(x1489)))+(((cj13)*(x1485)))+(((x1481)*(x1484)))+(((IkReal(-1.00000000000000))*(x1483)*(x1494)))+(((IkReal(-1.00000000000000))*(r11)*(x1479)*(x1484))));
06395 evalcond[4]=((((r12)*(x1489)))+(((x1480)*(x1492)))+(((x1480)*(x1493)))+(((cj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x1479)*(x1488)))+(((IkReal(-1.00000000000000))*(cj13)*(x1479)*(x1486)))+(((r02)*(x1484)))+(((cj11)*(sj10))));
06396 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x1494)))+(((cj14)*(r00)*(x1484)))+(((x1481)*(x1489)))+(((IkReal(-1.00000000000000))*(sj13)*(x1479)*(x1486)))+(((sj10)*(sj11)))+(((IkReal(-1.00000000000000))*(x1483)*(x1491)))+(((IkReal(-1.00000000000000))*(cj10)*(cj11)))+(((IkReal(-1.00000000000000))*(r01)*(x1479)*(x1484))));
06397 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  )
06398 {
06399 continue;
06400 }
06401 }
06402 
06403 {
06404 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06405 vinfos[0].jointtype = 1;
06406 vinfos[0].foffset = j9;
06407 vinfos[0].indices[0] = _ij9[0];
06408 vinfos[0].indices[1] = _ij9[1];
06409 vinfos[0].maxsolutions = _nj9;
06410 vinfos[1].jointtype = 1;
06411 vinfos[1].foffset = j10;
06412 vinfos[1].indices[0] = _ij10[0];
06413 vinfos[1].indices[1] = _ij10[1];
06414 vinfos[1].maxsolutions = _nj10;
06415 vinfos[2].jointtype = 1;
06416 vinfos[2].foffset = j11;
06417 vinfos[2].indices[0] = _ij11[0];
06418 vinfos[2].indices[1] = _ij11[1];
06419 vinfos[2].maxsolutions = _nj11;
06420 vinfos[3].jointtype = 1;
06421 vinfos[3].foffset = j12;
06422 vinfos[3].indices[0] = _ij12[0];
06423 vinfos[3].indices[1] = _ij12[1];
06424 vinfos[3].maxsolutions = _nj12;
06425 vinfos[4].jointtype = 1;
06426 vinfos[4].foffset = j13;
06427 vinfos[4].indices[0] = _ij13[0];
06428 vinfos[4].indices[1] = _ij13[1];
06429 vinfos[4].maxsolutions = _nj13;
06430 vinfos[5].jointtype = 1;
06431 vinfos[5].foffset = j14;
06432 vinfos[5].indices[0] = _ij14[0];
06433 vinfos[5].indices[1] = _ij14[1];
06434 vinfos[5].maxsolutions = _nj14;
06435 std::vector<int> vfree(0);
06436 solutions.AddSolution(vinfos,vfree);
06437 }
06438 }
06439 }
06440 
06441 }
06442 
06443 }
06444 }
06445 }
06446 
06447 }
06448 
06449 }
06450 
06451 } else
06452 {
06453 {
06454 IkReal j9array[1], cj9array[1], sj9array[1];
06455 bool j9valid[1]={false};
06456 _nj9 = 1;
06457 if( IKabs(((gconst39)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst39)*(((((cj14)*(r11)))+(((r10)*(sj14))))))) < IKFAST_ATAN2_MAGTHRESH )
06458     continue;
06459 j9array[0]=IKatan2(((gconst39)*(((((IkReal(-1.00000000000000))*(cj14)*(r01)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)))))), ((gconst39)*(((((cj14)*(r11)))+(((r10)*(sj14)))))));
06460 sj9array[0]=IKsin(j9array[0]);
06461 cj9array[0]=IKcos(j9array[0]);
06462 if( j9array[0] > IKPI )
06463 {
06464     j9array[0]-=IK2PI;
06465 }
06466 else if( j9array[0] < -IKPI )
06467 {    j9array[0]+=IK2PI;
06468 }
06469 j9valid[0] = true;
06470 for(int ij9 = 0; ij9 < 1; ++ij9)
06471 {
06472 if( !j9valid[ij9] )
06473 {
06474     continue;
06475 }
06476 _ij9[0] = ij9; _ij9[1] = -1;
06477 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
06478 {
06479 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
06480 {
06481     j9valid[iij9]=false; _ij9[1] = iij9; break; 
06482 }
06483 }
06484 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
06485 {
06486 IkReal evalcond[4];
06487 IkReal x1495=IKsin(j9);
06488 IkReal x1496=IKcos(j9);
06489 IkReal x1497=((r10)*(sj14));
06490 IkReal x1498=((cj14)*(r11));
06491 IkReal x1499=((cj14)*(r10));
06492 IkReal x1500=((cj14)*(r00));
06493 IkReal x1501=((r11)*(sj14));
06494 IkReal x1502=((r00)*(sj14));
06495 IkReal x1503=((IkReal(1.00000000000000))*(x1495));
06496 IkReal x1504=((cj13)*(x1495));
06497 IkReal x1505=((sj13)*(x1496));
06498 IkReal x1506=((r01)*(x1495));
06499 IkReal x1507=((IkReal(1.00000000000000))*(x1496));
06500 evalcond[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1498)*(x1507)))+(((x1495)*(x1502)))+(((IkReal(-1.00000000000000))*(x1497)*(x1507)))+(((cj14)*(x1506))));
06501 evalcond[1]=((((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1507)))+(((IkReal(-1.00000000000000))*(x1498)*(x1503)))+(((IkReal(-1.00000000000000))*(x1497)*(x1503)))+(((IkReal(-1.00000000000000))*(x1502)*(x1507))));
06502 evalcond[2]=((((cj13)*(x1496)*(x1499)))+(((r12)*(x1505)))+(((IkReal(-1.00000000000000))*(cj13)*(x1501)*(x1507)))+(((r01)*(sj14)*(x1504)))+(((IkReal(-1.00000000000000))*(cj13)*(x1500)*(x1503)))+(((IkReal(-1.00000000000000))*(r02)*(sj13)*(x1503))));
06503 evalcond[3]=((((x1499)*(x1505)))+(((sj13)*(sj14)*(x1506)))+(((r02)*(x1504)))+(((IkReal(-1.00000000000000))*(sj13)*(x1500)*(x1503)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1507)))+(((IkReal(-1.00000000000000))*(x1501)*(x1505))));
06504 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06505 {
06506 continue;
06507 }
06508 }
06509 
06510 {
06511 IkReal dummyeval[1];
06512 IkReal gconst42;
06513 gconst42=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
06514 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
06515 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06516 {
06517 {
06518 IkReal dummyeval[1];
06519 IkReal gconst43;
06520 gconst43=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
06521 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
06522 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06523 {
06524 continue;
06525 
06526 } else
06527 {
06528 {
06529 IkReal j10array[1], cj10array[1], sj10array[1];
06530 bool j10valid[1]={false};
06531 _nj10 = 1;
06532 IkReal x1508=((cj13)*(sj14));
06533 IkReal x1509=((IkReal(1.00000000000000))*(cj11));
06534 IkReal x1510=((r11)*(sj9));
06535 IkReal x1511=((IkReal(1.00000000000000))*(sj11));
06536 IkReal x1512=((cj13)*(cj14));
06537 IkReal x1513=((cj11)*(sj13));
06538 IkReal x1514=((r12)*(sj9));
06539 IkReal x1515=((cj9)*(r01));
06540 IkReal x1516=((sj11)*(sj13));
06541 IkReal x1517=((cj9)*(r02));
06542 IkReal x1518=((r10)*(sj9));
06543 IkReal x1519=((cj9)*(r00));
06544 if( IKabs(((gconst43)*(((((x1513)*(x1514)))+(((x1513)*(x1517)))+(((r21)*(sj11)*(x1508)))+(((IkReal(-1.00000000000000))*(x1508)*(x1509)*(x1510)))+(((IkReal(-1.00000000000000))*(x1508)*(x1509)*(x1515)))+(((IkReal(-1.00000000000000))*(r20)*(x1511)*(x1512)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1511)))+(((cj11)*(x1512)*(x1518)))+(((cj11)*(x1512)*(x1519))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst43)*(((((x1514)*(x1516)))+(((x1516)*(x1517)))+(((cj11)*(r20)*(x1512)))+(((IkReal(-1.00000000000000))*(r21)*(x1508)*(x1509)))+(((r22)*(x1513)))+(((sj11)*(x1512)*(x1519)))+(((sj11)*(x1512)*(x1518)))+(((IkReal(-1.00000000000000))*(x1508)*(x1510)*(x1511)))+(((IkReal(-1.00000000000000))*(x1508)*(x1511)*(x1515))))))) < IKFAST_ATAN2_MAGTHRESH )
06545     continue;
06546 j10array[0]=IKatan2(((gconst43)*(((((x1513)*(x1514)))+(((x1513)*(x1517)))+(((r21)*(sj11)*(x1508)))+(((IkReal(-1.00000000000000))*(x1508)*(x1509)*(x1510)))+(((IkReal(-1.00000000000000))*(x1508)*(x1509)*(x1515)))+(((IkReal(-1.00000000000000))*(r20)*(x1511)*(x1512)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1511)))+(((cj11)*(x1512)*(x1518)))+(((cj11)*(x1512)*(x1519)))))), ((gconst43)*(((((x1514)*(x1516)))+(((x1516)*(x1517)))+(((cj11)*(r20)*(x1512)))+(((IkReal(-1.00000000000000))*(r21)*(x1508)*(x1509)))+(((r22)*(x1513)))+(((sj11)*(x1512)*(x1519)))+(((sj11)*(x1512)*(x1518)))+(((IkReal(-1.00000000000000))*(x1508)*(x1510)*(x1511)))+(((IkReal(-1.00000000000000))*(x1508)*(x1511)*(x1515)))))));
06547 sj10array[0]=IKsin(j10array[0]);
06548 cj10array[0]=IKcos(j10array[0]);
06549 if( j10array[0] > IKPI )
06550 {
06551     j10array[0]-=IK2PI;
06552 }
06553 else if( j10array[0] < -IKPI )
06554 {    j10array[0]+=IK2PI;
06555 }
06556 j10valid[0] = true;
06557 for(int ij10 = 0; ij10 < 1; ++ij10)
06558 {
06559 if( !j10valid[ij10] )
06560 {
06561     continue;
06562 }
06563 _ij10[0] = ij10; _ij10[1] = -1;
06564 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
06565 {
06566 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
06567 {
06568     j10valid[iij10]=false; _ij10[1] = iij10; break; 
06569 }
06570 }
06571 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
06572 {
06573 IkReal evalcond[4];
06574 IkReal x1520=IKsin(j10);
06575 IkReal x1521=IKcos(j10);
06576 IkReal x1522=((IkReal(1.00000000000000))*(sj13));
06577 IkReal x1523=((r11)*(sj9));
06578 IkReal x1524=((cj9)*(r01));
06579 IkReal x1525=((IkReal(1.00000000000000))*(cj11));
06580 IkReal x1526=((r21)*(sj14));
06581 IkReal x1527=((cj9)*(r02));
06582 IkReal x1528=((sj13)*(sj9));
06583 IkReal x1529=((cj14)*(r10));
06584 IkReal x1530=((IkReal(1.00000000000000))*(cj13));
06585 IkReal x1531=((cj14)*(r20));
06586 IkReal x1532=((sj11)*(x1520));
06587 IkReal x1533=((sj14)*(x1530));
06588 IkReal x1534=((sj11)*(x1521));
06589 IkReal x1535=((cj14)*(cj9)*(r00));
06590 IkReal x1536=((x1521)*(x1525));
06591 evalcond[0]=((((IkReal(-1.00000000000000))*(x1530)*(x1531)))+(((IkReal(-1.00000000000000))*(x1536)))+(((IkReal(-1.00000000000000))*(r22)*(x1522)))+(x1532)+(((cj13)*(x1526))));
06592 evalcond[1]=((((IkReal(-1.00000000000000))*(x1534)))+(((sj13)*(x1526)))+(((IkReal(-1.00000000000000))*(x1522)*(x1531)))+(((IkReal(-1.00000000000000))*(x1520)*(x1525)))+(((cj13)*(r22))));
06593 evalcond[2]=((((IkReal(-1.00000000000000))*(x1524)*(x1533)))+(((cj11)*(x1520)))+(((r12)*(x1528)))+(((cj13)*(sj9)*(x1529)))+(x1534)+(((cj13)*(x1535)))+(((sj13)*(x1527)))+(((IkReal(-1.00000000000000))*(x1523)*(x1533))));
06594 evalcond[3]=((((x1528)*(x1529)))+(((IkReal(-1.00000000000000))*(x1536)))+(x1532)+(((IkReal(-1.00000000000000))*(sj14)*(x1522)*(x1523)))+(((IkReal(-1.00000000000000))*(sj14)*(x1522)*(x1524)))+(((sj13)*(x1535)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1530)))+(((IkReal(-1.00000000000000))*(x1527)*(x1530))));
06595 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06596 {
06597 continue;
06598 }
06599 }
06600 
06601 {
06602 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06603 vinfos[0].jointtype = 1;
06604 vinfos[0].foffset = j9;
06605 vinfos[0].indices[0] = _ij9[0];
06606 vinfos[0].indices[1] = _ij9[1];
06607 vinfos[0].maxsolutions = _nj9;
06608 vinfos[1].jointtype = 1;
06609 vinfos[1].foffset = j10;
06610 vinfos[1].indices[0] = _ij10[0];
06611 vinfos[1].indices[1] = _ij10[1];
06612 vinfos[1].maxsolutions = _nj10;
06613 vinfos[2].jointtype = 1;
06614 vinfos[2].foffset = j11;
06615 vinfos[2].indices[0] = _ij11[0];
06616 vinfos[2].indices[1] = _ij11[1];
06617 vinfos[2].maxsolutions = _nj11;
06618 vinfos[3].jointtype = 1;
06619 vinfos[3].foffset = j12;
06620 vinfos[3].indices[0] = _ij12[0];
06621 vinfos[3].indices[1] = _ij12[1];
06622 vinfos[3].maxsolutions = _nj12;
06623 vinfos[4].jointtype = 1;
06624 vinfos[4].foffset = j13;
06625 vinfos[4].indices[0] = _ij13[0];
06626 vinfos[4].indices[1] = _ij13[1];
06627 vinfos[4].maxsolutions = _nj13;
06628 vinfos[5].jointtype = 1;
06629 vinfos[5].foffset = j14;
06630 vinfos[5].indices[0] = _ij14[0];
06631 vinfos[5].indices[1] = _ij14[1];
06632 vinfos[5].maxsolutions = _nj14;
06633 std::vector<int> vfree(0);
06634 solutions.AddSolution(vinfos,vfree);
06635 }
06636 }
06637 }
06638 
06639 }
06640 
06641 }
06642 
06643 } else
06644 {
06645 {
06646 IkReal j10array[1], cj10array[1], sj10array[1];
06647 bool j10valid[1]={false};
06648 _nj10 = 1;
06649 IkReal x1537=((cj11)*(r22));
06650 IkReal x1538=((IkReal(1.00000000000000))*(sj13));
06651 IkReal x1539=((cj13)*(sj11));
06652 IkReal x1540=((r21)*(sj14));
06653 IkReal x1541=((cj11)*(cj13));
06654 IkReal x1542=((sj11)*(sj13));
06655 IkReal x1543=((cj14)*(r20));
06656 if( IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1539)*(x1540)))+(((cj11)*(sj13)*(x1540)))+(((x1539)*(x1543)))+(((IkReal(-1.00000000000000))*(cj11)*(x1538)*(x1543)))+(((cj13)*(x1537)))+(((r22)*(x1542))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst42)*(((((IkReal(-1.00000000000000))*(x1541)*(x1543)))+(((IkReal(-1.00000000000000))*(x1537)*(x1538)))+(((x1540)*(x1541)))+(((x1540)*(x1542)))+(((r22)*(x1539)))+(((IkReal(-1.00000000000000))*(sj11)*(x1538)*(x1543))))))) < IKFAST_ATAN2_MAGTHRESH )
06657     continue;
06658 j10array[0]=IKatan2(((gconst42)*(((((IkReal(-1.00000000000000))*(x1539)*(x1540)))+(((cj11)*(sj13)*(x1540)))+(((x1539)*(x1543)))+(((IkReal(-1.00000000000000))*(cj11)*(x1538)*(x1543)))+(((cj13)*(x1537)))+(((r22)*(x1542)))))), ((gconst42)*(((((IkReal(-1.00000000000000))*(x1541)*(x1543)))+(((IkReal(-1.00000000000000))*(x1537)*(x1538)))+(((x1540)*(x1541)))+(((x1540)*(x1542)))+(((r22)*(x1539)))+(((IkReal(-1.00000000000000))*(sj11)*(x1538)*(x1543)))))));
06659 sj10array[0]=IKsin(j10array[0]);
06660 cj10array[0]=IKcos(j10array[0]);
06661 if( j10array[0] > IKPI )
06662 {
06663     j10array[0]-=IK2PI;
06664 }
06665 else if( j10array[0] < -IKPI )
06666 {    j10array[0]+=IK2PI;
06667 }
06668 j10valid[0] = true;
06669 for(int ij10 = 0; ij10 < 1; ++ij10)
06670 {
06671 if( !j10valid[ij10] )
06672 {
06673     continue;
06674 }
06675 _ij10[0] = ij10; _ij10[1] = -1;
06676 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
06677 {
06678 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
06679 {
06680     j10valid[iij10]=false; _ij10[1] = iij10; break; 
06681 }
06682 }
06683 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
06684 {
06685 IkReal evalcond[4];
06686 IkReal x1544=IKsin(j10);
06687 IkReal x1545=IKcos(j10);
06688 IkReal x1546=((IkReal(1.00000000000000))*(sj13));
06689 IkReal x1547=((r11)*(sj9));
06690 IkReal x1548=((cj9)*(r01));
06691 IkReal x1549=((IkReal(1.00000000000000))*(cj11));
06692 IkReal x1550=((r21)*(sj14));
06693 IkReal x1551=((cj9)*(r02));
06694 IkReal x1552=((sj13)*(sj9));
06695 IkReal x1553=((cj14)*(r10));
06696 IkReal x1554=((IkReal(1.00000000000000))*(cj13));
06697 IkReal x1555=((cj14)*(r20));
06698 IkReal x1556=((sj11)*(x1544));
06699 IkReal x1557=((sj14)*(x1554));
06700 IkReal x1558=((sj11)*(x1545));
06701 IkReal x1559=((cj14)*(cj9)*(r00));
06702 IkReal x1560=((x1545)*(x1549));
06703 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x1546)))+(x1556)+(((cj13)*(x1550)))+(((IkReal(-1.00000000000000))*(x1560)))+(((IkReal(-1.00000000000000))*(x1554)*(x1555))));
06704 evalcond[1]=((((IkReal(-1.00000000000000))*(x1558)))+(((IkReal(-1.00000000000000))*(x1546)*(x1555)))+(((sj13)*(x1550)))+(((IkReal(-1.00000000000000))*(x1544)*(x1549)))+(((cj13)*(r22))));
06705 evalcond[2]=((((sj13)*(x1551)))+(((cj11)*(x1544)))+(((IkReal(-1.00000000000000))*(x1548)*(x1557)))+(((r12)*(x1552)))+(x1558)+(((cj13)*(x1559)))+(((IkReal(-1.00000000000000))*(x1547)*(x1557)))+(((cj13)*(sj9)*(x1553))));
06706 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x1546)*(x1548)))+(((IkReal(-1.00000000000000))*(sj14)*(x1546)*(x1547)))+(((x1552)*(x1553)))+(((sj13)*(x1559)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1554)))+(x1556)+(((IkReal(-1.00000000000000))*(x1551)*(x1554)))+(((IkReal(-1.00000000000000))*(x1560))));
06707 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06708 {
06709 continue;
06710 }
06711 }
06712 
06713 {
06714 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06715 vinfos[0].jointtype = 1;
06716 vinfos[0].foffset = j9;
06717 vinfos[0].indices[0] = _ij9[0];
06718 vinfos[0].indices[1] = _ij9[1];
06719 vinfos[0].maxsolutions = _nj9;
06720 vinfos[1].jointtype = 1;
06721 vinfos[1].foffset = j10;
06722 vinfos[1].indices[0] = _ij10[0];
06723 vinfos[1].indices[1] = _ij10[1];
06724 vinfos[1].maxsolutions = _nj10;
06725 vinfos[2].jointtype = 1;
06726 vinfos[2].foffset = j11;
06727 vinfos[2].indices[0] = _ij11[0];
06728 vinfos[2].indices[1] = _ij11[1];
06729 vinfos[2].maxsolutions = _nj11;
06730 vinfos[3].jointtype = 1;
06731 vinfos[3].foffset = j12;
06732 vinfos[3].indices[0] = _ij12[0];
06733 vinfos[3].indices[1] = _ij12[1];
06734 vinfos[3].maxsolutions = _nj12;
06735 vinfos[4].jointtype = 1;
06736 vinfos[4].foffset = j13;
06737 vinfos[4].indices[0] = _ij13[0];
06738 vinfos[4].indices[1] = _ij13[1];
06739 vinfos[4].maxsolutions = _nj13;
06740 vinfos[5].jointtype = 1;
06741 vinfos[5].foffset = j14;
06742 vinfos[5].indices[0] = _ij14[0];
06743 vinfos[5].indices[1] = _ij14[1];
06744 vinfos[5].maxsolutions = _nj14;
06745 std::vector<int> vfree(0);
06746 solutions.AddSolution(vinfos,vfree);
06747 }
06748 }
06749 }
06750 
06751 }
06752 
06753 }
06754 }
06755 }
06756 
06757 }
06758 
06759 }
06760 
06761 } else
06762 {
06763 if( 1 )
06764 {
06765 continue;
06766 
06767 } else
06768 {
06769 }
06770 }
06771 }
06772 }
06773 }
06774 }
06775 
06776 } else
06777 {
06778 {
06779 IkReal j9array[1], cj9array[1], sj9array[1];
06780 bool j9valid[1]={false};
06781 _nj9 = 1;
06782 IkReal x1561=((cj12)*(sj13));
06783 IkReal x1562=((cj12)*(cj13));
06784 IkReal x1563=((IkReal(1.00000000000000))*(sj14));
06785 if( IKabs(((gconst2)*(((((r12)*(x1561)))+(((IkReal(-1.00000000000000))*(r11)*(x1562)*(x1563)))+(((cj14)*(r10)*(x1562))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(r01)*(x1562)*(x1563)))+(((cj14)*(r00)*(x1562)))+(((r02)*(x1561))))))) < IKFAST_ATAN2_MAGTHRESH )
06786     continue;
06787 j9array[0]=IKatan2(((gconst2)*(((((r12)*(x1561)))+(((IkReal(-1.00000000000000))*(r11)*(x1562)*(x1563)))+(((cj14)*(r10)*(x1562)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(r01)*(x1562)*(x1563)))+(((cj14)*(r00)*(x1562)))+(((r02)*(x1561)))))));
06788 sj9array[0]=IKsin(j9array[0]);
06789 cj9array[0]=IKcos(j9array[0]);
06790 if( j9array[0] > IKPI )
06791 {
06792     j9array[0]-=IK2PI;
06793 }
06794 else if( j9array[0] < -IKPI )
06795 {    j9array[0]+=IK2PI;
06796 }
06797 j9valid[0] = true;
06798 for(int ij9 = 0; ij9 < 1; ++ij9)
06799 {
06800 if( !j9valid[ij9] )
06801 {
06802     continue;
06803 }
06804 _ij9[0] = ij9; _ij9[1] = -1;
06805 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
06806 {
06807 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
06808 {
06809     j9valid[iij9]=false; _ij9[1] = iij9; break; 
06810 }
06811 }
06812 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
06813 {
06814 IkReal evalcond[3];
06815 IkReal x1564=IKsin(j9);
06816 IkReal x1565=IKcos(j9);
06817 IkReal x1566=((IkReal(1.00000000000000))*(sj14));
06818 IkReal x1567=((sj13)*(x1565));
06819 IkReal x1568=((cj13)*(x1564));
06820 IkReal x1569=((IkReal(1.00000000000000))*(cj14)*(r00));
06821 IkReal x1570=((r01)*(x1564));
06822 IkReal x1571=((r10)*(x1565));
06823 IkReal x1572=((sj13)*(x1564));
06824 IkReal x1573=((cj13)*(x1565));
06825 evalcond[0]=((((IkReal(-1.00000000000000))*(x1566)*(x1571)))+(cj12)+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1565)))+(((r00)*(sj14)*(x1564)))+(((cj14)*(x1570))));
06826 evalcond[1]=((((r01)*(sj14)*(x1568)))+(((cj13)*(cj14)*(x1571)))+(((r12)*(x1567)))+(((IkReal(-1.00000000000000))*(x1568)*(x1569)))+(((IkReal(-1.00000000000000))*(r11)*(x1566)*(x1573)))+(((IkReal(-1.00000000000000))*(r02)*(x1572))));
06827 evalcond[2]=((sj12)+(((IkReal(-1.00000000000000))*(x1569)*(x1572)))+(((cj14)*(r10)*(x1567)))+(((sj13)*(sj14)*(x1570)))+(((IkReal(-1.00000000000000))*(r12)*(x1573)))+(((IkReal(-1.00000000000000))*(r11)*(x1566)*(x1567)))+(((r02)*(x1568))));
06828 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
06829 {
06830 continue;
06831 }
06832 }
06833 
06834 {
06835 IkReal dummyeval[1];
06836 IkReal gconst6;
06837 gconst6=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
06838 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
06839 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06840 {
06841 {
06842 IkReal dummyeval[1];
06843 IkReal gconst7;
06844 gconst7=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
06845 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
06846 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06847 {
06848 {
06849 IkReal evalcond[9];
06850 IkReal x1574=((r00)*(sj9));
06851 IkReal x1575=((IkReal(1.00000000000000))*(sj13));
06852 IkReal x1576=((cj13)*(sj14));
06853 IkReal x1577=((cj9)*(sj14));
06854 IkReal x1578=((cj13)*(r02));
06855 IkReal x1579=((sj13)*(sj14));
06856 IkReal x1580=((r01)*(sj9));
06857 IkReal x1581=((cj9)*(sj13));
06858 IkReal x1582=((IkReal(1.00000000000000))*(cj9));
06859 IkReal x1583=((cj14)*(r10));
06860 IkReal x1584=((cj14)*(npx));
06861 IkReal x1585=((IkReal(1.00000000000000))*(cj13));
06862 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
06863 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
06864 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x1575)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x1584)*(x1585)))+(((npy)*(x1576))));
06865 evalcond[3]=((((sj14)*(x1574)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1582)))+(((IkReal(-1.00000000000000))*(r10)*(x1577)))+(((cj14)*(x1580))));
06866 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x1575)))+(((r21)*(x1579)))+(((cj13)*(r22))));
06867 evalcond[5]=((IkReal(0.0950000000000000))+(((npy)*(x1579)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x1575)*(x1584))));
06868 evalcond[6]=((((cj13)*(cj9)*(x1583)))+(((IkReal(-1.00000000000000))*(cj14)*(x1574)*(x1585)))+(((x1576)*(x1580)))+(((r12)*(x1581)))+(((IkReal(-1.00000000000000))*(r11)*(x1576)*(x1582)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x1575))));
06869 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1582)))+(((x1579)*(x1580)))+(((IkReal(-1.00000000000000))*(r11)*(x1575)*(x1577)))+(((IkReal(-1.00000000000000))*(cj14)*(x1574)*(x1575)))+(((sj9)*(x1578)))+(((x1581)*(x1583))));
06870 evalcond[8]=((((IkReal(-1.00000000000000))*(x1578)*(x1582)))+(((IkReal(-1.00000000000000))*(r01)*(x1575)*(x1577)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x1575)))+(((sj13)*(sj9)*(x1583)))+(((cj14)*(r00)*(x1581)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1585))));
06871 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  )
06872 {
06873 {
06874 IkReal dummyeval[1];
06875 IkReal gconst8;
06876 gconst8=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
06877 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
06878 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06879 {
06880 {
06881 IkReal dummyeval[1];
06882 IkReal gconst9;
06883 gconst9=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
06884 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
06885 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
06886 {
06887 continue;
06888 
06889 } else
06890 {
06891 {
06892 IkReal j10array[1], cj10array[1], sj10array[1];
06893 bool j10valid[1]={false};
06894 _nj10 = 1;
06895 IkReal x1586=((IkReal(1.00000000000000))*(cj11));
06896 IkReal x1587=((r20)*(sj14));
06897 IkReal x1588=((cj14)*(r21));
06898 IkReal x1589=((cj14)*(cj9)*(r01));
06899 IkReal x1590=((r10)*(sj14)*(sj9));
06900 IkReal x1591=((cj9)*(r00)*(sj14));
06901 IkReal x1592=((cj14)*(r11)*(sj9));
06902 if( IKabs(((gconst9)*(((((sj11)*(x1592)))+(((sj11)*(x1590)))+(((sj11)*(x1591)))+(((sj11)*(x1589)))+(((cj11)*(x1588)))+(((cj11)*(x1587))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((((sj11)*(x1588)))+(((sj11)*(x1587)))+(((IkReal(-1.00000000000000))*(x1586)*(x1591)))+(((IkReal(-1.00000000000000))*(x1586)*(x1590)))+(((IkReal(-1.00000000000000))*(x1586)*(x1592)))+(((IkReal(-1.00000000000000))*(x1586)*(x1589))))))) < IKFAST_ATAN2_MAGTHRESH )
06903     continue;
06904 j10array[0]=IKatan2(((gconst9)*(((((sj11)*(x1592)))+(((sj11)*(x1590)))+(((sj11)*(x1591)))+(((sj11)*(x1589)))+(((cj11)*(x1588)))+(((cj11)*(x1587)))))), ((gconst9)*(((((sj11)*(x1588)))+(((sj11)*(x1587)))+(((IkReal(-1.00000000000000))*(x1586)*(x1591)))+(((IkReal(-1.00000000000000))*(x1586)*(x1590)))+(((IkReal(-1.00000000000000))*(x1586)*(x1592)))+(((IkReal(-1.00000000000000))*(x1586)*(x1589)))))));
06905 sj10array[0]=IKsin(j10array[0]);
06906 cj10array[0]=IKcos(j10array[0]);
06907 if( j10array[0] > IKPI )
06908 {
06909     j10array[0]-=IK2PI;
06910 }
06911 else if( j10array[0] < -IKPI )
06912 {    j10array[0]+=IK2PI;
06913 }
06914 j10valid[0] = true;
06915 for(int ij10 = 0; ij10 < 1; ++ij10)
06916 {
06917 if( !j10valid[ij10] )
06918 {
06919     continue;
06920 }
06921 _ij10[0] = ij10; _ij10[1] = -1;
06922 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
06923 {
06924 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
06925 {
06926     j10valid[iij10]=false; _ij10[1] = iij10; break; 
06927 }
06928 }
06929 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
06930 {
06931 IkReal evalcond[4];
06932 IkReal x1593=IKsin(j10);
06933 IkReal x1594=IKcos(j10);
06934 IkReal x1595=((cj13)*(sj14));
06935 IkReal x1596=((cj13)*(cj14));
06936 IkReal x1597=((r10)*(sj9));
06937 IkReal x1598=((IkReal(1.00000000000000))*(cj9));
06938 IkReal x1599=((sj11)*(x1593));
06939 IkReal x1600=((IkReal(1.00000000000000))*(x1594));
06940 IkReal x1601=((cj11)*(x1593));
06941 IkReal x1602=((IkReal(1.00000000000000))*(r11)*(sj9));
06942 IkReal x1603=((cj11)*(x1600));
06943 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x1601)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x1600))));
06944 evalcond[1]=((((IkReal(-1.00000000000000))*(x1603)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(x1599)+(((r21)*(x1595)))+(((IkReal(-1.00000000000000))*(r20)*(x1596))));
06945 evalcond[2]=((((IkReal(-1.00000000000000))*(x1603)))+(((IkReal(-1.00000000000000))*(cj14)*(x1602)))+(x1599)+(((IkReal(-1.00000000000000))*(sj14)*(x1597)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1598)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x1598))));
06946 evalcond[3]=((((x1596)*(x1597)))+(((cj9)*(r00)*(x1596)))+(((sj11)*(x1594)))+(x1601)+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(x1595)*(x1602)))+(((IkReal(-1.00000000000000))*(r01)*(x1595)*(x1598)))+(((r12)*(sj13)*(sj9))));
06947 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
06948 {
06949 continue;
06950 }
06951 }
06952 
06953 {
06954 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
06955 vinfos[0].jointtype = 1;
06956 vinfos[0].foffset = j9;
06957 vinfos[0].indices[0] = _ij9[0];
06958 vinfos[0].indices[1] = _ij9[1];
06959 vinfos[0].maxsolutions = _nj9;
06960 vinfos[1].jointtype = 1;
06961 vinfos[1].foffset = j10;
06962 vinfos[1].indices[0] = _ij10[0];
06963 vinfos[1].indices[1] = _ij10[1];
06964 vinfos[1].maxsolutions = _nj10;
06965 vinfos[2].jointtype = 1;
06966 vinfos[2].foffset = j11;
06967 vinfos[2].indices[0] = _ij11[0];
06968 vinfos[2].indices[1] = _ij11[1];
06969 vinfos[2].maxsolutions = _nj11;
06970 vinfos[3].jointtype = 1;
06971 vinfos[3].foffset = j12;
06972 vinfos[3].indices[0] = _ij12[0];
06973 vinfos[3].indices[1] = _ij12[1];
06974 vinfos[3].maxsolutions = _nj12;
06975 vinfos[4].jointtype = 1;
06976 vinfos[4].foffset = j13;
06977 vinfos[4].indices[0] = _ij13[0];
06978 vinfos[4].indices[1] = _ij13[1];
06979 vinfos[4].maxsolutions = _nj13;
06980 vinfos[5].jointtype = 1;
06981 vinfos[5].foffset = j14;
06982 vinfos[5].indices[0] = _ij14[0];
06983 vinfos[5].indices[1] = _ij14[1];
06984 vinfos[5].maxsolutions = _nj14;
06985 std::vector<int> vfree(0);
06986 solutions.AddSolution(vinfos,vfree);
06987 }
06988 }
06989 }
06990 
06991 }
06992 
06993 }
06994 
06995 } else
06996 {
06997 {
06998 IkReal j10array[1], cj10array[1], sj10array[1];
06999 bool j10valid[1]={false};
07000 _nj10 = 1;
07001 IkReal x1604=((cj11)*(r20));
07002 IkReal x1605=((IkReal(1.00000000000000))*(cj13));
07003 IkReal x1606=((r21)*(sj14));
07004 IkReal x1607=((r22)*(sj13));
07005 IkReal x1608=((cj14)*(sj11));
07006 if( IKabs(((gconst8)*(((((IkReal(-1.00000000000000))*(sj11)*(x1605)*(x1606)))+(((cj11)*(cj14)*(r21)))+(((sj11)*(x1607)))+(((sj14)*(x1604)))+(((cj13)*(r20)*(x1608))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((((r21)*(x1608)))+(((IkReal(-1.00000000000000))*(cj14)*(x1604)*(x1605)))+(((IkReal(-1.00000000000000))*(cj11)*(x1607)))+(((r20)*(sj11)*(sj14)))+(((cj11)*(cj13)*(x1606))))))) < IKFAST_ATAN2_MAGTHRESH )
07007     continue;
07008 j10array[0]=IKatan2(((gconst8)*(((((IkReal(-1.00000000000000))*(sj11)*(x1605)*(x1606)))+(((cj11)*(cj14)*(r21)))+(((sj11)*(x1607)))+(((sj14)*(x1604)))+(((cj13)*(r20)*(x1608)))))), ((gconst8)*(((((r21)*(x1608)))+(((IkReal(-1.00000000000000))*(cj14)*(x1604)*(x1605)))+(((IkReal(-1.00000000000000))*(cj11)*(x1607)))+(((r20)*(sj11)*(sj14)))+(((cj11)*(cj13)*(x1606)))))));
07009 sj10array[0]=IKsin(j10array[0]);
07010 cj10array[0]=IKcos(j10array[0]);
07011 if( j10array[0] > IKPI )
07012 {
07013     j10array[0]-=IK2PI;
07014 }
07015 else if( j10array[0] < -IKPI )
07016 {    j10array[0]+=IK2PI;
07017 }
07018 j10valid[0] = true;
07019 for(int ij10 = 0; ij10 < 1; ++ij10)
07020 {
07021 if( !j10valid[ij10] )
07022 {
07023     continue;
07024 }
07025 _ij10[0] = ij10; _ij10[1] = -1;
07026 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07027 {
07028 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07029 {
07030     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07031 }
07032 }
07033 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07034 {
07035 IkReal evalcond[4];
07036 IkReal x1609=IKsin(j10);
07037 IkReal x1610=IKcos(j10);
07038 IkReal x1611=((cj13)*(sj14));
07039 IkReal x1612=((cj13)*(cj14));
07040 IkReal x1613=((r10)*(sj9));
07041 IkReal x1614=((IkReal(1.00000000000000))*(cj9));
07042 IkReal x1615=((sj11)*(x1609));
07043 IkReal x1616=((IkReal(1.00000000000000))*(x1610));
07044 IkReal x1617=((cj11)*(x1609));
07045 IkReal x1618=((IkReal(1.00000000000000))*(r11)*(sj9));
07046 IkReal x1619=((cj11)*(x1616));
07047 evalcond[0]=((((IkReal(-1.00000000000000))*(x1617)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x1616))));
07048 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x1612)))+(((r21)*(x1611)))+(x1615)+(((IkReal(-1.00000000000000))*(x1619)))+(((IkReal(-1.00000000000000))*(r22)*(sj13))));
07049 evalcond[2]=((((IkReal(-1.00000000000000))*(sj14)*(x1613)))+(x1615)+(((IkReal(-1.00000000000000))*(x1619)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1614)))+(((IkReal(-1.00000000000000))*(cj14)*(x1618)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x1614))));
07050 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x1611)*(x1614)))+(((IkReal(-1.00000000000000))*(x1611)*(x1618)))+(x1617)+(((cj9)*(r02)*(sj13)))+(((sj11)*(x1610)))+(((cj9)*(r00)*(x1612)))+(((x1612)*(x1613)))+(((r12)*(sj13)*(sj9))));
07051 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07052 {
07053 continue;
07054 }
07055 }
07056 
07057 {
07058 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07059 vinfos[0].jointtype = 1;
07060 vinfos[0].foffset = j9;
07061 vinfos[0].indices[0] = _ij9[0];
07062 vinfos[0].indices[1] = _ij9[1];
07063 vinfos[0].maxsolutions = _nj9;
07064 vinfos[1].jointtype = 1;
07065 vinfos[1].foffset = j10;
07066 vinfos[1].indices[0] = _ij10[0];
07067 vinfos[1].indices[1] = _ij10[1];
07068 vinfos[1].maxsolutions = _nj10;
07069 vinfos[2].jointtype = 1;
07070 vinfos[2].foffset = j11;
07071 vinfos[2].indices[0] = _ij11[0];
07072 vinfos[2].indices[1] = _ij11[1];
07073 vinfos[2].maxsolutions = _nj11;
07074 vinfos[3].jointtype = 1;
07075 vinfos[3].foffset = j12;
07076 vinfos[3].indices[0] = _ij12[0];
07077 vinfos[3].indices[1] = _ij12[1];
07078 vinfos[3].maxsolutions = _nj12;
07079 vinfos[4].jointtype = 1;
07080 vinfos[4].foffset = j13;
07081 vinfos[4].indices[0] = _ij13[0];
07082 vinfos[4].indices[1] = _ij13[1];
07083 vinfos[4].maxsolutions = _nj13;
07084 vinfos[5].jointtype = 1;
07085 vinfos[5].foffset = j14;
07086 vinfos[5].indices[0] = _ij14[0];
07087 vinfos[5].indices[1] = _ij14[1];
07088 vinfos[5].maxsolutions = _nj14;
07089 std::vector<int> vfree(0);
07090 solutions.AddSolution(vinfos,vfree);
07091 }
07092 }
07093 }
07094 
07095 }
07096 
07097 }
07098 
07099 } else
07100 {
07101 IkReal x1620=((r00)*(sj9));
07102 IkReal x1621=((IkReal(1.00000000000000))*(sj13));
07103 IkReal x1622=((cj13)*(sj14));
07104 IkReal x1623=((cj9)*(sj14));
07105 IkReal x1624=((cj13)*(r02));
07106 IkReal x1625=((sj13)*(sj14));
07107 IkReal x1626=((r01)*(sj9));
07108 IkReal x1627=((cj9)*(sj13));
07109 IkReal x1628=((IkReal(1.00000000000000))*(cj9));
07110 IkReal x1629=((cj14)*(r10));
07111 IkReal x1630=((cj14)*(npx));
07112 IkReal x1631=((IkReal(1.00000000000000))*(cj13));
07113 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
07114 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
07115 evalcond[2]=((IkReal(0.235000000000000))+(((npy)*(x1622)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x1630)*(x1631)))+(((IkReal(-1.00000000000000))*(npz)*(x1621))));
07116 evalcond[3]=((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1628)))+(((sj14)*(x1620)))+(((IkReal(-1.00000000000000))*(r10)*(x1623)))+(((cj14)*(x1626))));
07117 evalcond[4]=((((r21)*(x1625)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x1621)))+(((cj13)*(r22))));
07118 evalcond[5]=((IkReal(-0.0950000000000000))+(((npy)*(x1625)))+(((IkReal(-1.00000000000000))*(x1621)*(x1630)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
07119 evalcond[6]=((((cj13)*(cj9)*(x1629)))+(((IkReal(-1.00000000000000))*(r11)*(x1622)*(x1628)))+(((x1622)*(x1626)))+(((r12)*(x1627)))+(((IkReal(-1.00000000000000))*(cj14)*(x1620)*(x1631)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x1621))));
07120 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(x1620)*(x1621)))+(((x1627)*(x1629)))+(((IkReal(-1.00000000000000))*(r11)*(x1621)*(x1623)))+(((sj9)*(x1624)))+(((x1625)*(x1626)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x1628))));
07121 evalcond[8]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1631)))+(((IkReal(-1.00000000000000))*(r01)*(x1621)*(x1623)))+(((cj14)*(r00)*(x1627)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x1621)))+(((IkReal(-1.00000000000000))*(x1624)*(x1628)))+(((sj13)*(sj9)*(x1629))));
07122 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  )
07123 {
07124 {
07125 IkReal dummyeval[1];
07126 IkReal gconst10;
07127 gconst10=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
07128 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
07129 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07130 {
07131 {
07132 IkReal dummyeval[1];
07133 IkReal gconst11;
07134 gconst11=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
07135 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
07136 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07137 {
07138 continue;
07139 
07140 } else
07141 {
07142 {
07143 IkReal j10array[1], cj10array[1], sj10array[1];
07144 bool j10valid[1]={false};
07145 _nj10 = 1;
07146 IkReal x1632=((IkReal(1.00000000000000))*(sj11));
07147 IkReal x1633=((cj14)*(r21));
07148 IkReal x1634=((IkReal(1.00000000000000))*(cj11));
07149 IkReal x1635=((r20)*(sj14));
07150 IkReal x1636=((cj9)*(r00)*(sj14));
07151 IkReal x1637=((cj14)*(r11)*(sj9));
07152 IkReal x1638=((cj14)*(cj9)*(r01));
07153 IkReal x1639=((r10)*(sj14)*(sj9));
07154 if( IKabs(((gconst11)*(((((IkReal(-1.00000000000000))*(x1634)*(x1635)))+(((IkReal(-1.00000000000000))*(x1633)*(x1634)))+(((IkReal(-1.00000000000000))*(x1632)*(x1639)))+(((IkReal(-1.00000000000000))*(x1632)*(x1638)))+(((IkReal(-1.00000000000000))*(x1632)*(x1637)))+(((IkReal(-1.00000000000000))*(x1632)*(x1636))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((((cj11)*(x1636)))+(((cj11)*(x1637)))+(((cj11)*(x1638)))+(((cj11)*(x1639)))+(((IkReal(-1.00000000000000))*(x1632)*(x1635)))+(((IkReal(-1.00000000000000))*(x1632)*(x1633))))))) < IKFAST_ATAN2_MAGTHRESH )
07155     continue;
07156 j10array[0]=IKatan2(((gconst11)*(((((IkReal(-1.00000000000000))*(x1634)*(x1635)))+(((IkReal(-1.00000000000000))*(x1633)*(x1634)))+(((IkReal(-1.00000000000000))*(x1632)*(x1639)))+(((IkReal(-1.00000000000000))*(x1632)*(x1638)))+(((IkReal(-1.00000000000000))*(x1632)*(x1637)))+(((IkReal(-1.00000000000000))*(x1632)*(x1636)))))), ((gconst11)*(((((cj11)*(x1636)))+(((cj11)*(x1637)))+(((cj11)*(x1638)))+(((cj11)*(x1639)))+(((IkReal(-1.00000000000000))*(x1632)*(x1635)))+(((IkReal(-1.00000000000000))*(x1632)*(x1633)))))));
07157 sj10array[0]=IKsin(j10array[0]);
07158 cj10array[0]=IKcos(j10array[0]);
07159 if( j10array[0] > IKPI )
07160 {
07161     j10array[0]-=IK2PI;
07162 }
07163 else if( j10array[0] < -IKPI )
07164 {    j10array[0]+=IK2PI;
07165 }
07166 j10valid[0] = true;
07167 for(int ij10 = 0; ij10 < 1; ++ij10)
07168 {
07169 if( !j10valid[ij10] )
07170 {
07171     continue;
07172 }
07173 _ij10[0] = ij10; _ij10[1] = -1;
07174 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07175 {
07176 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07177 {
07178     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07179 }
07180 }
07181 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07182 {
07183 IkReal evalcond[4];
07184 IkReal x1640=IKsin(j10);
07185 IkReal x1641=IKcos(j10);
07186 IkReal x1642=((cj14)*(sj9));
07187 IkReal x1643=((IkReal(1.00000000000000))*(r11));
07188 IkReal x1644=((cj13)*(sj14));
07189 IkReal x1645=((IkReal(1.00000000000000))*(cj9));
07190 IkReal x1646=((cj13)*(cj14));
07191 IkReal x1647=((cj11)*(x1640));
07192 IkReal x1648=((sj11)*(x1641));
07193 IkReal x1649=((cj11)*(x1641));
07194 IkReal x1650=((sj11)*(x1640));
07195 IkReal x1651=((x1647)+(x1648));
07196 evalcond[0]=((((cj14)*(r21)))+(x1651)+(((r20)*(sj14))));
07197 evalcond[1]=((((r21)*(x1644)))+(x1650)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x1649)))+(((IkReal(-1.00000000000000))*(r20)*(x1646))));
07198 evalcond[2]=((x1649)+(((IkReal(-1.00000000000000))*(x1650)))+(((IkReal(-1.00000000000000))*(x1642)*(x1643)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1645)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x1645))));
07199 evalcond[3]=((((IkReal(-1.00000000000000))*(sj9)*(x1643)*(x1644)))+(x1651)+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x1644)*(x1645)))+(((cj13)*(r10)*(x1642)))+(((cj9)*(r00)*(x1646)))+(((r12)*(sj13)*(sj9))));
07200 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07201 {
07202 continue;
07203 }
07204 }
07205 
07206 {
07207 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07208 vinfos[0].jointtype = 1;
07209 vinfos[0].foffset = j9;
07210 vinfos[0].indices[0] = _ij9[0];
07211 vinfos[0].indices[1] = _ij9[1];
07212 vinfos[0].maxsolutions = _nj9;
07213 vinfos[1].jointtype = 1;
07214 vinfos[1].foffset = j10;
07215 vinfos[1].indices[0] = _ij10[0];
07216 vinfos[1].indices[1] = _ij10[1];
07217 vinfos[1].maxsolutions = _nj10;
07218 vinfos[2].jointtype = 1;
07219 vinfos[2].foffset = j11;
07220 vinfos[2].indices[0] = _ij11[0];
07221 vinfos[2].indices[1] = _ij11[1];
07222 vinfos[2].maxsolutions = _nj11;
07223 vinfos[3].jointtype = 1;
07224 vinfos[3].foffset = j12;
07225 vinfos[3].indices[0] = _ij12[0];
07226 vinfos[3].indices[1] = _ij12[1];
07227 vinfos[3].maxsolutions = _nj12;
07228 vinfos[4].jointtype = 1;
07229 vinfos[4].foffset = j13;
07230 vinfos[4].indices[0] = _ij13[0];
07231 vinfos[4].indices[1] = _ij13[1];
07232 vinfos[4].maxsolutions = _nj13;
07233 vinfos[5].jointtype = 1;
07234 vinfos[5].foffset = j14;
07235 vinfos[5].indices[0] = _ij14[0];
07236 vinfos[5].indices[1] = _ij14[1];
07237 vinfos[5].maxsolutions = _nj14;
07238 std::vector<int> vfree(0);
07239 solutions.AddSolution(vinfos,vfree);
07240 }
07241 }
07242 }
07243 
07244 }
07245 
07246 }
07247 
07248 } else
07249 {
07250 {
07251 IkReal j10array[1], cj10array[1], sj10array[1];
07252 bool j10valid[1]={false};
07253 _nj10 = 1;
07254 IkReal x1652=((cj13)*(sj11));
07255 IkReal x1653=((r21)*(sj14));
07256 IkReal x1654=((cj14)*(r20));
07257 IkReal x1655=((cj11)*(cj13));
07258 IkReal x1656=((r22)*(sj13));
07259 IkReal x1657=((r20)*(sj14));
07260 IkReal x1658=((cj14)*(r21));
07261 if( IKabs(((gconst10)*(((((IkReal(-1.00000000000000))*(sj11)*(x1656)))+(((IkReal(-1.00000000000000))*(x1652)*(x1654)))+(((cj11)*(x1658)))+(((cj11)*(x1657)))+(((x1652)*(x1653))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((((sj11)*(x1657)))+(((sj11)*(x1658)))+(((x1654)*(x1655)))+(((IkReal(-1.00000000000000))*(x1653)*(x1655)))+(((cj11)*(x1656))))))) < IKFAST_ATAN2_MAGTHRESH )
07262     continue;
07263 j10array[0]=IKatan2(((gconst10)*(((((IkReal(-1.00000000000000))*(sj11)*(x1656)))+(((IkReal(-1.00000000000000))*(x1652)*(x1654)))+(((cj11)*(x1658)))+(((cj11)*(x1657)))+(((x1652)*(x1653)))))), ((gconst10)*(((((sj11)*(x1657)))+(((sj11)*(x1658)))+(((x1654)*(x1655)))+(((IkReal(-1.00000000000000))*(x1653)*(x1655)))+(((cj11)*(x1656)))))));
07264 sj10array[0]=IKsin(j10array[0]);
07265 cj10array[0]=IKcos(j10array[0]);
07266 if( j10array[0] > IKPI )
07267 {
07268     j10array[0]-=IK2PI;
07269 }
07270 else if( j10array[0] < -IKPI )
07271 {    j10array[0]+=IK2PI;
07272 }
07273 j10valid[0] = true;
07274 for(int ij10 = 0; ij10 < 1; ++ij10)
07275 {
07276 if( !j10valid[ij10] )
07277 {
07278     continue;
07279 }
07280 _ij10[0] = ij10; _ij10[1] = -1;
07281 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07282 {
07283 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07284 {
07285     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07286 }
07287 }
07288 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07289 {
07290 IkReal evalcond[4];
07291 IkReal x1659=IKsin(j10);
07292 IkReal x1660=IKcos(j10);
07293 IkReal x1661=((cj14)*(sj9));
07294 IkReal x1662=((IkReal(1.00000000000000))*(r11));
07295 IkReal x1663=((cj13)*(sj14));
07296 IkReal x1664=((IkReal(1.00000000000000))*(cj9));
07297 IkReal x1665=((cj13)*(cj14));
07298 IkReal x1666=((cj11)*(x1659));
07299 IkReal x1667=((sj11)*(x1660));
07300 IkReal x1668=((cj11)*(x1660));
07301 IkReal x1669=((sj11)*(x1659));
07302 IkReal x1670=((x1667)+(x1666));
07303 evalcond[0]=((((cj14)*(r21)))+(x1670)+(((r20)*(sj14))));
07304 evalcond[1]=((x1669)+(((IkReal(-1.00000000000000))*(x1668)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x1665)))+(((r21)*(x1663))));
07305 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj14)*(x1664)))+(((IkReal(-1.00000000000000))*(x1661)*(x1662)))+(x1668)+(((IkReal(-1.00000000000000))*(x1669)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x1664))));
07306 evalcond[3]=((((IkReal(-1.00000000000000))*(sj9)*(x1662)*(x1663)))+(((IkReal(-1.00000000000000))*(r01)*(x1663)*(x1664)))+(x1670)+(((cj9)*(r02)*(sj13)))+(((cj9)*(r00)*(x1665)))+(((r12)*(sj13)*(sj9)))+(((cj13)*(r10)*(x1661))));
07307 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07308 {
07309 continue;
07310 }
07311 }
07312 
07313 {
07314 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07315 vinfos[0].jointtype = 1;
07316 vinfos[0].foffset = j9;
07317 vinfos[0].indices[0] = _ij9[0];
07318 vinfos[0].indices[1] = _ij9[1];
07319 vinfos[0].maxsolutions = _nj9;
07320 vinfos[1].jointtype = 1;
07321 vinfos[1].foffset = j10;
07322 vinfos[1].indices[0] = _ij10[0];
07323 vinfos[1].indices[1] = _ij10[1];
07324 vinfos[1].maxsolutions = _nj10;
07325 vinfos[2].jointtype = 1;
07326 vinfos[2].foffset = j11;
07327 vinfos[2].indices[0] = _ij11[0];
07328 vinfos[2].indices[1] = _ij11[1];
07329 vinfos[2].maxsolutions = _nj11;
07330 vinfos[3].jointtype = 1;
07331 vinfos[3].foffset = j12;
07332 vinfos[3].indices[0] = _ij12[0];
07333 vinfos[3].indices[1] = _ij12[1];
07334 vinfos[3].maxsolutions = _nj12;
07335 vinfos[4].jointtype = 1;
07336 vinfos[4].foffset = j13;
07337 vinfos[4].indices[0] = _ij13[0];
07338 vinfos[4].indices[1] = _ij13[1];
07339 vinfos[4].maxsolutions = _nj13;
07340 vinfos[5].jointtype = 1;
07341 vinfos[5].foffset = j14;
07342 vinfos[5].indices[0] = _ij14[0];
07343 vinfos[5].indices[1] = _ij14[1];
07344 vinfos[5].maxsolutions = _nj14;
07345 std::vector<int> vfree(0);
07346 solutions.AddSolution(vinfos,vfree);
07347 }
07348 }
07349 }
07350 
07351 }
07352 
07353 }
07354 
07355 } else
07356 {
07357 IkReal x1671=((cj9)*(r10));
07358 IkReal x1672=((cj13)*(cj14));
07359 IkReal x1673=((sj14)*(sj9));
07360 IkReal x1674=((IkReal(1.00000000000000))*(sj14));
07361 IkReal x1675=((cj9)*(sj13));
07362 IkReal x1676=((r02)*(sj9));
07363 IkReal x1677=((cj13)*(cj9));
07364 IkReal x1678=((cj14)*(r01));
07365 IkReal x1679=((IkReal(1.00000000000000))*(npx));
07366 IkReal x1680=((cj14)*(sj13));
07367 IkReal x1681=((IkReal(1.00000000000000))*(cj9));
07368 IkReal x1682=((npy)*(sj14));
07369 IkReal x1683=((IkReal(1.00000000000000))*(sj13));
07370 IkReal x1684=((IkReal(1.00000000000000))*(cj14)*(sj9));
07371 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
07372 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
07373 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
07374 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x1672)*(x1679)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x1682)))+(((IkReal(-1.00000000000000))*(npz)*(x1683))));
07375 evalcond[4]=((IkReal(1.00000000000000))+(((r00)*(x1673)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1681)))+(((IkReal(-1.00000000000000))*(x1671)*(x1674)))+(((sj9)*(x1678))));
07376 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x1679)*(x1680)))+(((cj13)*(npz)))+(((sj13)*(x1682)))+(((IkReal(0.0900000000000000))*(sj13))));
07377 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x1684)))+(((IkReal(-1.00000000000000))*(r10)*(x1673)))+(((IkReal(-1.00000000000000))*(x1678)*(x1681)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x1674))));
07378 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(sj9)*(x1672)))+(((cj13)*(r01)*(x1673)))+(((IkReal(-1.00000000000000))*(x1676)*(x1683)))+(((IkReal(-1.00000000000000))*(r11)*(x1674)*(x1677)))+(((x1671)*(x1672)))+(((r12)*(x1675))));
07379 evalcond[8]=((((r01)*(sj13)*(x1673)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x1680)))+(((x1671)*(x1680)))+(((IkReal(-1.00000000000000))*(r11)*(x1674)*(x1675)))+(((IkReal(-1.00000000000000))*(r12)*(x1677)))+(((cj13)*(x1676))));
07380 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  )
07381 {
07382 {
07383 IkReal dummyeval[1];
07384 IkReal gconst12;
07385 gconst12=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
07386 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
07387 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07388 {
07389 {
07390 IkReal dummyeval[1];
07391 IkReal gconst13;
07392 gconst13=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
07393 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
07394 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07395 {
07396 continue;
07397 
07398 } else
07399 {
07400 {
07401 IkReal j10array[1], cj10array[1], sj10array[1];
07402 bool j10valid[1]={false};
07403 _nj10 = 1;
07404 IkReal x1685=((cj13)*(sj14));
07405 IkReal x1686=((IkReal(1.00000000000000))*(cj11));
07406 IkReal x1687=((r11)*(sj9));
07407 IkReal x1688=((IkReal(1.00000000000000))*(sj11));
07408 IkReal x1689=((cj13)*(cj14));
07409 IkReal x1690=((cj9)*(r01));
07410 IkReal x1691=((cj9)*(sj11));
07411 IkReal x1692=((r02)*(sj13));
07412 IkReal x1693=((r10)*(sj9));
07413 IkReal x1694=((cj11)*(cj9));
07414 IkReal x1695=((r22)*(sj13));
07415 IkReal x1696=((r12)*(sj13)*(sj9));
07416 if( IKabs(((gconst13)*(((((IkReal(-1.00000000000000))*(x1688)*(x1695)))+(((IkReal(-1.00000000000000))*(x1685)*(x1686)*(x1690)))+(((IkReal(-1.00000000000000))*(r20)*(x1688)*(x1689)))+(((IkReal(-1.00000000000000))*(x1685)*(x1686)*(x1687)))+(((r00)*(x1689)*(x1694)))+(((x1692)*(x1694)))+(((cj11)*(x1696)))+(((r21)*(sj11)*(x1685)))+(((cj11)*(x1689)*(x1693))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst13)*(((((sj11)*(x1696)))+(((r00)*(x1689)*(x1691)))+(((x1691)*(x1692)))+(((sj11)*(x1689)*(x1693)))+(((cj11)*(x1695)))+(((cj11)*(r20)*(x1689)))+(((IkReal(-1.00000000000000))*(x1685)*(x1687)*(x1688)))+(((IkReal(-1.00000000000000))*(r21)*(x1685)*(x1686)))+(((IkReal(-1.00000000000000))*(x1685)*(x1688)*(x1690))))))) < IKFAST_ATAN2_MAGTHRESH )
07417     continue;
07418 j10array[0]=IKatan2(((gconst13)*(((((IkReal(-1.00000000000000))*(x1688)*(x1695)))+(((IkReal(-1.00000000000000))*(x1685)*(x1686)*(x1690)))+(((IkReal(-1.00000000000000))*(r20)*(x1688)*(x1689)))+(((IkReal(-1.00000000000000))*(x1685)*(x1686)*(x1687)))+(((r00)*(x1689)*(x1694)))+(((x1692)*(x1694)))+(((cj11)*(x1696)))+(((r21)*(sj11)*(x1685)))+(((cj11)*(x1689)*(x1693)))))), ((gconst13)*(((((sj11)*(x1696)))+(((r00)*(x1689)*(x1691)))+(((x1691)*(x1692)))+(((sj11)*(x1689)*(x1693)))+(((cj11)*(x1695)))+(((cj11)*(r20)*(x1689)))+(((IkReal(-1.00000000000000))*(x1685)*(x1687)*(x1688)))+(((IkReal(-1.00000000000000))*(r21)*(x1685)*(x1686)))+(((IkReal(-1.00000000000000))*(x1685)*(x1688)*(x1690)))))));
07419 sj10array[0]=IKsin(j10array[0]);
07420 cj10array[0]=IKcos(j10array[0]);
07421 if( j10array[0] > IKPI )
07422 {
07423     j10array[0]-=IK2PI;
07424 }
07425 else if( j10array[0] < -IKPI )
07426 {    j10array[0]+=IK2PI;
07427 }
07428 j10valid[0] = true;
07429 for(int ij10 = 0; ij10 < 1; ++ij10)
07430 {
07431 if( !j10valid[ij10] )
07432 {
07433     continue;
07434 }
07435 _ij10[0] = ij10; _ij10[1] = -1;
07436 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07437 {
07438 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07439 {
07440     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07441 }
07442 }
07443 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07444 {
07445 IkReal evalcond[4];
07446 IkReal x1697=IKsin(j10);
07447 IkReal x1698=IKcos(j10);
07448 IkReal x1699=((IkReal(1.00000000000000))*(sj13));
07449 IkReal x1700=((r11)*(sj9));
07450 IkReal x1701=((cj9)*(r01));
07451 IkReal x1702=((r21)*(sj14));
07452 IkReal x1703=((cj9)*(r02));
07453 IkReal x1704=((sj13)*(sj9));
07454 IkReal x1705=((cj14)*(r10));
07455 IkReal x1706=((IkReal(1.00000000000000))*(cj13));
07456 IkReal x1707=((cj14)*(r20));
07457 IkReal x1708=((cj11)*(x1697));
07458 IkReal x1709=((sj11)*(x1698));
07459 IkReal x1710=((sj14)*(x1706));
07460 IkReal x1711=((sj11)*(x1697));
07461 IkReal x1712=((cj11)*(x1698));
07462 IkReal x1713=((cj14)*(cj9)*(r00));
07463 IkReal x1714=((x1708)+(x1709));
07464 evalcond[0]=((x1711)+(((IkReal(-1.00000000000000))*(x1712)))+(((IkReal(-1.00000000000000))*(r22)*(x1699)))+(((IkReal(-1.00000000000000))*(x1706)*(x1707)))+(((cj13)*(x1702))));
07465 evalcond[1]=((x1714)+(((IkReal(-1.00000000000000))*(x1699)*(x1707)))+(((sj13)*(x1702)))+(((cj13)*(r22))));
07466 evalcond[2]=((((IkReal(-1.00000000000000))*(x1701)*(x1710)))+(((cj13)*(x1713)))+(((r12)*(x1704)))+(x1714)+(((sj13)*(x1703)))+(((IkReal(-1.00000000000000))*(x1700)*(x1710)))+(((cj13)*(sj9)*(x1705))));
07467 evalcond[3]=((x1712)+(((sj13)*(x1713)))+(((IkReal(-1.00000000000000))*(x1711)))+(((x1704)*(x1705)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1706)))+(((IkReal(-1.00000000000000))*(x1703)*(x1706)))+(((IkReal(-1.00000000000000))*(sj14)*(x1699)*(x1700)))+(((IkReal(-1.00000000000000))*(sj14)*(x1699)*(x1701))));
07468 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07469 {
07470 continue;
07471 }
07472 }
07473 
07474 {
07475 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07476 vinfos[0].jointtype = 1;
07477 vinfos[0].foffset = j9;
07478 vinfos[0].indices[0] = _ij9[0];
07479 vinfos[0].indices[1] = _ij9[1];
07480 vinfos[0].maxsolutions = _nj9;
07481 vinfos[1].jointtype = 1;
07482 vinfos[1].foffset = j10;
07483 vinfos[1].indices[0] = _ij10[0];
07484 vinfos[1].indices[1] = _ij10[1];
07485 vinfos[1].maxsolutions = _nj10;
07486 vinfos[2].jointtype = 1;
07487 vinfos[2].foffset = j11;
07488 vinfos[2].indices[0] = _ij11[0];
07489 vinfos[2].indices[1] = _ij11[1];
07490 vinfos[2].maxsolutions = _nj11;
07491 vinfos[3].jointtype = 1;
07492 vinfos[3].foffset = j12;
07493 vinfos[3].indices[0] = _ij12[0];
07494 vinfos[3].indices[1] = _ij12[1];
07495 vinfos[3].maxsolutions = _nj12;
07496 vinfos[4].jointtype = 1;
07497 vinfos[4].foffset = j13;
07498 vinfos[4].indices[0] = _ij13[0];
07499 vinfos[4].indices[1] = _ij13[1];
07500 vinfos[4].maxsolutions = _nj13;
07501 vinfos[5].jointtype = 1;
07502 vinfos[5].foffset = j14;
07503 vinfos[5].indices[0] = _ij14[0];
07504 vinfos[5].indices[1] = _ij14[1];
07505 vinfos[5].maxsolutions = _nj14;
07506 std::vector<int> vfree(0);
07507 solutions.AddSolution(vinfos,vfree);
07508 }
07509 }
07510 }
07511 
07512 }
07513 
07514 }
07515 
07516 } else
07517 {
07518 {
07519 IkReal j10array[1], cj10array[1], sj10array[1];
07520 bool j10valid[1]={false};
07521 _nj10 = 1;
07522 IkReal x1715=((IkReal(1.00000000000000))*(cj11));
07523 IkReal x1716=((cj11)*(r22));
07524 IkReal x1717=((sj11)*(sj13));
07525 IkReal x1718=((r21)*(sj14));
07526 IkReal x1719=((cj13)*(sj11));
07527 IkReal x1720=((cj14)*(r20));
07528 IkReal x1721=((cj13)*(x1718));
07529 IkReal x1722=((IkReal(1.00000000000000))*(x1720));
07530 if( IKabs(((gconst12)*(((((cj13)*(x1716)))+(((cj11)*(sj13)*(x1718)))+(((IkReal(-1.00000000000000))*(r22)*(x1717)))+(((IkReal(-1.00000000000000))*(sj13)*(x1715)*(x1720)))+(((IkReal(-1.00000000000000))*(x1719)*(x1722)))+(((x1718)*(x1719))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst12)*(((((r22)*(x1719)))+(((IkReal(-1.00000000000000))*(x1715)*(x1721)))+(((sj13)*(x1716)))+(((IkReal(-1.00000000000000))*(x1717)*(x1722)))+(((cj11)*(cj13)*(x1720)))+(((x1717)*(x1718))))))) < IKFAST_ATAN2_MAGTHRESH )
07531     continue;
07532 j10array[0]=IKatan2(((gconst12)*(((((cj13)*(x1716)))+(((cj11)*(sj13)*(x1718)))+(((IkReal(-1.00000000000000))*(r22)*(x1717)))+(((IkReal(-1.00000000000000))*(sj13)*(x1715)*(x1720)))+(((IkReal(-1.00000000000000))*(x1719)*(x1722)))+(((x1718)*(x1719)))))), ((gconst12)*(((((r22)*(x1719)))+(((IkReal(-1.00000000000000))*(x1715)*(x1721)))+(((sj13)*(x1716)))+(((IkReal(-1.00000000000000))*(x1717)*(x1722)))+(((cj11)*(cj13)*(x1720)))+(((x1717)*(x1718)))))));
07533 sj10array[0]=IKsin(j10array[0]);
07534 cj10array[0]=IKcos(j10array[0]);
07535 if( j10array[0] > IKPI )
07536 {
07537     j10array[0]-=IK2PI;
07538 }
07539 else if( j10array[0] < -IKPI )
07540 {    j10array[0]+=IK2PI;
07541 }
07542 j10valid[0] = true;
07543 for(int ij10 = 0; ij10 < 1; ++ij10)
07544 {
07545 if( !j10valid[ij10] )
07546 {
07547     continue;
07548 }
07549 _ij10[0] = ij10; _ij10[1] = -1;
07550 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07551 {
07552 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07553 {
07554     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07555 }
07556 }
07557 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07558 {
07559 IkReal evalcond[4];
07560 IkReal x1723=IKsin(j10);
07561 IkReal x1724=IKcos(j10);
07562 IkReal x1725=((IkReal(1.00000000000000))*(sj13));
07563 IkReal x1726=((r11)*(sj9));
07564 IkReal x1727=((cj9)*(r01));
07565 IkReal x1728=((r21)*(sj14));
07566 IkReal x1729=((cj9)*(r02));
07567 IkReal x1730=((sj13)*(sj9));
07568 IkReal x1731=((cj14)*(r10));
07569 IkReal x1732=((IkReal(1.00000000000000))*(cj13));
07570 IkReal x1733=((cj14)*(r20));
07571 IkReal x1734=((cj11)*(x1723));
07572 IkReal x1735=((sj11)*(x1724));
07573 IkReal x1736=((sj14)*(x1732));
07574 IkReal x1737=((sj11)*(x1723));
07575 IkReal x1738=((cj11)*(x1724));
07576 IkReal x1739=((cj14)*(cj9)*(r00));
07577 IkReal x1740=((x1735)+(x1734));
07578 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x1725)))+(x1737)+(((cj13)*(x1728)))+(((IkReal(-1.00000000000000))*(x1738)))+(((IkReal(-1.00000000000000))*(x1732)*(x1733))));
07579 evalcond[1]=((x1740)+(((IkReal(-1.00000000000000))*(x1725)*(x1733)))+(((cj13)*(r22)))+(((sj13)*(x1728))));
07580 evalcond[2]=((((cj13)*(sj9)*(x1731)))+(x1740)+(((IkReal(-1.00000000000000))*(x1726)*(x1736)))+(((cj13)*(x1739)))+(((r12)*(x1730)))+(((IkReal(-1.00000000000000))*(x1727)*(x1736)))+(((sj13)*(x1729))));
07581 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1732)))+(((x1730)*(x1731)))+(x1738)+(((IkReal(-1.00000000000000))*(sj14)*(x1725)*(x1727)))+(((IkReal(-1.00000000000000))*(sj14)*(x1725)*(x1726)))+(((IkReal(-1.00000000000000))*(x1729)*(x1732)))+(((IkReal(-1.00000000000000))*(x1737)))+(((sj13)*(x1739))));
07582 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07583 {
07584 continue;
07585 }
07586 }
07587 
07588 {
07589 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07590 vinfos[0].jointtype = 1;
07591 vinfos[0].foffset = j9;
07592 vinfos[0].indices[0] = _ij9[0];
07593 vinfos[0].indices[1] = _ij9[1];
07594 vinfos[0].maxsolutions = _nj9;
07595 vinfos[1].jointtype = 1;
07596 vinfos[1].foffset = j10;
07597 vinfos[1].indices[0] = _ij10[0];
07598 vinfos[1].indices[1] = _ij10[1];
07599 vinfos[1].maxsolutions = _nj10;
07600 vinfos[2].jointtype = 1;
07601 vinfos[2].foffset = j11;
07602 vinfos[2].indices[0] = _ij11[0];
07603 vinfos[2].indices[1] = _ij11[1];
07604 vinfos[2].maxsolutions = _nj11;
07605 vinfos[3].jointtype = 1;
07606 vinfos[3].foffset = j12;
07607 vinfos[3].indices[0] = _ij12[0];
07608 vinfos[3].indices[1] = _ij12[1];
07609 vinfos[3].maxsolutions = _nj12;
07610 vinfos[4].jointtype = 1;
07611 vinfos[4].foffset = j13;
07612 vinfos[4].indices[0] = _ij13[0];
07613 vinfos[4].indices[1] = _ij13[1];
07614 vinfos[4].maxsolutions = _nj13;
07615 vinfos[5].jointtype = 1;
07616 vinfos[5].foffset = j14;
07617 vinfos[5].indices[0] = _ij14[0];
07618 vinfos[5].indices[1] = _ij14[1];
07619 vinfos[5].maxsolutions = _nj14;
07620 std::vector<int> vfree(0);
07621 solutions.AddSolution(vinfos,vfree);
07622 }
07623 }
07624 }
07625 
07626 }
07627 
07628 }
07629 
07630 } else
07631 {
07632 IkReal x1741=((cj9)*(r10));
07633 IkReal x1742=((cj13)*(cj14));
07634 IkReal x1743=((sj14)*(sj9));
07635 IkReal x1744=((IkReal(1.00000000000000))*(sj14));
07636 IkReal x1745=((cj9)*(sj13));
07637 IkReal x1746=((r02)*(sj9));
07638 IkReal x1747=((cj13)*(cj9));
07639 IkReal x1748=((cj14)*(r01));
07640 IkReal x1749=((IkReal(1.00000000000000))*(npx));
07641 IkReal x1750=((cj14)*(sj13));
07642 IkReal x1751=((IkReal(1.00000000000000))*(cj9));
07643 IkReal x1752=((npy)*(sj14));
07644 IkReal x1753=((IkReal(1.00000000000000))*(sj13));
07645 IkReal x1754=((IkReal(1.00000000000000))*(cj14)*(sj9));
07646 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
07647 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
07648 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
07649 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x1753)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x1752)))+(((IkReal(-1.00000000000000))*(x1742)*(x1749))));
07650 evalcond[4]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x1741)*(x1744)))+(((sj9)*(x1748)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1751)))+(((r00)*(x1743))));
07651 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x1749)*(x1750)))+(((cj13)*(npz)))+(((sj13)*(x1752)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(0.250000000000000))*(sj11))));
07652 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x1754)))+(((IkReal(-1.00000000000000))*(r10)*(x1743)))+(((IkReal(-1.00000000000000))*(x1748)*(x1751)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x1744))));
07653 evalcond[7]=((((r12)*(x1745)))+(((cj13)*(r01)*(x1743)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x1742)))+(((IkReal(-1.00000000000000))*(x1746)*(x1753)))+(((IkReal(-1.00000000000000))*(r11)*(x1744)*(x1747)))+(((x1741)*(x1742))));
07654 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(sj9)*(x1750)))+(((IkReal(-1.00000000000000))*(r12)*(x1747)))+(((cj13)*(x1746)))+(((r01)*(sj13)*(x1743)))+(((IkReal(-1.00000000000000))*(r11)*(x1744)*(x1745)))+(((x1741)*(x1750))));
07655 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  )
07656 {
07657 {
07658 IkReal dummyeval[1];
07659 IkReal gconst14;
07660 gconst14=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
07661 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
07662 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07663 {
07664 {
07665 IkReal dummyeval[1];
07666 IkReal gconst15;
07667 gconst15=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
07668 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
07669 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
07670 {
07671 continue;
07672 
07673 } else
07674 {
07675 {
07676 IkReal j10array[1], cj10array[1], sj10array[1];
07677 bool j10valid[1]={false};
07678 _nj10 = 1;
07679 IkReal x1755=((cj13)*(sj14));
07680 IkReal x1756=((IkReal(1.00000000000000))*(cj11));
07681 IkReal x1757=((r11)*(sj9));
07682 IkReal x1758=((IkReal(1.00000000000000))*(sj11));
07683 IkReal x1759=((cj13)*(cj14));
07684 IkReal x1760=((cj11)*(sj13));
07685 IkReal x1761=((r12)*(sj9));
07686 IkReal x1762=((cj9)*(r01));
07687 IkReal x1763=((sj11)*(sj13));
07688 IkReal x1764=((cj9)*(r02));
07689 IkReal x1765=((r10)*(sj9));
07690 IkReal x1766=((cj9)*(r00));
07691 if( IKabs(((gconst15)*(((((IkReal(-1.00000000000000))*(x1755)*(x1756)*(x1757)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1758)))+(((r21)*(sj11)*(x1755)))+(((IkReal(-1.00000000000000))*(r20)*(x1758)*(x1759)))+(((IkReal(-1.00000000000000))*(x1755)*(x1756)*(x1762)))+(((cj11)*(x1759)*(x1765)))+(((cj11)*(x1759)*(x1766)))+(((x1760)*(x1761)))+(((x1760)*(x1764))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst15)*(((((cj11)*(r20)*(x1759)))+(((IkReal(-1.00000000000000))*(x1755)*(x1758)*(x1762)))+(((IkReal(-1.00000000000000))*(r21)*(x1755)*(x1756)))+(((r22)*(x1760)))+(((IkReal(-1.00000000000000))*(x1755)*(x1757)*(x1758)))+(((x1761)*(x1763)))+(((sj11)*(x1759)*(x1766)))+(((sj11)*(x1759)*(x1765)))+(((x1763)*(x1764))))))) < IKFAST_ATAN2_MAGTHRESH )
07692     continue;
07693 j10array[0]=IKatan2(((gconst15)*(((((IkReal(-1.00000000000000))*(x1755)*(x1756)*(x1757)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x1758)))+(((r21)*(sj11)*(x1755)))+(((IkReal(-1.00000000000000))*(r20)*(x1758)*(x1759)))+(((IkReal(-1.00000000000000))*(x1755)*(x1756)*(x1762)))+(((cj11)*(x1759)*(x1765)))+(((cj11)*(x1759)*(x1766)))+(((x1760)*(x1761)))+(((x1760)*(x1764)))))), ((gconst15)*(((((cj11)*(r20)*(x1759)))+(((IkReal(-1.00000000000000))*(x1755)*(x1758)*(x1762)))+(((IkReal(-1.00000000000000))*(r21)*(x1755)*(x1756)))+(((r22)*(x1760)))+(((IkReal(-1.00000000000000))*(x1755)*(x1757)*(x1758)))+(((x1761)*(x1763)))+(((sj11)*(x1759)*(x1766)))+(((sj11)*(x1759)*(x1765)))+(((x1763)*(x1764)))))));
07694 sj10array[0]=IKsin(j10array[0]);
07695 cj10array[0]=IKcos(j10array[0]);
07696 if( j10array[0] > IKPI )
07697 {
07698     j10array[0]-=IK2PI;
07699 }
07700 else if( j10array[0] < -IKPI )
07701 {    j10array[0]+=IK2PI;
07702 }
07703 j10valid[0] = true;
07704 for(int ij10 = 0; ij10 < 1; ++ij10)
07705 {
07706 if( !j10valid[ij10] )
07707 {
07708     continue;
07709 }
07710 _ij10[0] = ij10; _ij10[1] = -1;
07711 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07712 {
07713 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07714 {
07715     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07716 }
07717 }
07718 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07719 {
07720 IkReal evalcond[4];
07721 IkReal x1767=IKsin(j10);
07722 IkReal x1768=IKcos(j10);
07723 IkReal x1769=((IkReal(1.00000000000000))*(sj13));
07724 IkReal x1770=((r11)*(sj9));
07725 IkReal x1771=((cj9)*(r01));
07726 IkReal x1772=((IkReal(1.00000000000000))*(cj11));
07727 IkReal x1773=((r21)*(sj14));
07728 IkReal x1774=((cj9)*(r02));
07729 IkReal x1775=((sj13)*(sj9));
07730 IkReal x1776=((cj14)*(r10));
07731 IkReal x1777=((IkReal(1.00000000000000))*(cj13));
07732 IkReal x1778=((cj14)*(r20));
07733 IkReal x1779=((sj11)*(x1767));
07734 IkReal x1780=((sj14)*(x1777));
07735 IkReal x1781=((sj11)*(x1768));
07736 IkReal x1782=((cj14)*(cj9)*(r00));
07737 IkReal x1783=((x1768)*(x1772));
07738 evalcond[0]=((((IkReal(-1.00000000000000))*(x1783)))+(x1779)+(((IkReal(-1.00000000000000))*(r22)*(x1769)))+(((IkReal(-1.00000000000000))*(x1777)*(x1778)))+(((cj13)*(x1773))));
07739 evalcond[1]=((((IkReal(-1.00000000000000))*(x1767)*(x1772)))+(((sj13)*(x1773)))+(((IkReal(-1.00000000000000))*(x1781)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x1769)*(x1778))));
07740 evalcond[2]=((((IkReal(-1.00000000000000))*(x1770)*(x1780)))+(((r12)*(x1775)))+(x1781)+(((cj11)*(x1767)))+(((sj13)*(x1774)))+(((cj13)*(x1782)))+(((cj13)*(sj9)*(x1776)))+(((IkReal(-1.00000000000000))*(x1771)*(x1780))));
07741 evalcond[3]=((((IkReal(-1.00000000000000))*(x1783)))+(x1779)+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1777)))+(((x1775)*(x1776)))+(((IkReal(-1.00000000000000))*(x1774)*(x1777)))+(((sj13)*(x1782)))+(((IkReal(-1.00000000000000))*(sj14)*(x1769)*(x1771)))+(((IkReal(-1.00000000000000))*(sj14)*(x1769)*(x1770))));
07742 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07743 {
07744 continue;
07745 }
07746 }
07747 
07748 {
07749 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07750 vinfos[0].jointtype = 1;
07751 vinfos[0].foffset = j9;
07752 vinfos[0].indices[0] = _ij9[0];
07753 vinfos[0].indices[1] = _ij9[1];
07754 vinfos[0].maxsolutions = _nj9;
07755 vinfos[1].jointtype = 1;
07756 vinfos[1].foffset = j10;
07757 vinfos[1].indices[0] = _ij10[0];
07758 vinfos[1].indices[1] = _ij10[1];
07759 vinfos[1].maxsolutions = _nj10;
07760 vinfos[2].jointtype = 1;
07761 vinfos[2].foffset = j11;
07762 vinfos[2].indices[0] = _ij11[0];
07763 vinfos[2].indices[1] = _ij11[1];
07764 vinfos[2].maxsolutions = _nj11;
07765 vinfos[3].jointtype = 1;
07766 vinfos[3].foffset = j12;
07767 vinfos[3].indices[0] = _ij12[0];
07768 vinfos[3].indices[1] = _ij12[1];
07769 vinfos[3].maxsolutions = _nj12;
07770 vinfos[4].jointtype = 1;
07771 vinfos[4].foffset = j13;
07772 vinfos[4].indices[0] = _ij13[0];
07773 vinfos[4].indices[1] = _ij13[1];
07774 vinfos[4].maxsolutions = _nj13;
07775 vinfos[5].jointtype = 1;
07776 vinfos[5].foffset = j14;
07777 vinfos[5].indices[0] = _ij14[0];
07778 vinfos[5].indices[1] = _ij14[1];
07779 vinfos[5].maxsolutions = _nj14;
07780 std::vector<int> vfree(0);
07781 solutions.AddSolution(vinfos,vfree);
07782 }
07783 }
07784 }
07785 
07786 }
07787 
07788 }
07789 
07790 } else
07791 {
07792 {
07793 IkReal j10array[1], cj10array[1], sj10array[1];
07794 bool j10valid[1]={false};
07795 _nj10 = 1;
07796 IkReal x1784=((IkReal(1.00000000000000))*(sj11));
07797 IkReal x1785=((cj11)*(r22));
07798 IkReal x1786=((IkReal(1.00000000000000))*(sj13));
07799 IkReal x1787=((sj11)*(sj13));
07800 IkReal x1788=((r21)*(sj14));
07801 IkReal x1789=((cj14)*(r20));
07802 IkReal x1790=((cj13)*(sj11));
07803 IkReal x1791=((cj13)*(x1788));
07804 if( IKabs(((gconst14)*(((((cj13)*(x1785)))+(((x1789)*(x1790)))+(((r22)*(x1787)))+(((IkReal(-1.00000000000000))*(x1784)*(x1791)))+(((cj11)*(sj13)*(x1788)))+(((IkReal(-1.00000000000000))*(cj11)*(x1786)*(x1789))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst14)*(((((IkReal(-1.00000000000000))*(sj13)*(x1784)*(x1789)))+(((x1787)*(x1788)))+(((IkReal(-1.00000000000000))*(x1785)*(x1786)))+(((r22)*(x1790)))+(((cj11)*(x1791)))+(((IkReal(-1.00000000000000))*(cj11)*(cj13)*(x1789))))))) < IKFAST_ATAN2_MAGTHRESH )
07805     continue;
07806 j10array[0]=IKatan2(((gconst14)*(((((cj13)*(x1785)))+(((x1789)*(x1790)))+(((r22)*(x1787)))+(((IkReal(-1.00000000000000))*(x1784)*(x1791)))+(((cj11)*(sj13)*(x1788)))+(((IkReal(-1.00000000000000))*(cj11)*(x1786)*(x1789)))))), ((gconst14)*(((((IkReal(-1.00000000000000))*(sj13)*(x1784)*(x1789)))+(((x1787)*(x1788)))+(((IkReal(-1.00000000000000))*(x1785)*(x1786)))+(((r22)*(x1790)))+(((cj11)*(x1791)))+(((IkReal(-1.00000000000000))*(cj11)*(cj13)*(x1789)))))));
07807 sj10array[0]=IKsin(j10array[0]);
07808 cj10array[0]=IKcos(j10array[0]);
07809 if( j10array[0] > IKPI )
07810 {
07811     j10array[0]-=IK2PI;
07812 }
07813 else if( j10array[0] < -IKPI )
07814 {    j10array[0]+=IK2PI;
07815 }
07816 j10valid[0] = true;
07817 for(int ij10 = 0; ij10 < 1; ++ij10)
07818 {
07819 if( !j10valid[ij10] )
07820 {
07821     continue;
07822 }
07823 _ij10[0] = ij10; _ij10[1] = -1;
07824 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07825 {
07826 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07827 {
07828     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07829 }
07830 }
07831 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07832 {
07833 IkReal evalcond[4];
07834 IkReal x1792=IKsin(j10);
07835 IkReal x1793=IKcos(j10);
07836 IkReal x1794=((IkReal(1.00000000000000))*(sj13));
07837 IkReal x1795=((r11)*(sj9));
07838 IkReal x1796=((cj9)*(r01));
07839 IkReal x1797=((IkReal(1.00000000000000))*(cj11));
07840 IkReal x1798=((r21)*(sj14));
07841 IkReal x1799=((cj9)*(r02));
07842 IkReal x1800=((sj13)*(sj9));
07843 IkReal x1801=((cj14)*(r10));
07844 IkReal x1802=((IkReal(1.00000000000000))*(cj13));
07845 IkReal x1803=((cj14)*(r20));
07846 IkReal x1804=((sj11)*(x1792));
07847 IkReal x1805=((sj14)*(x1802));
07848 IkReal x1806=((sj11)*(x1793));
07849 IkReal x1807=((cj14)*(cj9)*(r00));
07850 IkReal x1808=((x1793)*(x1797));
07851 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x1794)))+(((cj13)*(x1798)))+(((IkReal(-1.00000000000000))*(x1802)*(x1803)))+(((IkReal(-1.00000000000000))*(x1808)))+(x1804));
07852 evalcond[1]=((((sj13)*(x1798)))+(((IkReal(-1.00000000000000))*(x1792)*(x1797)))+(((IkReal(-1.00000000000000))*(x1794)*(x1803)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x1806))));
07853 evalcond[2]=((((sj13)*(x1799)))+(((IkReal(-1.00000000000000))*(x1795)*(x1805)))+(((IkReal(-1.00000000000000))*(x1796)*(x1805)))+(((cj13)*(x1807)))+(((r12)*(x1800)))+(x1806)+(((cj11)*(x1792)))+(((cj13)*(sj9)*(x1801))));
07854 evalcond[3]=((((x1800)*(x1801)))+(((IkReal(-1.00000000000000))*(x1799)*(x1802)))+(((IkReal(-1.00000000000000))*(x1808)))+(x1804)+(((IkReal(-1.00000000000000))*(sj14)*(x1794)*(x1795)))+(((IkReal(-1.00000000000000))*(sj14)*(x1794)*(x1796)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x1802)))+(((sj13)*(x1807))));
07855 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
07856 {
07857 continue;
07858 }
07859 }
07860 
07861 {
07862 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07863 vinfos[0].jointtype = 1;
07864 vinfos[0].foffset = j9;
07865 vinfos[0].indices[0] = _ij9[0];
07866 vinfos[0].indices[1] = _ij9[1];
07867 vinfos[0].maxsolutions = _nj9;
07868 vinfos[1].jointtype = 1;
07869 vinfos[1].foffset = j10;
07870 vinfos[1].indices[0] = _ij10[0];
07871 vinfos[1].indices[1] = _ij10[1];
07872 vinfos[1].maxsolutions = _nj10;
07873 vinfos[2].jointtype = 1;
07874 vinfos[2].foffset = j11;
07875 vinfos[2].indices[0] = _ij11[0];
07876 vinfos[2].indices[1] = _ij11[1];
07877 vinfos[2].maxsolutions = _nj11;
07878 vinfos[3].jointtype = 1;
07879 vinfos[3].foffset = j12;
07880 vinfos[3].indices[0] = _ij12[0];
07881 vinfos[3].indices[1] = _ij12[1];
07882 vinfos[3].maxsolutions = _nj12;
07883 vinfos[4].jointtype = 1;
07884 vinfos[4].foffset = j13;
07885 vinfos[4].indices[0] = _ij13[0];
07886 vinfos[4].indices[1] = _ij13[1];
07887 vinfos[4].maxsolutions = _nj13;
07888 vinfos[5].jointtype = 1;
07889 vinfos[5].foffset = j14;
07890 vinfos[5].indices[0] = _ij14[0];
07891 vinfos[5].indices[1] = _ij14[1];
07892 vinfos[5].maxsolutions = _nj14;
07893 std::vector<int> vfree(0);
07894 solutions.AddSolution(vinfos,vfree);
07895 }
07896 }
07897 }
07898 
07899 }
07900 
07901 }
07902 
07903 } else
07904 {
07905 if( 1 )
07906 {
07907 continue;
07908 
07909 } else
07910 {
07911 }
07912 }
07913 }
07914 }
07915 }
07916 }
07917 
07918 } else
07919 {
07920 {
07921 IkReal j10array[1], cj10array[1], sj10array[1];
07922 bool j10valid[1]={false};
07923 _nj10 = 1;
07924 IkReal x1809=((r21)*(sj14));
07925 IkReal x1810=((cj12)*(cj13));
07926 IkReal x1811=((sj11)*(sj13));
07927 IkReal x1812=((cj14)*(r20));
07928 IkReal x1813=((IkReal(1.00000000000000))*(sj11));
07929 IkReal x1814=((cj12)*(r22));
07930 IkReal x1815=((IkReal(1.00000000000000))*(cj11));
07931 IkReal x1816=((cj13)*(r22));
07932 IkReal x1817=((sj13)*(x1815));
07933 if( IKabs(((gconst7)*(((((IkReal(-1.00000000000000))*(x1809)*(x1817)))+(((sj11)*(x1810)*(x1812)))+(((IkReal(-1.00000000000000))*(x1809)*(x1810)*(x1813)))+(((cj11)*(sj13)*(x1812)))+(((IkReal(-1.00000000000000))*(x1815)*(x1816)))+(((x1811)*(x1814))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((((IkReal(-1.00000000000000))*(x1810)*(x1812)*(x1815)))+(((IkReal(-1.00000000000000))*(x1813)*(x1816)))+(((IkReal(-1.00000000000000))*(x1809)*(x1811)))+(((IkReal(-1.00000000000000))*(x1814)*(x1817)))+(((x1811)*(x1812)))+(((cj11)*(x1809)*(x1810))))))) < IKFAST_ATAN2_MAGTHRESH )
07934     continue;
07935 j10array[0]=IKatan2(((gconst7)*(((((IkReal(-1.00000000000000))*(x1809)*(x1817)))+(((sj11)*(x1810)*(x1812)))+(((IkReal(-1.00000000000000))*(x1809)*(x1810)*(x1813)))+(((cj11)*(sj13)*(x1812)))+(((IkReal(-1.00000000000000))*(x1815)*(x1816)))+(((x1811)*(x1814)))))), ((gconst7)*(((((IkReal(-1.00000000000000))*(x1810)*(x1812)*(x1815)))+(((IkReal(-1.00000000000000))*(x1813)*(x1816)))+(((IkReal(-1.00000000000000))*(x1809)*(x1811)))+(((IkReal(-1.00000000000000))*(x1814)*(x1817)))+(((x1811)*(x1812)))+(((cj11)*(x1809)*(x1810)))))));
07936 sj10array[0]=IKsin(j10array[0]);
07937 cj10array[0]=IKcos(j10array[0]);
07938 if( j10array[0] > IKPI )
07939 {
07940     j10array[0]-=IK2PI;
07941 }
07942 else if( j10array[0] < -IKPI )
07943 {    j10array[0]+=IK2PI;
07944 }
07945 j10valid[0] = true;
07946 for(int ij10 = 0; ij10 < 1; ++ij10)
07947 {
07948 if( !j10valid[ij10] )
07949 {
07950     continue;
07951 }
07952 _ij10[0] = ij10; _ij10[1] = -1;
07953 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
07954 {
07955 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
07956 {
07957     j10valid[iij10]=false; _ij10[1] = iij10; break; 
07958 }
07959 }
07960 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
07961 {
07962 IkReal evalcond[6];
07963 IkReal x1818=IKsin(j10);
07964 IkReal x1819=IKcos(j10);
07965 IkReal x1820=((IkReal(1.00000000000000))*(cj13));
07966 IkReal x1821=((cj9)*(r02));
07967 IkReal x1822=((IkReal(1.00000000000000))*(sj13));
07968 IkReal x1823=((r11)*(sj9));
07969 IkReal x1824=((IkReal(1.00000000000000))*(cj14));
07970 IkReal x1825=((cj9)*(r01));
07971 IkReal x1826=((r21)*(sj14));
07972 IkReal x1827=((IkReal(1.00000000000000))*(sj12));
07973 IkReal x1828=((r10)*(sj9));
07974 IkReal x1829=((cj14)*(sj13));
07975 IkReal x1830=((cj14)*(r20));
07976 IkReal x1831=((IkReal(1.00000000000000))*(sj14));
07977 IkReal x1832=((r12)*(sj9));
07978 IkReal x1833=((cj13)*(cj14));
07979 IkReal x1834=((cj9)*(r00));
07980 IkReal x1835=((sj11)*(x1818));
07981 IkReal x1836=((cj11)*(x1818));
07982 IkReal x1837=((sj11)*(x1819));
07983 IkReal x1838=((cj11)*(x1819));
07984 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x1827)*(x1836)))+(((IkReal(-1.00000000000000))*(x1827)*(x1837))));
07985 evalcond[1]=((((IkReal(-1.00000000000000))*(x1838)))+(((cj13)*(x1826)))+(((IkReal(-1.00000000000000))*(r22)*(x1822)))+(x1835)+(((IkReal(-1.00000000000000))*(x1820)*(x1830))));
07986 evalcond[2]=((((sj13)*(x1826)))+(((cj12)*(x1836)))+(((cj12)*(x1837)))+(((IkReal(-1.00000000000000))*(x1822)*(x1830)))+(((cj13)*(r22))));
07987 evalcond[3]=((((IkReal(-1.00000000000000))*(x1828)*(x1831)))+(((IkReal(-1.00000000000000))*(x1827)*(x1838)))+(((IkReal(-1.00000000000000))*(x1823)*(x1824)))+(((IkReal(-1.00000000000000))*(x1831)*(x1834)))+(((IkReal(-1.00000000000000))*(x1824)*(x1825)))+(((sj12)*(x1835))));
07988 evalcond[4]=((((sj13)*(x1821)))+(x1836)+(x1837)+(((IkReal(-1.00000000000000))*(sj14)*(x1820)*(x1823)))+(((IkReal(-1.00000000000000))*(sj14)*(x1820)*(x1825)))+(((x1833)*(x1834)))+(((x1828)*(x1833)))+(((sj13)*(x1832))));
07989 evalcond[5]=((((x1829)*(x1834)))+(((IkReal(-1.00000000000000))*(sj14)*(x1822)*(x1825)))+(((IkReal(-1.00000000000000))*(sj14)*(x1822)*(x1823)))+(((cj12)*(x1838)))+(((IkReal(-1.00000000000000))*(cj12)*(x1835)))+(((x1828)*(x1829)))+(((IkReal(-1.00000000000000))*(x1820)*(x1832)))+(((IkReal(-1.00000000000000))*(x1820)*(x1821))));
07990 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  )
07991 {
07992 continue;
07993 }
07994 }
07995 
07996 {
07997 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
07998 vinfos[0].jointtype = 1;
07999 vinfos[0].foffset = j9;
08000 vinfos[0].indices[0] = _ij9[0];
08001 vinfos[0].indices[1] = _ij9[1];
08002 vinfos[0].maxsolutions = _nj9;
08003 vinfos[1].jointtype = 1;
08004 vinfos[1].foffset = j10;
08005 vinfos[1].indices[0] = _ij10[0];
08006 vinfos[1].indices[1] = _ij10[1];
08007 vinfos[1].maxsolutions = _nj10;
08008 vinfos[2].jointtype = 1;
08009 vinfos[2].foffset = j11;
08010 vinfos[2].indices[0] = _ij11[0];
08011 vinfos[2].indices[1] = _ij11[1];
08012 vinfos[2].maxsolutions = _nj11;
08013 vinfos[3].jointtype = 1;
08014 vinfos[3].foffset = j12;
08015 vinfos[3].indices[0] = _ij12[0];
08016 vinfos[3].indices[1] = _ij12[1];
08017 vinfos[3].maxsolutions = _nj12;
08018 vinfos[4].jointtype = 1;
08019 vinfos[4].foffset = j13;
08020 vinfos[4].indices[0] = _ij13[0];
08021 vinfos[4].indices[1] = _ij13[1];
08022 vinfos[4].maxsolutions = _nj13;
08023 vinfos[5].jointtype = 1;
08024 vinfos[5].foffset = j14;
08025 vinfos[5].indices[0] = _ij14[0];
08026 vinfos[5].indices[1] = _ij14[1];
08027 vinfos[5].maxsolutions = _nj14;
08028 std::vector<int> vfree(0);
08029 solutions.AddSolution(vinfos,vfree);
08030 }
08031 }
08032 }
08033 
08034 }
08035 
08036 }
08037 
08038 } else
08039 {
08040 {
08041 IkReal j10array[1], cj10array[1], sj10array[1];
08042 bool j10valid[1]={false};
08043 _nj10 = 1;
08044 IkReal x1839=((cj11)*(sj12));
08045 IkReal x1840=((r22)*(sj13));
08046 IkReal x1841=((r20)*(sj14));
08047 IkReal x1842=((cj14)*(sj11));
08048 IkReal x1843=((cj13)*(r20));
08049 IkReal x1844=((sj11)*(sj12));
08050 IkReal x1845=((cj13)*(r21)*(sj14));
08051 if( IKabs(((gconst6)*(((((cj11)*(cj14)*(r21)))+(((sj12)*(x1842)*(x1843)))+(((x1840)*(x1844)))+(((IkReal(-1.00000000000000))*(x1844)*(x1845)))+(((cj11)*(x1841))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((((sj11)*(x1841)))+(((IkReal(-1.00000000000000))*(x1839)*(x1840)))+(((x1839)*(x1845)))+(((r21)*(x1842)))+(((IkReal(-1.00000000000000))*(cj14)*(x1839)*(x1843))))))) < IKFAST_ATAN2_MAGTHRESH )
08052     continue;
08053 j10array[0]=IKatan2(((gconst6)*(((((cj11)*(cj14)*(r21)))+(((sj12)*(x1842)*(x1843)))+(((x1840)*(x1844)))+(((IkReal(-1.00000000000000))*(x1844)*(x1845)))+(((cj11)*(x1841)))))), ((gconst6)*(((((sj11)*(x1841)))+(((IkReal(-1.00000000000000))*(x1839)*(x1840)))+(((x1839)*(x1845)))+(((r21)*(x1842)))+(((IkReal(-1.00000000000000))*(cj14)*(x1839)*(x1843)))))));
08054 sj10array[0]=IKsin(j10array[0]);
08055 cj10array[0]=IKcos(j10array[0]);
08056 if( j10array[0] > IKPI )
08057 {
08058     j10array[0]-=IK2PI;
08059 }
08060 else if( j10array[0] < -IKPI )
08061 {    j10array[0]+=IK2PI;
08062 }
08063 j10valid[0] = true;
08064 for(int ij10 = 0; ij10 < 1; ++ij10)
08065 {
08066 if( !j10valid[ij10] )
08067 {
08068     continue;
08069 }
08070 _ij10[0] = ij10; _ij10[1] = -1;
08071 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
08072 {
08073 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
08074 {
08075     j10valid[iij10]=false; _ij10[1] = iij10; break; 
08076 }
08077 }
08078 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
08079 {
08080 IkReal evalcond[6];
08081 IkReal x1846=IKsin(j10);
08082 IkReal x1847=IKcos(j10);
08083 IkReal x1848=((IkReal(1.00000000000000))*(cj13));
08084 IkReal x1849=((cj9)*(r02));
08085 IkReal x1850=((IkReal(1.00000000000000))*(sj13));
08086 IkReal x1851=((r11)*(sj9));
08087 IkReal x1852=((IkReal(1.00000000000000))*(cj14));
08088 IkReal x1853=((cj9)*(r01));
08089 IkReal x1854=((r21)*(sj14));
08090 IkReal x1855=((IkReal(1.00000000000000))*(sj12));
08091 IkReal x1856=((r10)*(sj9));
08092 IkReal x1857=((cj14)*(sj13));
08093 IkReal x1858=((cj14)*(r20));
08094 IkReal x1859=((IkReal(1.00000000000000))*(sj14));
08095 IkReal x1860=((r12)*(sj9));
08096 IkReal x1861=((cj13)*(cj14));
08097 IkReal x1862=((cj9)*(r00));
08098 IkReal x1863=((sj11)*(x1846));
08099 IkReal x1864=((cj11)*(x1846));
08100 IkReal x1865=((sj11)*(x1847));
08101 IkReal x1866=((cj11)*(x1847));
08102 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x1855)*(x1864)))+(((IkReal(-1.00000000000000))*(x1855)*(x1865)))+(((r20)*(sj14))));
08103 evalcond[1]=((((IkReal(-1.00000000000000))*(x1848)*(x1858)))+(((cj13)*(x1854)))+(((IkReal(-1.00000000000000))*(r22)*(x1850)))+(x1863)+(((IkReal(-1.00000000000000))*(x1866))));
08104 evalcond[2]=((((sj13)*(x1854)))+(((IkReal(-1.00000000000000))*(x1850)*(x1858)))+(((cj13)*(r22)))+(((cj12)*(x1864)))+(((cj12)*(x1865))));
08105 evalcond[3]=((((sj12)*(x1863)))+(((IkReal(-1.00000000000000))*(x1855)*(x1866)))+(((IkReal(-1.00000000000000))*(x1852)*(x1853)))+(((IkReal(-1.00000000000000))*(x1851)*(x1852)))+(((IkReal(-1.00000000000000))*(x1856)*(x1859)))+(((IkReal(-1.00000000000000))*(x1859)*(x1862))));
08106 evalcond[4]=((((sj13)*(x1860)))+(((IkReal(-1.00000000000000))*(sj14)*(x1848)*(x1853)))+(((IkReal(-1.00000000000000))*(sj14)*(x1848)*(x1851)))+(((x1856)*(x1861)))+(x1865)+(x1864)+(((sj13)*(x1849)))+(((x1861)*(x1862))));
08107 evalcond[5]=((((x1856)*(x1857)))+(((IkReal(-1.00000000000000))*(x1848)*(x1860)))+(((IkReal(-1.00000000000000))*(sj14)*(x1850)*(x1851)))+(((IkReal(-1.00000000000000))*(sj14)*(x1850)*(x1853)))+(((IkReal(-1.00000000000000))*(x1848)*(x1849)))+(((x1857)*(x1862)))+(((IkReal(-1.00000000000000))*(cj12)*(x1863)))+(((cj12)*(x1866))));
08108 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  )
08109 {
08110 continue;
08111 }
08112 }
08113 
08114 {
08115 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08116 vinfos[0].jointtype = 1;
08117 vinfos[0].foffset = j9;
08118 vinfos[0].indices[0] = _ij9[0];
08119 vinfos[0].indices[1] = _ij9[1];
08120 vinfos[0].maxsolutions = _nj9;
08121 vinfos[1].jointtype = 1;
08122 vinfos[1].foffset = j10;
08123 vinfos[1].indices[0] = _ij10[0];
08124 vinfos[1].indices[1] = _ij10[1];
08125 vinfos[1].maxsolutions = _nj10;
08126 vinfos[2].jointtype = 1;
08127 vinfos[2].foffset = j11;
08128 vinfos[2].indices[0] = _ij11[0];
08129 vinfos[2].indices[1] = _ij11[1];
08130 vinfos[2].maxsolutions = _nj11;
08131 vinfos[3].jointtype = 1;
08132 vinfos[3].foffset = j12;
08133 vinfos[3].indices[0] = _ij12[0];
08134 vinfos[3].indices[1] = _ij12[1];
08135 vinfos[3].maxsolutions = _nj12;
08136 vinfos[4].jointtype = 1;
08137 vinfos[4].foffset = j13;
08138 vinfos[4].indices[0] = _ij13[0];
08139 vinfos[4].indices[1] = _ij13[1];
08140 vinfos[4].maxsolutions = _nj13;
08141 vinfos[5].jointtype = 1;
08142 vinfos[5].foffset = j14;
08143 vinfos[5].indices[0] = _ij14[0];
08144 vinfos[5].indices[1] = _ij14[1];
08145 vinfos[5].maxsolutions = _nj14;
08146 std::vector<int> vfree(0);
08147 solutions.AddSolution(vinfos,vfree);
08148 }
08149 }
08150 }
08151 
08152 }
08153 
08154 }
08155 }
08156 }
08157 
08158 }
08159 
08160 }
08161 
08162 } else
08163 {
08164 {
08165 IkReal j10array[1], cj10array[1], sj10array[1];
08166 bool j10valid[1]={false};
08167 _nj10 = 1;
08168 IkReal x1867=((sj11)*(sj13));
08169 IkReal x1868=((cj14)*(r20));
08170 IkReal x1869=((IkReal(1.00000000000000))*(sj11));
08171 IkReal x1870=((cj12)*(r22));
08172 IkReal x1871=((r21)*(sj14));
08173 IkReal x1872=((cj12)*(cj13));
08174 IkReal x1873=((IkReal(1.00000000000000))*(cj11));
08175 IkReal x1874=((cj13)*(r22));
08176 IkReal x1875=((sj13)*(x1873));
08177 IkReal x1876=((x1871)*(x1872));
08178 if( IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(x1873)*(x1874)))+(((IkReal(-1.00000000000000))*(x1869)*(x1876)))+(((IkReal(-1.00000000000000))*(x1871)*(x1875)))+(((cj11)*(sj13)*(x1868)))+(((sj11)*(x1868)*(x1872)))+(((x1867)*(x1870))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((x1867)*(x1868)))+(((IkReal(-1.00000000000000))*(x1869)*(x1874)))+(((IkReal(-1.00000000000000))*(x1870)*(x1875)))+(((cj11)*(x1876)))+(((IkReal(-1.00000000000000))*(x1867)*(x1871)))+(((IkReal(-1.00000000000000))*(x1868)*(x1872)*(x1873))))))) < IKFAST_ATAN2_MAGTHRESH )
08179     continue;
08180 j10array[0]=IKatan2(((gconst5)*(((((IkReal(-1.00000000000000))*(x1873)*(x1874)))+(((IkReal(-1.00000000000000))*(x1869)*(x1876)))+(((IkReal(-1.00000000000000))*(x1871)*(x1875)))+(((cj11)*(sj13)*(x1868)))+(((sj11)*(x1868)*(x1872)))+(((x1867)*(x1870)))))), ((gconst5)*(((((x1867)*(x1868)))+(((IkReal(-1.00000000000000))*(x1869)*(x1874)))+(((IkReal(-1.00000000000000))*(x1870)*(x1875)))+(((cj11)*(x1876)))+(((IkReal(-1.00000000000000))*(x1867)*(x1871)))+(((IkReal(-1.00000000000000))*(x1868)*(x1872)*(x1873)))))));
08181 sj10array[0]=IKsin(j10array[0]);
08182 cj10array[0]=IKcos(j10array[0]);
08183 if( j10array[0] > IKPI )
08184 {
08185     j10array[0]-=IK2PI;
08186 }
08187 else if( j10array[0] < -IKPI )
08188 {    j10array[0]+=IK2PI;
08189 }
08190 j10valid[0] = true;
08191 for(int ij10 = 0; ij10 < 1; ++ij10)
08192 {
08193 if( !j10valid[ij10] )
08194 {
08195     continue;
08196 }
08197 _ij10[0] = ij10; _ij10[1] = -1;
08198 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
08199 {
08200 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
08201 {
08202     j10valid[iij10]=false; _ij10[1] = iij10; break; 
08203 }
08204 }
08205 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
08206 {
08207 IkReal evalcond[3];
08208 IkReal x1877=IKsin(j10);
08209 IkReal x1878=IKcos(j10);
08210 IkReal x1879=((IkReal(1.00000000000000))*(sj13));
08211 IkReal x1880=((cj14)*(r20));
08212 IkReal x1881=((r21)*(sj14));
08213 IkReal x1882=((IkReal(1.00000000000000))*(x1878));
08214 IkReal x1883=((cj11)*(x1877));
08215 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj12)*(x1883)))+(((IkReal(-1.00000000000000))*(sj11)*(sj12)*(x1882))));
08216 evalcond[1]=((((IkReal(-1.00000000000000))*(cj13)*(x1880)))+(((sj11)*(x1877)))+(((IkReal(-1.00000000000000))*(r22)*(x1879)))+(((cj13)*(x1881)))+(((IkReal(-1.00000000000000))*(cj11)*(x1882))));
08217 evalcond[2]=((((IkReal(-1.00000000000000))*(x1879)*(x1880)))+(((cj12)*(x1883)))+(((sj13)*(x1881)))+(((cj12)*(sj11)*(x1878)))+(((cj13)*(r22))));
08218 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
08219 {
08220 continue;
08221 }
08222 }
08223 
08224 {
08225 IkReal dummyeval[1];
08226 IkReal gconst16;
08227 IkReal x1884=(cj14)*(cj14);
08228 IkReal x1885=(sj14)*(sj14);
08229 IkReal x1886=((IkReal(1.00000000000000))*(r01));
08230 IkReal x1887=((sj13)*(sj14));
08231 IkReal x1888=((cj14)*(sj13));
08232 IkReal x1889=((r00)*(r11));
08233 IkReal x1890=((cj13)*(x1884));
08234 IkReal x1891=((cj13)*(x1885));
08235 gconst16=IKsign(((((IkReal(-1.00000000000000))*(r00)*(r12)*(x1887)))+(((r02)*(r10)*(x1887)))+(((x1889)*(x1891)))+(((x1889)*(x1890)))+(((r02)*(r11)*(x1888)))+(((IkReal(-1.00000000000000))*(r12)*(x1886)*(x1888)))+(((IkReal(-1.00000000000000))*(r10)*(x1886)*(x1890)))+(((IkReal(-1.00000000000000))*(r10)*(x1886)*(x1891)))));
08236 IkReal x1892=(cj14)*(cj14);
08237 IkReal x1893=(sj14)*(sj14);
08238 IkReal x1894=((IkReal(1.00000000000000))*(r01));
08239 IkReal x1895=((sj13)*(sj14));
08240 IkReal x1896=((cj14)*(sj13));
08241 IkReal x1897=((r00)*(r11));
08242 IkReal x1898=((cj13)*(x1892));
08243 IkReal x1899=((cj13)*(x1893));
08244 dummyeval[0]=((((x1897)*(x1899)))+(((x1897)*(x1898)))+(((IkReal(-1.00000000000000))*(r10)*(x1894)*(x1899)))+(((IkReal(-1.00000000000000))*(r10)*(x1894)*(x1898)))+(((IkReal(-1.00000000000000))*(r12)*(x1894)*(x1896)))+(((r02)*(r11)*(x1896)))+(((r02)*(r10)*(x1895)))+(((IkReal(-1.00000000000000))*(r00)*(r12)*(x1895))));
08245 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08246 {
08247 {
08248 IkReal dummyeval[1];
08249 IkReal gconst17;
08250 IkReal x1900=(sj14)*(sj14);
08251 IkReal x1901=(cj14)*(cj14);
08252 IkReal x1902=((cj13)*(r12));
08253 IkReal x1903=((IkReal(1.00000000000000))*(r10));
08254 IkReal x1904=((cj13)*(r02));
08255 IkReal x1905=((r01)*(sj13));
08256 IkReal x1906=((r00)*(r11)*(sj13));
08257 gconst17=IKsign(((((x1901)*(x1906)))+(((IkReal(-1.00000000000000))*(sj14)*(x1903)*(x1904)))+(((IkReal(-1.00000000000000))*(x1901)*(x1903)*(x1905)))+(((r00)*(sj14)*(x1902)))+(((IkReal(-1.00000000000000))*(x1900)*(x1903)*(x1905)))+(((x1900)*(x1906)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1904)))+(((cj14)*(r01)*(x1902)))));
08258 IkReal x1907=(sj14)*(sj14);
08259 IkReal x1908=(cj14)*(cj14);
08260 IkReal x1909=((cj13)*(r12));
08261 IkReal x1910=((IkReal(1.00000000000000))*(r10));
08262 IkReal x1911=((cj13)*(r02));
08263 IkReal x1912=((r01)*(sj13));
08264 IkReal x1913=((r00)*(r11)*(sj13));
08265 dummyeval[0]=((((x1907)*(x1913)))+(((IkReal(-1.00000000000000))*(x1907)*(x1910)*(x1912)))+(((r00)*(sj14)*(x1909)))+(((IkReal(-1.00000000000000))*(x1908)*(x1910)*(x1912)))+(((x1908)*(x1913)))+(((IkReal(-1.00000000000000))*(sj14)*(x1910)*(x1911)))+(((cj14)*(r01)*(x1909)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1911))));
08266 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08267 {
08268 continue;
08269 
08270 } else
08271 {
08272 {
08273 IkReal j9array[1], cj9array[1], sj9array[1];
08274 bool j9valid[1]={false};
08275 _nj9 = 1;
08276 IkReal x1914=((sj12)*(sj14));
08277 IkReal x1915=((cj14)*(sj12));
08278 IkReal x1916=((cj12)*(cj14)*(sj13));
08279 IkReal x1917=((IkReal(1.00000000000000))*(cj12)*(cj13));
08280 IkReal x1918=((IkReal(1.00000000000000))*(cj12)*(sj13)*(sj14));
08281 if( IKabs(((gconst17)*(((((r10)*(x1914)))+(((r10)*(x1916)))+(((IkReal(-1.00000000000000))*(r12)*(x1917)))+(((IkReal(-1.00000000000000))*(r11)*(x1918)))+(((r11)*(x1915))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((IkReal(-1.00000000000000))*(r01)*(x1918)))+(((IkReal(-1.00000000000000))*(r02)*(x1917)))+(((r00)*(x1916)))+(((r00)*(x1914)))+(((r01)*(x1915))))))) < IKFAST_ATAN2_MAGTHRESH )
08282     continue;
08283 j9array[0]=IKatan2(((gconst17)*(((((r10)*(x1914)))+(((r10)*(x1916)))+(((IkReal(-1.00000000000000))*(r12)*(x1917)))+(((IkReal(-1.00000000000000))*(r11)*(x1918)))+(((r11)*(x1915)))))), ((gconst17)*(((((IkReal(-1.00000000000000))*(r01)*(x1918)))+(((IkReal(-1.00000000000000))*(r02)*(x1917)))+(((r00)*(x1916)))+(((r00)*(x1914)))+(((r01)*(x1915)))))));
08284 sj9array[0]=IKsin(j9array[0]);
08285 cj9array[0]=IKcos(j9array[0]);
08286 if( j9array[0] > IKPI )
08287 {
08288     j9array[0]-=IK2PI;
08289 }
08290 else if( j9array[0] < -IKPI )
08291 {    j9array[0]+=IK2PI;
08292 }
08293 j9valid[0] = true;
08294 for(int ij9 = 0; ij9 < 1; ++ij9)
08295 {
08296 if( !j9valid[ij9] )
08297 {
08298     continue;
08299 }
08300 _ij9[0] = ij9; _ij9[1] = -1;
08301 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
08302 {
08303 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
08304 {
08305     j9valid[iij9]=false; _ij9[1] = iij9; break; 
08306 }
08307 }
08308 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
08309 {
08310 IkReal evalcond[6];
08311 IkReal x1919=IKsin(j9);
08312 IkReal x1920=IKcos(j9);
08313 IkReal x1921=((cj10)*(cj11));
08314 IkReal x1922=((IkReal(1.00000000000000))*(cj14));
08315 IkReal x1923=((IkReal(1.00000000000000))*(sj14));
08316 IkReal x1924=((cj13)*(cj14));
08317 IkReal x1925=((cj14)*(r10));
08318 IkReal x1926=((r01)*(sj14));
08319 IkReal x1927=((sj10)*(sj11));
08320 IkReal x1928=((IkReal(1.00000000000000))*(r12));
08321 IkReal x1929=((sj13)*(x1920));
08322 IkReal x1930=((r02)*(x1919));
08323 IkReal x1931=((r11)*(x1919));
08324 IkReal x1932=((r10)*(x1920));
08325 IkReal x1933=((r01)*(x1920));
08326 IkReal x1934=((sj13)*(x1919));
08327 IkReal x1935=((r11)*(x1920));
08328 IkReal x1936=((cj13)*(x1919));
08329 IkReal x1937=((r10)*(x1919));
08330 IkReal x1938=((r00)*(x1920));
08331 IkReal x1939=((cj13)*(x1920));
08332 evalcond[0]=((((r00)*(sj14)*(x1919)))+(((IkReal(-1.00000000000000))*(x1923)*(x1932)))+(cj12)+(((cj14)*(r01)*(x1919)))+(((IkReal(-1.00000000000000))*(x1922)*(x1935))));
08333 evalcond[1]=((((IkReal(-1.00000000000000))*(sj12)*(x1921)))+(((IkReal(-1.00000000000000))*(x1923)*(x1938)))+(((IkReal(-1.00000000000000))*(x1923)*(x1937)))+(((IkReal(-1.00000000000000))*(x1922)*(x1931)))+(((IkReal(-1.00000000000000))*(x1922)*(x1933)))+(((sj12)*(x1927))));
08334 evalcond[2]=((((IkReal(-1.00000000000000))*(sj13)*(x1930)))+(((IkReal(-1.00000000000000))*(r00)*(x1922)*(x1936)))+(((x1924)*(x1932)))+(((x1926)*(x1936)))+(((IkReal(-1.00000000000000))*(cj13)*(x1923)*(x1935)))+(((r12)*(x1929))));
08335 evalcond[3]=((((IkReal(-1.00000000000000))*(x1928)*(x1939)))+(((IkReal(-1.00000000000000))*(r00)*(x1922)*(x1934)))+(((cj13)*(x1930)))+(((IkReal(-1.00000000000000))*(r11)*(x1923)*(x1929)))+(((x1926)*(x1934)))+(sj12)+(((x1925)*(x1929))));
08336 evalcond[4]=((((cj10)*(sj11)))+(((x1924)*(x1938)))+(((x1924)*(x1937)))+(((r12)*(x1934)))+(((r02)*(x1929)))+(((IkReal(-1.00000000000000))*(cj13)*(x1923)*(x1933)))+(((IkReal(-1.00000000000000))*(cj13)*(x1923)*(x1931)))+(((cj11)*(sj10))));
08337 evalcond[5]=((((IkReal(-1.00000000000000))*(x1928)*(x1936)))+(((IkReal(-1.00000000000000))*(sj13)*(x1923)*(x1931)))+(((IkReal(-1.00000000000000))*(r01)*(x1923)*(x1929)))+(((x1925)*(x1934)))+(((cj12)*(x1921)))+(((IkReal(-1.00000000000000))*(cj12)*(x1927)))+(((cj14)*(r00)*(x1929)))+(((IkReal(-1.00000000000000))*(r02)*(x1939))));
08338 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  )
08339 {
08340 continue;
08341 }
08342 }
08343 
08344 {
08345 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08346 vinfos[0].jointtype = 1;
08347 vinfos[0].foffset = j9;
08348 vinfos[0].indices[0] = _ij9[0];
08349 vinfos[0].indices[1] = _ij9[1];
08350 vinfos[0].maxsolutions = _nj9;
08351 vinfos[1].jointtype = 1;
08352 vinfos[1].foffset = j10;
08353 vinfos[1].indices[0] = _ij10[0];
08354 vinfos[1].indices[1] = _ij10[1];
08355 vinfos[1].maxsolutions = _nj10;
08356 vinfos[2].jointtype = 1;
08357 vinfos[2].foffset = j11;
08358 vinfos[2].indices[0] = _ij11[0];
08359 vinfos[2].indices[1] = _ij11[1];
08360 vinfos[2].maxsolutions = _nj11;
08361 vinfos[3].jointtype = 1;
08362 vinfos[3].foffset = j12;
08363 vinfos[3].indices[0] = _ij12[0];
08364 vinfos[3].indices[1] = _ij12[1];
08365 vinfos[3].maxsolutions = _nj12;
08366 vinfos[4].jointtype = 1;
08367 vinfos[4].foffset = j13;
08368 vinfos[4].indices[0] = _ij13[0];
08369 vinfos[4].indices[1] = _ij13[1];
08370 vinfos[4].maxsolutions = _nj13;
08371 vinfos[5].jointtype = 1;
08372 vinfos[5].foffset = j14;
08373 vinfos[5].indices[0] = _ij14[0];
08374 vinfos[5].indices[1] = _ij14[1];
08375 vinfos[5].maxsolutions = _nj14;
08376 std::vector<int> vfree(0);
08377 solutions.AddSolution(vinfos,vfree);
08378 }
08379 }
08380 }
08381 
08382 }
08383 
08384 }
08385 
08386 } else
08387 {
08388 {
08389 IkReal j9array[1], cj9array[1], sj9array[1];
08390 bool j9valid[1]={false};
08391 _nj9 = 1;
08392 IkReal x1940=((cj12)*(sj13));
08393 IkReal x1941=((cj12)*(cj13));
08394 IkReal x1942=((IkReal(1.00000000000000))*(sj14));
08395 if( IKabs(((gconst16)*(((((r12)*(x1940)))+(((cj14)*(r10)*(x1941)))+(((IkReal(-1.00000000000000))*(r11)*(x1941)*(x1942))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(r01)*(x1941)*(x1942)))+(((cj14)*(r00)*(x1941)))+(((r02)*(x1940))))))) < IKFAST_ATAN2_MAGTHRESH )
08396     continue;
08397 j9array[0]=IKatan2(((gconst16)*(((((r12)*(x1940)))+(((cj14)*(r10)*(x1941)))+(((IkReal(-1.00000000000000))*(r11)*(x1941)*(x1942)))))), ((gconst16)*(((((IkReal(-1.00000000000000))*(r01)*(x1941)*(x1942)))+(((cj14)*(r00)*(x1941)))+(((r02)*(x1940)))))));
08398 sj9array[0]=IKsin(j9array[0]);
08399 cj9array[0]=IKcos(j9array[0]);
08400 if( j9array[0] > IKPI )
08401 {
08402     j9array[0]-=IK2PI;
08403 }
08404 else if( j9array[0] < -IKPI )
08405 {    j9array[0]+=IK2PI;
08406 }
08407 j9valid[0] = true;
08408 for(int ij9 = 0; ij9 < 1; ++ij9)
08409 {
08410 if( !j9valid[ij9] )
08411 {
08412     continue;
08413 }
08414 _ij9[0] = ij9; _ij9[1] = -1;
08415 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
08416 {
08417 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
08418 {
08419     j9valid[iij9]=false; _ij9[1] = iij9; break; 
08420 }
08421 }
08422 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
08423 {
08424 IkReal evalcond[6];
08425 IkReal x1943=IKsin(j9);
08426 IkReal x1944=IKcos(j9);
08427 IkReal x1945=((cj10)*(cj11));
08428 IkReal x1946=((IkReal(1.00000000000000))*(cj14));
08429 IkReal x1947=((IkReal(1.00000000000000))*(sj14));
08430 IkReal x1948=((cj13)*(cj14));
08431 IkReal x1949=((cj14)*(r10));
08432 IkReal x1950=((r01)*(sj14));
08433 IkReal x1951=((sj10)*(sj11));
08434 IkReal x1952=((IkReal(1.00000000000000))*(r12));
08435 IkReal x1953=((sj13)*(x1944));
08436 IkReal x1954=((r02)*(x1943));
08437 IkReal x1955=((r11)*(x1943));
08438 IkReal x1956=((r10)*(x1944));
08439 IkReal x1957=((r01)*(x1944));
08440 IkReal x1958=((sj13)*(x1943));
08441 IkReal x1959=((r11)*(x1944));
08442 IkReal x1960=((cj13)*(x1943));
08443 IkReal x1961=((r10)*(x1943));
08444 IkReal x1962=((r00)*(x1944));
08445 IkReal x1963=((cj13)*(x1944));
08446 evalcond[0]=((((cj14)*(r01)*(x1943)))+(((IkReal(-1.00000000000000))*(x1947)*(x1956)))+(cj12)+(((IkReal(-1.00000000000000))*(x1946)*(x1959)))+(((r00)*(sj14)*(x1943))));
08447 evalcond[1]=((((sj12)*(x1951)))+(((IkReal(-1.00000000000000))*(x1947)*(x1962)))+(((IkReal(-1.00000000000000))*(x1947)*(x1961)))+(((IkReal(-1.00000000000000))*(x1946)*(x1957)))+(((IkReal(-1.00000000000000))*(x1946)*(x1955)))+(((IkReal(-1.00000000000000))*(sj12)*(x1945))));
08448 evalcond[2]=((((r12)*(x1953)))+(((IkReal(-1.00000000000000))*(cj13)*(x1947)*(x1959)))+(((x1950)*(x1960)))+(((x1948)*(x1956)))+(((IkReal(-1.00000000000000))*(sj13)*(x1954)))+(((IkReal(-1.00000000000000))*(r00)*(x1946)*(x1960))));
08449 evalcond[3]=((((IkReal(-1.00000000000000))*(x1952)*(x1963)))+(((IkReal(-1.00000000000000))*(r11)*(x1947)*(x1953)))+(((IkReal(-1.00000000000000))*(r00)*(x1946)*(x1958)))+(((cj13)*(x1954)))+(((x1950)*(x1958)))+(sj12)+(((x1949)*(x1953))));
08450 evalcond[4]=((((r12)*(x1958)))+(((IkReal(-1.00000000000000))*(cj13)*(x1947)*(x1955)))+(((IkReal(-1.00000000000000))*(cj13)*(x1947)*(x1957)))+(((cj10)*(sj11)))+(((r02)*(x1953)))+(((cj11)*(sj10)))+(((x1948)*(x1961)))+(((x1948)*(x1962))));
08451 evalcond[5]=((((IkReal(-1.00000000000000))*(x1952)*(x1960)))+(((IkReal(-1.00000000000000))*(r01)*(x1947)*(x1953)))+(((cj12)*(x1945)))+(((IkReal(-1.00000000000000))*(sj13)*(x1947)*(x1955)))+(((IkReal(-1.00000000000000))*(cj12)*(x1951)))+(((cj14)*(r00)*(x1953)))+(((IkReal(-1.00000000000000))*(r02)*(x1963)))+(((x1949)*(x1958))));
08452 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  )
08453 {
08454 continue;
08455 }
08456 }
08457 
08458 {
08459 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08460 vinfos[0].jointtype = 1;
08461 vinfos[0].foffset = j9;
08462 vinfos[0].indices[0] = _ij9[0];
08463 vinfos[0].indices[1] = _ij9[1];
08464 vinfos[0].maxsolutions = _nj9;
08465 vinfos[1].jointtype = 1;
08466 vinfos[1].foffset = j10;
08467 vinfos[1].indices[0] = _ij10[0];
08468 vinfos[1].indices[1] = _ij10[1];
08469 vinfos[1].maxsolutions = _nj10;
08470 vinfos[2].jointtype = 1;
08471 vinfos[2].foffset = j11;
08472 vinfos[2].indices[0] = _ij11[0];
08473 vinfos[2].indices[1] = _ij11[1];
08474 vinfos[2].maxsolutions = _nj11;
08475 vinfos[3].jointtype = 1;
08476 vinfos[3].foffset = j12;
08477 vinfos[3].indices[0] = _ij12[0];
08478 vinfos[3].indices[1] = _ij12[1];
08479 vinfos[3].maxsolutions = _nj12;
08480 vinfos[4].jointtype = 1;
08481 vinfos[4].foffset = j13;
08482 vinfos[4].indices[0] = _ij13[0];
08483 vinfos[4].indices[1] = _ij13[1];
08484 vinfos[4].maxsolutions = _nj13;
08485 vinfos[5].jointtype = 1;
08486 vinfos[5].foffset = j14;
08487 vinfos[5].indices[0] = _ij14[0];
08488 vinfos[5].indices[1] = _ij14[1];
08489 vinfos[5].maxsolutions = _nj14;
08490 std::vector<int> vfree(0);
08491 solutions.AddSolution(vinfos,vfree);
08492 }
08493 }
08494 }
08495 
08496 }
08497 
08498 }
08499 }
08500 }
08501 
08502 }
08503 
08504 }
08505 
08506 } else
08507 {
08508 {
08509 IkReal j10array[1], cj10array[1], sj10array[1];
08510 bool j10valid[1]={false};
08511 _nj10 = 1;
08512 IkReal x1964=((cj11)*(sj12));
08513 IkReal x1965=((r22)*(sj13));
08514 IkReal x1966=((r20)*(sj14));
08515 IkReal x1967=((cj14)*(sj11));
08516 IkReal x1968=((cj13)*(r20));
08517 IkReal x1969=((sj11)*(sj12));
08518 IkReal x1970=((cj13)*(r21)*(sj14));
08519 if( IKabs(((gconst4)*(((((cj11)*(cj14)*(r21)))+(((sj12)*(x1967)*(x1968)))+(((IkReal(-1.00000000000000))*(x1969)*(x1970)))+(((cj11)*(x1966)))+(((x1965)*(x1969))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((x1964)*(x1970)))+(((IkReal(-1.00000000000000))*(x1964)*(x1965)))+(((r21)*(x1967)))+(((sj11)*(x1966)))+(((IkReal(-1.00000000000000))*(cj14)*(x1964)*(x1968))))))) < IKFAST_ATAN2_MAGTHRESH )
08520     continue;
08521 j10array[0]=IKatan2(((gconst4)*(((((cj11)*(cj14)*(r21)))+(((sj12)*(x1967)*(x1968)))+(((IkReal(-1.00000000000000))*(x1969)*(x1970)))+(((cj11)*(x1966)))+(((x1965)*(x1969)))))), ((gconst4)*(((((x1964)*(x1970)))+(((IkReal(-1.00000000000000))*(x1964)*(x1965)))+(((r21)*(x1967)))+(((sj11)*(x1966)))+(((IkReal(-1.00000000000000))*(cj14)*(x1964)*(x1968)))))));
08522 sj10array[0]=IKsin(j10array[0]);
08523 cj10array[0]=IKcos(j10array[0]);
08524 if( j10array[0] > IKPI )
08525 {
08526     j10array[0]-=IK2PI;
08527 }
08528 else if( j10array[0] < -IKPI )
08529 {    j10array[0]+=IK2PI;
08530 }
08531 j10valid[0] = true;
08532 for(int ij10 = 0; ij10 < 1; ++ij10)
08533 {
08534 if( !j10valid[ij10] )
08535 {
08536     continue;
08537 }
08538 _ij10[0] = ij10; _ij10[1] = -1;
08539 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
08540 {
08541 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
08542 {
08543     j10valid[iij10]=false; _ij10[1] = iij10; break; 
08544 }
08545 }
08546 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
08547 {
08548 IkReal evalcond[3];
08549 IkReal x1971=IKsin(j10);
08550 IkReal x1972=IKcos(j10);
08551 IkReal x1973=((IkReal(1.00000000000000))*(sj13));
08552 IkReal x1974=((cj14)*(r20));
08553 IkReal x1975=((r21)*(sj14));
08554 IkReal x1976=((IkReal(1.00000000000000))*(x1972));
08555 IkReal x1977=((cj11)*(x1971));
08556 evalcond[0]=((((IkReal(-1.00000000000000))*(sj11)*(sj12)*(x1976)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj12)*(x1977))));
08557 evalcond[1]=((((cj13)*(x1975)))+(((IkReal(-1.00000000000000))*(cj11)*(x1976)))+(((IkReal(-1.00000000000000))*(r22)*(x1973)))+(((IkReal(-1.00000000000000))*(cj13)*(x1974)))+(((sj11)*(x1971))));
08558 evalcond[2]=((((cj12)*(sj11)*(x1972)))+(((cj12)*(x1977)))+(((IkReal(-1.00000000000000))*(x1973)*(x1974)))+(((sj13)*(x1975)))+(((cj13)*(r22))));
08559 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
08560 {
08561 continue;
08562 }
08563 }
08564 
08565 {
08566 IkReal dummyeval[1];
08567 IkReal gconst16;
08568 IkReal x1978=(cj14)*(cj14);
08569 IkReal x1979=(sj14)*(sj14);
08570 IkReal x1980=((IkReal(1.00000000000000))*(r01));
08571 IkReal x1981=((sj13)*(sj14));
08572 IkReal x1982=((cj14)*(sj13));
08573 IkReal x1983=((r00)*(r11));
08574 IkReal x1984=((cj13)*(x1978));
08575 IkReal x1985=((cj13)*(x1979));
08576 gconst16=IKsign(((((IkReal(-1.00000000000000))*(r00)*(r12)*(x1981)))+(((IkReal(-1.00000000000000))*(r10)*(x1980)*(x1985)))+(((IkReal(-1.00000000000000))*(r10)*(x1980)*(x1984)))+(((r02)*(r11)*(x1982)))+(((x1983)*(x1984)))+(((x1983)*(x1985)))+(((IkReal(-1.00000000000000))*(r12)*(x1980)*(x1982)))+(((r02)*(r10)*(x1981)))));
08577 IkReal x1986=(cj14)*(cj14);
08578 IkReal x1987=(sj14)*(sj14);
08579 IkReal x1988=((IkReal(1.00000000000000))*(r01));
08580 IkReal x1989=((sj13)*(sj14));
08581 IkReal x1990=((cj14)*(sj13));
08582 IkReal x1991=((r00)*(r11));
08583 IkReal x1992=((cj13)*(x1986));
08584 IkReal x1993=((cj13)*(x1987));
08585 dummyeval[0]=((((IkReal(-1.00000000000000))*(r00)*(r12)*(x1989)))+(((x1991)*(x1993)))+(((x1991)*(x1992)))+(((IkReal(-1.00000000000000))*(r12)*(x1988)*(x1990)))+(((IkReal(-1.00000000000000))*(r10)*(x1988)*(x1992)))+(((IkReal(-1.00000000000000))*(r10)*(x1988)*(x1993)))+(((r02)*(r11)*(x1990)))+(((r02)*(r10)*(x1989))));
08586 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08587 {
08588 {
08589 IkReal dummyeval[1];
08590 IkReal gconst17;
08591 IkReal x1994=(sj14)*(sj14);
08592 IkReal x1995=(cj14)*(cj14);
08593 IkReal x1996=((cj13)*(r12));
08594 IkReal x1997=((IkReal(1.00000000000000))*(r10));
08595 IkReal x1998=((cj13)*(r02));
08596 IkReal x1999=((r01)*(sj13));
08597 IkReal x2000=((r00)*(r11)*(sj13));
08598 gconst17=IKsign(((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x1998)))+(((cj14)*(r01)*(x1996)))+(((IkReal(-1.00000000000000))*(x1995)*(x1997)*(x1999)))+(((x1994)*(x2000)))+(((x1995)*(x2000)))+(((IkReal(-1.00000000000000))*(sj14)*(x1997)*(x1998)))+(((r00)*(sj14)*(x1996)))+(((IkReal(-1.00000000000000))*(x1994)*(x1997)*(x1999)))));
08599 IkReal x2001=(sj14)*(sj14);
08600 IkReal x2002=(cj14)*(cj14);
08601 IkReal x2003=((cj13)*(r12));
08602 IkReal x2004=((IkReal(1.00000000000000))*(r10));
08603 IkReal x2005=((cj13)*(r02));
08604 IkReal x2006=((r01)*(sj13));
08605 IkReal x2007=((r00)*(r11)*(sj13));
08606 dummyeval[0]=((((x2002)*(x2007)))+(((IkReal(-1.00000000000000))*(x2002)*(x2004)*(x2006)))+(((cj14)*(r01)*(x2003)))+(((IkReal(-1.00000000000000))*(x2001)*(x2004)*(x2006)))+(((IkReal(-1.00000000000000))*(sj14)*(x2004)*(x2005)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2005)))+(((r00)*(sj14)*(x2003)))+(((x2001)*(x2007))));
08607 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08608 {
08609 continue;
08610 
08611 } else
08612 {
08613 {
08614 IkReal j9array[1], cj9array[1], sj9array[1];
08615 bool j9valid[1]={false};
08616 _nj9 = 1;
08617 IkReal x2008=((sj12)*(sj14));
08618 IkReal x2009=((cj14)*(sj12));
08619 IkReal x2010=((cj12)*(cj14)*(sj13));
08620 IkReal x2011=((IkReal(1.00000000000000))*(cj12)*(cj13));
08621 IkReal x2012=((IkReal(1.00000000000000))*(cj12)*(sj13)*(sj14));
08622 if( IKabs(((gconst17)*(((((r11)*(x2009)))+(((r10)*(x2008)))+(((r10)*(x2010)))+(((IkReal(-1.00000000000000))*(r12)*(x2011)))+(((IkReal(-1.00000000000000))*(r11)*(x2012))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst17)*(((((r01)*(x2009)))+(((r00)*(x2008)))+(((r00)*(x2010)))+(((IkReal(-1.00000000000000))*(r02)*(x2011)))+(((IkReal(-1.00000000000000))*(r01)*(x2012))))))) < IKFAST_ATAN2_MAGTHRESH )
08623     continue;
08624 j9array[0]=IKatan2(((gconst17)*(((((r11)*(x2009)))+(((r10)*(x2008)))+(((r10)*(x2010)))+(((IkReal(-1.00000000000000))*(r12)*(x2011)))+(((IkReal(-1.00000000000000))*(r11)*(x2012)))))), ((gconst17)*(((((r01)*(x2009)))+(((r00)*(x2008)))+(((r00)*(x2010)))+(((IkReal(-1.00000000000000))*(r02)*(x2011)))+(((IkReal(-1.00000000000000))*(r01)*(x2012)))))));
08625 sj9array[0]=IKsin(j9array[0]);
08626 cj9array[0]=IKcos(j9array[0]);
08627 if( j9array[0] > IKPI )
08628 {
08629     j9array[0]-=IK2PI;
08630 }
08631 else if( j9array[0] < -IKPI )
08632 {    j9array[0]+=IK2PI;
08633 }
08634 j9valid[0] = true;
08635 for(int ij9 = 0; ij9 < 1; ++ij9)
08636 {
08637 if( !j9valid[ij9] )
08638 {
08639     continue;
08640 }
08641 _ij9[0] = ij9; _ij9[1] = -1;
08642 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
08643 {
08644 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
08645 {
08646     j9valid[iij9]=false; _ij9[1] = iij9; break; 
08647 }
08648 }
08649 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
08650 {
08651 IkReal evalcond[6];
08652 IkReal x2013=IKsin(j9);
08653 IkReal x2014=IKcos(j9);
08654 IkReal x2015=((cj10)*(cj11));
08655 IkReal x2016=((IkReal(1.00000000000000))*(cj14));
08656 IkReal x2017=((IkReal(1.00000000000000))*(sj14));
08657 IkReal x2018=((cj13)*(cj14));
08658 IkReal x2019=((cj14)*(r10));
08659 IkReal x2020=((r01)*(sj14));
08660 IkReal x2021=((sj10)*(sj11));
08661 IkReal x2022=((IkReal(1.00000000000000))*(r12));
08662 IkReal x2023=((sj13)*(x2014));
08663 IkReal x2024=((r02)*(x2013));
08664 IkReal x2025=((r11)*(x2013));
08665 IkReal x2026=((r10)*(x2014));
08666 IkReal x2027=((r01)*(x2014));
08667 IkReal x2028=((sj13)*(x2013));
08668 IkReal x2029=((r11)*(x2014));
08669 IkReal x2030=((cj13)*(x2013));
08670 IkReal x2031=((r10)*(x2013));
08671 IkReal x2032=((r00)*(x2014));
08672 IkReal x2033=((cj13)*(x2014));
08673 evalcond[0]=((((r00)*(sj14)*(x2013)))+(((IkReal(-1.00000000000000))*(x2016)*(x2029)))+(((IkReal(-1.00000000000000))*(x2017)*(x2026)))+(cj12)+(((cj14)*(r01)*(x2013))));
08674 evalcond[1]=((((IkReal(-1.00000000000000))*(x2016)*(x2025)))+(((IkReal(-1.00000000000000))*(x2016)*(x2027)))+(((sj12)*(x2021)))+(((IkReal(-1.00000000000000))*(sj12)*(x2015)))+(((IkReal(-1.00000000000000))*(x2017)*(x2032)))+(((IkReal(-1.00000000000000))*(x2017)*(x2031))));
08675 evalcond[2]=((((x2018)*(x2026)))+(((IkReal(-1.00000000000000))*(r00)*(x2016)*(x2030)))+(((IkReal(-1.00000000000000))*(sj13)*(x2024)))+(((x2020)*(x2030)))+(((r12)*(x2023)))+(((IkReal(-1.00000000000000))*(cj13)*(x2017)*(x2029))));
08676 evalcond[3]=((((x2020)*(x2028)))+(((IkReal(-1.00000000000000))*(r11)*(x2017)*(x2023)))+(((cj13)*(x2024)))+(((x2019)*(x2023)))+(((IkReal(-1.00000000000000))*(x2022)*(x2033)))+(sj12)+(((IkReal(-1.00000000000000))*(r00)*(x2016)*(x2028))));
08677 evalcond[4]=((((x2018)*(x2031)))+(((x2018)*(x2032)))+(((cj10)*(sj11)))+(((r02)*(x2023)))+(((cj11)*(sj10)))+(((r12)*(x2028)))+(((IkReal(-1.00000000000000))*(cj13)*(x2017)*(x2025)))+(((IkReal(-1.00000000000000))*(cj13)*(x2017)*(x2027))));
08678 evalcond[5]=((((x2019)*(x2028)))+(((IkReal(-1.00000000000000))*(cj12)*(x2021)))+(((IkReal(-1.00000000000000))*(x2022)*(x2030)))+(((IkReal(-1.00000000000000))*(sj13)*(x2017)*(x2025)))+(((IkReal(-1.00000000000000))*(r01)*(x2017)*(x2023)))+(((cj14)*(r00)*(x2023)))+(((cj12)*(x2015)))+(((IkReal(-1.00000000000000))*(r02)*(x2033))));
08679 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  )
08680 {
08681 continue;
08682 }
08683 }
08684 
08685 {
08686 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08687 vinfos[0].jointtype = 1;
08688 vinfos[0].foffset = j9;
08689 vinfos[0].indices[0] = _ij9[0];
08690 vinfos[0].indices[1] = _ij9[1];
08691 vinfos[0].maxsolutions = _nj9;
08692 vinfos[1].jointtype = 1;
08693 vinfos[1].foffset = j10;
08694 vinfos[1].indices[0] = _ij10[0];
08695 vinfos[1].indices[1] = _ij10[1];
08696 vinfos[1].maxsolutions = _nj10;
08697 vinfos[2].jointtype = 1;
08698 vinfos[2].foffset = j11;
08699 vinfos[2].indices[0] = _ij11[0];
08700 vinfos[2].indices[1] = _ij11[1];
08701 vinfos[2].maxsolutions = _nj11;
08702 vinfos[3].jointtype = 1;
08703 vinfos[3].foffset = j12;
08704 vinfos[3].indices[0] = _ij12[0];
08705 vinfos[3].indices[1] = _ij12[1];
08706 vinfos[3].maxsolutions = _nj12;
08707 vinfos[4].jointtype = 1;
08708 vinfos[4].foffset = j13;
08709 vinfos[4].indices[0] = _ij13[0];
08710 vinfos[4].indices[1] = _ij13[1];
08711 vinfos[4].maxsolutions = _nj13;
08712 vinfos[5].jointtype = 1;
08713 vinfos[5].foffset = j14;
08714 vinfos[5].indices[0] = _ij14[0];
08715 vinfos[5].indices[1] = _ij14[1];
08716 vinfos[5].maxsolutions = _nj14;
08717 std::vector<int> vfree(0);
08718 solutions.AddSolution(vinfos,vfree);
08719 }
08720 }
08721 }
08722 
08723 }
08724 
08725 }
08726 
08727 } else
08728 {
08729 {
08730 IkReal j9array[1], cj9array[1], sj9array[1];
08731 bool j9valid[1]={false};
08732 _nj9 = 1;
08733 IkReal x2034=((cj12)*(sj13));
08734 IkReal x2035=((cj12)*(cj13));
08735 IkReal x2036=((IkReal(1.00000000000000))*(sj14));
08736 if( IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(r11)*(x2035)*(x2036)))+(((r12)*(x2034)))+(((cj14)*(r10)*(x2035))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst16)*(((((IkReal(-1.00000000000000))*(r01)*(x2035)*(x2036)))+(((r02)*(x2034)))+(((cj14)*(r00)*(x2035))))))) < IKFAST_ATAN2_MAGTHRESH )
08737     continue;
08738 j9array[0]=IKatan2(((gconst16)*(((((IkReal(-1.00000000000000))*(r11)*(x2035)*(x2036)))+(((r12)*(x2034)))+(((cj14)*(r10)*(x2035)))))), ((gconst16)*(((((IkReal(-1.00000000000000))*(r01)*(x2035)*(x2036)))+(((r02)*(x2034)))+(((cj14)*(r00)*(x2035)))))));
08739 sj9array[0]=IKsin(j9array[0]);
08740 cj9array[0]=IKcos(j9array[0]);
08741 if( j9array[0] > IKPI )
08742 {
08743     j9array[0]-=IK2PI;
08744 }
08745 else if( j9array[0] < -IKPI )
08746 {    j9array[0]+=IK2PI;
08747 }
08748 j9valid[0] = true;
08749 for(int ij9 = 0; ij9 < 1; ++ij9)
08750 {
08751 if( !j9valid[ij9] )
08752 {
08753     continue;
08754 }
08755 _ij9[0] = ij9; _ij9[1] = -1;
08756 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
08757 {
08758 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
08759 {
08760     j9valid[iij9]=false; _ij9[1] = iij9; break; 
08761 }
08762 }
08763 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
08764 {
08765 IkReal evalcond[6];
08766 IkReal x2037=IKsin(j9);
08767 IkReal x2038=IKcos(j9);
08768 IkReal x2039=((cj10)*(cj11));
08769 IkReal x2040=((IkReal(1.00000000000000))*(cj14));
08770 IkReal x2041=((IkReal(1.00000000000000))*(sj14));
08771 IkReal x2042=((cj13)*(cj14));
08772 IkReal x2043=((cj14)*(r10));
08773 IkReal x2044=((r01)*(sj14));
08774 IkReal x2045=((sj10)*(sj11));
08775 IkReal x2046=((IkReal(1.00000000000000))*(r12));
08776 IkReal x2047=((sj13)*(x2038));
08777 IkReal x2048=((r02)*(x2037));
08778 IkReal x2049=((r11)*(x2037));
08779 IkReal x2050=((r10)*(x2038));
08780 IkReal x2051=((r01)*(x2038));
08781 IkReal x2052=((sj13)*(x2037));
08782 IkReal x2053=((r11)*(x2038));
08783 IkReal x2054=((cj13)*(x2037));
08784 IkReal x2055=((r10)*(x2037));
08785 IkReal x2056=((r00)*(x2038));
08786 IkReal x2057=((cj13)*(x2038));
08787 evalcond[0]=((((cj14)*(r01)*(x2037)))+(cj12)+(((IkReal(-1.00000000000000))*(x2040)*(x2053)))+(((IkReal(-1.00000000000000))*(x2041)*(x2050)))+(((r00)*(sj14)*(x2037))));
08788 evalcond[1]=((((sj12)*(x2045)))+(((IkReal(-1.00000000000000))*(sj12)*(x2039)))+(((IkReal(-1.00000000000000))*(x2040)*(x2049)))+(((IkReal(-1.00000000000000))*(x2040)*(x2051)))+(((IkReal(-1.00000000000000))*(x2041)*(x2055)))+(((IkReal(-1.00000000000000))*(x2041)*(x2056))));
08789 evalcond[2]=((((IkReal(-1.00000000000000))*(sj13)*(x2048)))+(((x2042)*(x2050)))+(((r12)*(x2047)))+(((IkReal(-1.00000000000000))*(r00)*(x2040)*(x2054)))+(((x2044)*(x2054)))+(((IkReal(-1.00000000000000))*(cj13)*(x2041)*(x2053))));
08790 evalcond[3]=((((x2043)*(x2047)))+(((cj13)*(x2048)))+(((IkReal(-1.00000000000000))*(r00)*(x2040)*(x2052)))+(((x2044)*(x2052)))+(((IkReal(-1.00000000000000))*(x2046)*(x2057)))+(sj12)+(((IkReal(-1.00000000000000))*(r11)*(x2041)*(x2047))));
08791 evalcond[4]=((((r12)*(x2052)))+(((x2042)*(x2055)))+(((x2042)*(x2056)))+(((r02)*(x2047)))+(((cj10)*(sj11)))+(((IkReal(-1.00000000000000))*(cj13)*(x2041)*(x2051)))+(((cj11)*(sj10)))+(((IkReal(-1.00000000000000))*(cj13)*(x2041)*(x2049))));
08792 evalcond[5]=((((IkReal(-1.00000000000000))*(r01)*(x2041)*(x2047)))+(((IkReal(-1.00000000000000))*(r02)*(x2057)))+(((cj12)*(x2039)))+(((x2043)*(x2052)))+(((IkReal(-1.00000000000000))*(sj13)*(x2041)*(x2049)))+(((IkReal(-1.00000000000000))*(x2046)*(x2054)))+(((cj14)*(r00)*(x2047)))+(((IkReal(-1.00000000000000))*(cj12)*(x2045))));
08793 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  )
08794 {
08795 continue;
08796 }
08797 }
08798 
08799 {
08800 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
08801 vinfos[0].jointtype = 1;
08802 vinfos[0].foffset = j9;
08803 vinfos[0].indices[0] = _ij9[0];
08804 vinfos[0].indices[1] = _ij9[1];
08805 vinfos[0].maxsolutions = _nj9;
08806 vinfos[1].jointtype = 1;
08807 vinfos[1].foffset = j10;
08808 vinfos[1].indices[0] = _ij10[0];
08809 vinfos[1].indices[1] = _ij10[1];
08810 vinfos[1].maxsolutions = _nj10;
08811 vinfos[2].jointtype = 1;
08812 vinfos[2].foffset = j11;
08813 vinfos[2].indices[0] = _ij11[0];
08814 vinfos[2].indices[1] = _ij11[1];
08815 vinfos[2].maxsolutions = _nj11;
08816 vinfos[3].jointtype = 1;
08817 vinfos[3].foffset = j12;
08818 vinfos[3].indices[0] = _ij12[0];
08819 vinfos[3].indices[1] = _ij12[1];
08820 vinfos[3].maxsolutions = _nj12;
08821 vinfos[4].jointtype = 1;
08822 vinfos[4].foffset = j13;
08823 vinfos[4].indices[0] = _ij13[0];
08824 vinfos[4].indices[1] = _ij13[1];
08825 vinfos[4].maxsolutions = _nj13;
08826 vinfos[5].jointtype = 1;
08827 vinfos[5].foffset = j14;
08828 vinfos[5].indices[0] = _ij14[0];
08829 vinfos[5].indices[1] = _ij14[1];
08830 vinfos[5].maxsolutions = _nj14;
08831 std::vector<int> vfree(0);
08832 solutions.AddSolution(vinfos,vfree);
08833 }
08834 }
08835 }
08836 
08837 }
08838 
08839 }
08840 }
08841 }
08842 
08843 }
08844 
08845 }
08846 }
08847 }
08848 
08849 }
08850 
08851 }
08852 
08853 } else
08854 {
08855 {
08856 IkReal j9array[1], cj9array[1], sj9array[1];
08857 bool j9valid[1]={false};
08858 _nj9 = 1;
08859 IkReal x2058=((sj12)*(sj14));
08860 IkReal x2059=((cj14)*(sj12));
08861 IkReal x2060=((cj12)*(cj14)*(sj13));
08862 IkReal x2061=((IkReal(1.00000000000000))*(cj12)*(cj13));
08863 IkReal x2062=((IkReal(1.00000000000000))*(cj12)*(sj13)*(sj14));
08864 if( IKabs(((gconst1)*(((((r10)*(x2058)))+(((IkReal(-1.00000000000000))*(r12)*(x2061)))+(((r11)*(x2059)))+(((IkReal(-1.00000000000000))*(r11)*(x2062)))+(((r10)*(x2060))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((r01)*(x2059)))+(((IkReal(-1.00000000000000))*(r02)*(x2061)))+(((r00)*(x2060)))+(((IkReal(-1.00000000000000))*(r01)*(x2062)))+(((r00)*(x2058))))))) < IKFAST_ATAN2_MAGTHRESH )
08865     continue;
08866 j9array[0]=IKatan2(((gconst1)*(((((r10)*(x2058)))+(((IkReal(-1.00000000000000))*(r12)*(x2061)))+(((r11)*(x2059)))+(((IkReal(-1.00000000000000))*(r11)*(x2062)))+(((r10)*(x2060)))))), ((gconst1)*(((((r01)*(x2059)))+(((IkReal(-1.00000000000000))*(r02)*(x2061)))+(((r00)*(x2060)))+(((IkReal(-1.00000000000000))*(r01)*(x2062)))+(((r00)*(x2058)))))));
08867 sj9array[0]=IKsin(j9array[0]);
08868 cj9array[0]=IKcos(j9array[0]);
08869 if( j9array[0] > IKPI )
08870 {
08871     j9array[0]-=IK2PI;
08872 }
08873 else if( j9array[0] < -IKPI )
08874 {    j9array[0]+=IK2PI;
08875 }
08876 j9valid[0] = true;
08877 for(int ij9 = 0; ij9 < 1; ++ij9)
08878 {
08879 if( !j9valid[ij9] )
08880 {
08881     continue;
08882 }
08883 _ij9[0] = ij9; _ij9[1] = -1;
08884 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
08885 {
08886 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
08887 {
08888     j9valid[iij9]=false; _ij9[1] = iij9; break; 
08889 }
08890 }
08891 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
08892 {
08893 IkReal evalcond[3];
08894 IkReal x2063=IKsin(j9);
08895 IkReal x2064=IKcos(j9);
08896 IkReal x2065=((IkReal(1.00000000000000))*(sj14));
08897 IkReal x2066=((sj13)*(x2064));
08898 IkReal x2067=((cj13)*(x2063));
08899 IkReal x2068=((IkReal(1.00000000000000))*(cj14)*(r00));
08900 IkReal x2069=((r01)*(x2063));
08901 IkReal x2070=((r10)*(x2064));
08902 IkReal x2071=((sj13)*(x2063));
08903 IkReal x2072=((cj13)*(x2064));
08904 evalcond[0]=((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2064)))+(((cj14)*(x2069)))+(cj12)+(((r00)*(sj14)*(x2063)))+(((IkReal(-1.00000000000000))*(x2065)*(x2070))));
08905 evalcond[1]=((((cj13)*(cj14)*(x2070)))+(((IkReal(-1.00000000000000))*(r11)*(x2065)*(x2072)))+(((r12)*(x2066)))+(((IkReal(-1.00000000000000))*(r02)*(x2071)))+(((r01)*(sj14)*(x2067)))+(((IkReal(-1.00000000000000))*(x2067)*(x2068))));
08906 evalcond[2]=((((IkReal(-1.00000000000000))*(r11)*(x2065)*(x2066)))+(((r02)*(x2067)))+(sj12)+(((cj14)*(r10)*(x2066)))+(((IkReal(-1.00000000000000))*(r12)*(x2072)))+(((sj13)*(sj14)*(x2069)))+(((IkReal(-1.00000000000000))*(x2068)*(x2071))));
08907 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
08908 {
08909 continue;
08910 }
08911 }
08912 
08913 {
08914 IkReal dummyeval[1];
08915 dummyeval[0]=sj12;
08916 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08917 {
08918 {
08919 IkReal dummyeval[1];
08920 dummyeval[0]=cj12;
08921 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08922 {
08923 {
08924 IkReal evalcond[7];
08925 IkReal x2073=((IkReal(1.00000000000000))*(sj13));
08926 IkReal x2074=((cj14)*(sj9));
08927 IkReal x2075=((cj9)*(sj14));
08928 IkReal x2076=((cj13)*(sj9));
08929 IkReal x2077=((sj13)*(sj14));
08930 IkReal x2078=((cj9)*(sj13));
08931 IkReal x2079=((IkReal(1.00000000000000))*(cj13));
08932 IkReal x2080=((cj14)*(r10));
08933 IkReal x2081=((sj14)*(sj9));
08934 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
08935 evalcond[1]=((((IkReal(-1.00000000000000))*(r10)*(x2075)))+(((IkReal(-1.00000000000000))*(cj14)*(cj9)*(r11)))+(((r01)*(x2074)))+(((r00)*(x2081))));
08936 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2073)))+(((cj13)*(r22)))+(((r21)*(x2077))));
08937 evalcond[3]=((IkReal(0.0950000000000000))+(((npy)*(x2077)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x2073))));
08938 evalcond[4]=((((r12)*(x2078)))+(((IkReal(-1.00000000000000))*(r00)*(x2074)*(x2079)))+(((cj13)*(cj9)*(x2080)))+(((IkReal(-1.00000000000000))*(r11)*(x2075)*(x2079)))+(((r01)*(sj14)*(x2076)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2073))));
08939 evalcond[5]=((IkReal(1.00000000000000))+(((x2078)*(x2080)))+(((r02)*(x2076)))+(((IkReal(-1.00000000000000))*(r00)*(x2073)*(x2074)))+(((IkReal(-1.00000000000000))*(cj9)*(r12)*(x2079)))+(((IkReal(-1.00000000000000))*(r11)*(x2073)*(x2075)))+(((r01)*(sj9)*(x2077))));
08940 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(x2073)*(x2081)))+(((IkReal(-1.00000000000000))*(r01)*(x2073)*(x2075)))+(((cj14)*(r00)*(x2078)))+(((r10)*(sj13)*(x2074)))+(((IkReal(-1.00000000000000))*(r12)*(x2076)))+(((IkReal(-1.00000000000000))*(cj9)*(r02)*(x2079))));
08941 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  )
08942 {
08943 {
08944 IkReal j11array[1], cj11array[1], sj11array[1];
08945 bool j11valid[1]={false};
08946 _nj11 = 1;
08947 IkReal x2082=((IkReal(4.00000000000000))*(sj14));
08948 IkReal x2083=((IkReal(4.00000000000000))*(cj14));
08949 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2083)))+(((IkReal(-1.00000000000000))*(npx)*(x2082))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2082)))+(((cj13)*(npx)*(x2083)))+(((IkReal(-0.360000000000000))*(cj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2083)))+(((IkReal(-1.00000000000000))*(npx)*(x2082)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2082)))+(((cj13)*(npx)*(x2083)))+(((IkReal(-0.360000000000000))*(cj13)))))-1) <= IKFAST_SINCOS_THRESH )
08950     continue;
08951 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2083)))+(((IkReal(-1.00000000000000))*(npx)*(x2082)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2082)))+(((cj13)*(npx)*(x2083)))+(((IkReal(-0.360000000000000))*(cj13)))));
08952 sj11array[0]=IKsin(j11array[0]);
08953 cj11array[0]=IKcos(j11array[0]);
08954 if( j11array[0] > IKPI )
08955 {
08956     j11array[0]-=IK2PI;
08957 }
08958 else if( j11array[0] < -IKPI )
08959 {    j11array[0]+=IK2PI;
08960 }
08961 j11valid[0] = true;
08962 for(int ij11 = 0; ij11 < 1; ++ij11)
08963 {
08964 if( !j11valid[ij11] )
08965 {
08966     continue;
08967 }
08968 _ij11[0] = ij11; _ij11[1] = -1;
08969 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
08970 {
08971 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
08972 {
08973     j11valid[iij11]=false; _ij11[1] = iij11; break; 
08974 }
08975 }
08976 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
08977 {
08978 IkReal evalcond[2];
08979 evalcond[0]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(IKsin(j11)))));
08980 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(npx)))+(((cj13)*(npy)*(sj14)))+(((IkReal(-1.00000000000000))*(npz)*(sj13))));
08981 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
08982 {
08983 continue;
08984 }
08985 }
08986 
08987 {
08988 IkReal dummyeval[1];
08989 IkReal gconst56;
08990 gconst56=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
08991 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
08992 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
08993 {
08994 {
08995 IkReal dummyeval[1];
08996 IkReal gconst57;
08997 gconst57=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
08998 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
08999 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09000 {
09001 continue;
09002 
09003 } else
09004 {
09005 {
09006 IkReal j10array[1], cj10array[1], sj10array[1];
09007 bool j10valid[1]={false};
09008 _nj10 = 1;
09009 IkReal x2084=((IkReal(1.00000000000000))*(cj11));
09010 IkReal x2085=((r20)*(sj14));
09011 IkReal x2086=((cj14)*(r21));
09012 IkReal x2087=((cj14)*(cj9)*(r01));
09013 IkReal x2088=((r10)*(sj14)*(sj9));
09014 IkReal x2089=((cj9)*(r00)*(sj14));
09015 IkReal x2090=((cj14)*(r11)*(sj9));
09016 if( IKabs(((gconst57)*(((((cj11)*(x2086)))+(((cj11)*(x2085)))+(((sj11)*(x2087)))+(((sj11)*(x2089)))+(((sj11)*(x2088)))+(((sj11)*(x2090))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst57)*(((((IkReal(-1.00000000000000))*(x2084)*(x2087)))+(((IkReal(-1.00000000000000))*(x2084)*(x2088)))+(((IkReal(-1.00000000000000))*(x2084)*(x2089)))+(((sj11)*(x2086)))+(((sj11)*(x2085)))+(((IkReal(-1.00000000000000))*(x2084)*(x2090))))))) < IKFAST_ATAN2_MAGTHRESH )
09017     continue;
09018 j10array[0]=IKatan2(((gconst57)*(((((cj11)*(x2086)))+(((cj11)*(x2085)))+(((sj11)*(x2087)))+(((sj11)*(x2089)))+(((sj11)*(x2088)))+(((sj11)*(x2090)))))), ((gconst57)*(((((IkReal(-1.00000000000000))*(x2084)*(x2087)))+(((IkReal(-1.00000000000000))*(x2084)*(x2088)))+(((IkReal(-1.00000000000000))*(x2084)*(x2089)))+(((sj11)*(x2086)))+(((sj11)*(x2085)))+(((IkReal(-1.00000000000000))*(x2084)*(x2090)))))));
09019 sj10array[0]=IKsin(j10array[0]);
09020 cj10array[0]=IKcos(j10array[0]);
09021 if( j10array[0] > IKPI )
09022 {
09023     j10array[0]-=IK2PI;
09024 }
09025 else if( j10array[0] < -IKPI )
09026 {    j10array[0]+=IK2PI;
09027 }
09028 j10valid[0] = true;
09029 for(int ij10 = 0; ij10 < 1; ++ij10)
09030 {
09031 if( !j10valid[ij10] )
09032 {
09033     continue;
09034 }
09035 _ij10[0] = ij10; _ij10[1] = -1;
09036 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09037 {
09038 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09039 {
09040     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09041 }
09042 }
09043 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09044 {
09045 IkReal evalcond[4];
09046 IkReal x2091=IKsin(j10);
09047 IkReal x2092=IKcos(j10);
09048 IkReal x2093=((cj13)*(sj14));
09049 IkReal x2094=((cj13)*(cj14));
09050 IkReal x2095=((r10)*(sj9));
09051 IkReal x2096=((IkReal(1.00000000000000))*(cj9));
09052 IkReal x2097=((sj11)*(x2091));
09053 IkReal x2098=((IkReal(1.00000000000000))*(x2092));
09054 IkReal x2099=((cj11)*(x2091));
09055 IkReal x2100=((IkReal(1.00000000000000))*(r11)*(sj9));
09056 IkReal x2101=((cj11)*(x2098));
09057 evalcond[0]=((((IkReal(-1.00000000000000))*(sj11)*(x2098)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x2099))));
09058 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x2094)))+(((IkReal(-1.00000000000000))*(x2101)))+(x2097)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x2093))));
09059 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x2100)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2096)))+(((IkReal(-1.00000000000000))*(x2101)))+(x2097)+(((IkReal(-1.00000000000000))*(sj14)*(x2095)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2096))));
09060 evalcond[3]=((((IkReal(-1.00000000000000))*(x2093)*(x2100)))+(((x2094)*(x2095)))+(x2099)+(((cj9)*(r02)*(sj13)))+(((sj11)*(x2092)))+(((IkReal(-1.00000000000000))*(r01)*(x2093)*(x2096)))+(((cj9)*(r00)*(x2094)))+(((r12)*(sj13)*(sj9))));
09061 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09062 {
09063 continue;
09064 }
09065 }
09066 
09067 {
09068 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09069 vinfos[0].jointtype = 1;
09070 vinfos[0].foffset = j9;
09071 vinfos[0].indices[0] = _ij9[0];
09072 vinfos[0].indices[1] = _ij9[1];
09073 vinfos[0].maxsolutions = _nj9;
09074 vinfos[1].jointtype = 1;
09075 vinfos[1].foffset = j10;
09076 vinfos[1].indices[0] = _ij10[0];
09077 vinfos[1].indices[1] = _ij10[1];
09078 vinfos[1].maxsolutions = _nj10;
09079 vinfos[2].jointtype = 1;
09080 vinfos[2].foffset = j11;
09081 vinfos[2].indices[0] = _ij11[0];
09082 vinfos[2].indices[1] = _ij11[1];
09083 vinfos[2].maxsolutions = _nj11;
09084 vinfos[3].jointtype = 1;
09085 vinfos[3].foffset = j12;
09086 vinfos[3].indices[0] = _ij12[0];
09087 vinfos[3].indices[1] = _ij12[1];
09088 vinfos[3].maxsolutions = _nj12;
09089 vinfos[4].jointtype = 1;
09090 vinfos[4].foffset = j13;
09091 vinfos[4].indices[0] = _ij13[0];
09092 vinfos[4].indices[1] = _ij13[1];
09093 vinfos[4].maxsolutions = _nj13;
09094 vinfos[5].jointtype = 1;
09095 vinfos[5].foffset = j14;
09096 vinfos[5].indices[0] = _ij14[0];
09097 vinfos[5].indices[1] = _ij14[1];
09098 vinfos[5].maxsolutions = _nj14;
09099 std::vector<int> vfree(0);
09100 solutions.AddSolution(vinfos,vfree);
09101 }
09102 }
09103 }
09104 
09105 }
09106 
09107 }
09108 
09109 } else
09110 {
09111 {
09112 IkReal j10array[1], cj10array[1], sj10array[1];
09113 bool j10valid[1]={false};
09114 _nj10 = 1;
09115 IkReal x2102=((r20)*(sj14));
09116 IkReal x2103=((IkReal(1.00000000000000))*(cj13));
09117 IkReal x2104=((cj14)*(r20));
09118 IkReal x2105=((r21)*(sj14));
09119 IkReal x2106=((r22)*(sj13));
09120 IkReal x2107=((cj14)*(r21));
09121 if( IKabs(((gconst56)*(((((cj13)*(sj11)*(x2104)))+(((IkReal(-1.00000000000000))*(sj11)*(x2103)*(x2105)))+(((cj11)*(x2102)))+(((cj11)*(x2107)))+(((sj11)*(x2106))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(cj11)*(x2106)))+(((cj11)*(cj13)*(x2105)))+(((IkReal(-1.00000000000000))*(cj11)*(x2103)*(x2104)))+(((sj11)*(x2102)))+(((sj11)*(x2107))))))) < IKFAST_ATAN2_MAGTHRESH )
09122     continue;
09123 j10array[0]=IKatan2(((gconst56)*(((((cj13)*(sj11)*(x2104)))+(((IkReal(-1.00000000000000))*(sj11)*(x2103)*(x2105)))+(((cj11)*(x2102)))+(((cj11)*(x2107)))+(((sj11)*(x2106)))))), ((gconst56)*(((((IkReal(-1.00000000000000))*(cj11)*(x2106)))+(((cj11)*(cj13)*(x2105)))+(((IkReal(-1.00000000000000))*(cj11)*(x2103)*(x2104)))+(((sj11)*(x2102)))+(((sj11)*(x2107)))))));
09124 sj10array[0]=IKsin(j10array[0]);
09125 cj10array[0]=IKcos(j10array[0]);
09126 if( j10array[0] > IKPI )
09127 {
09128     j10array[0]-=IK2PI;
09129 }
09130 else if( j10array[0] < -IKPI )
09131 {    j10array[0]+=IK2PI;
09132 }
09133 j10valid[0] = true;
09134 for(int ij10 = 0; ij10 < 1; ++ij10)
09135 {
09136 if( !j10valid[ij10] )
09137 {
09138     continue;
09139 }
09140 _ij10[0] = ij10; _ij10[1] = -1;
09141 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09142 {
09143 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09144 {
09145     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09146 }
09147 }
09148 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09149 {
09150 IkReal evalcond[4];
09151 IkReal x2108=IKsin(j10);
09152 IkReal x2109=IKcos(j10);
09153 IkReal x2110=((cj13)*(sj14));
09154 IkReal x2111=((cj13)*(cj14));
09155 IkReal x2112=((r10)*(sj9));
09156 IkReal x2113=((IkReal(1.00000000000000))*(cj9));
09157 IkReal x2114=((sj11)*(x2108));
09158 IkReal x2115=((IkReal(1.00000000000000))*(x2109));
09159 IkReal x2116=((cj11)*(x2108));
09160 IkReal x2117=((IkReal(1.00000000000000))*(r11)*(sj9));
09161 IkReal x2118=((cj11)*(x2115));
09162 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x2116)))+(((IkReal(-1.00000000000000))*(sj11)*(x2115))));
09163 evalcond[1]=((((r21)*(x2110)))+(x2114)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2118)))+(((IkReal(-1.00000000000000))*(r20)*(x2111))));
09164 evalcond[2]=((x2114)+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2113)))+(((IkReal(-1.00000000000000))*(cj14)*(x2117)))+(((IkReal(-1.00000000000000))*(x2118)))+(((IkReal(-1.00000000000000))*(sj14)*(x2112)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2113))));
09165 evalcond[3]=((((cj9)*(r02)*(sj13)))+(x2116)+(((x2111)*(x2112)))+(((cj9)*(r00)*(x2111)))+(((IkReal(-1.00000000000000))*(x2110)*(x2117)))+(((IkReal(-1.00000000000000))*(r01)*(x2110)*(x2113)))+(((r12)*(sj13)*(sj9)))+(((sj11)*(x2109))));
09166 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09167 {
09168 continue;
09169 }
09170 }
09171 
09172 {
09173 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09174 vinfos[0].jointtype = 1;
09175 vinfos[0].foffset = j9;
09176 vinfos[0].indices[0] = _ij9[0];
09177 vinfos[0].indices[1] = _ij9[1];
09178 vinfos[0].maxsolutions = _nj9;
09179 vinfos[1].jointtype = 1;
09180 vinfos[1].foffset = j10;
09181 vinfos[1].indices[0] = _ij10[0];
09182 vinfos[1].indices[1] = _ij10[1];
09183 vinfos[1].maxsolutions = _nj10;
09184 vinfos[2].jointtype = 1;
09185 vinfos[2].foffset = j11;
09186 vinfos[2].indices[0] = _ij11[0];
09187 vinfos[2].indices[1] = _ij11[1];
09188 vinfos[2].maxsolutions = _nj11;
09189 vinfos[3].jointtype = 1;
09190 vinfos[3].foffset = j12;
09191 vinfos[3].indices[0] = _ij12[0];
09192 vinfos[3].indices[1] = _ij12[1];
09193 vinfos[3].maxsolutions = _nj12;
09194 vinfos[4].jointtype = 1;
09195 vinfos[4].foffset = j13;
09196 vinfos[4].indices[0] = _ij13[0];
09197 vinfos[4].indices[1] = _ij13[1];
09198 vinfos[4].maxsolutions = _nj13;
09199 vinfos[5].jointtype = 1;
09200 vinfos[5].foffset = j14;
09201 vinfos[5].indices[0] = _ij14[0];
09202 vinfos[5].indices[1] = _ij14[1];
09203 vinfos[5].maxsolutions = _nj14;
09204 std::vector<int> vfree(0);
09205 solutions.AddSolution(vinfos,vfree);
09206 }
09207 }
09208 }
09209 
09210 }
09211 
09212 }
09213 }
09214 }
09215 
09216 } else
09217 {
09218 IkReal x2119=((IkReal(1.00000000000000))*(sj13));
09219 IkReal x2120=((cj14)*(sj9));
09220 IkReal x2121=((cj9)*(sj14));
09221 IkReal x2122=((cj13)*(sj9));
09222 IkReal x2123=((sj13)*(sj14));
09223 IkReal x2124=((cj9)*(sj13));
09224 IkReal x2125=((IkReal(1.00000000000000))*(cj13));
09225 IkReal x2126=((cj14)*(r10));
09226 IkReal x2127=((sj14)*(sj9));
09227 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
09228 evalcond[1]=((((IkReal(-1.00000000000000))*(cj14)*(cj9)*(r11)))+(((r01)*(x2120)))+(((IkReal(-1.00000000000000))*(r10)*(x2121)))+(((r00)*(x2127))));
09229 evalcond[2]=((((r21)*(x2123)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2119))));
09230 evalcond[3]=((IkReal(-0.0950000000000000))+(((npy)*(x2123)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x2119))));
09231 evalcond[4]=((((r12)*(x2124)))+(((r01)*(sj14)*(x2122)))+(((cj13)*(cj9)*(x2126)))+(((IkReal(-1.00000000000000))*(r00)*(x2120)*(x2125)))+(((IkReal(-1.00000000000000))*(r11)*(x2121)*(x2125)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2119))));
09232 evalcond[5]=((IkReal(-1.00000000000000))+(((r01)*(sj9)*(x2123)))+(((IkReal(-1.00000000000000))*(r00)*(x2119)*(x2120)))+(((IkReal(-1.00000000000000))*(r11)*(x2119)*(x2121)))+(((r02)*(x2122)))+(((x2124)*(x2126)))+(((IkReal(-1.00000000000000))*(cj9)*(r12)*(x2125))));
09233 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x2119)*(x2121)))+(((IkReal(-1.00000000000000))*(r11)*(x2119)*(x2127)))+(((IkReal(-1.00000000000000))*(r12)*(x2122)))+(((IkReal(-1.00000000000000))*(cj9)*(r02)*(x2125)))+(((cj14)*(r00)*(x2124)))+(((r10)*(sj13)*(x2120))));
09234 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  )
09235 {
09236 {
09237 IkReal j11array[1], cj11array[1], sj11array[1];
09238 bool j11valid[1]={false};
09239 _nj11 = 1;
09240 IkReal x2128=((IkReal(4.00000000000000))*(sj14));
09241 IkReal x2129=((IkReal(4.00000000000000))*(cj14));
09242 if( IKabs(((IkReal(0.120000000000000))+(((npx)*(x2128)))+(((npy)*(x2129))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2128)))+(((cj13)*(npx)*(x2129)))+(((IkReal(-0.360000000000000))*(cj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((npx)*(x2128)))+(((npy)*(x2129)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2128)))+(((cj13)*(npx)*(x2129)))+(((IkReal(-0.360000000000000))*(cj13)))))-1) <= IKFAST_SINCOS_THRESH )
09243     continue;
09244 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((npx)*(x2128)))+(((npy)*(x2129)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2128)))+(((cj13)*(npx)*(x2129)))+(((IkReal(-0.360000000000000))*(cj13)))));
09245 sj11array[0]=IKsin(j11array[0]);
09246 cj11array[0]=IKcos(j11array[0]);
09247 if( j11array[0] > IKPI )
09248 {
09249     j11array[0]-=IK2PI;
09250 }
09251 else if( j11array[0] < -IKPI )
09252 {    j11array[0]+=IK2PI;
09253 }
09254 j11valid[0] = true;
09255 for(int ij11 = 0; ij11 < 1; ++ij11)
09256 {
09257 if( !j11valid[ij11] )
09258 {
09259     continue;
09260 }
09261 _ij11[0] = ij11; _ij11[1] = -1;
09262 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
09263 {
09264 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
09265 {
09266     j11valid[iij11]=false; _ij11[1] = iij11; break; 
09267 }
09268 }
09269 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
09270 {
09271 IkReal evalcond[2];
09272 evalcond[0]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(IKsin(j11))))+(((cj14)*(npy)))+(((npx)*(sj14))));
09273 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(npx)))+(((cj13)*(npy)*(sj14)))+(((IkReal(-1.00000000000000))*(npz)*(sj13))));
09274 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09275 {
09276 continue;
09277 }
09278 }
09279 
09280 {
09281 IkReal dummyeval[1];
09282 IkReal gconst58;
09283 gconst58=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
09284 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
09285 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09286 {
09287 {
09288 IkReal dummyeval[1];
09289 IkReal gconst59;
09290 gconst59=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
09291 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
09292 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09293 {
09294 continue;
09295 
09296 } else
09297 {
09298 {
09299 IkReal j10array[1], cj10array[1], sj10array[1];
09300 bool j10valid[1]={false};
09301 _nj10 = 1;
09302 IkReal x2130=((IkReal(1.00000000000000))*(sj11));
09303 IkReal x2131=((cj14)*(r21));
09304 IkReal x2132=((IkReal(1.00000000000000))*(cj11));
09305 IkReal x2133=((r20)*(sj14));
09306 IkReal x2134=((cj9)*(r00)*(sj14));
09307 IkReal x2135=((cj14)*(r11)*(sj9));
09308 IkReal x2136=((cj14)*(cj9)*(r01));
09309 IkReal x2137=((r10)*(sj14)*(sj9));
09310 if( IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(x2132)*(x2133)))+(((IkReal(-1.00000000000000))*(x2130)*(x2137)))+(((IkReal(-1.00000000000000))*(x2130)*(x2136)))+(((IkReal(-1.00000000000000))*(x2130)*(x2135)))+(((IkReal(-1.00000000000000))*(x2130)*(x2134)))+(((IkReal(-1.00000000000000))*(x2131)*(x2132))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((cj11)*(x2136)))+(((cj11)*(x2137)))+(((cj11)*(x2134)))+(((cj11)*(x2135)))+(((IkReal(-1.00000000000000))*(x2130)*(x2133)))+(((IkReal(-1.00000000000000))*(x2130)*(x2131))))))) < IKFAST_ATAN2_MAGTHRESH )
09311     continue;
09312 j10array[0]=IKatan2(((gconst59)*(((((IkReal(-1.00000000000000))*(x2132)*(x2133)))+(((IkReal(-1.00000000000000))*(x2130)*(x2137)))+(((IkReal(-1.00000000000000))*(x2130)*(x2136)))+(((IkReal(-1.00000000000000))*(x2130)*(x2135)))+(((IkReal(-1.00000000000000))*(x2130)*(x2134)))+(((IkReal(-1.00000000000000))*(x2131)*(x2132)))))), ((gconst59)*(((((cj11)*(x2136)))+(((cj11)*(x2137)))+(((cj11)*(x2134)))+(((cj11)*(x2135)))+(((IkReal(-1.00000000000000))*(x2130)*(x2133)))+(((IkReal(-1.00000000000000))*(x2130)*(x2131)))))));
09313 sj10array[0]=IKsin(j10array[0]);
09314 cj10array[0]=IKcos(j10array[0]);
09315 if( j10array[0] > IKPI )
09316 {
09317     j10array[0]-=IK2PI;
09318 }
09319 else if( j10array[0] < -IKPI )
09320 {    j10array[0]+=IK2PI;
09321 }
09322 j10valid[0] = true;
09323 for(int ij10 = 0; ij10 < 1; ++ij10)
09324 {
09325 if( !j10valid[ij10] )
09326 {
09327     continue;
09328 }
09329 _ij10[0] = ij10; _ij10[1] = -1;
09330 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09331 {
09332 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09333 {
09334     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09335 }
09336 }
09337 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09338 {
09339 IkReal evalcond[4];
09340 IkReal x2138=IKsin(j10);
09341 IkReal x2139=IKcos(j10);
09342 IkReal x2140=((cj14)*(sj9));
09343 IkReal x2141=((IkReal(1.00000000000000))*(r11));
09344 IkReal x2142=((cj13)*(sj14));
09345 IkReal x2143=((IkReal(1.00000000000000))*(cj9));
09346 IkReal x2144=((cj13)*(cj14));
09347 IkReal x2145=((cj11)*(x2138));
09348 IkReal x2146=((sj11)*(x2139));
09349 IkReal x2147=((cj11)*(x2139));
09350 IkReal x2148=((sj11)*(x2138));
09351 IkReal x2149=((x2146)+(x2145));
09352 evalcond[0]=((((cj14)*(r21)))+(x2149)+(((r20)*(sj14))));
09353 evalcond[1]=((((IkReal(-1.00000000000000))*(x2147)))+(((IkReal(-1.00000000000000))*(r20)*(x2144)))+(x2148)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x2142))));
09354 evalcond[2]=((((IkReal(-1.00000000000000))*(x2148)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2143)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2143)))+(x2147)+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x2140)*(x2141))));
09355 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2142)*(x2143)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(sj9)*(x2141)*(x2142)))+(x2149)+(((cj9)*(r00)*(x2144)))+(((r12)*(sj13)*(sj9)))+(((cj13)*(r10)*(x2140))));
09356 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09357 {
09358 continue;
09359 }
09360 }
09361 
09362 {
09363 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09364 vinfos[0].jointtype = 1;
09365 vinfos[0].foffset = j9;
09366 vinfos[0].indices[0] = _ij9[0];
09367 vinfos[0].indices[1] = _ij9[1];
09368 vinfos[0].maxsolutions = _nj9;
09369 vinfos[1].jointtype = 1;
09370 vinfos[1].foffset = j10;
09371 vinfos[1].indices[0] = _ij10[0];
09372 vinfos[1].indices[1] = _ij10[1];
09373 vinfos[1].maxsolutions = _nj10;
09374 vinfos[2].jointtype = 1;
09375 vinfos[2].foffset = j11;
09376 vinfos[2].indices[0] = _ij11[0];
09377 vinfos[2].indices[1] = _ij11[1];
09378 vinfos[2].maxsolutions = _nj11;
09379 vinfos[3].jointtype = 1;
09380 vinfos[3].foffset = j12;
09381 vinfos[3].indices[0] = _ij12[0];
09382 vinfos[3].indices[1] = _ij12[1];
09383 vinfos[3].maxsolutions = _nj12;
09384 vinfos[4].jointtype = 1;
09385 vinfos[4].foffset = j13;
09386 vinfos[4].indices[0] = _ij13[0];
09387 vinfos[4].indices[1] = _ij13[1];
09388 vinfos[4].maxsolutions = _nj13;
09389 vinfos[5].jointtype = 1;
09390 vinfos[5].foffset = j14;
09391 vinfos[5].indices[0] = _ij14[0];
09392 vinfos[5].indices[1] = _ij14[1];
09393 vinfos[5].maxsolutions = _nj14;
09394 std::vector<int> vfree(0);
09395 solutions.AddSolution(vinfos,vfree);
09396 }
09397 }
09398 }
09399 
09400 }
09401 
09402 }
09403 
09404 } else
09405 {
09406 {
09407 IkReal j10array[1], cj10array[1], sj10array[1];
09408 bool j10valid[1]={false};
09409 _nj10 = 1;
09410 IkReal x2150=((cj13)*(sj11));
09411 IkReal x2151=((r21)*(sj14));
09412 IkReal x2152=((cj14)*(r20));
09413 IkReal x2153=((cj11)*(cj13));
09414 IkReal x2154=((r22)*(sj13));
09415 IkReal x2155=((r20)*(sj14));
09416 IkReal x2156=((cj14)*(r21));
09417 if( IKabs(((gconst58)*(((((IkReal(-1.00000000000000))*(sj11)*(x2154)))+(((IkReal(-1.00000000000000))*(x2150)*(x2152)))+(((cj11)*(x2155)))+(((cj11)*(x2156)))+(((x2150)*(x2151))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst58)*(((((x2152)*(x2153)))+(((cj11)*(x2154)))+(((IkReal(-1.00000000000000))*(x2151)*(x2153)))+(((sj11)*(x2156)))+(((sj11)*(x2155))))))) < IKFAST_ATAN2_MAGTHRESH )
09418     continue;
09419 j10array[0]=IKatan2(((gconst58)*(((((IkReal(-1.00000000000000))*(sj11)*(x2154)))+(((IkReal(-1.00000000000000))*(x2150)*(x2152)))+(((cj11)*(x2155)))+(((cj11)*(x2156)))+(((x2150)*(x2151)))))), ((gconst58)*(((((x2152)*(x2153)))+(((cj11)*(x2154)))+(((IkReal(-1.00000000000000))*(x2151)*(x2153)))+(((sj11)*(x2156)))+(((sj11)*(x2155)))))));
09420 sj10array[0]=IKsin(j10array[0]);
09421 cj10array[0]=IKcos(j10array[0]);
09422 if( j10array[0] > IKPI )
09423 {
09424     j10array[0]-=IK2PI;
09425 }
09426 else if( j10array[0] < -IKPI )
09427 {    j10array[0]+=IK2PI;
09428 }
09429 j10valid[0] = true;
09430 for(int ij10 = 0; ij10 < 1; ++ij10)
09431 {
09432 if( !j10valid[ij10] )
09433 {
09434     continue;
09435 }
09436 _ij10[0] = ij10; _ij10[1] = -1;
09437 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09438 {
09439 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09440 {
09441     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09442 }
09443 }
09444 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09445 {
09446 IkReal evalcond[4];
09447 IkReal x2157=IKsin(j10);
09448 IkReal x2158=IKcos(j10);
09449 IkReal x2159=((cj14)*(sj9));
09450 IkReal x2160=((IkReal(1.00000000000000))*(r11));
09451 IkReal x2161=((cj13)*(sj14));
09452 IkReal x2162=((IkReal(1.00000000000000))*(cj9));
09453 IkReal x2163=((cj13)*(cj14));
09454 IkReal x2164=((cj11)*(x2157));
09455 IkReal x2165=((sj11)*(x2158));
09456 IkReal x2166=((cj11)*(x2158));
09457 IkReal x2167=((sj11)*(x2157));
09458 IkReal x2168=((x2165)+(x2164));
09459 evalcond[0]=((((cj14)*(r21)))+(x2168)+(((r20)*(sj14))));
09460 evalcond[1]=((x2167)+(((r21)*(x2161)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2166)))+(((IkReal(-1.00000000000000))*(r20)*(x2163))));
09461 evalcond[2]=((x2166)+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2162)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x2159)*(x2160)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2162)))+(((IkReal(-1.00000000000000))*(x2167))));
09462 evalcond[3]=((((cj13)*(r10)*(x2159)))+(((cj9)*(r02)*(sj13)))+(x2168)+(((cj9)*(r00)*(x2163)))+(((IkReal(-1.00000000000000))*(sj9)*(x2160)*(x2161)))+(((IkReal(-1.00000000000000))*(r01)*(x2161)*(x2162)))+(((r12)*(sj13)*(sj9))));
09463 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09464 {
09465 continue;
09466 }
09467 }
09468 
09469 {
09470 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09471 vinfos[0].jointtype = 1;
09472 vinfos[0].foffset = j9;
09473 vinfos[0].indices[0] = _ij9[0];
09474 vinfos[0].indices[1] = _ij9[1];
09475 vinfos[0].maxsolutions = _nj9;
09476 vinfos[1].jointtype = 1;
09477 vinfos[1].foffset = j10;
09478 vinfos[1].indices[0] = _ij10[0];
09479 vinfos[1].indices[1] = _ij10[1];
09480 vinfos[1].maxsolutions = _nj10;
09481 vinfos[2].jointtype = 1;
09482 vinfos[2].foffset = j11;
09483 vinfos[2].indices[0] = _ij11[0];
09484 vinfos[2].indices[1] = _ij11[1];
09485 vinfos[2].maxsolutions = _nj11;
09486 vinfos[3].jointtype = 1;
09487 vinfos[3].foffset = j12;
09488 vinfos[3].indices[0] = _ij12[0];
09489 vinfos[3].indices[1] = _ij12[1];
09490 vinfos[3].maxsolutions = _nj12;
09491 vinfos[4].jointtype = 1;
09492 vinfos[4].foffset = j13;
09493 vinfos[4].indices[0] = _ij13[0];
09494 vinfos[4].indices[1] = _ij13[1];
09495 vinfos[4].maxsolutions = _nj13;
09496 vinfos[5].jointtype = 1;
09497 vinfos[5].foffset = j14;
09498 vinfos[5].indices[0] = _ij14[0];
09499 vinfos[5].indices[1] = _ij14[1];
09500 vinfos[5].maxsolutions = _nj14;
09501 std::vector<int> vfree(0);
09502 solutions.AddSolution(vinfos,vfree);
09503 }
09504 }
09505 }
09506 
09507 }
09508 
09509 }
09510 }
09511 }
09512 
09513 } else
09514 {
09515 IkReal x2169=((cj13)*(sj9));
09516 IkReal x2170=((r01)*(sj14));
09517 IkReal x2171=((cj9)*(sj13));
09518 IkReal x2172=((sj13)*(sj9));
09519 IkReal x2173=((cj14)*(r01));
09520 IkReal x2174=((cj14)*(r10));
09521 IkReal x2175=((cj13)*(cj9));
09522 IkReal x2176=((IkReal(1.00000000000000))*(cj9));
09523 IkReal x2177=((sj14)*(sj9));
09524 IkReal x2178=((IkReal(1.00000000000000))*(cj14)*(sj9));
09525 IkReal x2179=((sj14)*(x2176));
09526 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
09527 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
09528 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
09529 evalcond[3]=((IkReal(1.00000000000000))+(((r00)*(x2177)))+(((sj9)*(x2173)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2176)))+(((IkReal(-1.00000000000000))*(r10)*(x2179))));
09530 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x2177)))+(((IkReal(-1.00000000000000))*(x2173)*(x2176)))+(((IkReal(-1.00000000000000))*(r11)*(x2178)))+(((IkReal(-1.00000000000000))*(r00)*(x2179))));
09531 evalcond[5]=((((x2174)*(x2175)))+(((IkReal(-1.00000000000000))*(r02)*(x2172)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(x2175)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x2169)))+(((x2169)*(x2170)))+(((r12)*(x2171))));
09532 evalcond[6]=((((IkReal(-1.00000000000000))*(r12)*(x2175)))+(((x2170)*(x2172)))+(((x2171)*(x2174)))+(((r02)*(x2169)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(x2171)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x2172))));
09533 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  )
09534 {
09535 {
09536 IkReal j11array[1], cj11array[1], sj11array[1];
09537 bool j11valid[1]={false};
09538 _nj11 = 1;
09539 IkReal x2180=((IkReal(4.00000000000000))*(cj13));
09540 IkReal x2181=((npy)*(sj14));
09541 IkReal x2182=((cj14)*(npx));
09542 IkReal x2183=((IkReal(4.00000000000000))*(sj13));
09543 if( IKabs(((IkReal(0.120000000000000))+(((npz)*(x2180)))+(((IkReal(0.360000000000000))*(sj13)))+(((x2181)*(x2183)))+(((IkReal(-1.00000000000000))*(x2182)*(x2183))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x2183)))+(((IkReal(-1.00000000000000))*(x2180)*(x2181)))+(((x2180)*(x2182)))+(((IkReal(-0.360000000000000))*(cj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((npz)*(x2180)))+(((IkReal(0.360000000000000))*(sj13)))+(((x2181)*(x2183)))+(((IkReal(-1.00000000000000))*(x2182)*(x2183)))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x2183)))+(((IkReal(-1.00000000000000))*(x2180)*(x2181)))+(((x2180)*(x2182)))+(((IkReal(-0.360000000000000))*(cj13)))))-1) <= IKFAST_SINCOS_THRESH )
09544     continue;
09545 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((npz)*(x2180)))+(((IkReal(0.360000000000000))*(sj13)))+(((x2181)*(x2183)))+(((IkReal(-1.00000000000000))*(x2182)*(x2183)))), ((IkReal(-0.940000000000000))+(((npz)*(x2183)))+(((IkReal(-1.00000000000000))*(x2180)*(x2181)))+(((x2180)*(x2182)))+(((IkReal(-0.360000000000000))*(cj13)))));
09546 sj11array[0]=IKsin(j11array[0]);
09547 cj11array[0]=IKcos(j11array[0]);
09548 if( j11array[0] > IKPI )
09549 {
09550     j11array[0]-=IK2PI;
09551 }
09552 else if( j11array[0] < -IKPI )
09553 {    j11array[0]+=IK2PI;
09554 }
09555 j11valid[0] = true;
09556 for(int ij11 = 0; ij11 < 1; ++ij11)
09557 {
09558 if( !j11valid[ij11] )
09559 {
09560     continue;
09561 }
09562 _ij11[0] = ij11; _ij11[1] = -1;
09563 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
09564 {
09565 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
09566 {
09567     j11valid[iij11]=false; _ij11[1] = iij11; break; 
09568 }
09569 }
09570 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
09571 {
09572 IkReal evalcond[2];
09573 IkReal x2184=((IkReal(1.00000000000000))*(sj13));
09574 IkReal x2185=((cj14)*(npx));
09575 IkReal x2186=((npy)*(sj14));
09576 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x2184)))+(((cj13)*(x2186)))+(((IkReal(-1.00000000000000))*(cj13)*(x2185))));
09577 evalcond[1]=((IkReal(0.0300000000000000))+(((sj13)*(x2186)))+(((IkReal(-0.250000000000000))*(IKsin(j11))))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x2184)*(x2185))));
09578 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09579 {
09580 continue;
09581 }
09582 }
09583 
09584 {
09585 IkReal dummyeval[1];
09586 IkReal gconst60;
09587 gconst60=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
09588 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
09589 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09590 {
09591 {
09592 IkReal dummyeval[1];
09593 IkReal gconst61;
09594 gconst61=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
09595 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
09596 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09597 {
09598 continue;
09599 
09600 } else
09601 {
09602 {
09603 IkReal j10array[1], cj10array[1], sj10array[1];
09604 bool j10valid[1]={false};
09605 _nj10 = 1;
09606 IkReal x2187=((cj13)*(sj14));
09607 IkReal x2188=((IkReal(1.00000000000000))*(cj11));
09608 IkReal x2189=((r11)*(sj9));
09609 IkReal x2190=((cj11)*(sj13));
09610 IkReal x2191=((r12)*(sj9));
09611 IkReal x2192=((cj9)*(r00));
09612 IkReal x2193=((sj11)*(sj13));
09613 IkReal x2194=((cj9)*(r02));
09614 IkReal x2195=((cj9)*(r01));
09615 IkReal x2196=((IkReal(1.00000000000000))*(sj11));
09616 IkReal x2197=((r10)*(sj9));
09617 IkReal x2198=((cj13)*(cj14)*(sj11));
09618 IkReal x2199=((cj11)*(cj13)*(cj14));
09619 if( IKabs(((gconst61)*(((((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2189)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2196)))+(((x2192)*(x2199)))+(((r21)*(sj11)*(x2187)))+(((x2190)*(x2194)))+(((x2190)*(x2191)))+(((IkReal(-1.00000000000000))*(r22)*(x2193)))+(((x2197)*(x2199)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2195))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((r22)*(x2190)))+(((x2191)*(x2193)))+(((x2193)*(x2194)))+(((x2192)*(x2198)))+(((r20)*(x2199)))+(((IkReal(-1.00000000000000))*(x2187)*(x2195)*(x2196)))+(((IkReal(-1.00000000000000))*(x2187)*(x2189)*(x2196)))+(((x2197)*(x2198)))+(((IkReal(-1.00000000000000))*(r21)*(x2187)*(x2188))))))) < IKFAST_ATAN2_MAGTHRESH )
09620     continue;
09621 j10array[0]=IKatan2(((gconst61)*(((((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2189)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2196)))+(((x2192)*(x2199)))+(((r21)*(sj11)*(x2187)))+(((x2190)*(x2194)))+(((x2190)*(x2191)))+(((IkReal(-1.00000000000000))*(r22)*(x2193)))+(((x2197)*(x2199)))+(((IkReal(-1.00000000000000))*(x2187)*(x2188)*(x2195)))))), ((gconst61)*(((((r22)*(x2190)))+(((x2191)*(x2193)))+(((x2193)*(x2194)))+(((x2192)*(x2198)))+(((r20)*(x2199)))+(((IkReal(-1.00000000000000))*(x2187)*(x2195)*(x2196)))+(((IkReal(-1.00000000000000))*(x2187)*(x2189)*(x2196)))+(((x2197)*(x2198)))+(((IkReal(-1.00000000000000))*(r21)*(x2187)*(x2188)))))));
09622 sj10array[0]=IKsin(j10array[0]);
09623 cj10array[0]=IKcos(j10array[0]);
09624 if( j10array[0] > IKPI )
09625 {
09626     j10array[0]-=IK2PI;
09627 }
09628 else if( j10array[0] < -IKPI )
09629 {    j10array[0]+=IK2PI;
09630 }
09631 j10valid[0] = true;
09632 for(int ij10 = 0; ij10 < 1; ++ij10)
09633 {
09634 if( !j10valid[ij10] )
09635 {
09636     continue;
09637 }
09638 _ij10[0] = ij10; _ij10[1] = -1;
09639 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09640 {
09641 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09642 {
09643     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09644 }
09645 }
09646 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09647 {
09648 IkReal evalcond[4];
09649 IkReal x2200=IKsin(j10);
09650 IkReal x2201=IKcos(j10);
09651 IkReal x2202=((IkReal(1.00000000000000))*(sj13));
09652 IkReal x2203=((r11)*(sj9));
09653 IkReal x2204=((cj9)*(r01));
09654 IkReal x2205=((r21)*(sj14));
09655 IkReal x2206=((cj9)*(r02));
09656 IkReal x2207=((sj13)*(sj9));
09657 IkReal x2208=((cj14)*(r10));
09658 IkReal x2209=((IkReal(1.00000000000000))*(cj13));
09659 IkReal x2210=((cj14)*(r20));
09660 IkReal x2211=((cj11)*(x2200));
09661 IkReal x2212=((sj11)*(x2201));
09662 IkReal x2213=((sj14)*(x2209));
09663 IkReal x2214=((sj11)*(x2200));
09664 IkReal x2215=((cj11)*(x2201));
09665 IkReal x2216=((cj14)*(cj9)*(r00));
09666 IkReal x2217=((x2212)+(x2211));
09667 evalcond[0]=((((IkReal(-1.00000000000000))*(x2215)))+(x2214)+(((IkReal(-1.00000000000000))*(r22)*(x2202)))+(((cj13)*(x2205)))+(((IkReal(-1.00000000000000))*(x2209)*(x2210))));
09668 evalcond[1]=((x2217)+(((IkReal(-1.00000000000000))*(x2202)*(x2210)))+(((sj13)*(x2205)))+(((cj13)*(r22))));
09669 evalcond[2]=((x2217)+(((IkReal(-1.00000000000000))*(x2204)*(x2213)))+(((r12)*(x2207)))+(((cj13)*(x2216)))+(((cj13)*(sj9)*(x2208)))+(((sj13)*(x2206)))+(((IkReal(-1.00000000000000))*(x2203)*(x2213))));
09670 evalcond[3]=((((IkReal(-1.00000000000000))*(x2214)))+(x2215)+(((IkReal(-1.00000000000000))*(sj14)*(x2202)*(x2204)))+(((IkReal(-1.00000000000000))*(sj14)*(x2202)*(x2203)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2209)))+(((IkReal(-1.00000000000000))*(x2206)*(x2209)))+(((x2207)*(x2208)))+(((sj13)*(x2216))));
09671 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09672 {
09673 continue;
09674 }
09675 }
09676 
09677 {
09678 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09679 vinfos[0].jointtype = 1;
09680 vinfos[0].foffset = j9;
09681 vinfos[0].indices[0] = _ij9[0];
09682 vinfos[0].indices[1] = _ij9[1];
09683 vinfos[0].maxsolutions = _nj9;
09684 vinfos[1].jointtype = 1;
09685 vinfos[1].foffset = j10;
09686 vinfos[1].indices[0] = _ij10[0];
09687 vinfos[1].indices[1] = _ij10[1];
09688 vinfos[1].maxsolutions = _nj10;
09689 vinfos[2].jointtype = 1;
09690 vinfos[2].foffset = j11;
09691 vinfos[2].indices[0] = _ij11[0];
09692 vinfos[2].indices[1] = _ij11[1];
09693 vinfos[2].maxsolutions = _nj11;
09694 vinfos[3].jointtype = 1;
09695 vinfos[3].foffset = j12;
09696 vinfos[3].indices[0] = _ij12[0];
09697 vinfos[3].indices[1] = _ij12[1];
09698 vinfos[3].maxsolutions = _nj12;
09699 vinfos[4].jointtype = 1;
09700 vinfos[4].foffset = j13;
09701 vinfos[4].indices[0] = _ij13[0];
09702 vinfos[4].indices[1] = _ij13[1];
09703 vinfos[4].maxsolutions = _nj13;
09704 vinfos[5].jointtype = 1;
09705 vinfos[5].foffset = j14;
09706 vinfos[5].indices[0] = _ij14[0];
09707 vinfos[5].indices[1] = _ij14[1];
09708 vinfos[5].maxsolutions = _nj14;
09709 std::vector<int> vfree(0);
09710 solutions.AddSolution(vinfos,vfree);
09711 }
09712 }
09713 }
09714 
09715 }
09716 
09717 }
09718 
09719 } else
09720 {
09721 {
09722 IkReal j10array[1], cj10array[1], sj10array[1];
09723 bool j10valid[1]={false};
09724 _nj10 = 1;
09725 IkReal x2218=((cj13)*(sj11));
09726 IkReal x2219=((r21)*(sj14));
09727 IkReal x2220=((cj11)*(cj13));
09728 IkReal x2221=((sj11)*(sj13));
09729 IkReal x2222=((cj11)*(sj13));
09730 IkReal x2223=((IkReal(1.00000000000000))*(cj14)*(r20));
09731 if( IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(x2222)*(x2223)))+(((r22)*(x2220)))+(((IkReal(-1.00000000000000))*(r22)*(x2221)))+(((x2219)*(x2222)))+(((IkReal(-1.00000000000000))*(x2218)*(x2223)))+(((x2218)*(x2219))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((r22)*(x2222)))+(((IkReal(-1.00000000000000))*(x2219)*(x2220)))+(((IkReal(-1.00000000000000))*(x2221)*(x2223)))+(((x2219)*(x2221)))+(((r22)*(x2218)))+(((cj14)*(r20)*(x2220))))))) < IKFAST_ATAN2_MAGTHRESH )
09732     continue;
09733 j10array[0]=IKatan2(((gconst60)*(((((IkReal(-1.00000000000000))*(x2222)*(x2223)))+(((r22)*(x2220)))+(((IkReal(-1.00000000000000))*(r22)*(x2221)))+(((x2219)*(x2222)))+(((IkReal(-1.00000000000000))*(x2218)*(x2223)))+(((x2218)*(x2219)))))), ((gconst60)*(((((r22)*(x2222)))+(((IkReal(-1.00000000000000))*(x2219)*(x2220)))+(((IkReal(-1.00000000000000))*(x2221)*(x2223)))+(((x2219)*(x2221)))+(((r22)*(x2218)))+(((cj14)*(r20)*(x2220)))))));
09734 sj10array[0]=IKsin(j10array[0]);
09735 cj10array[0]=IKcos(j10array[0]);
09736 if( j10array[0] > IKPI )
09737 {
09738     j10array[0]-=IK2PI;
09739 }
09740 else if( j10array[0] < -IKPI )
09741 {    j10array[0]+=IK2PI;
09742 }
09743 j10valid[0] = true;
09744 for(int ij10 = 0; ij10 < 1; ++ij10)
09745 {
09746 if( !j10valid[ij10] )
09747 {
09748     continue;
09749 }
09750 _ij10[0] = ij10; _ij10[1] = -1;
09751 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09752 {
09753 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09754 {
09755     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09756 }
09757 }
09758 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09759 {
09760 IkReal evalcond[4];
09761 IkReal x2224=IKsin(j10);
09762 IkReal x2225=IKcos(j10);
09763 IkReal x2226=((IkReal(1.00000000000000))*(sj13));
09764 IkReal x2227=((r11)*(sj9));
09765 IkReal x2228=((cj9)*(r01));
09766 IkReal x2229=((r21)*(sj14));
09767 IkReal x2230=((cj9)*(r02));
09768 IkReal x2231=((sj13)*(sj9));
09769 IkReal x2232=((cj14)*(r10));
09770 IkReal x2233=((IkReal(1.00000000000000))*(cj13));
09771 IkReal x2234=((cj14)*(r20));
09772 IkReal x2235=((cj11)*(x2224));
09773 IkReal x2236=((sj11)*(x2225));
09774 IkReal x2237=((sj14)*(x2233));
09775 IkReal x2238=((sj11)*(x2224));
09776 IkReal x2239=((cj11)*(x2225));
09777 IkReal x2240=((cj14)*(cj9)*(r00));
09778 IkReal x2241=((x2235)+(x2236));
09779 evalcond[0]=((((cj13)*(x2229)))+(x2238)+(((IkReal(-1.00000000000000))*(x2239)))+(((IkReal(-1.00000000000000))*(r22)*(x2226)))+(((IkReal(-1.00000000000000))*(x2233)*(x2234))));
09780 evalcond[1]=((x2241)+(((IkReal(-1.00000000000000))*(x2226)*(x2234)))+(((sj13)*(x2229)))+(((cj13)*(r22))));
09781 evalcond[2]=((x2241)+(((sj13)*(x2230)))+(((IkReal(-1.00000000000000))*(x2227)*(x2237)))+(((cj13)*(x2240)))+(((IkReal(-1.00000000000000))*(x2228)*(x2237)))+(((cj13)*(sj9)*(x2232)))+(((r12)*(x2231))));
09782 evalcond[3]=((x2239)+(((IkReal(-1.00000000000000))*(x2238)))+(((x2231)*(x2232)))+(((IkReal(-1.00000000000000))*(x2230)*(x2233)))+(((IkReal(-1.00000000000000))*(sj14)*(x2226)*(x2227)))+(((IkReal(-1.00000000000000))*(sj14)*(x2226)*(x2228)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2233)))+(((sj13)*(x2240))));
09783 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09784 {
09785 continue;
09786 }
09787 }
09788 
09789 {
09790 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09791 vinfos[0].jointtype = 1;
09792 vinfos[0].foffset = j9;
09793 vinfos[0].indices[0] = _ij9[0];
09794 vinfos[0].indices[1] = _ij9[1];
09795 vinfos[0].maxsolutions = _nj9;
09796 vinfos[1].jointtype = 1;
09797 vinfos[1].foffset = j10;
09798 vinfos[1].indices[0] = _ij10[0];
09799 vinfos[1].indices[1] = _ij10[1];
09800 vinfos[1].maxsolutions = _nj10;
09801 vinfos[2].jointtype = 1;
09802 vinfos[2].foffset = j11;
09803 vinfos[2].indices[0] = _ij11[0];
09804 vinfos[2].indices[1] = _ij11[1];
09805 vinfos[2].maxsolutions = _nj11;
09806 vinfos[3].jointtype = 1;
09807 vinfos[3].foffset = j12;
09808 vinfos[3].indices[0] = _ij12[0];
09809 vinfos[3].indices[1] = _ij12[1];
09810 vinfos[3].maxsolutions = _nj12;
09811 vinfos[4].jointtype = 1;
09812 vinfos[4].foffset = j13;
09813 vinfos[4].indices[0] = _ij13[0];
09814 vinfos[4].indices[1] = _ij13[1];
09815 vinfos[4].maxsolutions = _nj13;
09816 vinfos[5].jointtype = 1;
09817 vinfos[5].foffset = j14;
09818 vinfos[5].indices[0] = _ij14[0];
09819 vinfos[5].indices[1] = _ij14[1];
09820 vinfos[5].maxsolutions = _nj14;
09821 std::vector<int> vfree(0);
09822 solutions.AddSolution(vinfos,vfree);
09823 }
09824 }
09825 }
09826 
09827 }
09828 
09829 }
09830 }
09831 }
09832 
09833 } else
09834 {
09835 IkReal x2242=((cj13)*(sj9));
09836 IkReal x2243=((r01)*(sj14));
09837 IkReal x2244=((cj9)*(sj13));
09838 IkReal x2245=((sj13)*(sj9));
09839 IkReal x2246=((cj14)*(r01));
09840 IkReal x2247=((cj14)*(r10));
09841 IkReal x2248=((cj13)*(cj9));
09842 IkReal x2249=((IkReal(1.00000000000000))*(cj9));
09843 IkReal x2250=((sj14)*(sj9));
09844 IkReal x2251=((IkReal(1.00000000000000))*(cj14)*(sj9));
09845 IkReal x2252=((sj14)*(x2249));
09846 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
09847 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
09848 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
09849 evalcond[3]=((IkReal(-1.00000000000000))+(((sj9)*(x2246)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2249)))+(((IkReal(-1.00000000000000))*(r10)*(x2252)))+(((r00)*(x2250))));
09850 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x2250)))+(((IkReal(-1.00000000000000))*(r00)*(x2252)))+(((IkReal(-1.00000000000000))*(r11)*(x2251)))+(((IkReal(-1.00000000000000))*(x2246)*(x2249))));
09851 evalcond[5]=((((IkReal(-1.00000000000000))*(r11)*(sj14)*(x2248)))+(((IkReal(-1.00000000000000))*(r02)*(x2245)))+(((x2247)*(x2248)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x2242)))+(((x2242)*(x2243)))+(((r12)*(x2244))));
09852 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(sj14)*(x2244)))+(((x2243)*(x2245)))+(((x2244)*(x2247)))+(((IkReal(-1.00000000000000))*(r12)*(x2248)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x2245)))+(((r02)*(x2242))));
09853 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  )
09854 {
09855 {
09856 IkReal j11array[1], cj11array[1], sj11array[1];
09857 bool j11valid[1]={false};
09858 _nj11 = 1;
09859 IkReal x2253=((IkReal(4.00000000000000))*(cj13));
09860 IkReal x2254=((npy)*(sj14));
09861 IkReal x2255=((cj14)*(npx));
09862 IkReal x2256=((IkReal(4.00000000000000))*(sj13));
09863 if( IKabs(((IkReal(0.120000000000000))+(((x2255)*(x2256)))+(((IkReal(-1.00000000000000))*(npz)*(x2253)))+(((IkReal(-1.00000000000000))*(x2254)*(x2256)))+(((IkReal(-0.360000000000000))*(sj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((x2253)*(x2255)))+(((IkReal(-1.00000000000000))*(x2253)*(x2254)))+(((npz)*(x2256)))+(((IkReal(-0.360000000000000))*(cj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((x2255)*(x2256)))+(((IkReal(-1.00000000000000))*(npz)*(x2253)))+(((IkReal(-1.00000000000000))*(x2254)*(x2256)))+(((IkReal(-0.360000000000000))*(sj13)))))+IKsqr(((IkReal(-0.940000000000000))+(((x2253)*(x2255)))+(((IkReal(-1.00000000000000))*(x2253)*(x2254)))+(((npz)*(x2256)))+(((IkReal(-0.360000000000000))*(cj13)))))-1) <= IKFAST_SINCOS_THRESH )
09864     continue;
09865 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((x2255)*(x2256)))+(((IkReal(-1.00000000000000))*(npz)*(x2253)))+(((IkReal(-1.00000000000000))*(x2254)*(x2256)))+(((IkReal(-0.360000000000000))*(sj13)))), ((IkReal(-0.940000000000000))+(((x2253)*(x2255)))+(((IkReal(-1.00000000000000))*(x2253)*(x2254)))+(((npz)*(x2256)))+(((IkReal(-0.360000000000000))*(cj13)))));
09866 sj11array[0]=IKsin(j11array[0]);
09867 cj11array[0]=IKcos(j11array[0]);
09868 if( j11array[0] > IKPI )
09869 {
09870     j11array[0]-=IK2PI;
09871 }
09872 else if( j11array[0] < -IKPI )
09873 {    j11array[0]+=IK2PI;
09874 }
09875 j11valid[0] = true;
09876 for(int ij11 = 0; ij11 < 1; ++ij11)
09877 {
09878 if( !j11valid[ij11] )
09879 {
09880     continue;
09881 }
09882 _ij11[0] = ij11; _ij11[1] = -1;
09883 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
09884 {
09885 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
09886 {
09887     j11valid[iij11]=false; _ij11[1] = iij11; break; 
09888 }
09889 }
09890 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
09891 {
09892 IkReal evalcond[2];
09893 IkReal x2257=((IkReal(1.00000000000000))*(sj13));
09894 IkReal x2258=((cj14)*(npx));
09895 IkReal x2259=((npy)*(sj14));
09896 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x2257)))+(((IkReal(-1.00000000000000))*(cj13)*(x2258)))+(((cj13)*(x2259))));
09897 evalcond[1]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x2257)*(x2258)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((sj13)*(x2259)))+(((IkReal(0.250000000000000))*(IKsin(j11)))));
09898 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
09899 {
09900 continue;
09901 }
09902 }
09903 
09904 {
09905 IkReal dummyeval[1];
09906 IkReal gconst62;
09907 gconst62=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
09908 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
09909 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09910 {
09911 {
09912 IkReal dummyeval[1];
09913 IkReal gconst63;
09914 gconst63=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
09915 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
09916 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
09917 {
09918 continue;
09919 
09920 } else
09921 {
09922 {
09923 IkReal j10array[1], cj10array[1], sj10array[1];
09924 bool j10valid[1]={false};
09925 _nj10 = 1;
09926 IkReal x2260=((cj13)*(sj14));
09927 IkReal x2261=((IkReal(1.00000000000000))*(cj11));
09928 IkReal x2262=((r11)*(sj9));
09929 IkReal x2263=((IkReal(1.00000000000000))*(sj11));
09930 IkReal x2264=((cj13)*(cj14));
09931 IkReal x2265=((cj11)*(sj13));
09932 IkReal x2266=((r12)*(sj9));
09933 IkReal x2267=((sj11)*(sj13));
09934 IkReal x2268=((cj9)*(r02));
09935 IkReal x2269=((cj9)*(r01));
09936 IkReal x2270=((r10)*(sj9));
09937 IkReal x2271=((cj9)*(r00));
09938 if( IKabs(((gconst63)*(((((r21)*(sj11)*(x2260)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2263)))+(((IkReal(-1.00000000000000))*(x2260)*(x2261)*(x2269)))+(((IkReal(-1.00000000000000))*(x2260)*(x2261)*(x2262)))+(((IkReal(-1.00000000000000))*(r20)*(x2263)*(x2264)))+(((cj11)*(x2264)*(x2271)))+(((cj11)*(x2264)*(x2270)))+(((x2265)*(x2266)))+(((x2265)*(x2268))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst63)*(((((IkReal(-1.00000000000000))*(x2260)*(x2262)*(x2263)))+(((IkReal(-1.00000000000000))*(x2260)*(x2263)*(x2269)))+(((r22)*(x2265)))+(((sj11)*(x2264)*(x2270)))+(((sj11)*(x2264)*(x2271)))+(((IkReal(-1.00000000000000))*(r21)*(x2260)*(x2261)))+(((x2266)*(x2267)))+(((x2267)*(x2268)))+(((cj11)*(r20)*(x2264))))))) < IKFAST_ATAN2_MAGTHRESH )
09939     continue;
09940 j10array[0]=IKatan2(((gconst63)*(((((r21)*(sj11)*(x2260)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2263)))+(((IkReal(-1.00000000000000))*(x2260)*(x2261)*(x2269)))+(((IkReal(-1.00000000000000))*(x2260)*(x2261)*(x2262)))+(((IkReal(-1.00000000000000))*(r20)*(x2263)*(x2264)))+(((cj11)*(x2264)*(x2271)))+(((cj11)*(x2264)*(x2270)))+(((x2265)*(x2266)))+(((x2265)*(x2268)))))), ((gconst63)*(((((IkReal(-1.00000000000000))*(x2260)*(x2262)*(x2263)))+(((IkReal(-1.00000000000000))*(x2260)*(x2263)*(x2269)))+(((r22)*(x2265)))+(((sj11)*(x2264)*(x2270)))+(((sj11)*(x2264)*(x2271)))+(((IkReal(-1.00000000000000))*(r21)*(x2260)*(x2261)))+(((x2266)*(x2267)))+(((x2267)*(x2268)))+(((cj11)*(r20)*(x2264)))))));
09941 sj10array[0]=IKsin(j10array[0]);
09942 cj10array[0]=IKcos(j10array[0]);
09943 if( j10array[0] > IKPI )
09944 {
09945     j10array[0]-=IK2PI;
09946 }
09947 else if( j10array[0] < -IKPI )
09948 {    j10array[0]+=IK2PI;
09949 }
09950 j10valid[0] = true;
09951 for(int ij10 = 0; ij10 < 1; ++ij10)
09952 {
09953 if( !j10valid[ij10] )
09954 {
09955     continue;
09956 }
09957 _ij10[0] = ij10; _ij10[1] = -1;
09958 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
09959 {
09960 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
09961 {
09962     j10valid[iij10]=false; _ij10[1] = iij10; break; 
09963 }
09964 }
09965 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
09966 {
09967 IkReal evalcond[4];
09968 IkReal x2272=IKsin(j10);
09969 IkReal x2273=IKcos(j10);
09970 IkReal x2274=((IkReal(1.00000000000000))*(sj13));
09971 IkReal x2275=((r11)*(sj9));
09972 IkReal x2276=((cj9)*(r01));
09973 IkReal x2277=((IkReal(1.00000000000000))*(cj11));
09974 IkReal x2278=((r21)*(sj14));
09975 IkReal x2279=((cj9)*(r02));
09976 IkReal x2280=((sj13)*(sj9));
09977 IkReal x2281=((cj14)*(r10));
09978 IkReal x2282=((IkReal(1.00000000000000))*(cj13));
09979 IkReal x2283=((cj14)*(r20));
09980 IkReal x2284=((sj11)*(x2272));
09981 IkReal x2285=((sj14)*(x2282));
09982 IkReal x2286=((sj11)*(x2273));
09983 IkReal x2287=((cj14)*(cj9)*(r00));
09984 IkReal x2288=((x2273)*(x2277));
09985 evalcond[0]=((((IkReal(-1.00000000000000))*(x2282)*(x2283)))+(x2284)+(((cj13)*(x2278)))+(((IkReal(-1.00000000000000))*(x2288)))+(((IkReal(-1.00000000000000))*(r22)*(x2274))));
09986 evalcond[1]=((((IkReal(-1.00000000000000))*(x2286)))+(((sj13)*(x2278)))+(((IkReal(-1.00000000000000))*(x2274)*(x2283)))+(((IkReal(-1.00000000000000))*(x2272)*(x2277)))+(((cj13)*(r22))));
09987 evalcond[2]=((((IkReal(-1.00000000000000))*(x2276)*(x2285)))+(x2286)+(((cj13)*(sj9)*(x2281)))+(((r12)*(x2280)))+(((cj11)*(x2272)))+(((sj13)*(x2279)))+(((cj13)*(x2287)))+(((IkReal(-1.00000000000000))*(x2275)*(x2285))));
09988 evalcond[3]=((x2284)+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2282)))+(((IkReal(-1.00000000000000))*(x2288)))+(((x2280)*(x2281)))+(((IkReal(-1.00000000000000))*(x2279)*(x2282)))+(((IkReal(-1.00000000000000))*(sj14)*(x2274)*(x2275)))+(((IkReal(-1.00000000000000))*(sj14)*(x2274)*(x2276)))+(((sj13)*(x2287))));
09989 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
09990 {
09991 continue;
09992 }
09993 }
09994 
09995 {
09996 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
09997 vinfos[0].jointtype = 1;
09998 vinfos[0].foffset = j9;
09999 vinfos[0].indices[0] = _ij9[0];
10000 vinfos[0].indices[1] = _ij9[1];
10001 vinfos[0].maxsolutions = _nj9;
10002 vinfos[1].jointtype = 1;
10003 vinfos[1].foffset = j10;
10004 vinfos[1].indices[0] = _ij10[0];
10005 vinfos[1].indices[1] = _ij10[1];
10006 vinfos[1].maxsolutions = _nj10;
10007 vinfos[2].jointtype = 1;
10008 vinfos[2].foffset = j11;
10009 vinfos[2].indices[0] = _ij11[0];
10010 vinfos[2].indices[1] = _ij11[1];
10011 vinfos[2].maxsolutions = _nj11;
10012 vinfos[3].jointtype = 1;
10013 vinfos[3].foffset = j12;
10014 vinfos[3].indices[0] = _ij12[0];
10015 vinfos[3].indices[1] = _ij12[1];
10016 vinfos[3].maxsolutions = _nj12;
10017 vinfos[4].jointtype = 1;
10018 vinfos[4].foffset = j13;
10019 vinfos[4].indices[0] = _ij13[0];
10020 vinfos[4].indices[1] = _ij13[1];
10021 vinfos[4].maxsolutions = _nj13;
10022 vinfos[5].jointtype = 1;
10023 vinfos[5].foffset = j14;
10024 vinfos[5].indices[0] = _ij14[0];
10025 vinfos[5].indices[1] = _ij14[1];
10026 vinfos[5].maxsolutions = _nj14;
10027 std::vector<int> vfree(0);
10028 solutions.AddSolution(vinfos,vfree);
10029 }
10030 }
10031 }
10032 
10033 }
10034 
10035 }
10036 
10037 } else
10038 {
10039 {
10040 IkReal j10array[1], cj10array[1], sj10array[1];
10041 bool j10valid[1]={false};
10042 _nj10 = 1;
10043 IkReal x2289=((cj13)*(r22));
10044 IkReal x2290=((IkReal(1.00000000000000))*(sj11));
10045 IkReal x2291=((IkReal(1.00000000000000))*(cj11));
10046 IkReal x2292=((r22)*(sj13));
10047 IkReal x2293=((cj14)*(r20));
10048 IkReal x2294=((cj13)*(r21)*(sj14));
10049 IkReal x2295=((r21)*(sj13)*(sj14));
10050 if( IKabs(((gconst62)*(((((sj11)*(x2292)))+(((cj13)*(sj11)*(x2293)))+(((IkReal(-1.00000000000000))*(sj13)*(x2291)*(x2293)))+(((cj11)*(x2295)))+(((IkReal(-1.00000000000000))*(x2290)*(x2294)))+(((cj11)*(x2289))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((sj11)*(x2295)))+(((sj11)*(x2289)))+(((IkReal(-1.00000000000000))*(cj13)*(x2291)*(x2293)))+(((IkReal(-1.00000000000000))*(x2291)*(x2292)))+(((cj11)*(x2294)))+(((IkReal(-1.00000000000000))*(sj13)*(x2290)*(x2293))))))) < IKFAST_ATAN2_MAGTHRESH )
10051     continue;
10052 j10array[0]=IKatan2(((gconst62)*(((((sj11)*(x2292)))+(((cj13)*(sj11)*(x2293)))+(((IkReal(-1.00000000000000))*(sj13)*(x2291)*(x2293)))+(((cj11)*(x2295)))+(((IkReal(-1.00000000000000))*(x2290)*(x2294)))+(((cj11)*(x2289)))))), ((gconst62)*(((((sj11)*(x2295)))+(((sj11)*(x2289)))+(((IkReal(-1.00000000000000))*(cj13)*(x2291)*(x2293)))+(((IkReal(-1.00000000000000))*(x2291)*(x2292)))+(((cj11)*(x2294)))+(((IkReal(-1.00000000000000))*(sj13)*(x2290)*(x2293)))))));
10053 sj10array[0]=IKsin(j10array[0]);
10054 cj10array[0]=IKcos(j10array[0]);
10055 if( j10array[0] > IKPI )
10056 {
10057     j10array[0]-=IK2PI;
10058 }
10059 else if( j10array[0] < -IKPI )
10060 {    j10array[0]+=IK2PI;
10061 }
10062 j10valid[0] = true;
10063 for(int ij10 = 0; ij10 < 1; ++ij10)
10064 {
10065 if( !j10valid[ij10] )
10066 {
10067     continue;
10068 }
10069 _ij10[0] = ij10; _ij10[1] = -1;
10070 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10071 {
10072 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10073 {
10074     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10075 }
10076 }
10077 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10078 {
10079 IkReal evalcond[4];
10080 IkReal x2296=IKsin(j10);
10081 IkReal x2297=IKcos(j10);
10082 IkReal x2298=((IkReal(1.00000000000000))*(sj13));
10083 IkReal x2299=((r11)*(sj9));
10084 IkReal x2300=((cj9)*(r01));
10085 IkReal x2301=((IkReal(1.00000000000000))*(cj11));
10086 IkReal x2302=((r21)*(sj14));
10087 IkReal x2303=((cj9)*(r02));
10088 IkReal x2304=((sj13)*(sj9));
10089 IkReal x2305=((cj14)*(r10));
10090 IkReal x2306=((IkReal(1.00000000000000))*(cj13));
10091 IkReal x2307=((cj14)*(r20));
10092 IkReal x2308=((sj11)*(x2296));
10093 IkReal x2309=((sj14)*(x2306));
10094 IkReal x2310=((sj11)*(x2297));
10095 IkReal x2311=((cj14)*(cj9)*(r00));
10096 IkReal x2312=((x2297)*(x2301));
10097 evalcond[0]=((((IkReal(-1.00000000000000))*(x2306)*(x2307)))+(((cj13)*(x2302)))+(x2308)+(((IkReal(-1.00000000000000))*(r22)*(x2298)))+(((IkReal(-1.00000000000000))*(x2312))));
10098 evalcond[1]=((((IkReal(-1.00000000000000))*(x2310)))+(((sj13)*(x2302)))+(((IkReal(-1.00000000000000))*(x2296)*(x2301)))+(((IkReal(-1.00000000000000))*(x2298)*(x2307)))+(((cj13)*(r22))));
10099 evalcond[2]=((((r12)*(x2304)))+(((sj13)*(x2303)))+(((IkReal(-1.00000000000000))*(x2300)*(x2309)))+(x2310)+(((IkReal(-1.00000000000000))*(x2299)*(x2309)))+(((cj11)*(x2296)))+(((cj13)*(x2311)))+(((cj13)*(sj9)*(x2305))));
10100 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2306)))+(((x2304)*(x2305)))+(x2308)+(((IkReal(-1.00000000000000))*(x2303)*(x2306)))+(((IkReal(-1.00000000000000))*(sj14)*(x2298)*(x2299)))+(((sj13)*(x2311)))+(((IkReal(-1.00000000000000))*(sj14)*(x2298)*(x2300)))+(((IkReal(-1.00000000000000))*(x2312))));
10101 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10102 {
10103 continue;
10104 }
10105 }
10106 
10107 {
10108 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10109 vinfos[0].jointtype = 1;
10110 vinfos[0].foffset = j9;
10111 vinfos[0].indices[0] = _ij9[0];
10112 vinfos[0].indices[1] = _ij9[1];
10113 vinfos[0].maxsolutions = _nj9;
10114 vinfos[1].jointtype = 1;
10115 vinfos[1].foffset = j10;
10116 vinfos[1].indices[0] = _ij10[0];
10117 vinfos[1].indices[1] = _ij10[1];
10118 vinfos[1].maxsolutions = _nj10;
10119 vinfos[2].jointtype = 1;
10120 vinfos[2].foffset = j11;
10121 vinfos[2].indices[0] = _ij11[0];
10122 vinfos[2].indices[1] = _ij11[1];
10123 vinfos[2].maxsolutions = _nj11;
10124 vinfos[3].jointtype = 1;
10125 vinfos[3].foffset = j12;
10126 vinfos[3].indices[0] = _ij12[0];
10127 vinfos[3].indices[1] = _ij12[1];
10128 vinfos[3].maxsolutions = _nj12;
10129 vinfos[4].jointtype = 1;
10130 vinfos[4].foffset = j13;
10131 vinfos[4].indices[0] = _ij13[0];
10132 vinfos[4].indices[1] = _ij13[1];
10133 vinfos[4].maxsolutions = _nj13;
10134 vinfos[5].jointtype = 1;
10135 vinfos[5].foffset = j14;
10136 vinfos[5].indices[0] = _ij14[0];
10137 vinfos[5].indices[1] = _ij14[1];
10138 vinfos[5].maxsolutions = _nj14;
10139 std::vector<int> vfree(0);
10140 solutions.AddSolution(vinfos,vfree);
10141 }
10142 }
10143 }
10144 
10145 }
10146 
10147 }
10148 }
10149 }
10150 
10151 } else
10152 {
10153 if( 1 )
10154 {
10155 continue;
10156 
10157 } else
10158 {
10159 }
10160 }
10161 }
10162 }
10163 }
10164 }
10165 
10166 } else
10167 {
10168 {
10169 IkReal j11array[1], cj11array[1], sj11array[1];
10170 bool j11valid[1]={false};
10171 _nj11 = 1;
10172 IkReal x2313=((IkReal(4.00000000000000))*(cj13));
10173 IkReal x2314=((npy)*(sj14));
10174 IkReal x2315=((IkReal(4.00000000000000))*(sj13));
10175 IkReal x2316=((cj14)*(npx));
10176 if( IKabs(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x2313)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(-1.00000000000000))*(x2315)*(x2316)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((x2314)*(x2315))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x2315)))+(((IkReal(-1.00000000000000))*(x2313)*(x2314)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x2313)*(x2316))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x2313)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(-1.00000000000000))*(x2315)*(x2316)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((x2314)*(x2315)))))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x2315)))+(((IkReal(-1.00000000000000))*(x2313)*(x2314)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x2313)*(x2316)))))-1) <= IKFAST_SINCOS_THRESH )
10177     continue;
10178 j11array[0]=IKatan2(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x2313)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(-1.00000000000000))*(x2315)*(x2316)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((x2314)*(x2315)))))), ((IkReal(-0.940000000000000))+(((npz)*(x2315)))+(((IkReal(-1.00000000000000))*(x2313)*(x2314)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x2313)*(x2316)))));
10179 sj11array[0]=IKsin(j11array[0]);
10180 cj11array[0]=IKcos(j11array[0]);
10181 if( j11array[0] > IKPI )
10182 {
10183     j11array[0]-=IK2PI;
10184 }
10185 else if( j11array[0] < -IKPI )
10186 {    j11array[0]+=IK2PI;
10187 }
10188 j11valid[0] = true;
10189 for(int ij11 = 0; ij11 < 1; ++ij11)
10190 {
10191 if( !j11valid[ij11] )
10192 {
10193     continue;
10194 }
10195 _ij11[0] = ij11; _ij11[1] = -1;
10196 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
10197 {
10198 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
10199 {
10200     j11valid[iij11]=false; _ij11[1] = iij11; break; 
10201 }
10202 }
10203 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
10204 {
10205 IkReal evalcond[3];
10206 IkReal x2317=IKsin(j11);
10207 IkReal x2318=((IkReal(1.00000000000000))*(sj13));
10208 IkReal x2319=((cj14)*(npx));
10209 IkReal x2320=((npy)*(sj14));
10210 IkReal x2321=((IkReal(0.250000000000000))*(x2317));
10211 evalcond[0]=((((IkReal(0.0950000000000000))*(cj12)))+(((cj14)*(npy)))+(((IkReal(-0.0300000000000000))*(sj12)))+(((npx)*(sj14)))+(((sj12)*(x2321))));
10212 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(x2319)))+(((IkReal(-1.00000000000000))*(npz)*(x2318)))+(((cj13)*(x2320))));
10213 evalcond[2]=((((IkReal(-1.00000000000000))*(x2318)*(x2319)))+(((IkReal(0.0950000000000000))*(sj12)))+(((cj13)*(npz)))+(((IkReal(0.0300000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(cj12)*(x2321)))+(((IkReal(0.0900000000000000))*(sj13)))+(((sj13)*(x2320))));
10214 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
10215 {
10216 continue;
10217 }
10218 }
10219 
10220 {
10221 IkReal dummyeval[1];
10222 IkReal gconst46;
10223 gconst46=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
10224 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
10225 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10226 {
10227 {
10228 IkReal dummyeval[1];
10229 IkReal gconst47;
10230 gconst47=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
10231 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
10232 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10233 {
10234 {
10235 IkReal evalcond[9];
10236 IkReal x2322=((r00)*(sj9));
10237 IkReal x2323=((IkReal(1.00000000000000))*(sj13));
10238 IkReal x2324=((cj13)*(sj14));
10239 IkReal x2325=((cj9)*(sj14));
10240 IkReal x2326=((cj13)*(r02));
10241 IkReal x2327=((sj13)*(sj14));
10242 IkReal x2328=((r01)*(sj9));
10243 IkReal x2329=((cj9)*(sj13));
10244 IkReal x2330=((IkReal(1.00000000000000))*(cj9));
10245 IkReal x2331=((cj14)*(r10));
10246 IkReal x2332=((cj14)*(npx));
10247 IkReal x2333=((IkReal(1.00000000000000))*(cj13));
10248 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
10249 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
10250 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x2332)*(x2333)))+(((npy)*(x2324)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x2323))));
10251 evalcond[3]=((((sj14)*(x2322)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2330)))+(((cj14)*(x2328)))+(((IkReal(-1.00000000000000))*(r10)*(x2325))));
10252 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2323)))+(((r21)*(x2327)))+(((cj13)*(r22))));
10253 evalcond[5]=((IkReal(0.0950000000000000))+(((npy)*(x2327)))+(((cj13)*(npz)))+(((IkReal(-1.00000000000000))*(x2323)*(x2332)))+(((IkReal(0.0900000000000000))*(sj13))));
10254 evalcond[6]=((((r12)*(x2329)))+(((IkReal(-1.00000000000000))*(cj14)*(x2322)*(x2333)))+(((cj13)*(cj9)*(x2331)))+(((IkReal(-1.00000000000000))*(r11)*(x2324)*(x2330)))+(((x2324)*(x2328)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2323))));
10255 evalcond[7]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r11)*(x2323)*(x2325)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x2330)))+(((x2329)*(x2331)))+(((x2327)*(x2328)))+(((IkReal(-1.00000000000000))*(cj14)*(x2322)*(x2323)))+(((sj9)*(x2326))));
10256 evalcond[8]=((((sj13)*(sj9)*(x2331)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x2323)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2333)))+(((cj14)*(r00)*(x2329)))+(((IkReal(-1.00000000000000))*(r01)*(x2323)*(x2325)))+(((IkReal(-1.00000000000000))*(x2326)*(x2330))));
10257 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  )
10258 {
10259 {
10260 IkReal dummyeval[1];
10261 IkReal gconst48;
10262 gconst48=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
10263 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
10264 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10265 {
10266 {
10267 IkReal dummyeval[1];
10268 IkReal gconst49;
10269 gconst49=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
10270 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
10271 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10272 {
10273 continue;
10274 
10275 } else
10276 {
10277 {
10278 IkReal j10array[1], cj10array[1], sj10array[1];
10279 bool j10valid[1]={false};
10280 _nj10 = 1;
10281 IkReal x2334=((IkReal(1.00000000000000))*(cj11));
10282 IkReal x2335=((sj11)*(sj14));
10283 IkReal x2336=((r10)*(sj9));
10284 IkReal x2337=((cj9)*(r00));
10285 IkReal x2338=((cj14)*(sj11));
10286 IkReal x2339=((r11)*(sj9));
10287 IkReal x2340=((cj14)*(cj9)*(r01));
10288 if( IKabs(((gconst49)*(((((cj11)*(cj14)*(r21)))+(((cj9)*(r01)*(x2338)))+(((cj11)*(r20)*(sj14)))+(((x2335)*(x2337)))+(((x2335)*(x2336)))+(((x2338)*(x2339))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((r21)*(x2338)))+(((IkReal(-1.00000000000000))*(sj14)*(x2334)*(x2337)))+(((IkReal(-1.00000000000000))*(sj14)*(x2334)*(x2336)))+(((IkReal(-1.00000000000000))*(x2334)*(x2340)))+(((IkReal(-1.00000000000000))*(cj14)*(x2334)*(x2339)))+(((r20)*(x2335))))))) < IKFAST_ATAN2_MAGTHRESH )
10289     continue;
10290 j10array[0]=IKatan2(((gconst49)*(((((cj11)*(cj14)*(r21)))+(((cj9)*(r01)*(x2338)))+(((cj11)*(r20)*(sj14)))+(((x2335)*(x2337)))+(((x2335)*(x2336)))+(((x2338)*(x2339)))))), ((gconst49)*(((((r21)*(x2338)))+(((IkReal(-1.00000000000000))*(sj14)*(x2334)*(x2337)))+(((IkReal(-1.00000000000000))*(sj14)*(x2334)*(x2336)))+(((IkReal(-1.00000000000000))*(x2334)*(x2340)))+(((IkReal(-1.00000000000000))*(cj14)*(x2334)*(x2339)))+(((r20)*(x2335)))))));
10291 sj10array[0]=IKsin(j10array[0]);
10292 cj10array[0]=IKcos(j10array[0]);
10293 if( j10array[0] > IKPI )
10294 {
10295     j10array[0]-=IK2PI;
10296 }
10297 else if( j10array[0] < -IKPI )
10298 {    j10array[0]+=IK2PI;
10299 }
10300 j10valid[0] = true;
10301 for(int ij10 = 0; ij10 < 1; ++ij10)
10302 {
10303 if( !j10valid[ij10] )
10304 {
10305     continue;
10306 }
10307 _ij10[0] = ij10; _ij10[1] = -1;
10308 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10309 {
10310 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10311 {
10312     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10313 }
10314 }
10315 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10316 {
10317 IkReal evalcond[4];
10318 IkReal x2341=IKsin(j10);
10319 IkReal x2342=IKcos(j10);
10320 IkReal x2343=((cj13)*(sj14));
10321 IkReal x2344=((cj13)*(cj14));
10322 IkReal x2345=((r10)*(sj9));
10323 IkReal x2346=((IkReal(1.00000000000000))*(cj9));
10324 IkReal x2347=((sj11)*(x2341));
10325 IkReal x2348=((IkReal(1.00000000000000))*(x2342));
10326 IkReal x2349=((cj11)*(x2341));
10327 IkReal x2350=((IkReal(1.00000000000000))*(r11)*(sj9));
10328 IkReal x2351=((cj11)*(x2348));
10329 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x2349)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x2348))));
10330 evalcond[1]=((x2347)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x2344)))+(((r21)*(x2343)))+(((IkReal(-1.00000000000000))*(x2351))));
10331 evalcond[2]=((x2347)+(((IkReal(-1.00000000000000))*(sj14)*(x2345)))+(((IkReal(-1.00000000000000))*(cj14)*(x2350)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2346)))+(((IkReal(-1.00000000000000))*(x2351)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2346))));
10332 evalcond[3]=((x2349)+(((cj9)*(r00)*(x2344)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x2343)*(x2346)))+(((x2344)*(x2345)))+(((IkReal(-1.00000000000000))*(x2343)*(x2350)))+(((r12)*(sj13)*(sj9)))+(((sj11)*(x2342))));
10333 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10334 {
10335 continue;
10336 }
10337 }
10338 
10339 {
10340 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10341 vinfos[0].jointtype = 1;
10342 vinfos[0].foffset = j9;
10343 vinfos[0].indices[0] = _ij9[0];
10344 vinfos[0].indices[1] = _ij9[1];
10345 vinfos[0].maxsolutions = _nj9;
10346 vinfos[1].jointtype = 1;
10347 vinfos[1].foffset = j10;
10348 vinfos[1].indices[0] = _ij10[0];
10349 vinfos[1].indices[1] = _ij10[1];
10350 vinfos[1].maxsolutions = _nj10;
10351 vinfos[2].jointtype = 1;
10352 vinfos[2].foffset = j11;
10353 vinfos[2].indices[0] = _ij11[0];
10354 vinfos[2].indices[1] = _ij11[1];
10355 vinfos[2].maxsolutions = _nj11;
10356 vinfos[3].jointtype = 1;
10357 vinfos[3].foffset = j12;
10358 vinfos[3].indices[0] = _ij12[0];
10359 vinfos[3].indices[1] = _ij12[1];
10360 vinfos[3].maxsolutions = _nj12;
10361 vinfos[4].jointtype = 1;
10362 vinfos[4].foffset = j13;
10363 vinfos[4].indices[0] = _ij13[0];
10364 vinfos[4].indices[1] = _ij13[1];
10365 vinfos[4].maxsolutions = _nj13;
10366 vinfos[5].jointtype = 1;
10367 vinfos[5].foffset = j14;
10368 vinfos[5].indices[0] = _ij14[0];
10369 vinfos[5].indices[1] = _ij14[1];
10370 vinfos[5].maxsolutions = _nj14;
10371 std::vector<int> vfree(0);
10372 solutions.AddSolution(vinfos,vfree);
10373 }
10374 }
10375 }
10376 
10377 }
10378 
10379 }
10380 
10381 } else
10382 {
10383 {
10384 IkReal j10array[1], cj10array[1], sj10array[1];
10385 bool j10valid[1]={false};
10386 _nj10 = 1;
10387 IkReal x2352=((cj11)*(r20));
10388 IkReal x2353=((IkReal(1.00000000000000))*(cj13));
10389 IkReal x2354=((r21)*(sj14));
10390 IkReal x2355=((r22)*(sj13));
10391 IkReal x2356=((r20)*(sj11));
10392 IkReal x2357=((cj14)*(r21));
10393 if( IKabs(((gconst48)*(((((cj11)*(x2357)))+(((IkReal(-1.00000000000000))*(sj11)*(x2353)*(x2354)))+(((sj11)*(x2355)))+(((cj13)*(cj14)*(x2356)))+(((sj14)*(x2352))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((sj11)*(x2357)))+(((cj11)*(cj13)*(x2354)))+(((IkReal(-1.00000000000000))*(cj11)*(x2355)))+(((IkReal(-1.00000000000000))*(cj14)*(x2352)*(x2353)))+(((sj14)*(x2356))))))) < IKFAST_ATAN2_MAGTHRESH )
10394     continue;
10395 j10array[0]=IKatan2(((gconst48)*(((((cj11)*(x2357)))+(((IkReal(-1.00000000000000))*(sj11)*(x2353)*(x2354)))+(((sj11)*(x2355)))+(((cj13)*(cj14)*(x2356)))+(((sj14)*(x2352)))))), ((gconst48)*(((((sj11)*(x2357)))+(((cj11)*(cj13)*(x2354)))+(((IkReal(-1.00000000000000))*(cj11)*(x2355)))+(((IkReal(-1.00000000000000))*(cj14)*(x2352)*(x2353)))+(((sj14)*(x2356)))))));
10396 sj10array[0]=IKsin(j10array[0]);
10397 cj10array[0]=IKcos(j10array[0]);
10398 if( j10array[0] > IKPI )
10399 {
10400     j10array[0]-=IK2PI;
10401 }
10402 else if( j10array[0] < -IKPI )
10403 {    j10array[0]+=IK2PI;
10404 }
10405 j10valid[0] = true;
10406 for(int ij10 = 0; ij10 < 1; ++ij10)
10407 {
10408 if( !j10valid[ij10] )
10409 {
10410     continue;
10411 }
10412 _ij10[0] = ij10; _ij10[1] = -1;
10413 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10414 {
10415 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10416 {
10417     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10418 }
10419 }
10420 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10421 {
10422 IkReal evalcond[4];
10423 IkReal x2358=IKsin(j10);
10424 IkReal x2359=IKcos(j10);
10425 IkReal x2360=((cj13)*(sj14));
10426 IkReal x2361=((cj13)*(cj14));
10427 IkReal x2362=((r10)*(sj9));
10428 IkReal x2363=((IkReal(1.00000000000000))*(cj9));
10429 IkReal x2364=((sj11)*(x2358));
10430 IkReal x2365=((IkReal(1.00000000000000))*(x2359));
10431 IkReal x2366=((cj11)*(x2358));
10432 IkReal x2367=((IkReal(1.00000000000000))*(r11)*(sj9));
10433 IkReal x2368=((cj11)*(x2365));
10434 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x2366)))+(((IkReal(-1.00000000000000))*(sj11)*(x2365))));
10435 evalcond[1]=((x2364)+(((IkReal(-1.00000000000000))*(x2368)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x2360)))+(((IkReal(-1.00000000000000))*(r20)*(x2361))));
10436 evalcond[2]=((x2364)+(((IkReal(-1.00000000000000))*(x2368)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2363)))+(((IkReal(-1.00000000000000))*(cj14)*(x2367)))+(((IkReal(-1.00000000000000))*(sj14)*(x2362)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2363))));
10437 evalcond[3]=((((sj11)*(x2359)))+(x2366)+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x2360)*(x2363)))+(((x2361)*(x2362)))+(((cj9)*(r00)*(x2361)))+(((IkReal(-1.00000000000000))*(x2360)*(x2367)))+(((r12)*(sj13)*(sj9))));
10438 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10439 {
10440 continue;
10441 }
10442 }
10443 
10444 {
10445 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10446 vinfos[0].jointtype = 1;
10447 vinfos[0].foffset = j9;
10448 vinfos[0].indices[0] = _ij9[0];
10449 vinfos[0].indices[1] = _ij9[1];
10450 vinfos[0].maxsolutions = _nj9;
10451 vinfos[1].jointtype = 1;
10452 vinfos[1].foffset = j10;
10453 vinfos[1].indices[0] = _ij10[0];
10454 vinfos[1].indices[1] = _ij10[1];
10455 vinfos[1].maxsolutions = _nj10;
10456 vinfos[2].jointtype = 1;
10457 vinfos[2].foffset = j11;
10458 vinfos[2].indices[0] = _ij11[0];
10459 vinfos[2].indices[1] = _ij11[1];
10460 vinfos[2].maxsolutions = _nj11;
10461 vinfos[3].jointtype = 1;
10462 vinfos[3].foffset = j12;
10463 vinfos[3].indices[0] = _ij12[0];
10464 vinfos[3].indices[1] = _ij12[1];
10465 vinfos[3].maxsolutions = _nj12;
10466 vinfos[4].jointtype = 1;
10467 vinfos[4].foffset = j13;
10468 vinfos[4].indices[0] = _ij13[0];
10469 vinfos[4].indices[1] = _ij13[1];
10470 vinfos[4].maxsolutions = _nj13;
10471 vinfos[5].jointtype = 1;
10472 vinfos[5].foffset = j14;
10473 vinfos[5].indices[0] = _ij14[0];
10474 vinfos[5].indices[1] = _ij14[1];
10475 vinfos[5].maxsolutions = _nj14;
10476 std::vector<int> vfree(0);
10477 solutions.AddSolution(vinfos,vfree);
10478 }
10479 }
10480 }
10481 
10482 }
10483 
10484 }
10485 
10486 } else
10487 {
10488 IkReal x2369=((r00)*(sj9));
10489 IkReal x2370=((IkReal(1.00000000000000))*(sj13));
10490 IkReal x2371=((cj13)*(sj14));
10491 IkReal x2372=((cj9)*(sj14));
10492 IkReal x2373=((cj13)*(r02));
10493 IkReal x2374=((sj13)*(sj14));
10494 IkReal x2375=((r01)*(sj9));
10495 IkReal x2376=((cj9)*(sj13));
10496 IkReal x2377=((IkReal(1.00000000000000))*(cj9));
10497 IkReal x2378=((cj14)*(r10));
10498 IkReal x2379=((cj14)*(npx));
10499 IkReal x2380=((IkReal(1.00000000000000))*(cj13));
10500 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
10501 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
10502 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x2370)))+(((IkReal(-1.00000000000000))*(x2379)*(x2380)))+(((npy)*(x2371))));
10503 evalcond[3]=((((cj14)*(x2375)))+(((IkReal(-1.00000000000000))*(r10)*(x2372)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2377)))+(((sj14)*(x2369))));
10504 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2370)))+(((cj13)*(r22)))+(((r21)*(x2374))));
10505 evalcond[5]=((IkReal(-0.0950000000000000))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x2370)*(x2379)))+(((npy)*(x2374))));
10506 evalcond[6]=((((r12)*(x2376)))+(((x2371)*(x2375)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2370)))+(((IkReal(-1.00000000000000))*(cj14)*(x2369)*(x2380)))+(((IkReal(-1.00000000000000))*(r11)*(x2371)*(x2377)))+(((cj13)*(cj9)*(x2378))));
10507 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(x2369)*(x2370)))+(((IkReal(-1.00000000000000))*(r11)*(x2370)*(x2372)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x2377)))+(((x2374)*(x2375)))+(((sj9)*(x2373)))+(((x2376)*(x2378))));
10508 evalcond[8]=((((sj13)*(sj9)*(x2378)))+(((cj14)*(r00)*(x2376)))+(((IkReal(-1.00000000000000))*(r01)*(x2370)*(x2372)))+(((IkReal(-1.00000000000000))*(x2373)*(x2377)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2380)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x2370))));
10509 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  )
10510 {
10511 {
10512 IkReal dummyeval[1];
10513 IkReal gconst50;
10514 gconst50=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
10515 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
10516 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10517 {
10518 {
10519 IkReal dummyeval[1];
10520 IkReal gconst51;
10521 gconst51=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
10522 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
10523 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10524 {
10525 continue;
10526 
10527 } else
10528 {
10529 {
10530 IkReal j10array[1], cj10array[1], sj10array[1];
10531 bool j10valid[1]={false};
10532 _nj10 = 1;
10533 IkReal x2381=((IkReal(1.00000000000000))*(sj11));
10534 IkReal x2382=((cj14)*(r21));
10535 IkReal x2383=((IkReal(1.00000000000000))*(cj11));
10536 IkReal x2384=((r20)*(sj14));
10537 IkReal x2385=((cj9)*(r00)*(sj14));
10538 IkReal x2386=((cj14)*(r11)*(sj9));
10539 IkReal x2387=((cj14)*(cj9)*(r01));
10540 IkReal x2388=((r10)*(sj14)*(sj9));
10541 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x2381)*(x2386)))+(((IkReal(-1.00000000000000))*(x2381)*(x2388)))+(((IkReal(-1.00000000000000))*(x2381)*(x2385)))+(((IkReal(-1.00000000000000))*(x2381)*(x2387)))+(((IkReal(-1.00000000000000))*(x2382)*(x2383)))+(((IkReal(-1.00000000000000))*(x2383)*(x2384))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x2381)*(x2382)))+(((IkReal(-1.00000000000000))*(x2381)*(x2384)))+(((cj11)*(x2385)))+(((cj11)*(x2387)))+(((cj11)*(x2386)))+(((cj11)*(x2388))))))) < IKFAST_ATAN2_MAGTHRESH )
10542     continue;
10543 j10array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x2381)*(x2386)))+(((IkReal(-1.00000000000000))*(x2381)*(x2388)))+(((IkReal(-1.00000000000000))*(x2381)*(x2385)))+(((IkReal(-1.00000000000000))*(x2381)*(x2387)))+(((IkReal(-1.00000000000000))*(x2382)*(x2383)))+(((IkReal(-1.00000000000000))*(x2383)*(x2384)))))), ((gconst51)*(((((IkReal(-1.00000000000000))*(x2381)*(x2382)))+(((IkReal(-1.00000000000000))*(x2381)*(x2384)))+(((cj11)*(x2385)))+(((cj11)*(x2387)))+(((cj11)*(x2386)))+(((cj11)*(x2388)))))));
10544 sj10array[0]=IKsin(j10array[0]);
10545 cj10array[0]=IKcos(j10array[0]);
10546 if( j10array[0] > IKPI )
10547 {
10548     j10array[0]-=IK2PI;
10549 }
10550 else if( j10array[0] < -IKPI )
10551 {    j10array[0]+=IK2PI;
10552 }
10553 j10valid[0] = true;
10554 for(int ij10 = 0; ij10 < 1; ++ij10)
10555 {
10556 if( !j10valid[ij10] )
10557 {
10558     continue;
10559 }
10560 _ij10[0] = ij10; _ij10[1] = -1;
10561 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10562 {
10563 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10564 {
10565     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10566 }
10567 }
10568 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10569 {
10570 IkReal evalcond[4];
10571 IkReal x2389=IKsin(j10);
10572 IkReal x2390=IKcos(j10);
10573 IkReal x2391=((cj14)*(sj9));
10574 IkReal x2392=((IkReal(1.00000000000000))*(r11));
10575 IkReal x2393=((cj13)*(sj14));
10576 IkReal x2394=((IkReal(1.00000000000000))*(cj9));
10577 IkReal x2395=((cj13)*(cj14));
10578 IkReal x2396=((cj11)*(x2389));
10579 IkReal x2397=((sj11)*(x2390));
10580 IkReal x2398=((cj11)*(x2390));
10581 IkReal x2399=((sj11)*(x2389));
10582 IkReal x2400=((x2396)+(x2397));
10583 evalcond[0]=((x2400)+(((cj14)*(r21)))+(((r20)*(sj14))));
10584 evalcond[1]=((x2399)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2398)))+(((IkReal(-1.00000000000000))*(r20)*(x2395)))+(((r21)*(x2393))));
10585 evalcond[2]=((x2398)+(((IkReal(-1.00000000000000))*(x2399)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2394)))+(((IkReal(-1.00000000000000))*(x2391)*(x2392)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2394))));
10586 evalcond[3]=((x2400)+(((cj9)*(r02)*(sj13)))+(((cj13)*(r10)*(x2391)))+(((IkReal(-1.00000000000000))*(sj9)*(x2392)*(x2393)))+(((IkReal(-1.00000000000000))*(r01)*(x2393)*(x2394)))+(((cj9)*(r00)*(x2395)))+(((r12)*(sj13)*(sj9))));
10587 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10588 {
10589 continue;
10590 }
10591 }
10592 
10593 {
10594 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10595 vinfos[0].jointtype = 1;
10596 vinfos[0].foffset = j9;
10597 vinfos[0].indices[0] = _ij9[0];
10598 vinfos[0].indices[1] = _ij9[1];
10599 vinfos[0].maxsolutions = _nj9;
10600 vinfos[1].jointtype = 1;
10601 vinfos[1].foffset = j10;
10602 vinfos[1].indices[0] = _ij10[0];
10603 vinfos[1].indices[1] = _ij10[1];
10604 vinfos[1].maxsolutions = _nj10;
10605 vinfos[2].jointtype = 1;
10606 vinfos[2].foffset = j11;
10607 vinfos[2].indices[0] = _ij11[0];
10608 vinfos[2].indices[1] = _ij11[1];
10609 vinfos[2].maxsolutions = _nj11;
10610 vinfos[3].jointtype = 1;
10611 vinfos[3].foffset = j12;
10612 vinfos[3].indices[0] = _ij12[0];
10613 vinfos[3].indices[1] = _ij12[1];
10614 vinfos[3].maxsolutions = _nj12;
10615 vinfos[4].jointtype = 1;
10616 vinfos[4].foffset = j13;
10617 vinfos[4].indices[0] = _ij13[0];
10618 vinfos[4].indices[1] = _ij13[1];
10619 vinfos[4].maxsolutions = _nj13;
10620 vinfos[5].jointtype = 1;
10621 vinfos[5].foffset = j14;
10622 vinfos[5].indices[0] = _ij14[0];
10623 vinfos[5].indices[1] = _ij14[1];
10624 vinfos[5].maxsolutions = _nj14;
10625 std::vector<int> vfree(0);
10626 solutions.AddSolution(vinfos,vfree);
10627 }
10628 }
10629 }
10630 
10631 }
10632 
10633 }
10634 
10635 } else
10636 {
10637 {
10638 IkReal j10array[1], cj10array[1], sj10array[1];
10639 bool j10valid[1]={false};
10640 _nj10 = 1;
10641 IkReal x2401=((cj13)*(sj11));
10642 IkReal x2402=((r21)*(sj14));
10643 IkReal x2403=((cj14)*(r20));
10644 IkReal x2404=((cj11)*(cj13));
10645 IkReal x2405=((r22)*(sj13));
10646 IkReal x2406=((r20)*(sj14));
10647 IkReal x2407=((cj14)*(r21));
10648 if( IKabs(((gconst50)*(((((cj11)*(x2406)))+(((cj11)*(x2407)))+(((x2401)*(x2402)))+(((IkReal(-1.00000000000000))*(sj11)*(x2405)))+(((IkReal(-1.00000000000000))*(x2401)*(x2403))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((x2403)*(x2404)))+(((cj11)*(x2405)))+(((IkReal(-1.00000000000000))*(x2402)*(x2404)))+(((sj11)*(x2406)))+(((sj11)*(x2407))))))) < IKFAST_ATAN2_MAGTHRESH )
10649     continue;
10650 j10array[0]=IKatan2(((gconst50)*(((((cj11)*(x2406)))+(((cj11)*(x2407)))+(((x2401)*(x2402)))+(((IkReal(-1.00000000000000))*(sj11)*(x2405)))+(((IkReal(-1.00000000000000))*(x2401)*(x2403)))))), ((gconst50)*(((((x2403)*(x2404)))+(((cj11)*(x2405)))+(((IkReal(-1.00000000000000))*(x2402)*(x2404)))+(((sj11)*(x2406)))+(((sj11)*(x2407)))))));
10651 sj10array[0]=IKsin(j10array[0]);
10652 cj10array[0]=IKcos(j10array[0]);
10653 if( j10array[0] > IKPI )
10654 {
10655     j10array[0]-=IK2PI;
10656 }
10657 else if( j10array[0] < -IKPI )
10658 {    j10array[0]+=IK2PI;
10659 }
10660 j10valid[0] = true;
10661 for(int ij10 = 0; ij10 < 1; ++ij10)
10662 {
10663 if( !j10valid[ij10] )
10664 {
10665     continue;
10666 }
10667 _ij10[0] = ij10; _ij10[1] = -1;
10668 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10669 {
10670 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10671 {
10672     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10673 }
10674 }
10675 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10676 {
10677 IkReal evalcond[4];
10678 IkReal x2408=IKsin(j10);
10679 IkReal x2409=IKcos(j10);
10680 IkReal x2410=((cj14)*(sj9));
10681 IkReal x2411=((IkReal(1.00000000000000))*(r11));
10682 IkReal x2412=((cj13)*(sj14));
10683 IkReal x2413=((IkReal(1.00000000000000))*(cj9));
10684 IkReal x2414=((cj13)*(cj14));
10685 IkReal x2415=((cj11)*(x2408));
10686 IkReal x2416=((sj11)*(x2409));
10687 IkReal x2417=((cj11)*(x2409));
10688 IkReal x2418=((sj11)*(x2408));
10689 IkReal x2419=((x2415)+(x2416));
10690 evalcond[0]=((x2419)+(((cj14)*(r21)))+(((r20)*(sj14))));
10691 evalcond[1]=((x2418)+(((r21)*(x2412)))+(((IkReal(-1.00000000000000))*(x2417)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x2414))));
10692 evalcond[2]=((x2417)+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2413)))+(((IkReal(-1.00000000000000))*(x2418)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x2410)*(x2411)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2413))));
10693 evalcond[3]=((((cj13)*(r10)*(x2410)))+(x2419)+(((cj9)*(r00)*(x2414)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x2412)*(x2413)))+(((r12)*(sj13)*(sj9)))+(((IkReal(-1.00000000000000))*(sj9)*(x2411)*(x2412))));
10694 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10695 {
10696 continue;
10697 }
10698 }
10699 
10700 {
10701 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10702 vinfos[0].jointtype = 1;
10703 vinfos[0].foffset = j9;
10704 vinfos[0].indices[0] = _ij9[0];
10705 vinfos[0].indices[1] = _ij9[1];
10706 vinfos[0].maxsolutions = _nj9;
10707 vinfos[1].jointtype = 1;
10708 vinfos[1].foffset = j10;
10709 vinfos[1].indices[0] = _ij10[0];
10710 vinfos[1].indices[1] = _ij10[1];
10711 vinfos[1].maxsolutions = _nj10;
10712 vinfos[2].jointtype = 1;
10713 vinfos[2].foffset = j11;
10714 vinfos[2].indices[0] = _ij11[0];
10715 vinfos[2].indices[1] = _ij11[1];
10716 vinfos[2].maxsolutions = _nj11;
10717 vinfos[3].jointtype = 1;
10718 vinfos[3].foffset = j12;
10719 vinfos[3].indices[0] = _ij12[0];
10720 vinfos[3].indices[1] = _ij12[1];
10721 vinfos[3].maxsolutions = _nj12;
10722 vinfos[4].jointtype = 1;
10723 vinfos[4].foffset = j13;
10724 vinfos[4].indices[0] = _ij13[0];
10725 vinfos[4].indices[1] = _ij13[1];
10726 vinfos[4].maxsolutions = _nj13;
10727 vinfos[5].jointtype = 1;
10728 vinfos[5].foffset = j14;
10729 vinfos[5].indices[0] = _ij14[0];
10730 vinfos[5].indices[1] = _ij14[1];
10731 vinfos[5].maxsolutions = _nj14;
10732 std::vector<int> vfree(0);
10733 solutions.AddSolution(vinfos,vfree);
10734 }
10735 }
10736 }
10737 
10738 }
10739 
10740 }
10741 
10742 } else
10743 {
10744 IkReal x2420=((cj9)*(r10));
10745 IkReal x2421=((cj13)*(cj14));
10746 IkReal x2422=((sj14)*(sj9));
10747 IkReal x2423=((IkReal(1.00000000000000))*(sj14));
10748 IkReal x2424=((cj9)*(sj13));
10749 IkReal x2425=((r02)*(sj9));
10750 IkReal x2426=((cj13)*(cj9));
10751 IkReal x2427=((cj14)*(r01));
10752 IkReal x2428=((IkReal(1.00000000000000))*(npx));
10753 IkReal x2429=((cj14)*(sj13));
10754 IkReal x2430=((IkReal(1.00000000000000))*(cj9));
10755 IkReal x2431=((npy)*(sj14));
10756 IkReal x2432=((IkReal(1.00000000000000))*(sj13));
10757 IkReal x2433=((IkReal(1.00000000000000))*(cj14)*(sj9));
10758 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
10759 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
10760 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
10761 evalcond[3]=((IkReal(0.235000000000000))+(((cj13)*(x2431)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x2432)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x2421)*(x2428))));
10762 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2430)))+(((IkReal(-1.00000000000000))*(x2420)*(x2423)))+(((r00)*(x2422)))+(((sj9)*(x2427))));
10763 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x2428)*(x2429)))+(((sj13)*(x2431)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
10764 evalcond[6]=((((IkReal(-1.00000000000000))*(x2427)*(x2430)))+(((IkReal(-1.00000000000000))*(r10)*(x2422)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x2423)))+(((IkReal(-1.00000000000000))*(r11)*(x2433))));
10765 evalcond[7]=((((IkReal(-1.00000000000000))*(x2425)*(x2432)))+(((x2420)*(x2421)))+(((cj13)*(r01)*(x2422)))+(((r12)*(x2424)))+(((IkReal(-1.00000000000000))*(r11)*(x2423)*(x2426)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2421))));
10766 evalcond[8]=((((IkReal(-1.00000000000000))*(r12)*(x2426)))+(((x2420)*(x2429)))+(((r01)*(sj13)*(x2422)))+(((cj13)*(x2425)))+(((IkReal(-1.00000000000000))*(r11)*(x2423)*(x2424)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2429))));
10767 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  )
10768 {
10769 {
10770 IkReal dummyeval[1];
10771 IkReal gconst52;
10772 gconst52=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
10773 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
10774 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10775 {
10776 {
10777 IkReal dummyeval[1];
10778 IkReal gconst53;
10779 gconst53=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
10780 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
10781 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
10782 {
10783 continue;
10784 
10785 } else
10786 {
10787 {
10788 IkReal j10array[1], cj10array[1], sj10array[1];
10789 bool j10valid[1]={false};
10790 _nj10 = 1;
10791 IkReal x2434=((cj13)*(sj14));
10792 IkReal x2435=((IkReal(1.00000000000000))*(cj11));
10793 IkReal x2436=((r11)*(sj9));
10794 IkReal x2437=((IkReal(1.00000000000000))*(sj11));
10795 IkReal x2438=((cj13)*(cj14));
10796 IkReal x2439=((cj11)*(sj13));
10797 IkReal x2440=((r12)*(sj9));
10798 IkReal x2441=((sj11)*(sj13));
10799 IkReal x2442=((cj9)*(r02));
10800 IkReal x2443=((cj9)*(r01));
10801 IkReal x2444=((r10)*(sj9));
10802 IkReal x2445=((cj9)*(r00));
10803 if( IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(x2434)*(x2435)*(x2436)))+(((IkReal(-1.00000000000000))*(r20)*(x2437)*(x2438)))+(((cj11)*(x2438)*(x2445)))+(((cj11)*(x2438)*(x2444)))+(((r21)*(sj11)*(x2434)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2437)))+(((IkReal(-1.00000000000000))*(x2434)*(x2435)*(x2443)))+(((x2439)*(x2440)))+(((x2439)*(x2442))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((sj11)*(x2438)*(x2444)))+(((sj11)*(x2438)*(x2445)))+(((IkReal(-1.00000000000000))*(x2434)*(x2436)*(x2437)))+(((x2440)*(x2441)))+(((IkReal(-1.00000000000000))*(r21)*(x2434)*(x2435)))+(((r22)*(x2439)))+(((IkReal(-1.00000000000000))*(x2434)*(x2437)*(x2443)))+(((cj11)*(r20)*(x2438)))+(((x2441)*(x2442))))))) < IKFAST_ATAN2_MAGTHRESH )
10804     continue;
10805 j10array[0]=IKatan2(((gconst53)*(((((IkReal(-1.00000000000000))*(x2434)*(x2435)*(x2436)))+(((IkReal(-1.00000000000000))*(r20)*(x2437)*(x2438)))+(((cj11)*(x2438)*(x2445)))+(((cj11)*(x2438)*(x2444)))+(((r21)*(sj11)*(x2434)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2437)))+(((IkReal(-1.00000000000000))*(x2434)*(x2435)*(x2443)))+(((x2439)*(x2440)))+(((x2439)*(x2442)))))), ((gconst53)*(((((sj11)*(x2438)*(x2444)))+(((sj11)*(x2438)*(x2445)))+(((IkReal(-1.00000000000000))*(x2434)*(x2436)*(x2437)))+(((x2440)*(x2441)))+(((IkReal(-1.00000000000000))*(r21)*(x2434)*(x2435)))+(((r22)*(x2439)))+(((IkReal(-1.00000000000000))*(x2434)*(x2437)*(x2443)))+(((cj11)*(r20)*(x2438)))+(((x2441)*(x2442)))))));
10806 sj10array[0]=IKsin(j10array[0]);
10807 cj10array[0]=IKcos(j10array[0]);
10808 if( j10array[0] > IKPI )
10809 {
10810     j10array[0]-=IK2PI;
10811 }
10812 else if( j10array[0] < -IKPI )
10813 {    j10array[0]+=IK2PI;
10814 }
10815 j10valid[0] = true;
10816 for(int ij10 = 0; ij10 < 1; ++ij10)
10817 {
10818 if( !j10valid[ij10] )
10819 {
10820     continue;
10821 }
10822 _ij10[0] = ij10; _ij10[1] = -1;
10823 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10824 {
10825 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10826 {
10827     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10828 }
10829 }
10830 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10831 {
10832 IkReal evalcond[4];
10833 IkReal x2446=IKsin(j10);
10834 IkReal x2447=IKcos(j10);
10835 IkReal x2448=((IkReal(1.00000000000000))*(sj13));
10836 IkReal x2449=((r11)*(sj9));
10837 IkReal x2450=((cj9)*(r01));
10838 IkReal x2451=((r21)*(sj14));
10839 IkReal x2452=((cj9)*(r02));
10840 IkReal x2453=((sj13)*(sj9));
10841 IkReal x2454=((cj14)*(r10));
10842 IkReal x2455=((IkReal(1.00000000000000))*(cj13));
10843 IkReal x2456=((cj14)*(r20));
10844 IkReal x2457=((cj11)*(x2446));
10845 IkReal x2458=((sj11)*(x2447));
10846 IkReal x2459=((sj14)*(x2455));
10847 IkReal x2460=((sj11)*(x2446));
10848 IkReal x2461=((cj11)*(x2447));
10849 IkReal x2462=((cj14)*(cj9)*(r00));
10850 IkReal x2463=((x2458)+(x2457));
10851 evalcond[0]=((x2460)+(((IkReal(-1.00000000000000))*(x2461)))+(((cj13)*(x2451)))+(((IkReal(-1.00000000000000))*(r22)*(x2448)))+(((IkReal(-1.00000000000000))*(x2455)*(x2456))));
10852 evalcond[1]=((x2463)+(((sj13)*(x2451)))+(((IkReal(-1.00000000000000))*(x2448)*(x2456)))+(((cj13)*(r22))));
10853 evalcond[2]=((((IkReal(-1.00000000000000))*(x2450)*(x2459)))+(x2463)+(((sj13)*(x2452)))+(((cj13)*(x2462)))+(((IkReal(-1.00000000000000))*(x2449)*(x2459)))+(((r12)*(x2453)))+(((cj13)*(sj9)*(x2454))));
10854 evalcond[3]=((x2461)+(((IkReal(-1.00000000000000))*(x2452)*(x2455)))+(((x2453)*(x2454)))+(((IkReal(-1.00000000000000))*(x2460)))+(((IkReal(-1.00000000000000))*(sj14)*(x2448)*(x2450)))+(((sj13)*(x2462)))+(((IkReal(-1.00000000000000))*(sj14)*(x2448)*(x2449)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2455))));
10855 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10856 {
10857 continue;
10858 }
10859 }
10860 
10861 {
10862 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10863 vinfos[0].jointtype = 1;
10864 vinfos[0].foffset = j9;
10865 vinfos[0].indices[0] = _ij9[0];
10866 vinfos[0].indices[1] = _ij9[1];
10867 vinfos[0].maxsolutions = _nj9;
10868 vinfos[1].jointtype = 1;
10869 vinfos[1].foffset = j10;
10870 vinfos[1].indices[0] = _ij10[0];
10871 vinfos[1].indices[1] = _ij10[1];
10872 vinfos[1].maxsolutions = _nj10;
10873 vinfos[2].jointtype = 1;
10874 vinfos[2].foffset = j11;
10875 vinfos[2].indices[0] = _ij11[0];
10876 vinfos[2].indices[1] = _ij11[1];
10877 vinfos[2].maxsolutions = _nj11;
10878 vinfos[3].jointtype = 1;
10879 vinfos[3].foffset = j12;
10880 vinfos[3].indices[0] = _ij12[0];
10881 vinfos[3].indices[1] = _ij12[1];
10882 vinfos[3].maxsolutions = _nj12;
10883 vinfos[4].jointtype = 1;
10884 vinfos[4].foffset = j13;
10885 vinfos[4].indices[0] = _ij13[0];
10886 vinfos[4].indices[1] = _ij13[1];
10887 vinfos[4].maxsolutions = _nj13;
10888 vinfos[5].jointtype = 1;
10889 vinfos[5].foffset = j14;
10890 vinfos[5].indices[0] = _ij14[0];
10891 vinfos[5].indices[1] = _ij14[1];
10892 vinfos[5].maxsolutions = _nj14;
10893 std::vector<int> vfree(0);
10894 solutions.AddSolution(vinfos,vfree);
10895 }
10896 }
10897 }
10898 
10899 }
10900 
10901 }
10902 
10903 } else
10904 {
10905 {
10906 IkReal j10array[1], cj10array[1], sj10array[1];
10907 bool j10valid[1]={false};
10908 _nj10 = 1;
10909 IkReal x2464=((cj13)*(sj11));
10910 IkReal x2465=((r21)*(sj14));
10911 IkReal x2466=((cj11)*(cj13));
10912 IkReal x2467=((cj11)*(sj13));
10913 IkReal x2468=((sj11)*(sj13));
10914 IkReal x2469=((IkReal(1.00000000000000))*(cj14)*(r20));
10915 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x2464)*(x2469)))+(((x2464)*(x2465)))+(((x2465)*(x2467)))+(((r22)*(x2466)))+(((IkReal(-1.00000000000000))*(x2467)*(x2469)))+(((IkReal(-1.00000000000000))*(r22)*(x2468))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((cj14)*(r20)*(x2466)))+(((IkReal(-1.00000000000000))*(x2468)*(x2469)))+(((x2465)*(x2468)))+(((IkReal(-1.00000000000000))*(x2465)*(x2466)))+(((r22)*(x2464)))+(((r22)*(x2467))))))) < IKFAST_ATAN2_MAGTHRESH )
10916     continue;
10917 j10array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(x2464)*(x2469)))+(((x2464)*(x2465)))+(((x2465)*(x2467)))+(((r22)*(x2466)))+(((IkReal(-1.00000000000000))*(x2467)*(x2469)))+(((IkReal(-1.00000000000000))*(r22)*(x2468)))))), ((gconst52)*(((((cj14)*(r20)*(x2466)))+(((IkReal(-1.00000000000000))*(x2468)*(x2469)))+(((x2465)*(x2468)))+(((IkReal(-1.00000000000000))*(x2465)*(x2466)))+(((r22)*(x2464)))+(((r22)*(x2467)))))));
10918 sj10array[0]=IKsin(j10array[0]);
10919 cj10array[0]=IKcos(j10array[0]);
10920 if( j10array[0] > IKPI )
10921 {
10922     j10array[0]-=IK2PI;
10923 }
10924 else if( j10array[0] < -IKPI )
10925 {    j10array[0]+=IK2PI;
10926 }
10927 j10valid[0] = true;
10928 for(int ij10 = 0; ij10 < 1; ++ij10)
10929 {
10930 if( !j10valid[ij10] )
10931 {
10932     continue;
10933 }
10934 _ij10[0] = ij10; _ij10[1] = -1;
10935 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
10936 {
10937 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
10938 {
10939     j10valid[iij10]=false; _ij10[1] = iij10; break; 
10940 }
10941 }
10942 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
10943 {
10944 IkReal evalcond[4];
10945 IkReal x2470=IKsin(j10);
10946 IkReal x2471=IKcos(j10);
10947 IkReal x2472=((IkReal(1.00000000000000))*(sj13));
10948 IkReal x2473=((r11)*(sj9));
10949 IkReal x2474=((cj9)*(r01));
10950 IkReal x2475=((r21)*(sj14));
10951 IkReal x2476=((cj9)*(r02));
10952 IkReal x2477=((sj13)*(sj9));
10953 IkReal x2478=((cj14)*(r10));
10954 IkReal x2479=((IkReal(1.00000000000000))*(cj13));
10955 IkReal x2480=((cj14)*(r20));
10956 IkReal x2481=((cj11)*(x2470));
10957 IkReal x2482=((sj11)*(x2471));
10958 IkReal x2483=((sj14)*(x2479));
10959 IkReal x2484=((sj11)*(x2470));
10960 IkReal x2485=((cj11)*(x2471));
10961 IkReal x2486=((cj14)*(cj9)*(r00));
10962 IkReal x2487=((x2482)+(x2481));
10963 evalcond[0]=((x2484)+(((IkReal(-1.00000000000000))*(x2485)))+(((cj13)*(x2475)))+(((IkReal(-1.00000000000000))*(r22)*(x2472)))+(((IkReal(-1.00000000000000))*(x2479)*(x2480))));
10964 evalcond[1]=((x2487)+(((IkReal(-1.00000000000000))*(x2472)*(x2480)))+(((sj13)*(x2475)))+(((cj13)*(r22))));
10965 evalcond[2]=((((r12)*(x2477)))+(x2487)+(((cj13)*(sj9)*(x2478)))+(((cj13)*(x2486)))+(((IkReal(-1.00000000000000))*(x2473)*(x2483)))+(((IkReal(-1.00000000000000))*(x2474)*(x2483)))+(((sj13)*(x2476))));
10966 evalcond[3]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2479)))+(x2485)+(((IkReal(-1.00000000000000))*(x2484)))+(((sj13)*(x2486)))+(((x2477)*(x2478)))+(((IkReal(-1.00000000000000))*(x2476)*(x2479)))+(((IkReal(-1.00000000000000))*(sj14)*(x2472)*(x2474)))+(((IkReal(-1.00000000000000))*(sj14)*(x2472)*(x2473))));
10967 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
10968 {
10969 continue;
10970 }
10971 }
10972 
10973 {
10974 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
10975 vinfos[0].jointtype = 1;
10976 vinfos[0].foffset = j9;
10977 vinfos[0].indices[0] = _ij9[0];
10978 vinfos[0].indices[1] = _ij9[1];
10979 vinfos[0].maxsolutions = _nj9;
10980 vinfos[1].jointtype = 1;
10981 vinfos[1].foffset = j10;
10982 vinfos[1].indices[0] = _ij10[0];
10983 vinfos[1].indices[1] = _ij10[1];
10984 vinfos[1].maxsolutions = _nj10;
10985 vinfos[2].jointtype = 1;
10986 vinfos[2].foffset = j11;
10987 vinfos[2].indices[0] = _ij11[0];
10988 vinfos[2].indices[1] = _ij11[1];
10989 vinfos[2].maxsolutions = _nj11;
10990 vinfos[3].jointtype = 1;
10991 vinfos[3].foffset = j12;
10992 vinfos[3].indices[0] = _ij12[0];
10993 vinfos[3].indices[1] = _ij12[1];
10994 vinfos[3].maxsolutions = _nj12;
10995 vinfos[4].jointtype = 1;
10996 vinfos[4].foffset = j13;
10997 vinfos[4].indices[0] = _ij13[0];
10998 vinfos[4].indices[1] = _ij13[1];
10999 vinfos[4].maxsolutions = _nj13;
11000 vinfos[5].jointtype = 1;
11001 vinfos[5].foffset = j14;
11002 vinfos[5].indices[0] = _ij14[0];
11003 vinfos[5].indices[1] = _ij14[1];
11004 vinfos[5].maxsolutions = _nj14;
11005 std::vector<int> vfree(0);
11006 solutions.AddSolution(vinfos,vfree);
11007 }
11008 }
11009 }
11010 
11011 }
11012 
11013 }
11014 
11015 } else
11016 {
11017 IkReal x2488=((cj9)*(r10));
11018 IkReal x2489=((cj13)*(cj14));
11019 IkReal x2490=((sj14)*(sj9));
11020 IkReal x2491=((IkReal(1.00000000000000))*(sj14));
11021 IkReal x2492=((cj9)*(sj13));
11022 IkReal x2493=((r02)*(sj9));
11023 IkReal x2494=((cj13)*(cj9));
11024 IkReal x2495=((cj14)*(r01));
11025 IkReal x2496=((IkReal(1.00000000000000))*(npx));
11026 IkReal x2497=((cj14)*(sj13));
11027 IkReal x2498=((IkReal(1.00000000000000))*(cj9));
11028 IkReal x2499=((npy)*(sj14));
11029 IkReal x2500=((IkReal(1.00000000000000))*(sj13));
11030 IkReal x2501=((IkReal(1.00000000000000))*(cj14)*(sj9));
11031 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
11032 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
11033 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
11034 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x2499)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x2489)*(x2496)))+(((IkReal(-1.00000000000000))*(npz)*(x2500))));
11035 evalcond[4]=((IkReal(-1.00000000000000))+(((r00)*(x2490)))+(((sj9)*(x2495)))+(((IkReal(-1.00000000000000))*(x2488)*(x2491)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2498))));
11036 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x2496)*(x2497)))+(((cj13)*(npz)))+(((sj13)*(x2499)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(0.250000000000000))*(sj11))));
11037 evalcond[6]=((((IkReal(-1.00000000000000))*(x2495)*(x2498)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x2491)))+(((IkReal(-1.00000000000000))*(r11)*(x2501)))+(((IkReal(-1.00000000000000))*(r10)*(x2490))));
11038 evalcond[7]=((((cj13)*(r01)*(x2490)))+(((IkReal(-1.00000000000000))*(r11)*(x2491)*(x2494)))+(((x2488)*(x2489)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2489)))+(((IkReal(-1.00000000000000))*(x2493)*(x2500)))+(((r12)*(x2492))));
11039 evalcond[8]=((((r01)*(sj13)*(x2490)))+(((IkReal(-1.00000000000000))*(r12)*(x2494)))+(((x2488)*(x2497)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2497)))+(((IkReal(-1.00000000000000))*(r11)*(x2491)*(x2492)))+(((cj13)*(x2493))));
11040 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  )
11041 {
11042 {
11043 IkReal dummyeval[1];
11044 IkReal gconst54;
11045 gconst54=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
11046 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
11047 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11048 {
11049 {
11050 IkReal dummyeval[1];
11051 IkReal gconst55;
11052 gconst55=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
11053 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
11054 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11055 {
11056 continue;
11057 
11058 } else
11059 {
11060 {
11061 IkReal j10array[1], cj10array[1], sj10array[1];
11062 bool j10valid[1]={false};
11063 _nj10 = 1;
11064 IkReal x2502=((cj13)*(sj14));
11065 IkReal x2503=((IkReal(1.00000000000000))*(cj11));
11066 IkReal x2504=((r11)*(sj9));
11067 IkReal x2505=((cj11)*(sj13));
11068 IkReal x2506=((r12)*(sj9));
11069 IkReal x2507=((r10)*(sj9));
11070 IkReal x2508=((sj11)*(sj13));
11071 IkReal x2509=((cj9)*(r02));
11072 IkReal x2510=((IkReal(1.00000000000000))*(sj11));
11073 IkReal x2511=((cj9)*(r01));
11074 IkReal x2512=((cj9)*(r00));
11075 IkReal x2513=((cj13)*(cj14)*(sj11));
11076 IkReal x2514=((cj11)*(cj13)*(cj14));
11077 if( IKabs(((gconst55)*(((((x2512)*(x2514)))+(((x2505)*(x2506)))+(((x2505)*(x2509)))+(((r21)*(sj11)*(x2502)))+(((IkReal(-1.00000000000000))*(r22)*(x2508)))+(((x2507)*(x2514)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2510)))+(((IkReal(-1.00000000000000))*(x2502)*(x2503)*(x2504)))+(((IkReal(-1.00000000000000))*(x2502)*(x2503)*(x2511))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((x2512)*(x2513)))+(((r22)*(x2505)))+(((x2506)*(x2508)))+(((IkReal(-1.00000000000000))*(x2502)*(x2504)*(x2510)))+(((x2508)*(x2509)))+(((x2507)*(x2513)))+(((IkReal(-1.00000000000000))*(x2502)*(x2510)*(x2511)))+(((IkReal(-1.00000000000000))*(r21)*(x2502)*(x2503)))+(((r20)*(x2514))))))) < IKFAST_ATAN2_MAGTHRESH )
11078     continue;
11079 j10array[0]=IKatan2(((gconst55)*(((((x2512)*(x2514)))+(((x2505)*(x2506)))+(((x2505)*(x2509)))+(((r21)*(sj11)*(x2502)))+(((IkReal(-1.00000000000000))*(r22)*(x2508)))+(((x2507)*(x2514)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2510)))+(((IkReal(-1.00000000000000))*(x2502)*(x2503)*(x2504)))+(((IkReal(-1.00000000000000))*(x2502)*(x2503)*(x2511)))))), ((gconst55)*(((((x2512)*(x2513)))+(((r22)*(x2505)))+(((x2506)*(x2508)))+(((IkReal(-1.00000000000000))*(x2502)*(x2504)*(x2510)))+(((x2508)*(x2509)))+(((x2507)*(x2513)))+(((IkReal(-1.00000000000000))*(x2502)*(x2510)*(x2511)))+(((IkReal(-1.00000000000000))*(r21)*(x2502)*(x2503)))+(((r20)*(x2514)))))));
11080 sj10array[0]=IKsin(j10array[0]);
11081 cj10array[0]=IKcos(j10array[0]);
11082 if( j10array[0] > IKPI )
11083 {
11084     j10array[0]-=IK2PI;
11085 }
11086 else if( j10array[0] < -IKPI )
11087 {    j10array[0]+=IK2PI;
11088 }
11089 j10valid[0] = true;
11090 for(int ij10 = 0; ij10 < 1; ++ij10)
11091 {
11092 if( !j10valid[ij10] )
11093 {
11094     continue;
11095 }
11096 _ij10[0] = ij10; _ij10[1] = -1;
11097 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11098 {
11099 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11100 {
11101     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11102 }
11103 }
11104 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11105 {
11106 IkReal evalcond[4];
11107 IkReal x2515=IKsin(j10);
11108 IkReal x2516=IKcos(j10);
11109 IkReal x2517=((IkReal(1.00000000000000))*(sj13));
11110 IkReal x2518=((r11)*(sj9));
11111 IkReal x2519=((cj9)*(r01));
11112 IkReal x2520=((IkReal(1.00000000000000))*(cj11));
11113 IkReal x2521=((r21)*(sj14));
11114 IkReal x2522=((cj9)*(r02));
11115 IkReal x2523=((sj13)*(sj9));
11116 IkReal x2524=((cj14)*(r10));
11117 IkReal x2525=((IkReal(1.00000000000000))*(cj13));
11118 IkReal x2526=((cj14)*(r20));
11119 IkReal x2527=((sj11)*(x2515));
11120 IkReal x2528=((sj14)*(x2525));
11121 IkReal x2529=((sj11)*(x2516));
11122 IkReal x2530=((cj14)*(cj9)*(r00));
11123 IkReal x2531=((x2516)*(x2520));
11124 evalcond[0]=((x2527)+(((cj13)*(x2521)))+(((IkReal(-1.00000000000000))*(x2531)))+(((IkReal(-1.00000000000000))*(r22)*(x2517)))+(((IkReal(-1.00000000000000))*(x2525)*(x2526))));
11125 evalcond[1]=((((IkReal(-1.00000000000000))*(x2515)*(x2520)))+(((IkReal(-1.00000000000000))*(x2529)))+(((IkReal(-1.00000000000000))*(x2517)*(x2526)))+(((sj13)*(x2521)))+(((cj13)*(r22))));
11126 evalcond[2]=((x2529)+(((cj11)*(x2515)))+(((cj13)*(sj9)*(x2524)))+(((r12)*(x2523)))+(((sj13)*(x2522)))+(((cj13)*(x2530)))+(((IkReal(-1.00000000000000))*(x2519)*(x2528)))+(((IkReal(-1.00000000000000))*(x2518)*(x2528))));
11127 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x2517)*(x2518)))+(((IkReal(-1.00000000000000))*(sj14)*(x2517)*(x2519)))+(x2527)+(((sj13)*(x2530)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2525)))+(((IkReal(-1.00000000000000))*(x2531)))+(((IkReal(-1.00000000000000))*(x2522)*(x2525)))+(((x2523)*(x2524))));
11128 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11129 {
11130 continue;
11131 }
11132 }
11133 
11134 {
11135 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11136 vinfos[0].jointtype = 1;
11137 vinfos[0].foffset = j9;
11138 vinfos[0].indices[0] = _ij9[0];
11139 vinfos[0].indices[1] = _ij9[1];
11140 vinfos[0].maxsolutions = _nj9;
11141 vinfos[1].jointtype = 1;
11142 vinfos[1].foffset = j10;
11143 vinfos[1].indices[0] = _ij10[0];
11144 vinfos[1].indices[1] = _ij10[1];
11145 vinfos[1].maxsolutions = _nj10;
11146 vinfos[2].jointtype = 1;
11147 vinfos[2].foffset = j11;
11148 vinfos[2].indices[0] = _ij11[0];
11149 vinfos[2].indices[1] = _ij11[1];
11150 vinfos[2].maxsolutions = _nj11;
11151 vinfos[3].jointtype = 1;
11152 vinfos[3].foffset = j12;
11153 vinfos[3].indices[0] = _ij12[0];
11154 vinfos[3].indices[1] = _ij12[1];
11155 vinfos[3].maxsolutions = _nj12;
11156 vinfos[4].jointtype = 1;
11157 vinfos[4].foffset = j13;
11158 vinfos[4].indices[0] = _ij13[0];
11159 vinfos[4].indices[1] = _ij13[1];
11160 vinfos[4].maxsolutions = _nj13;
11161 vinfos[5].jointtype = 1;
11162 vinfos[5].foffset = j14;
11163 vinfos[5].indices[0] = _ij14[0];
11164 vinfos[5].indices[1] = _ij14[1];
11165 vinfos[5].maxsolutions = _nj14;
11166 std::vector<int> vfree(0);
11167 solutions.AddSolution(vinfos,vfree);
11168 }
11169 }
11170 }
11171 
11172 }
11173 
11174 }
11175 
11176 } else
11177 {
11178 {
11179 IkReal j10array[1], cj10array[1], sj10array[1];
11180 bool j10valid[1]={false};
11181 _nj10 = 1;
11182 IkReal x2532=((r22)*(sj11));
11183 IkReal x2533=((IkReal(1.00000000000000))*(sj11));
11184 IkReal x2534=((IkReal(1.00000000000000))*(cj11));
11185 IkReal x2535=((cj14)*(r20));
11186 IkReal x2536=((cj13)*(r21)*(sj14));
11187 IkReal x2537=((r21)*(sj13)*(sj14));
11188 if( IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(x2533)*(x2536)))+(((cj11)*(x2537)))+(((sj13)*(x2532)))+(((cj11)*(cj13)*(r22)))+(((cj13)*(sj11)*(x2535)))+(((IkReal(-1.00000000000000))*(sj13)*(x2534)*(x2535))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2534)))+(((cj11)*(x2536)))+(((IkReal(-1.00000000000000))*(cj13)*(x2534)*(x2535)))+(((sj11)*(x2537)))+(((cj13)*(x2532)))+(((IkReal(-1.00000000000000))*(sj13)*(x2533)*(x2535))))))) < IKFAST_ATAN2_MAGTHRESH )
11189     continue;
11190 j10array[0]=IKatan2(((gconst54)*(((((IkReal(-1.00000000000000))*(x2533)*(x2536)))+(((cj11)*(x2537)))+(((sj13)*(x2532)))+(((cj11)*(cj13)*(r22)))+(((cj13)*(sj11)*(x2535)))+(((IkReal(-1.00000000000000))*(sj13)*(x2534)*(x2535)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2534)))+(((cj11)*(x2536)))+(((IkReal(-1.00000000000000))*(cj13)*(x2534)*(x2535)))+(((sj11)*(x2537)))+(((cj13)*(x2532)))+(((IkReal(-1.00000000000000))*(sj13)*(x2533)*(x2535)))))));
11191 sj10array[0]=IKsin(j10array[0]);
11192 cj10array[0]=IKcos(j10array[0]);
11193 if( j10array[0] > IKPI )
11194 {
11195     j10array[0]-=IK2PI;
11196 }
11197 else if( j10array[0] < -IKPI )
11198 {    j10array[0]+=IK2PI;
11199 }
11200 j10valid[0] = true;
11201 for(int ij10 = 0; ij10 < 1; ++ij10)
11202 {
11203 if( !j10valid[ij10] )
11204 {
11205     continue;
11206 }
11207 _ij10[0] = ij10; _ij10[1] = -1;
11208 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11209 {
11210 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11211 {
11212     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11213 }
11214 }
11215 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11216 {
11217 IkReal evalcond[4];
11218 IkReal x2538=IKsin(j10);
11219 IkReal x2539=IKcos(j10);
11220 IkReal x2540=((IkReal(1.00000000000000))*(sj13));
11221 IkReal x2541=((r11)*(sj9));
11222 IkReal x2542=((cj9)*(r01));
11223 IkReal x2543=((IkReal(1.00000000000000))*(cj11));
11224 IkReal x2544=((r21)*(sj14));
11225 IkReal x2545=((cj9)*(r02));
11226 IkReal x2546=((sj13)*(sj9));
11227 IkReal x2547=((cj14)*(r10));
11228 IkReal x2548=((IkReal(1.00000000000000))*(cj13));
11229 IkReal x2549=((cj14)*(r20));
11230 IkReal x2550=((sj11)*(x2538));
11231 IkReal x2551=((sj14)*(x2548));
11232 IkReal x2552=((sj11)*(x2539));
11233 IkReal x2553=((cj14)*(cj9)*(r00));
11234 IkReal x2554=((x2539)*(x2543));
11235 evalcond[0]=((((IkReal(-1.00000000000000))*(x2548)*(x2549)))+(x2550)+(((cj13)*(x2544)))+(((IkReal(-1.00000000000000))*(r22)*(x2540)))+(((IkReal(-1.00000000000000))*(x2554))));
11236 evalcond[1]=((((IkReal(-1.00000000000000))*(x2552)))+(((sj13)*(x2544)))+(((IkReal(-1.00000000000000))*(x2538)*(x2543)))+(((IkReal(-1.00000000000000))*(x2540)*(x2549)))+(((cj13)*(r22))));
11237 evalcond[2]=((((cj13)*(x2553)))+(x2552)+(((IkReal(-1.00000000000000))*(x2542)*(x2551)))+(((cj11)*(x2538)))+(((cj13)*(sj9)*(x2547)))+(((r12)*(x2546)))+(((sj13)*(x2545)))+(((IkReal(-1.00000000000000))*(x2541)*(x2551))));
11238 evalcond[3]=((x2550)+(((IkReal(-1.00000000000000))*(x2545)*(x2548)))+(((IkReal(-1.00000000000000))*(sj14)*(x2540)*(x2542)))+(((IkReal(-1.00000000000000))*(sj14)*(x2540)*(x2541)))+(((sj13)*(x2553)))+(((x2546)*(x2547)))+(((IkReal(-1.00000000000000))*(x2554)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2548))));
11239 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11240 {
11241 continue;
11242 }
11243 }
11244 
11245 {
11246 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11247 vinfos[0].jointtype = 1;
11248 vinfos[0].foffset = j9;
11249 vinfos[0].indices[0] = _ij9[0];
11250 vinfos[0].indices[1] = _ij9[1];
11251 vinfos[0].maxsolutions = _nj9;
11252 vinfos[1].jointtype = 1;
11253 vinfos[1].foffset = j10;
11254 vinfos[1].indices[0] = _ij10[0];
11255 vinfos[1].indices[1] = _ij10[1];
11256 vinfos[1].maxsolutions = _nj10;
11257 vinfos[2].jointtype = 1;
11258 vinfos[2].foffset = j11;
11259 vinfos[2].indices[0] = _ij11[0];
11260 vinfos[2].indices[1] = _ij11[1];
11261 vinfos[2].maxsolutions = _nj11;
11262 vinfos[3].jointtype = 1;
11263 vinfos[3].foffset = j12;
11264 vinfos[3].indices[0] = _ij12[0];
11265 vinfos[3].indices[1] = _ij12[1];
11266 vinfos[3].maxsolutions = _nj12;
11267 vinfos[4].jointtype = 1;
11268 vinfos[4].foffset = j13;
11269 vinfos[4].indices[0] = _ij13[0];
11270 vinfos[4].indices[1] = _ij13[1];
11271 vinfos[4].maxsolutions = _nj13;
11272 vinfos[5].jointtype = 1;
11273 vinfos[5].foffset = j14;
11274 vinfos[5].indices[0] = _ij14[0];
11275 vinfos[5].indices[1] = _ij14[1];
11276 vinfos[5].maxsolutions = _nj14;
11277 std::vector<int> vfree(0);
11278 solutions.AddSolution(vinfos,vfree);
11279 }
11280 }
11281 }
11282 
11283 }
11284 
11285 }
11286 
11287 } else
11288 {
11289 if( 1 )
11290 {
11291 continue;
11292 
11293 } else
11294 {
11295 }
11296 }
11297 }
11298 }
11299 }
11300 }
11301 
11302 } else
11303 {
11304 {
11305 IkReal j10array[1], cj10array[1], sj10array[1];
11306 bool j10valid[1]={false};
11307 _nj10 = 1;
11308 IkReal x2555=((r21)*(sj14));
11309 IkReal x2556=((cj12)*(cj13));
11310 IkReal x2557=((sj11)*(sj13));
11311 IkReal x2558=((cj14)*(r20));
11312 IkReal x2559=((IkReal(1.00000000000000))*(sj11));
11313 IkReal x2560=((cj12)*(r22));
11314 IkReal x2561=((IkReal(1.00000000000000))*(cj11));
11315 IkReal x2562=((cj13)*(r22));
11316 IkReal x2563=((sj13)*(x2561));
11317 if( IKabs(((gconst47)*(((((sj11)*(x2556)*(x2558)))+(((IkReal(-1.00000000000000))*(x2555)*(x2563)))+(((x2557)*(x2560)))+(((IkReal(-1.00000000000000))*(x2555)*(x2556)*(x2559)))+(((IkReal(-1.00000000000000))*(x2561)*(x2562)))+(((cj11)*(sj13)*(x2558))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x2555)*(x2557)))+(((cj11)*(x2555)*(x2556)))+(((IkReal(-1.00000000000000))*(x2556)*(x2558)*(x2561)))+(((IkReal(-1.00000000000000))*(x2560)*(x2563)))+(((IkReal(-1.00000000000000))*(x2559)*(x2562)))+(((x2557)*(x2558))))))) < IKFAST_ATAN2_MAGTHRESH )
11318     continue;
11319 j10array[0]=IKatan2(((gconst47)*(((((sj11)*(x2556)*(x2558)))+(((IkReal(-1.00000000000000))*(x2555)*(x2563)))+(((x2557)*(x2560)))+(((IkReal(-1.00000000000000))*(x2555)*(x2556)*(x2559)))+(((IkReal(-1.00000000000000))*(x2561)*(x2562)))+(((cj11)*(sj13)*(x2558)))))), ((gconst47)*(((((IkReal(-1.00000000000000))*(x2555)*(x2557)))+(((cj11)*(x2555)*(x2556)))+(((IkReal(-1.00000000000000))*(x2556)*(x2558)*(x2561)))+(((IkReal(-1.00000000000000))*(x2560)*(x2563)))+(((IkReal(-1.00000000000000))*(x2559)*(x2562)))+(((x2557)*(x2558)))))));
11320 sj10array[0]=IKsin(j10array[0]);
11321 cj10array[0]=IKcos(j10array[0]);
11322 if( j10array[0] > IKPI )
11323 {
11324     j10array[0]-=IK2PI;
11325 }
11326 else if( j10array[0] < -IKPI )
11327 {    j10array[0]+=IK2PI;
11328 }
11329 j10valid[0] = true;
11330 for(int ij10 = 0; ij10 < 1; ++ij10)
11331 {
11332 if( !j10valid[ij10] )
11333 {
11334     continue;
11335 }
11336 _ij10[0] = ij10; _ij10[1] = -1;
11337 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11338 {
11339 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11340 {
11341     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11342 }
11343 }
11344 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11345 {
11346 IkReal evalcond[6];
11347 IkReal x2564=IKsin(j10);
11348 IkReal x2565=IKcos(j10);
11349 IkReal x2566=((IkReal(1.00000000000000))*(cj13));
11350 IkReal x2567=((cj9)*(r02));
11351 IkReal x2568=((IkReal(1.00000000000000))*(sj13));
11352 IkReal x2569=((r11)*(sj9));
11353 IkReal x2570=((IkReal(1.00000000000000))*(cj14));
11354 IkReal x2571=((cj9)*(r01));
11355 IkReal x2572=((r21)*(sj14));
11356 IkReal x2573=((IkReal(1.00000000000000))*(sj12));
11357 IkReal x2574=((r10)*(sj9));
11358 IkReal x2575=((cj14)*(sj13));
11359 IkReal x2576=((cj14)*(r20));
11360 IkReal x2577=((IkReal(1.00000000000000))*(sj14));
11361 IkReal x2578=((r12)*(sj9));
11362 IkReal x2579=((cj13)*(cj14));
11363 IkReal x2580=((cj9)*(r00));
11364 IkReal x2581=((sj11)*(x2564));
11365 IkReal x2582=((cj11)*(x2564));
11366 IkReal x2583=((sj11)*(x2565));
11367 IkReal x2584=((cj11)*(x2565));
11368 evalcond[0]=((((IkReal(-1.00000000000000))*(x2573)*(x2582)))+(((IkReal(-1.00000000000000))*(x2573)*(x2583)))+(((cj14)*(r21)))+(((r20)*(sj14))));
11369 evalcond[1]=((x2581)+(((IkReal(-1.00000000000000))*(r22)*(x2568)))+(((IkReal(-1.00000000000000))*(x2566)*(x2576)))+(((cj13)*(x2572)))+(((IkReal(-1.00000000000000))*(x2584))));
11370 evalcond[2]=((((cj12)*(x2582)))+(((cj12)*(x2583)))+(((IkReal(-1.00000000000000))*(x2568)*(x2576)))+(((sj13)*(x2572)))+(((cj13)*(r22))));
11371 evalcond[3]=((((IkReal(-1.00000000000000))*(x2569)*(x2570)))+(((IkReal(-1.00000000000000))*(x2573)*(x2584)))+(((sj12)*(x2581)))+(((IkReal(-1.00000000000000))*(x2570)*(x2571)))+(((IkReal(-1.00000000000000))*(x2577)*(x2580)))+(((IkReal(-1.00000000000000))*(x2574)*(x2577))));
11372 evalcond[4]=((((IkReal(-1.00000000000000))*(sj14)*(x2566)*(x2569)))+(x2583)+(x2582)+(((IkReal(-1.00000000000000))*(sj14)*(x2566)*(x2571)))+(((x2574)*(x2579)))+(((sj13)*(x2567)))+(((sj13)*(x2578)))+(((x2579)*(x2580))));
11373 evalcond[5]=((((IkReal(-1.00000000000000))*(x2566)*(x2578)))+(((cj12)*(x2584)))+(((x2574)*(x2575)))+(((IkReal(-1.00000000000000))*(x2566)*(x2567)))+(((IkReal(-1.00000000000000))*(sj14)*(x2568)*(x2569)))+(((x2575)*(x2580)))+(((IkReal(-1.00000000000000))*(sj14)*(x2568)*(x2571)))+(((IkReal(-1.00000000000000))*(cj12)*(x2581))));
11374 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  )
11375 {
11376 continue;
11377 }
11378 }
11379 
11380 {
11381 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11382 vinfos[0].jointtype = 1;
11383 vinfos[0].foffset = j9;
11384 vinfos[0].indices[0] = _ij9[0];
11385 vinfos[0].indices[1] = _ij9[1];
11386 vinfos[0].maxsolutions = _nj9;
11387 vinfos[1].jointtype = 1;
11388 vinfos[1].foffset = j10;
11389 vinfos[1].indices[0] = _ij10[0];
11390 vinfos[1].indices[1] = _ij10[1];
11391 vinfos[1].maxsolutions = _nj10;
11392 vinfos[2].jointtype = 1;
11393 vinfos[2].foffset = j11;
11394 vinfos[2].indices[0] = _ij11[0];
11395 vinfos[2].indices[1] = _ij11[1];
11396 vinfos[2].maxsolutions = _nj11;
11397 vinfos[3].jointtype = 1;
11398 vinfos[3].foffset = j12;
11399 vinfos[3].indices[0] = _ij12[0];
11400 vinfos[3].indices[1] = _ij12[1];
11401 vinfos[3].maxsolutions = _nj12;
11402 vinfos[4].jointtype = 1;
11403 vinfos[4].foffset = j13;
11404 vinfos[4].indices[0] = _ij13[0];
11405 vinfos[4].indices[1] = _ij13[1];
11406 vinfos[4].maxsolutions = _nj13;
11407 vinfos[5].jointtype = 1;
11408 vinfos[5].foffset = j14;
11409 vinfos[5].indices[0] = _ij14[0];
11410 vinfos[5].indices[1] = _ij14[1];
11411 vinfos[5].maxsolutions = _nj14;
11412 std::vector<int> vfree(0);
11413 solutions.AddSolution(vinfos,vfree);
11414 }
11415 }
11416 }
11417 
11418 }
11419 
11420 }
11421 
11422 } else
11423 {
11424 {
11425 IkReal j10array[1], cj10array[1], sj10array[1];
11426 bool j10valid[1]={false};
11427 _nj10 = 1;
11428 IkReal x2585=((cj11)*(sj12));
11429 IkReal x2586=((r22)*(sj13));
11430 IkReal x2587=((r20)*(sj14));
11431 IkReal x2588=((cj14)*(sj11));
11432 IkReal x2589=((cj13)*(r20));
11433 IkReal x2590=((sj11)*(sj12));
11434 IkReal x2591=((cj13)*(r21)*(sj14));
11435 if( IKabs(((gconst46)*(((((cj11)*(cj14)*(r21)))+(((x2586)*(x2590)))+(((IkReal(-1.00000000000000))*(x2590)*(x2591)))+(((sj12)*(x2588)*(x2589)))+(((cj11)*(x2587))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x2585)*(x2589)))+(((sj11)*(x2587)))+(((IkReal(-1.00000000000000))*(x2585)*(x2586)))+(((x2585)*(x2591)))+(((r21)*(x2588))))))) < IKFAST_ATAN2_MAGTHRESH )
11436     continue;
11437 j10array[0]=IKatan2(((gconst46)*(((((cj11)*(cj14)*(r21)))+(((x2586)*(x2590)))+(((IkReal(-1.00000000000000))*(x2590)*(x2591)))+(((sj12)*(x2588)*(x2589)))+(((cj11)*(x2587)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x2585)*(x2589)))+(((sj11)*(x2587)))+(((IkReal(-1.00000000000000))*(x2585)*(x2586)))+(((x2585)*(x2591)))+(((r21)*(x2588)))))));
11438 sj10array[0]=IKsin(j10array[0]);
11439 cj10array[0]=IKcos(j10array[0]);
11440 if( j10array[0] > IKPI )
11441 {
11442     j10array[0]-=IK2PI;
11443 }
11444 else if( j10array[0] < -IKPI )
11445 {    j10array[0]+=IK2PI;
11446 }
11447 j10valid[0] = true;
11448 for(int ij10 = 0; ij10 < 1; ++ij10)
11449 {
11450 if( !j10valid[ij10] )
11451 {
11452     continue;
11453 }
11454 _ij10[0] = ij10; _ij10[1] = -1;
11455 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11456 {
11457 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11458 {
11459     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11460 }
11461 }
11462 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11463 {
11464 IkReal evalcond[6];
11465 IkReal x2592=IKsin(j10);
11466 IkReal x2593=IKcos(j10);
11467 IkReal x2594=((IkReal(1.00000000000000))*(cj13));
11468 IkReal x2595=((cj9)*(r02));
11469 IkReal x2596=((IkReal(1.00000000000000))*(sj13));
11470 IkReal x2597=((r11)*(sj9));
11471 IkReal x2598=((IkReal(1.00000000000000))*(cj14));
11472 IkReal x2599=((cj9)*(r01));
11473 IkReal x2600=((r21)*(sj14));
11474 IkReal x2601=((IkReal(1.00000000000000))*(sj12));
11475 IkReal x2602=((r10)*(sj9));
11476 IkReal x2603=((cj14)*(sj13));
11477 IkReal x2604=((cj14)*(r20));
11478 IkReal x2605=((IkReal(1.00000000000000))*(sj14));
11479 IkReal x2606=((r12)*(sj9));
11480 IkReal x2607=((cj13)*(cj14));
11481 IkReal x2608=((cj9)*(r00));
11482 IkReal x2609=((sj11)*(x2592));
11483 IkReal x2610=((cj11)*(x2592));
11484 IkReal x2611=((sj11)*(x2593));
11485 IkReal x2612=((cj11)*(x2593));
11486 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x2601)*(x2610)))+(((IkReal(-1.00000000000000))*(x2601)*(x2611))));
11487 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x2596)))+(((IkReal(-1.00000000000000))*(x2612)))+(((cj13)*(x2600)))+(((IkReal(-1.00000000000000))*(x2594)*(x2604)))+(x2609));
11488 evalcond[2]=((((IkReal(-1.00000000000000))*(x2596)*(x2604)))+(((sj13)*(x2600)))+(((cj12)*(x2610)))+(((cj12)*(x2611)))+(((cj13)*(r22))));
11489 evalcond[3]=((((IkReal(-1.00000000000000))*(x2598)*(x2599)))+(((sj12)*(x2609)))+(((IkReal(-1.00000000000000))*(x2597)*(x2598)))+(((IkReal(-1.00000000000000))*(x2602)*(x2605)))+(((IkReal(-1.00000000000000))*(x2605)*(x2608)))+(((IkReal(-1.00000000000000))*(x2601)*(x2612))));
11490 evalcond[4]=((((x2607)*(x2608)))+(((sj13)*(x2606)))+(((x2602)*(x2607)))+(((sj13)*(x2595)))+(((IkReal(-1.00000000000000))*(sj14)*(x2594)*(x2599)))+(((IkReal(-1.00000000000000))*(sj14)*(x2594)*(x2597)))+(x2611)+(x2610));
11491 evalcond[5]=((((x2603)*(x2608)))+(((IkReal(-1.00000000000000))*(x2594)*(x2595)))+(((x2602)*(x2603)))+(((IkReal(-1.00000000000000))*(sj14)*(x2596)*(x2597)))+(((IkReal(-1.00000000000000))*(sj14)*(x2596)*(x2599)))+(((IkReal(-1.00000000000000))*(cj12)*(x2609)))+(((cj12)*(x2612)))+(((IkReal(-1.00000000000000))*(x2594)*(x2606))));
11492 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  )
11493 {
11494 continue;
11495 }
11496 }
11497 
11498 {
11499 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11500 vinfos[0].jointtype = 1;
11501 vinfos[0].foffset = j9;
11502 vinfos[0].indices[0] = _ij9[0];
11503 vinfos[0].indices[1] = _ij9[1];
11504 vinfos[0].maxsolutions = _nj9;
11505 vinfos[1].jointtype = 1;
11506 vinfos[1].foffset = j10;
11507 vinfos[1].indices[0] = _ij10[0];
11508 vinfos[1].indices[1] = _ij10[1];
11509 vinfos[1].maxsolutions = _nj10;
11510 vinfos[2].jointtype = 1;
11511 vinfos[2].foffset = j11;
11512 vinfos[2].indices[0] = _ij11[0];
11513 vinfos[2].indices[1] = _ij11[1];
11514 vinfos[2].maxsolutions = _nj11;
11515 vinfos[3].jointtype = 1;
11516 vinfos[3].foffset = j12;
11517 vinfos[3].indices[0] = _ij12[0];
11518 vinfos[3].indices[1] = _ij12[1];
11519 vinfos[3].maxsolutions = _nj12;
11520 vinfos[4].jointtype = 1;
11521 vinfos[4].foffset = j13;
11522 vinfos[4].indices[0] = _ij13[0];
11523 vinfos[4].indices[1] = _ij13[1];
11524 vinfos[4].maxsolutions = _nj13;
11525 vinfos[5].jointtype = 1;
11526 vinfos[5].foffset = j14;
11527 vinfos[5].indices[0] = _ij14[0];
11528 vinfos[5].indices[1] = _ij14[1];
11529 vinfos[5].maxsolutions = _nj14;
11530 std::vector<int> vfree(0);
11531 solutions.AddSolution(vinfos,vfree);
11532 }
11533 }
11534 }
11535 
11536 }
11537 
11538 }
11539 }
11540 }
11541 
11542 }
11543 
11544 }
11545 
11546 } else
11547 {
11548 {
11549 IkReal j11array[1], cj11array[1], sj11array[1];
11550 bool j11valid[1]={false};
11551 _nj11 = 1;
11552 IkReal x2613=((IkReal(4.00000000000000))*(sj14));
11553 IkReal x2614=((IkReal(4.00000000000000))*(cj14));
11554 if( IKabs(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npx)*(x2613)))+(((IkReal(-1.00000000000000))*(npy)*(x2614))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2613)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2614))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npx)*(x2613)))+(((IkReal(-1.00000000000000))*(npy)*(x2614)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2613)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2614)))))-1) <= IKFAST_SINCOS_THRESH )
11555     continue;
11556 j11array[0]=IKatan2(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npx)*(x2613)))+(((IkReal(-1.00000000000000))*(npy)*(x2614)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2613)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2614)))));
11557 sj11array[0]=IKsin(j11array[0]);
11558 cj11array[0]=IKcos(j11array[0]);
11559 if( j11array[0] > IKPI )
11560 {
11561     j11array[0]-=IK2PI;
11562 }
11563 else if( j11array[0] < -IKPI )
11564 {    j11array[0]+=IK2PI;
11565 }
11566 j11valid[0] = true;
11567 for(int ij11 = 0; ij11 < 1; ++ij11)
11568 {
11569 if( !j11valid[ij11] )
11570 {
11571     continue;
11572 }
11573 _ij11[0] = ij11; _ij11[1] = -1;
11574 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
11575 {
11576 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
11577 {
11578     j11valid[iij11]=false; _ij11[1] = iij11; break; 
11579 }
11580 }
11581 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
11582 {
11583 IkReal evalcond[3];
11584 IkReal x2615=IKsin(j11);
11585 IkReal x2616=((IkReal(1.00000000000000))*(sj13));
11586 IkReal x2617=((cj14)*(npx));
11587 IkReal x2618=((npy)*(sj14));
11588 IkReal x2619=((IkReal(0.250000000000000))*(x2615));
11589 evalcond[0]=((((IkReal(0.0950000000000000))*(cj12)))+(((sj12)*(x2619)))+(((cj14)*(npy)))+(((IkReal(-0.0300000000000000))*(sj12)))+(((npx)*(sj14))));
11590 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x2616)))+(((IkReal(-1.00000000000000))*(cj13)*(x2617)))+(((cj13)*(x2618))));
11591 evalcond[2]=((((sj13)*(x2618)))+(((IkReal(0.0950000000000000))*(sj12)))+(((cj13)*(npz)))+(((IkReal(0.0300000000000000))*(cj12)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x2616)*(x2617)))+(((IkReal(-1.00000000000000))*(cj12)*(x2619))));
11592 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
11593 {
11594 continue;
11595 }
11596 }
11597 
11598 {
11599 IkReal dummyeval[1];
11600 IkReal gconst46;
11601 gconst46=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
11602 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
11603 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11604 {
11605 {
11606 IkReal dummyeval[1];
11607 IkReal gconst47;
11608 gconst47=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
11609 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
11610 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11611 {
11612 {
11613 IkReal evalcond[9];
11614 IkReal x2620=((r00)*(sj9));
11615 IkReal x2621=((IkReal(1.00000000000000))*(sj13));
11616 IkReal x2622=((cj13)*(sj14));
11617 IkReal x2623=((cj9)*(sj14));
11618 IkReal x2624=((cj13)*(r02));
11619 IkReal x2625=((sj13)*(sj14));
11620 IkReal x2626=((r01)*(sj9));
11621 IkReal x2627=((cj9)*(sj13));
11622 IkReal x2628=((IkReal(1.00000000000000))*(cj9));
11623 IkReal x2629=((cj14)*(r10));
11624 IkReal x2630=((cj14)*(npx));
11625 IkReal x2631=((IkReal(1.00000000000000))*(cj13));
11626 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
11627 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
11628 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x2621)))+(((IkReal(-1.00000000000000))*(x2630)*(x2631)))+(((npy)*(x2622))));
11629 evalcond[3]=((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2628)))+(((IkReal(-1.00000000000000))*(r10)*(x2623)))+(((cj14)*(x2626)))+(((sj14)*(x2620))));
11630 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2621)))+(((r21)*(x2625)))+(((cj13)*(r22))));
11631 evalcond[5]=((IkReal(0.0950000000000000))+(((cj13)*(npz)))+(((IkReal(-1.00000000000000))*(x2621)*(x2630)))+(((IkReal(0.0900000000000000))*(sj13)))+(((npy)*(x2625))));
11632 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2621)))+(((cj13)*(cj9)*(x2629)))+(((IkReal(-1.00000000000000))*(r11)*(x2622)*(x2628)))+(((IkReal(-1.00000000000000))*(cj14)*(x2620)*(x2631)))+(((x2622)*(x2626)))+(((r12)*(x2627))));
11633 evalcond[7]=((IkReal(1.00000000000000))+(((sj9)*(x2624)))+(((x2627)*(x2629)))+(((IkReal(-1.00000000000000))*(cj14)*(x2620)*(x2621)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x2628)))+(((IkReal(-1.00000000000000))*(r11)*(x2621)*(x2623)))+(((x2625)*(x2626))));
11634 evalcond[8]=((((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x2621)))+(((IkReal(-1.00000000000000))*(x2624)*(x2628)))+(((sj13)*(sj9)*(x2629)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2631)))+(((IkReal(-1.00000000000000))*(r01)*(x2621)*(x2623)))+(((cj14)*(r00)*(x2627))));
11635 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  )
11636 {
11637 {
11638 IkReal dummyeval[1];
11639 IkReal gconst48;
11640 gconst48=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
11641 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
11642 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11643 {
11644 {
11645 IkReal dummyeval[1];
11646 IkReal gconst49;
11647 gconst49=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
11648 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
11649 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11650 {
11651 continue;
11652 
11653 } else
11654 {
11655 {
11656 IkReal j10array[1], cj10array[1], sj10array[1];
11657 bool j10valid[1]={false};
11658 _nj10 = 1;
11659 IkReal x2632=((IkReal(1.00000000000000))*(cj11));
11660 IkReal x2633=((sj11)*(sj14));
11661 IkReal x2634=((r10)*(sj9));
11662 IkReal x2635=((cj9)*(r00));
11663 IkReal x2636=((cj14)*(sj11));
11664 IkReal x2637=((r11)*(sj9));
11665 IkReal x2638=((cj14)*(cj9)*(r01));
11666 if( IKabs(((gconst49)*(((((cj9)*(r01)*(x2636)))+(((cj11)*(cj14)*(r21)))+(((cj11)*(r20)*(sj14)))+(((x2633)*(x2635)))+(((x2633)*(x2634)))+(((x2636)*(x2637))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(sj14)*(x2632)*(x2634)))+(((IkReal(-1.00000000000000))*(sj14)*(x2632)*(x2635)))+(((r21)*(x2636)))+(((IkReal(-1.00000000000000))*(x2632)*(x2638)))+(((r20)*(x2633)))+(((IkReal(-1.00000000000000))*(cj14)*(x2632)*(x2637))))))) < IKFAST_ATAN2_MAGTHRESH )
11667     continue;
11668 j10array[0]=IKatan2(((gconst49)*(((((cj9)*(r01)*(x2636)))+(((cj11)*(cj14)*(r21)))+(((cj11)*(r20)*(sj14)))+(((x2633)*(x2635)))+(((x2633)*(x2634)))+(((x2636)*(x2637)))))), ((gconst49)*(((((IkReal(-1.00000000000000))*(sj14)*(x2632)*(x2634)))+(((IkReal(-1.00000000000000))*(sj14)*(x2632)*(x2635)))+(((r21)*(x2636)))+(((IkReal(-1.00000000000000))*(x2632)*(x2638)))+(((r20)*(x2633)))+(((IkReal(-1.00000000000000))*(cj14)*(x2632)*(x2637)))))));
11669 sj10array[0]=IKsin(j10array[0]);
11670 cj10array[0]=IKcos(j10array[0]);
11671 if( j10array[0] > IKPI )
11672 {
11673     j10array[0]-=IK2PI;
11674 }
11675 else if( j10array[0] < -IKPI )
11676 {    j10array[0]+=IK2PI;
11677 }
11678 j10valid[0] = true;
11679 for(int ij10 = 0; ij10 < 1; ++ij10)
11680 {
11681 if( !j10valid[ij10] )
11682 {
11683     continue;
11684 }
11685 _ij10[0] = ij10; _ij10[1] = -1;
11686 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11687 {
11688 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11689 {
11690     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11691 }
11692 }
11693 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11694 {
11695 IkReal evalcond[4];
11696 IkReal x2639=IKsin(j10);
11697 IkReal x2640=IKcos(j10);
11698 IkReal x2641=((cj13)*(sj14));
11699 IkReal x2642=((cj13)*(cj14));
11700 IkReal x2643=((r10)*(sj9));
11701 IkReal x2644=((IkReal(1.00000000000000))*(cj9));
11702 IkReal x2645=((sj11)*(x2639));
11703 IkReal x2646=((IkReal(1.00000000000000))*(x2640));
11704 IkReal x2647=((cj11)*(x2639));
11705 IkReal x2648=((IkReal(1.00000000000000))*(r11)*(sj9));
11706 IkReal x2649=((cj11)*(x2646));
11707 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x2646)))+(((IkReal(-1.00000000000000))*(x2647))));
11708 evalcond[1]=((((r21)*(x2641)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2649)))+(((IkReal(-1.00000000000000))*(r20)*(x2642)))+(x2645));
11709 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x2648)))+(((IkReal(-1.00000000000000))*(sj14)*(x2643)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2644)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2644)))+(((IkReal(-1.00000000000000))*(x2649)))+(x2645));
11710 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x2641)*(x2644)))+(((cj9)*(r00)*(x2642)))+(((cj9)*(r02)*(sj13)))+(((sj11)*(x2640)))+(((IkReal(-1.00000000000000))*(x2641)*(x2648)))+(((x2642)*(x2643)))+(((r12)*(sj13)*(sj9)))+(x2647));
11711 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11712 {
11713 continue;
11714 }
11715 }
11716 
11717 {
11718 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11719 vinfos[0].jointtype = 1;
11720 vinfos[0].foffset = j9;
11721 vinfos[0].indices[0] = _ij9[0];
11722 vinfos[0].indices[1] = _ij9[1];
11723 vinfos[0].maxsolutions = _nj9;
11724 vinfos[1].jointtype = 1;
11725 vinfos[1].foffset = j10;
11726 vinfos[1].indices[0] = _ij10[0];
11727 vinfos[1].indices[1] = _ij10[1];
11728 vinfos[1].maxsolutions = _nj10;
11729 vinfos[2].jointtype = 1;
11730 vinfos[2].foffset = j11;
11731 vinfos[2].indices[0] = _ij11[0];
11732 vinfos[2].indices[1] = _ij11[1];
11733 vinfos[2].maxsolutions = _nj11;
11734 vinfos[3].jointtype = 1;
11735 vinfos[3].foffset = j12;
11736 vinfos[3].indices[0] = _ij12[0];
11737 vinfos[3].indices[1] = _ij12[1];
11738 vinfos[3].maxsolutions = _nj12;
11739 vinfos[4].jointtype = 1;
11740 vinfos[4].foffset = j13;
11741 vinfos[4].indices[0] = _ij13[0];
11742 vinfos[4].indices[1] = _ij13[1];
11743 vinfos[4].maxsolutions = _nj13;
11744 vinfos[5].jointtype = 1;
11745 vinfos[5].foffset = j14;
11746 vinfos[5].indices[0] = _ij14[0];
11747 vinfos[5].indices[1] = _ij14[1];
11748 vinfos[5].maxsolutions = _nj14;
11749 std::vector<int> vfree(0);
11750 solutions.AddSolution(vinfos,vfree);
11751 }
11752 }
11753 }
11754 
11755 }
11756 
11757 }
11758 
11759 } else
11760 {
11761 {
11762 IkReal j10array[1], cj10array[1], sj10array[1];
11763 bool j10valid[1]={false};
11764 _nj10 = 1;
11765 IkReal x2650=((cj11)*(r20));
11766 IkReal x2651=((IkReal(1.00000000000000))*(cj13));
11767 IkReal x2652=((r21)*(sj14));
11768 IkReal x2653=((r22)*(sj13));
11769 IkReal x2654=((r20)*(sj11));
11770 IkReal x2655=((cj14)*(r21));
11771 if( IKabs(((gconst48)*(((((sj14)*(x2650)))+(((IkReal(-1.00000000000000))*(sj11)*(x2651)*(x2652)))+(((cj13)*(cj14)*(x2654)))+(((sj11)*(x2653)))+(((cj11)*(x2655))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((sj14)*(x2654)))+(((sj11)*(x2655)))+(((IkReal(-1.00000000000000))*(cj14)*(x2650)*(x2651)))+(((IkReal(-1.00000000000000))*(cj11)*(x2653)))+(((cj11)*(cj13)*(x2652))))))) < IKFAST_ATAN2_MAGTHRESH )
11772     continue;
11773 j10array[0]=IKatan2(((gconst48)*(((((sj14)*(x2650)))+(((IkReal(-1.00000000000000))*(sj11)*(x2651)*(x2652)))+(((cj13)*(cj14)*(x2654)))+(((sj11)*(x2653)))+(((cj11)*(x2655)))))), ((gconst48)*(((((sj14)*(x2654)))+(((sj11)*(x2655)))+(((IkReal(-1.00000000000000))*(cj14)*(x2650)*(x2651)))+(((IkReal(-1.00000000000000))*(cj11)*(x2653)))+(((cj11)*(cj13)*(x2652)))))));
11774 sj10array[0]=IKsin(j10array[0]);
11775 cj10array[0]=IKcos(j10array[0]);
11776 if( j10array[0] > IKPI )
11777 {
11778     j10array[0]-=IK2PI;
11779 }
11780 else if( j10array[0] < -IKPI )
11781 {    j10array[0]+=IK2PI;
11782 }
11783 j10valid[0] = true;
11784 for(int ij10 = 0; ij10 < 1; ++ij10)
11785 {
11786 if( !j10valid[ij10] )
11787 {
11788     continue;
11789 }
11790 _ij10[0] = ij10; _ij10[1] = -1;
11791 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11792 {
11793 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11794 {
11795     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11796 }
11797 }
11798 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11799 {
11800 IkReal evalcond[4];
11801 IkReal x2656=IKsin(j10);
11802 IkReal x2657=IKcos(j10);
11803 IkReal x2658=((cj13)*(sj14));
11804 IkReal x2659=((cj13)*(cj14));
11805 IkReal x2660=((r10)*(sj9));
11806 IkReal x2661=((IkReal(1.00000000000000))*(cj9));
11807 IkReal x2662=((sj11)*(x2656));
11808 IkReal x2663=((IkReal(1.00000000000000))*(x2657));
11809 IkReal x2664=((cj11)*(x2656));
11810 IkReal x2665=((IkReal(1.00000000000000))*(r11)*(sj9));
11811 IkReal x2666=((cj11)*(x2663));
11812 evalcond[0]=((((IkReal(-1.00000000000000))*(x2664)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x2663))));
11813 evalcond[1]=((((r21)*(x2658)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2666)))+(((IkReal(-1.00000000000000))*(r20)*(x2659)))+(x2662));
11814 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x2665)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2661)))+(((IkReal(-1.00000000000000))*(x2666)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2661)))+(x2662)+(((IkReal(-1.00000000000000))*(sj14)*(x2660))));
11815 evalcond[3]=((((x2659)*(x2660)))+(((cj9)*(r00)*(x2659)))+(((sj11)*(x2657)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(x2658)*(x2665)))+(((IkReal(-1.00000000000000))*(r01)*(x2658)*(x2661)))+(((r12)*(sj13)*(sj9)))+(x2664));
11816 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11817 {
11818 continue;
11819 }
11820 }
11821 
11822 {
11823 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11824 vinfos[0].jointtype = 1;
11825 vinfos[0].foffset = j9;
11826 vinfos[0].indices[0] = _ij9[0];
11827 vinfos[0].indices[1] = _ij9[1];
11828 vinfos[0].maxsolutions = _nj9;
11829 vinfos[1].jointtype = 1;
11830 vinfos[1].foffset = j10;
11831 vinfos[1].indices[0] = _ij10[0];
11832 vinfos[1].indices[1] = _ij10[1];
11833 vinfos[1].maxsolutions = _nj10;
11834 vinfos[2].jointtype = 1;
11835 vinfos[2].foffset = j11;
11836 vinfos[2].indices[0] = _ij11[0];
11837 vinfos[2].indices[1] = _ij11[1];
11838 vinfos[2].maxsolutions = _nj11;
11839 vinfos[3].jointtype = 1;
11840 vinfos[3].foffset = j12;
11841 vinfos[3].indices[0] = _ij12[0];
11842 vinfos[3].indices[1] = _ij12[1];
11843 vinfos[3].maxsolutions = _nj12;
11844 vinfos[4].jointtype = 1;
11845 vinfos[4].foffset = j13;
11846 vinfos[4].indices[0] = _ij13[0];
11847 vinfos[4].indices[1] = _ij13[1];
11848 vinfos[4].maxsolutions = _nj13;
11849 vinfos[5].jointtype = 1;
11850 vinfos[5].foffset = j14;
11851 vinfos[5].indices[0] = _ij14[0];
11852 vinfos[5].indices[1] = _ij14[1];
11853 vinfos[5].maxsolutions = _nj14;
11854 std::vector<int> vfree(0);
11855 solutions.AddSolution(vinfos,vfree);
11856 }
11857 }
11858 }
11859 
11860 }
11861 
11862 }
11863 
11864 } else
11865 {
11866 IkReal x2667=((r00)*(sj9));
11867 IkReal x2668=((IkReal(1.00000000000000))*(sj13));
11868 IkReal x2669=((cj13)*(sj14));
11869 IkReal x2670=((cj9)*(sj14));
11870 IkReal x2671=((cj13)*(r02));
11871 IkReal x2672=((sj13)*(sj14));
11872 IkReal x2673=((r01)*(sj9));
11873 IkReal x2674=((cj9)*(sj13));
11874 IkReal x2675=((IkReal(1.00000000000000))*(cj9));
11875 IkReal x2676=((cj14)*(r10));
11876 IkReal x2677=((cj14)*(npx));
11877 IkReal x2678=((IkReal(1.00000000000000))*(cj13));
11878 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
11879 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
11880 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((npy)*(x2669)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x2677)*(x2678)))+(((IkReal(-1.00000000000000))*(npz)*(x2668))));
11881 evalcond[3]=((((sj14)*(x2667)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2675)))+(((IkReal(-1.00000000000000))*(r10)*(x2670)))+(((cj14)*(x2673))));
11882 evalcond[4]=((((r21)*(x2672)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2668)))+(((cj13)*(r22))));
11883 evalcond[5]=((IkReal(-0.0950000000000000))+(((npy)*(x2672)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x2668)*(x2677))));
11884 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2668)))+(((r12)*(x2674)))+(((IkReal(-1.00000000000000))*(cj14)*(x2667)*(x2678)))+(((IkReal(-1.00000000000000))*(r11)*(x2669)*(x2675)))+(((cj13)*(cj9)*(x2676)))+(((x2669)*(x2673))));
11885 evalcond[7]=((IkReal(-1.00000000000000))+(((x2672)*(x2673)))+(((IkReal(-1.00000000000000))*(cj14)*(x2667)*(x2668)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x2675)))+(((sj9)*(x2671)))+(((IkReal(-1.00000000000000))*(r11)*(x2668)*(x2670)))+(((x2674)*(x2676))));
11886 evalcond[8]=((((sj13)*(sj9)*(x2676)))+(((IkReal(-1.00000000000000))*(r01)*(x2668)*(x2670)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2678)))+(((IkReal(-1.00000000000000))*(x2671)*(x2675)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x2668)))+(((cj14)*(r00)*(x2674))));
11887 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  )
11888 {
11889 {
11890 IkReal dummyeval[1];
11891 IkReal gconst50;
11892 gconst50=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
11893 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
11894 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11895 {
11896 {
11897 IkReal dummyeval[1];
11898 IkReal gconst51;
11899 gconst51=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
11900 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
11901 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
11902 {
11903 continue;
11904 
11905 } else
11906 {
11907 {
11908 IkReal j10array[1], cj10array[1], sj10array[1];
11909 bool j10valid[1]={false};
11910 _nj10 = 1;
11911 IkReal x2679=((IkReal(1.00000000000000))*(sj11));
11912 IkReal x2680=((cj14)*(r21));
11913 IkReal x2681=((IkReal(1.00000000000000))*(cj11));
11914 IkReal x2682=((r20)*(sj14));
11915 IkReal x2683=((cj9)*(r00)*(sj14));
11916 IkReal x2684=((cj14)*(r11)*(sj9));
11917 IkReal x2685=((cj14)*(cj9)*(r01));
11918 IkReal x2686=((r10)*(sj14)*(sj9));
11919 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x2680)*(x2681)))+(((IkReal(-1.00000000000000))*(x2679)*(x2683)))+(((IkReal(-1.00000000000000))*(x2679)*(x2686)))+(((IkReal(-1.00000000000000))*(x2679)*(x2685)))+(((IkReal(-1.00000000000000))*(x2679)*(x2684)))+(((IkReal(-1.00000000000000))*(x2681)*(x2682))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x2679)*(x2682)))+(((IkReal(-1.00000000000000))*(x2679)*(x2680)))+(((cj11)*(x2683)))+(((cj11)*(x2684)))+(((cj11)*(x2685)))+(((cj11)*(x2686))))))) < IKFAST_ATAN2_MAGTHRESH )
11920     continue;
11921 j10array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x2680)*(x2681)))+(((IkReal(-1.00000000000000))*(x2679)*(x2683)))+(((IkReal(-1.00000000000000))*(x2679)*(x2686)))+(((IkReal(-1.00000000000000))*(x2679)*(x2685)))+(((IkReal(-1.00000000000000))*(x2679)*(x2684)))+(((IkReal(-1.00000000000000))*(x2681)*(x2682)))))), ((gconst51)*(((((IkReal(-1.00000000000000))*(x2679)*(x2682)))+(((IkReal(-1.00000000000000))*(x2679)*(x2680)))+(((cj11)*(x2683)))+(((cj11)*(x2684)))+(((cj11)*(x2685)))+(((cj11)*(x2686)))))));
11922 sj10array[0]=IKsin(j10array[0]);
11923 cj10array[0]=IKcos(j10array[0]);
11924 if( j10array[0] > IKPI )
11925 {
11926     j10array[0]-=IK2PI;
11927 }
11928 else if( j10array[0] < -IKPI )
11929 {    j10array[0]+=IK2PI;
11930 }
11931 j10valid[0] = true;
11932 for(int ij10 = 0; ij10 < 1; ++ij10)
11933 {
11934 if( !j10valid[ij10] )
11935 {
11936     continue;
11937 }
11938 _ij10[0] = ij10; _ij10[1] = -1;
11939 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
11940 {
11941 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
11942 {
11943     j10valid[iij10]=false; _ij10[1] = iij10; break; 
11944 }
11945 }
11946 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
11947 {
11948 IkReal evalcond[4];
11949 IkReal x2687=IKsin(j10);
11950 IkReal x2688=IKcos(j10);
11951 IkReal x2689=((cj14)*(sj9));
11952 IkReal x2690=((IkReal(1.00000000000000))*(r11));
11953 IkReal x2691=((cj13)*(sj14));
11954 IkReal x2692=((IkReal(1.00000000000000))*(cj9));
11955 IkReal x2693=((cj13)*(cj14));
11956 IkReal x2694=((cj11)*(x2687));
11957 IkReal x2695=((sj11)*(x2688));
11958 IkReal x2696=((cj11)*(x2688));
11959 IkReal x2697=((sj11)*(x2687));
11960 IkReal x2698=((x2695)+(x2694));
11961 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x2698));
11962 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x2693)))+(((r21)*(x2691)))+(((IkReal(-1.00000000000000))*(x2696)))+(x2697));
11963 evalcond[2]=((((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2692)))+(((IkReal(-1.00000000000000))*(x2689)*(x2690)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2692)))+(((IkReal(-1.00000000000000))*(x2697)))+(x2696));
11964 evalcond[3]=((((cj9)*(r00)*(x2693)))+(((cj9)*(r02)*(sj13)))+(((cj13)*(r10)*(x2689)))+(((IkReal(-1.00000000000000))*(sj9)*(x2690)*(x2691)))+(((IkReal(-1.00000000000000))*(r01)*(x2691)*(x2692)))+(((r12)*(sj13)*(sj9)))+(x2698));
11965 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
11966 {
11967 continue;
11968 }
11969 }
11970 
11971 {
11972 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
11973 vinfos[0].jointtype = 1;
11974 vinfos[0].foffset = j9;
11975 vinfos[0].indices[0] = _ij9[0];
11976 vinfos[0].indices[1] = _ij9[1];
11977 vinfos[0].maxsolutions = _nj9;
11978 vinfos[1].jointtype = 1;
11979 vinfos[1].foffset = j10;
11980 vinfos[1].indices[0] = _ij10[0];
11981 vinfos[1].indices[1] = _ij10[1];
11982 vinfos[1].maxsolutions = _nj10;
11983 vinfos[2].jointtype = 1;
11984 vinfos[2].foffset = j11;
11985 vinfos[2].indices[0] = _ij11[0];
11986 vinfos[2].indices[1] = _ij11[1];
11987 vinfos[2].maxsolutions = _nj11;
11988 vinfos[3].jointtype = 1;
11989 vinfos[3].foffset = j12;
11990 vinfos[3].indices[0] = _ij12[0];
11991 vinfos[3].indices[1] = _ij12[1];
11992 vinfos[3].maxsolutions = _nj12;
11993 vinfos[4].jointtype = 1;
11994 vinfos[4].foffset = j13;
11995 vinfos[4].indices[0] = _ij13[0];
11996 vinfos[4].indices[1] = _ij13[1];
11997 vinfos[4].maxsolutions = _nj13;
11998 vinfos[5].jointtype = 1;
11999 vinfos[5].foffset = j14;
12000 vinfos[5].indices[0] = _ij14[0];
12001 vinfos[5].indices[1] = _ij14[1];
12002 vinfos[5].maxsolutions = _nj14;
12003 std::vector<int> vfree(0);
12004 solutions.AddSolution(vinfos,vfree);
12005 }
12006 }
12007 }
12008 
12009 }
12010 
12011 }
12012 
12013 } else
12014 {
12015 {
12016 IkReal j10array[1], cj10array[1], sj10array[1];
12017 bool j10valid[1]={false};
12018 _nj10 = 1;
12019 IkReal x2699=((cj13)*(sj11));
12020 IkReal x2700=((r21)*(sj14));
12021 IkReal x2701=((cj14)*(r20));
12022 IkReal x2702=((cj11)*(cj13));
12023 IkReal x2703=((r22)*(sj13));
12024 IkReal x2704=((r20)*(sj14));
12025 IkReal x2705=((cj14)*(r21));
12026 if( IKabs(((gconst50)*(((((x2699)*(x2700)))+(((IkReal(-1.00000000000000))*(sj11)*(x2703)))+(((IkReal(-1.00000000000000))*(x2699)*(x2701)))+(((cj11)*(x2705)))+(((cj11)*(x2704))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x2700)*(x2702)))+(((sj11)*(x2704)))+(((sj11)*(x2705)))+(((x2701)*(x2702)))+(((cj11)*(x2703))))))) < IKFAST_ATAN2_MAGTHRESH )
12027     continue;
12028 j10array[0]=IKatan2(((gconst50)*(((((x2699)*(x2700)))+(((IkReal(-1.00000000000000))*(sj11)*(x2703)))+(((IkReal(-1.00000000000000))*(x2699)*(x2701)))+(((cj11)*(x2705)))+(((cj11)*(x2704)))))), ((gconst50)*(((((IkReal(-1.00000000000000))*(x2700)*(x2702)))+(((sj11)*(x2704)))+(((sj11)*(x2705)))+(((x2701)*(x2702)))+(((cj11)*(x2703)))))));
12029 sj10array[0]=IKsin(j10array[0]);
12030 cj10array[0]=IKcos(j10array[0]);
12031 if( j10array[0] > IKPI )
12032 {
12033     j10array[0]-=IK2PI;
12034 }
12035 else if( j10array[0] < -IKPI )
12036 {    j10array[0]+=IK2PI;
12037 }
12038 j10valid[0] = true;
12039 for(int ij10 = 0; ij10 < 1; ++ij10)
12040 {
12041 if( !j10valid[ij10] )
12042 {
12043     continue;
12044 }
12045 _ij10[0] = ij10; _ij10[1] = -1;
12046 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12047 {
12048 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12049 {
12050     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12051 }
12052 }
12053 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12054 {
12055 IkReal evalcond[4];
12056 IkReal x2706=IKsin(j10);
12057 IkReal x2707=IKcos(j10);
12058 IkReal x2708=((cj14)*(sj9));
12059 IkReal x2709=((IkReal(1.00000000000000))*(r11));
12060 IkReal x2710=((cj13)*(sj14));
12061 IkReal x2711=((IkReal(1.00000000000000))*(cj9));
12062 IkReal x2712=((cj13)*(cj14));
12063 IkReal x2713=((cj11)*(x2706));
12064 IkReal x2714=((sj11)*(x2707));
12065 IkReal x2715=((cj11)*(x2707));
12066 IkReal x2716=((sj11)*(x2706));
12067 IkReal x2717=((x2713)+(x2714));
12068 evalcond[0]=((x2717)+(((cj14)*(r21)))+(((r20)*(sj14))));
12069 evalcond[1]=((x2716)+(((IkReal(-1.00000000000000))*(x2715)))+(((IkReal(-1.00000000000000))*(r20)*(x2712)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x2710))));
12070 evalcond[2]=((x2715)+(((IkReal(-1.00000000000000))*(x2716)))+(((IkReal(-1.00000000000000))*(x2708)*(x2709)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2711)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2711))));
12071 evalcond[3]=((x2717)+(((cj9)*(r02)*(sj13)))+(((cj9)*(r00)*(x2712)))+(((IkReal(-1.00000000000000))*(sj9)*(x2709)*(x2710)))+(((IkReal(-1.00000000000000))*(r01)*(x2710)*(x2711)))+(((cj13)*(r10)*(x2708)))+(((r12)*(sj13)*(sj9))));
12072 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12073 {
12074 continue;
12075 }
12076 }
12077 
12078 {
12079 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12080 vinfos[0].jointtype = 1;
12081 vinfos[0].foffset = j9;
12082 vinfos[0].indices[0] = _ij9[0];
12083 vinfos[0].indices[1] = _ij9[1];
12084 vinfos[0].maxsolutions = _nj9;
12085 vinfos[1].jointtype = 1;
12086 vinfos[1].foffset = j10;
12087 vinfos[1].indices[0] = _ij10[0];
12088 vinfos[1].indices[1] = _ij10[1];
12089 vinfos[1].maxsolutions = _nj10;
12090 vinfos[2].jointtype = 1;
12091 vinfos[2].foffset = j11;
12092 vinfos[2].indices[0] = _ij11[0];
12093 vinfos[2].indices[1] = _ij11[1];
12094 vinfos[2].maxsolutions = _nj11;
12095 vinfos[3].jointtype = 1;
12096 vinfos[3].foffset = j12;
12097 vinfos[3].indices[0] = _ij12[0];
12098 vinfos[3].indices[1] = _ij12[1];
12099 vinfos[3].maxsolutions = _nj12;
12100 vinfos[4].jointtype = 1;
12101 vinfos[4].foffset = j13;
12102 vinfos[4].indices[0] = _ij13[0];
12103 vinfos[4].indices[1] = _ij13[1];
12104 vinfos[4].maxsolutions = _nj13;
12105 vinfos[5].jointtype = 1;
12106 vinfos[5].foffset = j14;
12107 vinfos[5].indices[0] = _ij14[0];
12108 vinfos[5].indices[1] = _ij14[1];
12109 vinfos[5].maxsolutions = _nj14;
12110 std::vector<int> vfree(0);
12111 solutions.AddSolution(vinfos,vfree);
12112 }
12113 }
12114 }
12115 
12116 }
12117 
12118 }
12119 
12120 } else
12121 {
12122 IkReal x2718=((cj9)*(r10));
12123 IkReal x2719=((cj13)*(cj14));
12124 IkReal x2720=((sj14)*(sj9));
12125 IkReal x2721=((IkReal(1.00000000000000))*(sj14));
12126 IkReal x2722=((cj9)*(sj13));
12127 IkReal x2723=((r02)*(sj9));
12128 IkReal x2724=((cj13)*(cj9));
12129 IkReal x2725=((cj14)*(r01));
12130 IkReal x2726=((IkReal(1.00000000000000))*(npx));
12131 IkReal x2727=((cj14)*(sj13));
12132 IkReal x2728=((IkReal(1.00000000000000))*(cj9));
12133 IkReal x2729=((npy)*(sj14));
12134 IkReal x2730=((IkReal(1.00000000000000))*(sj13));
12135 IkReal x2731=((IkReal(1.00000000000000))*(cj14)*(sj9));
12136 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
12137 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
12138 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
12139 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x2719)*(x2726)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x2730)))+(((cj13)*(x2729))));
12140 evalcond[4]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x2718)*(x2721)))+(((sj9)*(x2725)))+(((r00)*(x2720)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2728))));
12141 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x2726)*(x2727)))+(((sj13)*(x2729)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
12142 evalcond[6]=((((IkReal(-1.00000000000000))*(x2725)*(x2728)))+(((IkReal(-1.00000000000000))*(r11)*(x2731)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x2721)))+(((IkReal(-1.00000000000000))*(r10)*(x2720))));
12143 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x2721)*(x2724)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2719)))+(((IkReal(-1.00000000000000))*(x2723)*(x2730)))+(((x2718)*(x2719)))+(((r12)*(x2722)))+(((cj13)*(r01)*(x2720))));
12144 evalcond[8]=((((IkReal(-1.00000000000000))*(r11)*(x2721)*(x2722)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2727)))+(((IkReal(-1.00000000000000))*(r12)*(x2724)))+(((r01)*(sj13)*(x2720)))+(((x2718)*(x2727)))+(((cj13)*(x2723))));
12145 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  )
12146 {
12147 {
12148 IkReal dummyeval[1];
12149 IkReal gconst52;
12150 gconst52=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
12151 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
12152 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12153 {
12154 {
12155 IkReal dummyeval[1];
12156 IkReal gconst53;
12157 gconst53=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
12158 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
12159 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12160 {
12161 continue;
12162 
12163 } else
12164 {
12165 {
12166 IkReal j10array[1], cj10array[1], sj10array[1];
12167 bool j10valid[1]={false};
12168 _nj10 = 1;
12169 IkReal x2732=((cj13)*(sj14));
12170 IkReal x2733=((IkReal(1.00000000000000))*(cj11));
12171 IkReal x2734=((r11)*(sj9));
12172 IkReal x2735=((IkReal(1.00000000000000))*(sj11));
12173 IkReal x2736=((cj13)*(cj14));
12174 IkReal x2737=((cj11)*(sj13));
12175 IkReal x2738=((r12)*(sj9));
12176 IkReal x2739=((sj11)*(sj13));
12177 IkReal x2740=((cj9)*(r02));
12178 IkReal x2741=((cj9)*(r01));
12179 IkReal x2742=((r10)*(sj9));
12180 IkReal x2743=((cj9)*(r00));
12181 if( IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(x2732)*(x2733)*(x2741)))+(((cj11)*(x2736)*(x2743)))+(((cj11)*(x2736)*(x2742)))+(((IkReal(-1.00000000000000))*(r20)*(x2735)*(x2736)))+(((IkReal(-1.00000000000000))*(x2732)*(x2733)*(x2734)))+(((r21)*(sj11)*(x2732)))+(((x2737)*(x2738)))+(((x2737)*(x2740)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2735))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((cj11)*(r20)*(x2736)))+(((r22)*(x2737)))+(((x2739)*(x2740)))+(((IkReal(-1.00000000000000))*(x2732)*(x2735)*(x2741)))+(((IkReal(-1.00000000000000))*(r21)*(x2732)*(x2733)))+(((sj11)*(x2736)*(x2743)))+(((sj11)*(x2736)*(x2742)))+(((x2738)*(x2739)))+(((IkReal(-1.00000000000000))*(x2732)*(x2734)*(x2735))))))) < IKFAST_ATAN2_MAGTHRESH )
12182     continue;
12183 j10array[0]=IKatan2(((gconst53)*(((((IkReal(-1.00000000000000))*(x2732)*(x2733)*(x2741)))+(((cj11)*(x2736)*(x2743)))+(((cj11)*(x2736)*(x2742)))+(((IkReal(-1.00000000000000))*(r20)*(x2735)*(x2736)))+(((IkReal(-1.00000000000000))*(x2732)*(x2733)*(x2734)))+(((r21)*(sj11)*(x2732)))+(((x2737)*(x2738)))+(((x2737)*(x2740)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2735)))))), ((gconst53)*(((((cj11)*(r20)*(x2736)))+(((r22)*(x2737)))+(((x2739)*(x2740)))+(((IkReal(-1.00000000000000))*(x2732)*(x2735)*(x2741)))+(((IkReal(-1.00000000000000))*(r21)*(x2732)*(x2733)))+(((sj11)*(x2736)*(x2743)))+(((sj11)*(x2736)*(x2742)))+(((x2738)*(x2739)))+(((IkReal(-1.00000000000000))*(x2732)*(x2734)*(x2735)))))));
12184 sj10array[0]=IKsin(j10array[0]);
12185 cj10array[0]=IKcos(j10array[0]);
12186 if( j10array[0] > IKPI )
12187 {
12188     j10array[0]-=IK2PI;
12189 }
12190 else if( j10array[0] < -IKPI )
12191 {    j10array[0]+=IK2PI;
12192 }
12193 j10valid[0] = true;
12194 for(int ij10 = 0; ij10 < 1; ++ij10)
12195 {
12196 if( !j10valid[ij10] )
12197 {
12198     continue;
12199 }
12200 _ij10[0] = ij10; _ij10[1] = -1;
12201 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12202 {
12203 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12204 {
12205     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12206 }
12207 }
12208 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12209 {
12210 IkReal evalcond[4];
12211 IkReal x2744=IKsin(j10);
12212 IkReal x2745=IKcos(j10);
12213 IkReal x2746=((IkReal(1.00000000000000))*(sj13));
12214 IkReal x2747=((r11)*(sj9));
12215 IkReal x2748=((cj9)*(r01));
12216 IkReal x2749=((r21)*(sj14));
12217 IkReal x2750=((cj9)*(r02));
12218 IkReal x2751=((sj13)*(sj9));
12219 IkReal x2752=((cj14)*(r10));
12220 IkReal x2753=((IkReal(1.00000000000000))*(cj13));
12221 IkReal x2754=((cj14)*(r20));
12222 IkReal x2755=((cj11)*(x2744));
12223 IkReal x2756=((sj11)*(x2745));
12224 IkReal x2757=((sj14)*(x2753));
12225 IkReal x2758=((sj11)*(x2744));
12226 IkReal x2759=((cj11)*(x2745));
12227 IkReal x2760=((cj14)*(cj9)*(r00));
12228 IkReal x2761=((x2756)+(x2755));
12229 evalcond[0]=((x2758)+(((IkReal(-1.00000000000000))*(x2753)*(x2754)))+(((IkReal(-1.00000000000000))*(x2759)))+(((cj13)*(x2749)))+(((IkReal(-1.00000000000000))*(r22)*(x2746))));
12230 evalcond[1]=((x2761)+(((sj13)*(x2749)))+(((IkReal(-1.00000000000000))*(x2746)*(x2754)))+(((cj13)*(r22))));
12231 evalcond[2]=((x2761)+(((r12)*(x2751)))+(((sj13)*(x2750)))+(((IkReal(-1.00000000000000))*(x2748)*(x2757)))+(((cj13)*(sj9)*(x2752)))+(((cj13)*(x2760)))+(((IkReal(-1.00000000000000))*(x2747)*(x2757))));
12232 evalcond[3]=((x2759)+(((IkReal(-1.00000000000000))*(sj14)*(x2746)*(x2747)))+(((IkReal(-1.00000000000000))*(sj14)*(x2746)*(x2748)))+(((sj13)*(x2760)))+(((IkReal(-1.00000000000000))*(x2750)*(x2753)))+(((IkReal(-1.00000000000000))*(x2758)))+(((x2751)*(x2752)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2753))));
12233 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12234 {
12235 continue;
12236 }
12237 }
12238 
12239 {
12240 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12241 vinfos[0].jointtype = 1;
12242 vinfos[0].foffset = j9;
12243 vinfos[0].indices[0] = _ij9[0];
12244 vinfos[0].indices[1] = _ij9[1];
12245 vinfos[0].maxsolutions = _nj9;
12246 vinfos[1].jointtype = 1;
12247 vinfos[1].foffset = j10;
12248 vinfos[1].indices[0] = _ij10[0];
12249 vinfos[1].indices[1] = _ij10[1];
12250 vinfos[1].maxsolutions = _nj10;
12251 vinfos[2].jointtype = 1;
12252 vinfos[2].foffset = j11;
12253 vinfos[2].indices[0] = _ij11[0];
12254 vinfos[2].indices[1] = _ij11[1];
12255 vinfos[2].maxsolutions = _nj11;
12256 vinfos[3].jointtype = 1;
12257 vinfos[3].foffset = j12;
12258 vinfos[3].indices[0] = _ij12[0];
12259 vinfos[3].indices[1] = _ij12[1];
12260 vinfos[3].maxsolutions = _nj12;
12261 vinfos[4].jointtype = 1;
12262 vinfos[4].foffset = j13;
12263 vinfos[4].indices[0] = _ij13[0];
12264 vinfos[4].indices[1] = _ij13[1];
12265 vinfos[4].maxsolutions = _nj13;
12266 vinfos[5].jointtype = 1;
12267 vinfos[5].foffset = j14;
12268 vinfos[5].indices[0] = _ij14[0];
12269 vinfos[5].indices[1] = _ij14[1];
12270 vinfos[5].maxsolutions = _nj14;
12271 std::vector<int> vfree(0);
12272 solutions.AddSolution(vinfos,vfree);
12273 }
12274 }
12275 }
12276 
12277 }
12278 
12279 }
12280 
12281 } else
12282 {
12283 {
12284 IkReal j10array[1], cj10array[1], sj10array[1];
12285 bool j10valid[1]={false};
12286 _nj10 = 1;
12287 IkReal x2762=((cj13)*(sj11));
12288 IkReal x2763=((r21)*(sj14));
12289 IkReal x2764=((cj11)*(cj13));
12290 IkReal x2765=((cj11)*(sj13));
12291 IkReal x2766=((sj11)*(sj13));
12292 IkReal x2767=((IkReal(1.00000000000000))*(cj14)*(r20));
12293 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(r22)*(x2766)))+(((x2762)*(x2763)))+(((IkReal(-1.00000000000000))*(x2762)*(x2767)))+(((r22)*(x2764)))+(((x2763)*(x2765)))+(((IkReal(-1.00000000000000))*(x2765)*(x2767))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x2763)*(x2764)))+(((cj14)*(r20)*(x2764)))+(((r22)*(x2762)))+(((r22)*(x2765)))+(((IkReal(-1.00000000000000))*(x2766)*(x2767)))+(((x2763)*(x2766))))))) < IKFAST_ATAN2_MAGTHRESH )
12294     continue;
12295 j10array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(r22)*(x2766)))+(((x2762)*(x2763)))+(((IkReal(-1.00000000000000))*(x2762)*(x2767)))+(((r22)*(x2764)))+(((x2763)*(x2765)))+(((IkReal(-1.00000000000000))*(x2765)*(x2767)))))), ((gconst52)*(((((IkReal(-1.00000000000000))*(x2763)*(x2764)))+(((cj14)*(r20)*(x2764)))+(((r22)*(x2762)))+(((r22)*(x2765)))+(((IkReal(-1.00000000000000))*(x2766)*(x2767)))+(((x2763)*(x2766)))))));
12296 sj10array[0]=IKsin(j10array[0]);
12297 cj10array[0]=IKcos(j10array[0]);
12298 if( j10array[0] > IKPI )
12299 {
12300     j10array[0]-=IK2PI;
12301 }
12302 else if( j10array[0] < -IKPI )
12303 {    j10array[0]+=IK2PI;
12304 }
12305 j10valid[0] = true;
12306 for(int ij10 = 0; ij10 < 1; ++ij10)
12307 {
12308 if( !j10valid[ij10] )
12309 {
12310     continue;
12311 }
12312 _ij10[0] = ij10; _ij10[1] = -1;
12313 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12314 {
12315 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12316 {
12317     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12318 }
12319 }
12320 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12321 {
12322 IkReal evalcond[4];
12323 IkReal x2768=IKsin(j10);
12324 IkReal x2769=IKcos(j10);
12325 IkReal x2770=((IkReal(1.00000000000000))*(sj13));
12326 IkReal x2771=((r11)*(sj9));
12327 IkReal x2772=((cj9)*(r01));
12328 IkReal x2773=((r21)*(sj14));
12329 IkReal x2774=((cj9)*(r02));
12330 IkReal x2775=((sj13)*(sj9));
12331 IkReal x2776=((cj14)*(r10));
12332 IkReal x2777=((IkReal(1.00000000000000))*(cj13));
12333 IkReal x2778=((cj14)*(r20));
12334 IkReal x2779=((cj11)*(x2768));
12335 IkReal x2780=((sj11)*(x2769));
12336 IkReal x2781=((sj14)*(x2777));
12337 IkReal x2782=((sj11)*(x2768));
12338 IkReal x2783=((cj11)*(x2769));
12339 IkReal x2784=((cj14)*(cj9)*(r00));
12340 IkReal x2785=((x2779)+(x2780));
12341 evalcond[0]=((x2782)+(((IkReal(-1.00000000000000))*(x2777)*(x2778)))+(((cj13)*(x2773)))+(((IkReal(-1.00000000000000))*(x2783)))+(((IkReal(-1.00000000000000))*(r22)*(x2770))));
12342 evalcond[1]=((x2785)+(((IkReal(-1.00000000000000))*(x2770)*(x2778)))+(((sj13)*(x2773)))+(((cj13)*(r22))));
12343 evalcond[2]=((x2785)+(((cj13)*(x2784)))+(((sj13)*(x2774)))+(((cj13)*(sj9)*(x2776)))+(((IkReal(-1.00000000000000))*(x2772)*(x2781)))+(((IkReal(-1.00000000000000))*(x2771)*(x2781)))+(((r12)*(x2775))));
12344 evalcond[3]=((x2783)+(((IkReal(-1.00000000000000))*(sj14)*(x2770)*(x2771)))+(((IkReal(-1.00000000000000))*(sj14)*(x2770)*(x2772)))+(((x2775)*(x2776)))+(((IkReal(-1.00000000000000))*(x2782)))+(((IkReal(-1.00000000000000))*(x2774)*(x2777)))+(((sj13)*(x2784)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2777))));
12345 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12346 {
12347 continue;
12348 }
12349 }
12350 
12351 {
12352 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12353 vinfos[0].jointtype = 1;
12354 vinfos[0].foffset = j9;
12355 vinfos[0].indices[0] = _ij9[0];
12356 vinfos[0].indices[1] = _ij9[1];
12357 vinfos[0].maxsolutions = _nj9;
12358 vinfos[1].jointtype = 1;
12359 vinfos[1].foffset = j10;
12360 vinfos[1].indices[0] = _ij10[0];
12361 vinfos[1].indices[1] = _ij10[1];
12362 vinfos[1].maxsolutions = _nj10;
12363 vinfos[2].jointtype = 1;
12364 vinfos[2].foffset = j11;
12365 vinfos[2].indices[0] = _ij11[0];
12366 vinfos[2].indices[1] = _ij11[1];
12367 vinfos[2].maxsolutions = _nj11;
12368 vinfos[3].jointtype = 1;
12369 vinfos[3].foffset = j12;
12370 vinfos[3].indices[0] = _ij12[0];
12371 vinfos[3].indices[1] = _ij12[1];
12372 vinfos[3].maxsolutions = _nj12;
12373 vinfos[4].jointtype = 1;
12374 vinfos[4].foffset = j13;
12375 vinfos[4].indices[0] = _ij13[0];
12376 vinfos[4].indices[1] = _ij13[1];
12377 vinfos[4].maxsolutions = _nj13;
12378 vinfos[5].jointtype = 1;
12379 vinfos[5].foffset = j14;
12380 vinfos[5].indices[0] = _ij14[0];
12381 vinfos[5].indices[1] = _ij14[1];
12382 vinfos[5].maxsolutions = _nj14;
12383 std::vector<int> vfree(0);
12384 solutions.AddSolution(vinfos,vfree);
12385 }
12386 }
12387 }
12388 
12389 }
12390 
12391 }
12392 
12393 } else
12394 {
12395 IkReal x2786=((cj9)*(r10));
12396 IkReal x2787=((cj13)*(cj14));
12397 IkReal x2788=((sj14)*(sj9));
12398 IkReal x2789=((IkReal(1.00000000000000))*(sj14));
12399 IkReal x2790=((cj9)*(sj13));
12400 IkReal x2791=((r02)*(sj9));
12401 IkReal x2792=((cj13)*(cj9));
12402 IkReal x2793=((cj14)*(r01));
12403 IkReal x2794=((IkReal(1.00000000000000))*(npx));
12404 IkReal x2795=((cj14)*(sj13));
12405 IkReal x2796=((IkReal(1.00000000000000))*(cj9));
12406 IkReal x2797=((npy)*(sj14));
12407 IkReal x2798=((IkReal(1.00000000000000))*(sj13));
12408 IkReal x2799=((IkReal(1.00000000000000))*(cj14)*(sj9));
12409 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
12410 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
12411 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
12412 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x2798)))+(((IkReal(-1.00000000000000))*(x2787)*(x2794)))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x2797)))+(((IkReal(0.250000000000000))*(cj11))));
12413 evalcond[4]=((IkReal(-1.00000000000000))+(((sj9)*(x2793)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2796)))+(((IkReal(-1.00000000000000))*(x2786)*(x2789)))+(((r00)*(x2788))));
12414 evalcond[5]=((IkReal(-0.0300000000000000))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((sj13)*(x2797)))+(((IkReal(0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x2794)*(x2795))));
12415 evalcond[6]=((((IkReal(-1.00000000000000))*(cj9)*(r00)*(x2789)))+(((IkReal(-1.00000000000000))*(r10)*(x2788)))+(((IkReal(-1.00000000000000))*(x2793)*(x2796)))+(((IkReal(-1.00000000000000))*(r11)*(x2799))));
12416 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x2789)*(x2792)))+(((IkReal(-1.00000000000000))*(x2791)*(x2798)))+(((r12)*(x2790)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2787)))+(((cj13)*(r01)*(x2788)))+(((x2786)*(x2787))));
12417 evalcond[8]=((((x2786)*(x2795)))+(((IkReal(-1.00000000000000))*(r11)*(x2789)*(x2790)))+(((cj13)*(x2791)))+(((r01)*(sj13)*(x2788)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x2795)))+(((IkReal(-1.00000000000000))*(r12)*(x2792))));
12418 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  )
12419 {
12420 {
12421 IkReal dummyeval[1];
12422 IkReal gconst54;
12423 gconst54=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
12424 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
12425 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12426 {
12427 {
12428 IkReal dummyeval[1];
12429 IkReal gconst55;
12430 gconst55=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
12431 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
12432 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12433 {
12434 continue;
12435 
12436 } else
12437 {
12438 {
12439 IkReal j10array[1], cj10array[1], sj10array[1];
12440 bool j10valid[1]={false};
12441 _nj10 = 1;
12442 IkReal x2800=((cj13)*(sj14));
12443 IkReal x2801=((IkReal(1.00000000000000))*(cj11));
12444 IkReal x2802=((r11)*(sj9));
12445 IkReal x2803=((cj11)*(sj13));
12446 IkReal x2804=((r12)*(sj9));
12447 IkReal x2805=((r10)*(sj9));
12448 IkReal x2806=((sj11)*(sj13));
12449 IkReal x2807=((cj9)*(r02));
12450 IkReal x2808=((IkReal(1.00000000000000))*(sj11));
12451 IkReal x2809=((cj9)*(r01));
12452 IkReal x2810=((cj9)*(r00));
12453 IkReal x2811=((cj13)*(cj14)*(sj11));
12454 IkReal x2812=((cj11)*(cj13)*(cj14));
12455 if( IKabs(((gconst55)*(((((x2810)*(x2812)))+(((IkReal(-1.00000000000000))*(r22)*(x2806)))+(((x2803)*(x2804)))+(((x2803)*(x2807)))+(((r21)*(sj11)*(x2800)))+(((x2805)*(x2812)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)*(x2809)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)*(x2802)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2808))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((x2810)*(x2811)))+(((x2804)*(x2806)))+(((IkReal(-1.00000000000000))*(x2800)*(x2802)*(x2808)))+(((IkReal(-1.00000000000000))*(x2800)*(x2808)*(x2809)))+(((IkReal(-1.00000000000000))*(r21)*(x2800)*(x2801)))+(((x2805)*(x2811)))+(((r20)*(x2812)))+(((x2806)*(x2807)))+(((r22)*(x2803))))))) < IKFAST_ATAN2_MAGTHRESH )
12456     continue;
12457 j10array[0]=IKatan2(((gconst55)*(((((x2810)*(x2812)))+(((IkReal(-1.00000000000000))*(r22)*(x2806)))+(((x2803)*(x2804)))+(((x2803)*(x2807)))+(((r21)*(sj11)*(x2800)))+(((x2805)*(x2812)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)*(x2809)))+(((IkReal(-1.00000000000000))*(x2800)*(x2801)*(x2802)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x2808)))))), ((gconst55)*(((((x2810)*(x2811)))+(((x2804)*(x2806)))+(((IkReal(-1.00000000000000))*(x2800)*(x2802)*(x2808)))+(((IkReal(-1.00000000000000))*(x2800)*(x2808)*(x2809)))+(((IkReal(-1.00000000000000))*(r21)*(x2800)*(x2801)))+(((x2805)*(x2811)))+(((r20)*(x2812)))+(((x2806)*(x2807)))+(((r22)*(x2803)))))));
12458 sj10array[0]=IKsin(j10array[0]);
12459 cj10array[0]=IKcos(j10array[0]);
12460 if( j10array[0] > IKPI )
12461 {
12462     j10array[0]-=IK2PI;
12463 }
12464 else if( j10array[0] < -IKPI )
12465 {    j10array[0]+=IK2PI;
12466 }
12467 j10valid[0] = true;
12468 for(int ij10 = 0; ij10 < 1; ++ij10)
12469 {
12470 if( !j10valid[ij10] )
12471 {
12472     continue;
12473 }
12474 _ij10[0] = ij10; _ij10[1] = -1;
12475 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12476 {
12477 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12478 {
12479     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12480 }
12481 }
12482 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12483 {
12484 IkReal evalcond[4];
12485 IkReal x2813=IKsin(j10);
12486 IkReal x2814=IKcos(j10);
12487 IkReal x2815=((IkReal(1.00000000000000))*(sj13));
12488 IkReal x2816=((r11)*(sj9));
12489 IkReal x2817=((cj9)*(r01));
12490 IkReal x2818=((IkReal(1.00000000000000))*(cj11));
12491 IkReal x2819=((r21)*(sj14));
12492 IkReal x2820=((cj9)*(r02));
12493 IkReal x2821=((sj13)*(sj9));
12494 IkReal x2822=((cj14)*(r10));
12495 IkReal x2823=((IkReal(1.00000000000000))*(cj13));
12496 IkReal x2824=((cj14)*(r20));
12497 IkReal x2825=((sj11)*(x2813));
12498 IkReal x2826=((sj14)*(x2823));
12499 IkReal x2827=((sj11)*(x2814));
12500 IkReal x2828=((cj14)*(cj9)*(r00));
12501 IkReal x2829=((x2814)*(x2818));
12502 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x2815)))+(((cj13)*(x2819)))+(((IkReal(-1.00000000000000))*(x2823)*(x2824)))+(((IkReal(-1.00000000000000))*(x2829)))+(x2825));
12503 evalcond[1]=((((IkReal(-1.00000000000000))*(x2813)*(x2818)))+(((IkReal(-1.00000000000000))*(x2827)))+(((cj13)*(r22)))+(((sj13)*(x2819)))+(((IkReal(-1.00000000000000))*(x2815)*(x2824))));
12504 evalcond[2]=((((IkReal(-1.00000000000000))*(x2816)*(x2826)))+(((cj13)*(x2828)))+(((sj13)*(x2820)))+(((IkReal(-1.00000000000000))*(x2817)*(x2826)))+(((cj11)*(x2813)))+(((cj13)*(sj9)*(x2822)))+(x2827)+(((r12)*(x2821))));
12505 evalcond[3]=((((IkReal(-1.00000000000000))*(x2820)*(x2823)))+(((x2821)*(x2822)))+(((sj13)*(x2828)))+(((IkReal(-1.00000000000000))*(sj14)*(x2815)*(x2817)))+(((IkReal(-1.00000000000000))*(sj14)*(x2815)*(x2816)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2823)))+(((IkReal(-1.00000000000000))*(x2829)))+(x2825));
12506 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12507 {
12508 continue;
12509 }
12510 }
12511 
12512 {
12513 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12514 vinfos[0].jointtype = 1;
12515 vinfos[0].foffset = j9;
12516 vinfos[0].indices[0] = _ij9[0];
12517 vinfos[0].indices[1] = _ij9[1];
12518 vinfos[0].maxsolutions = _nj9;
12519 vinfos[1].jointtype = 1;
12520 vinfos[1].foffset = j10;
12521 vinfos[1].indices[0] = _ij10[0];
12522 vinfos[1].indices[1] = _ij10[1];
12523 vinfos[1].maxsolutions = _nj10;
12524 vinfos[2].jointtype = 1;
12525 vinfos[2].foffset = j11;
12526 vinfos[2].indices[0] = _ij11[0];
12527 vinfos[2].indices[1] = _ij11[1];
12528 vinfos[2].maxsolutions = _nj11;
12529 vinfos[3].jointtype = 1;
12530 vinfos[3].foffset = j12;
12531 vinfos[3].indices[0] = _ij12[0];
12532 vinfos[3].indices[1] = _ij12[1];
12533 vinfos[3].maxsolutions = _nj12;
12534 vinfos[4].jointtype = 1;
12535 vinfos[4].foffset = j13;
12536 vinfos[4].indices[0] = _ij13[0];
12537 vinfos[4].indices[1] = _ij13[1];
12538 vinfos[4].maxsolutions = _nj13;
12539 vinfos[5].jointtype = 1;
12540 vinfos[5].foffset = j14;
12541 vinfos[5].indices[0] = _ij14[0];
12542 vinfos[5].indices[1] = _ij14[1];
12543 vinfos[5].maxsolutions = _nj14;
12544 std::vector<int> vfree(0);
12545 solutions.AddSolution(vinfos,vfree);
12546 }
12547 }
12548 }
12549 
12550 }
12551 
12552 }
12553 
12554 } else
12555 {
12556 {
12557 IkReal j10array[1], cj10array[1], sj10array[1];
12558 bool j10valid[1]={false};
12559 _nj10 = 1;
12560 IkReal x2830=((r22)*(sj11));
12561 IkReal x2831=((IkReal(1.00000000000000))*(sj11));
12562 IkReal x2832=((IkReal(1.00000000000000))*(cj11));
12563 IkReal x2833=((cj14)*(r20));
12564 IkReal x2834=((cj13)*(r21)*(sj14));
12565 IkReal x2835=((r21)*(sj13)*(sj14));
12566 if( IKabs(((gconst54)*(((((cj13)*(sj11)*(x2833)))+(((sj13)*(x2830)))+(((cj11)*(cj13)*(r22)))+(((cj11)*(x2835)))+(((IkReal(-1.00000000000000))*(sj13)*(x2832)*(x2833)))+(((IkReal(-1.00000000000000))*(x2831)*(x2834))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2832)))+(((IkReal(-1.00000000000000))*(sj13)*(x2831)*(x2833)))+(((cj13)*(x2830)))+(((cj11)*(x2834)))+(((IkReal(-1.00000000000000))*(cj13)*(x2832)*(x2833)))+(((sj11)*(x2835))))))) < IKFAST_ATAN2_MAGTHRESH )
12567     continue;
12568 j10array[0]=IKatan2(((gconst54)*(((((cj13)*(sj11)*(x2833)))+(((sj13)*(x2830)))+(((cj11)*(cj13)*(r22)))+(((cj11)*(x2835)))+(((IkReal(-1.00000000000000))*(sj13)*(x2832)*(x2833)))+(((IkReal(-1.00000000000000))*(x2831)*(x2834)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x2832)))+(((IkReal(-1.00000000000000))*(sj13)*(x2831)*(x2833)))+(((cj13)*(x2830)))+(((cj11)*(x2834)))+(((IkReal(-1.00000000000000))*(cj13)*(x2832)*(x2833)))+(((sj11)*(x2835)))))));
12569 sj10array[0]=IKsin(j10array[0]);
12570 cj10array[0]=IKcos(j10array[0]);
12571 if( j10array[0] > IKPI )
12572 {
12573     j10array[0]-=IK2PI;
12574 }
12575 else if( j10array[0] < -IKPI )
12576 {    j10array[0]+=IK2PI;
12577 }
12578 j10valid[0] = true;
12579 for(int ij10 = 0; ij10 < 1; ++ij10)
12580 {
12581 if( !j10valid[ij10] )
12582 {
12583     continue;
12584 }
12585 _ij10[0] = ij10; _ij10[1] = -1;
12586 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12587 {
12588 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12589 {
12590     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12591 }
12592 }
12593 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12594 {
12595 IkReal evalcond[4];
12596 IkReal x2836=IKsin(j10);
12597 IkReal x2837=IKcos(j10);
12598 IkReal x2838=((IkReal(1.00000000000000))*(sj13));
12599 IkReal x2839=((r11)*(sj9));
12600 IkReal x2840=((cj9)*(r01));
12601 IkReal x2841=((IkReal(1.00000000000000))*(cj11));
12602 IkReal x2842=((r21)*(sj14));
12603 IkReal x2843=((cj9)*(r02));
12604 IkReal x2844=((sj13)*(sj9));
12605 IkReal x2845=((cj14)*(r10));
12606 IkReal x2846=((IkReal(1.00000000000000))*(cj13));
12607 IkReal x2847=((cj14)*(r20));
12608 IkReal x2848=((sj11)*(x2836));
12609 IkReal x2849=((sj14)*(x2846));
12610 IkReal x2850=((sj11)*(x2837));
12611 IkReal x2851=((cj14)*(cj9)*(r00));
12612 IkReal x2852=((x2837)*(x2841));
12613 evalcond[0]=((((IkReal(-1.00000000000000))*(x2846)*(x2847)))+(((cj13)*(x2842)))+(((IkReal(-1.00000000000000))*(r22)*(x2838)))+(x2848)+(((IkReal(-1.00000000000000))*(x2852))));
12614 evalcond[1]=((((sj13)*(x2842)))+(((IkReal(-1.00000000000000))*(x2836)*(x2841)))+(((IkReal(-1.00000000000000))*(x2838)*(x2847)))+(((IkReal(-1.00000000000000))*(x2850)))+(((cj13)*(r22))));
12615 evalcond[2]=((((cj13)*(x2851)))+(((IkReal(-1.00000000000000))*(x2840)*(x2849)))+(((sj13)*(x2843)))+(((r12)*(x2844)))+(((IkReal(-1.00000000000000))*(x2839)*(x2849)))+(((cj11)*(x2836)))+(x2850)+(((cj13)*(sj9)*(x2845))));
12616 evalcond[3]=((((IkReal(-1.00000000000000))*(x2843)*(x2846)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x2846)))+(((x2844)*(x2845)))+(((IkReal(-1.00000000000000))*(sj14)*(x2838)*(x2839)))+(((sj13)*(x2851)))+(((IkReal(-1.00000000000000))*(sj14)*(x2838)*(x2840)))+(x2848)+(((IkReal(-1.00000000000000))*(x2852))));
12617 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
12618 {
12619 continue;
12620 }
12621 }
12622 
12623 {
12624 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12625 vinfos[0].jointtype = 1;
12626 vinfos[0].foffset = j9;
12627 vinfos[0].indices[0] = _ij9[0];
12628 vinfos[0].indices[1] = _ij9[1];
12629 vinfos[0].maxsolutions = _nj9;
12630 vinfos[1].jointtype = 1;
12631 vinfos[1].foffset = j10;
12632 vinfos[1].indices[0] = _ij10[0];
12633 vinfos[1].indices[1] = _ij10[1];
12634 vinfos[1].maxsolutions = _nj10;
12635 vinfos[2].jointtype = 1;
12636 vinfos[2].foffset = j11;
12637 vinfos[2].indices[0] = _ij11[0];
12638 vinfos[2].indices[1] = _ij11[1];
12639 vinfos[2].maxsolutions = _nj11;
12640 vinfos[3].jointtype = 1;
12641 vinfos[3].foffset = j12;
12642 vinfos[3].indices[0] = _ij12[0];
12643 vinfos[3].indices[1] = _ij12[1];
12644 vinfos[3].maxsolutions = _nj12;
12645 vinfos[4].jointtype = 1;
12646 vinfos[4].foffset = j13;
12647 vinfos[4].indices[0] = _ij13[0];
12648 vinfos[4].indices[1] = _ij13[1];
12649 vinfos[4].maxsolutions = _nj13;
12650 vinfos[5].jointtype = 1;
12651 vinfos[5].foffset = j14;
12652 vinfos[5].indices[0] = _ij14[0];
12653 vinfos[5].indices[1] = _ij14[1];
12654 vinfos[5].maxsolutions = _nj14;
12655 std::vector<int> vfree(0);
12656 solutions.AddSolution(vinfos,vfree);
12657 }
12658 }
12659 }
12660 
12661 }
12662 
12663 }
12664 
12665 } else
12666 {
12667 if( 1 )
12668 {
12669 continue;
12670 
12671 } else
12672 {
12673 }
12674 }
12675 }
12676 }
12677 }
12678 }
12679 
12680 } else
12681 {
12682 {
12683 IkReal j10array[1], cj10array[1], sj10array[1];
12684 bool j10valid[1]={false};
12685 _nj10 = 1;
12686 IkReal x2853=((r21)*(sj14));
12687 IkReal x2854=((cj12)*(cj13));
12688 IkReal x2855=((sj11)*(sj13));
12689 IkReal x2856=((cj14)*(r20));
12690 IkReal x2857=((IkReal(1.00000000000000))*(sj11));
12691 IkReal x2858=((cj12)*(r22));
12692 IkReal x2859=((IkReal(1.00000000000000))*(cj11));
12693 IkReal x2860=((cj13)*(r22));
12694 IkReal x2861=((sj13)*(x2859));
12695 if( IKabs(((gconst47)*(((((x2855)*(x2858)))+(((sj11)*(x2854)*(x2856)))+(((IkReal(-1.00000000000000))*(x2853)*(x2854)*(x2857)))+(((IkReal(-1.00000000000000))*(x2853)*(x2861)))+(((IkReal(-1.00000000000000))*(x2859)*(x2860)))+(((cj11)*(sj13)*(x2856))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((x2855)*(x2856)))+(((IkReal(-1.00000000000000))*(x2854)*(x2856)*(x2859)))+(((IkReal(-1.00000000000000))*(x2857)*(x2860)))+(((IkReal(-1.00000000000000))*(x2853)*(x2855)))+(((IkReal(-1.00000000000000))*(x2858)*(x2861)))+(((cj11)*(x2853)*(x2854))))))) < IKFAST_ATAN2_MAGTHRESH )
12696     continue;
12697 j10array[0]=IKatan2(((gconst47)*(((((x2855)*(x2858)))+(((sj11)*(x2854)*(x2856)))+(((IkReal(-1.00000000000000))*(x2853)*(x2854)*(x2857)))+(((IkReal(-1.00000000000000))*(x2853)*(x2861)))+(((IkReal(-1.00000000000000))*(x2859)*(x2860)))+(((cj11)*(sj13)*(x2856)))))), ((gconst47)*(((((x2855)*(x2856)))+(((IkReal(-1.00000000000000))*(x2854)*(x2856)*(x2859)))+(((IkReal(-1.00000000000000))*(x2857)*(x2860)))+(((IkReal(-1.00000000000000))*(x2853)*(x2855)))+(((IkReal(-1.00000000000000))*(x2858)*(x2861)))+(((cj11)*(x2853)*(x2854)))))));
12698 sj10array[0]=IKsin(j10array[0]);
12699 cj10array[0]=IKcos(j10array[0]);
12700 if( j10array[0] > IKPI )
12701 {
12702     j10array[0]-=IK2PI;
12703 }
12704 else if( j10array[0] < -IKPI )
12705 {    j10array[0]+=IK2PI;
12706 }
12707 j10valid[0] = true;
12708 for(int ij10 = 0; ij10 < 1; ++ij10)
12709 {
12710 if( !j10valid[ij10] )
12711 {
12712     continue;
12713 }
12714 _ij10[0] = ij10; _ij10[1] = -1;
12715 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12716 {
12717 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12718 {
12719     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12720 }
12721 }
12722 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12723 {
12724 IkReal evalcond[6];
12725 IkReal x2862=IKsin(j10);
12726 IkReal x2863=IKcos(j10);
12727 IkReal x2864=((IkReal(1.00000000000000))*(cj13));
12728 IkReal x2865=((cj9)*(r02));
12729 IkReal x2866=((IkReal(1.00000000000000))*(sj13));
12730 IkReal x2867=((r11)*(sj9));
12731 IkReal x2868=((IkReal(1.00000000000000))*(cj14));
12732 IkReal x2869=((cj9)*(r01));
12733 IkReal x2870=((r21)*(sj14));
12734 IkReal x2871=((IkReal(1.00000000000000))*(sj12));
12735 IkReal x2872=((r10)*(sj9));
12736 IkReal x2873=((cj14)*(sj13));
12737 IkReal x2874=((cj14)*(r20));
12738 IkReal x2875=((IkReal(1.00000000000000))*(sj14));
12739 IkReal x2876=((r12)*(sj9));
12740 IkReal x2877=((cj13)*(cj14));
12741 IkReal x2878=((cj9)*(r00));
12742 IkReal x2879=((sj11)*(x2862));
12743 IkReal x2880=((cj11)*(x2862));
12744 IkReal x2881=((sj11)*(x2863));
12745 IkReal x2882=((cj11)*(x2863));
12746 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x2871)*(x2880)))+(((IkReal(-1.00000000000000))*(x2871)*(x2881)))+(((r20)*(sj14))));
12747 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x2866)))+(((IkReal(-1.00000000000000))*(x2864)*(x2874)))+(((IkReal(-1.00000000000000))*(x2882)))+(((cj13)*(x2870)))+(x2879));
12748 evalcond[2]=((((cj12)*(x2881)))+(((cj12)*(x2880)))+(((sj13)*(x2870)))+(((IkReal(-1.00000000000000))*(x2866)*(x2874)))+(((cj13)*(r22))));
12749 evalcond[3]=((((IkReal(-1.00000000000000))*(x2871)*(x2882)))+(((IkReal(-1.00000000000000))*(x2872)*(x2875)))+(((IkReal(-1.00000000000000))*(x2867)*(x2868)))+(((IkReal(-1.00000000000000))*(x2868)*(x2869)))+(((IkReal(-1.00000000000000))*(x2875)*(x2878)))+(((sj12)*(x2879))));
12750 evalcond[4]=((((x2877)*(x2878)))+(((x2872)*(x2877)))+(((IkReal(-1.00000000000000))*(sj14)*(x2864)*(x2867)))+(((IkReal(-1.00000000000000))*(sj14)*(x2864)*(x2869)))+(((sj13)*(x2876)))+(x2880)+(x2881)+(((sj13)*(x2865))));
12751 evalcond[5]=((((IkReal(-1.00000000000000))*(x2864)*(x2865)))+(((IkReal(-1.00000000000000))*(cj12)*(x2879)))+(((x2872)*(x2873)))+(((IkReal(-1.00000000000000))*(x2864)*(x2876)))+(((x2873)*(x2878)))+(((cj12)*(x2882)))+(((IkReal(-1.00000000000000))*(sj14)*(x2866)*(x2869)))+(((IkReal(-1.00000000000000))*(sj14)*(x2866)*(x2867))));
12752 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  )
12753 {
12754 continue;
12755 }
12756 }
12757 
12758 {
12759 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12760 vinfos[0].jointtype = 1;
12761 vinfos[0].foffset = j9;
12762 vinfos[0].indices[0] = _ij9[0];
12763 vinfos[0].indices[1] = _ij9[1];
12764 vinfos[0].maxsolutions = _nj9;
12765 vinfos[1].jointtype = 1;
12766 vinfos[1].foffset = j10;
12767 vinfos[1].indices[0] = _ij10[0];
12768 vinfos[1].indices[1] = _ij10[1];
12769 vinfos[1].maxsolutions = _nj10;
12770 vinfos[2].jointtype = 1;
12771 vinfos[2].foffset = j11;
12772 vinfos[2].indices[0] = _ij11[0];
12773 vinfos[2].indices[1] = _ij11[1];
12774 vinfos[2].maxsolutions = _nj11;
12775 vinfos[3].jointtype = 1;
12776 vinfos[3].foffset = j12;
12777 vinfos[3].indices[0] = _ij12[0];
12778 vinfos[3].indices[1] = _ij12[1];
12779 vinfos[3].maxsolutions = _nj12;
12780 vinfos[4].jointtype = 1;
12781 vinfos[4].foffset = j13;
12782 vinfos[4].indices[0] = _ij13[0];
12783 vinfos[4].indices[1] = _ij13[1];
12784 vinfos[4].maxsolutions = _nj13;
12785 vinfos[5].jointtype = 1;
12786 vinfos[5].foffset = j14;
12787 vinfos[5].indices[0] = _ij14[0];
12788 vinfos[5].indices[1] = _ij14[1];
12789 vinfos[5].maxsolutions = _nj14;
12790 std::vector<int> vfree(0);
12791 solutions.AddSolution(vinfos,vfree);
12792 }
12793 }
12794 }
12795 
12796 }
12797 
12798 }
12799 
12800 } else
12801 {
12802 {
12803 IkReal j10array[1], cj10array[1], sj10array[1];
12804 bool j10valid[1]={false};
12805 _nj10 = 1;
12806 IkReal x2883=((cj11)*(sj12));
12807 IkReal x2884=((r22)*(sj13));
12808 IkReal x2885=((r20)*(sj14));
12809 IkReal x2886=((cj14)*(sj11));
12810 IkReal x2887=((cj13)*(r20));
12811 IkReal x2888=((sj11)*(sj12));
12812 IkReal x2889=((cj13)*(r21)*(sj14));
12813 if( IKabs(((gconst46)*(((((x2884)*(x2888)))+(((cj11)*(x2885)))+(((cj11)*(cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x2888)*(x2889)))+(((sj12)*(x2886)*(x2887))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x2883)*(x2887)))+(((r21)*(x2886)))+(((sj11)*(x2885)))+(((IkReal(-1.00000000000000))*(x2883)*(x2884)))+(((x2883)*(x2889))))))) < IKFAST_ATAN2_MAGTHRESH )
12814     continue;
12815 j10array[0]=IKatan2(((gconst46)*(((((x2884)*(x2888)))+(((cj11)*(x2885)))+(((cj11)*(cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x2888)*(x2889)))+(((sj12)*(x2886)*(x2887)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x2883)*(x2887)))+(((r21)*(x2886)))+(((sj11)*(x2885)))+(((IkReal(-1.00000000000000))*(x2883)*(x2884)))+(((x2883)*(x2889)))))));
12816 sj10array[0]=IKsin(j10array[0]);
12817 cj10array[0]=IKcos(j10array[0]);
12818 if( j10array[0] > IKPI )
12819 {
12820     j10array[0]-=IK2PI;
12821 }
12822 else if( j10array[0] < -IKPI )
12823 {    j10array[0]+=IK2PI;
12824 }
12825 j10valid[0] = true;
12826 for(int ij10 = 0; ij10 < 1; ++ij10)
12827 {
12828 if( !j10valid[ij10] )
12829 {
12830     continue;
12831 }
12832 _ij10[0] = ij10; _ij10[1] = -1;
12833 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
12834 {
12835 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
12836 {
12837     j10valid[iij10]=false; _ij10[1] = iij10; break; 
12838 }
12839 }
12840 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
12841 {
12842 IkReal evalcond[6];
12843 IkReal x2890=IKsin(j10);
12844 IkReal x2891=IKcos(j10);
12845 IkReal x2892=((IkReal(1.00000000000000))*(cj13));
12846 IkReal x2893=((cj9)*(r02));
12847 IkReal x2894=((IkReal(1.00000000000000))*(sj13));
12848 IkReal x2895=((r11)*(sj9));
12849 IkReal x2896=((IkReal(1.00000000000000))*(cj14));
12850 IkReal x2897=((cj9)*(r01));
12851 IkReal x2898=((r21)*(sj14));
12852 IkReal x2899=((IkReal(1.00000000000000))*(sj12));
12853 IkReal x2900=((r10)*(sj9));
12854 IkReal x2901=((cj14)*(sj13));
12855 IkReal x2902=((cj14)*(r20));
12856 IkReal x2903=((IkReal(1.00000000000000))*(sj14));
12857 IkReal x2904=((r12)*(sj9));
12858 IkReal x2905=((cj13)*(cj14));
12859 IkReal x2906=((cj9)*(r00));
12860 IkReal x2907=((sj11)*(x2890));
12861 IkReal x2908=((cj11)*(x2890));
12862 IkReal x2909=((sj11)*(x2891));
12863 IkReal x2910=((cj11)*(x2891));
12864 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x2899)*(x2908)))+(((IkReal(-1.00000000000000))*(x2899)*(x2909))));
12865 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x2894)))+(((IkReal(-1.00000000000000))*(x2892)*(x2902)))+(((IkReal(-1.00000000000000))*(x2910)))+(((cj13)*(x2898)))+(x2907));
12866 evalcond[2]=((((sj13)*(x2898)))+(((cj12)*(x2908)))+(((cj12)*(x2909)))+(((IkReal(-1.00000000000000))*(x2894)*(x2902)))+(((cj13)*(r22))));
12867 evalcond[3]=((((IkReal(-1.00000000000000))*(x2899)*(x2910)))+(((IkReal(-1.00000000000000))*(x2900)*(x2903)))+(((IkReal(-1.00000000000000))*(x2895)*(x2896)))+(((IkReal(-1.00000000000000))*(x2896)*(x2897)))+(((IkReal(-1.00000000000000))*(x2903)*(x2906)))+(((sj12)*(x2907))));
12868 evalcond[4]=((((sj13)*(x2893)))+(((x2905)*(x2906)))+(((x2900)*(x2905)))+(((IkReal(-1.00000000000000))*(sj14)*(x2892)*(x2895)))+(((IkReal(-1.00000000000000))*(sj14)*(x2892)*(x2897)))+(((sj13)*(x2904)))+(x2909)+(x2908));
12869 evalcond[5]=((((IkReal(-1.00000000000000))*(cj12)*(x2907)))+(((x2901)*(x2906)))+(((x2900)*(x2901)))+(((IkReal(-1.00000000000000))*(x2892)*(x2893)))+(((IkReal(-1.00000000000000))*(sj14)*(x2894)*(x2895)))+(((IkReal(-1.00000000000000))*(sj14)*(x2894)*(x2897)))+(((IkReal(-1.00000000000000))*(x2892)*(x2904)))+(((cj12)*(x2910))));
12870 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  )
12871 {
12872 continue;
12873 }
12874 }
12875 
12876 {
12877 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
12878 vinfos[0].jointtype = 1;
12879 vinfos[0].foffset = j9;
12880 vinfos[0].indices[0] = _ij9[0];
12881 vinfos[0].indices[1] = _ij9[1];
12882 vinfos[0].maxsolutions = _nj9;
12883 vinfos[1].jointtype = 1;
12884 vinfos[1].foffset = j10;
12885 vinfos[1].indices[0] = _ij10[0];
12886 vinfos[1].indices[1] = _ij10[1];
12887 vinfos[1].maxsolutions = _nj10;
12888 vinfos[2].jointtype = 1;
12889 vinfos[2].foffset = j11;
12890 vinfos[2].indices[0] = _ij11[0];
12891 vinfos[2].indices[1] = _ij11[1];
12892 vinfos[2].maxsolutions = _nj11;
12893 vinfos[3].jointtype = 1;
12894 vinfos[3].foffset = j12;
12895 vinfos[3].indices[0] = _ij12[0];
12896 vinfos[3].indices[1] = _ij12[1];
12897 vinfos[3].maxsolutions = _nj12;
12898 vinfos[4].jointtype = 1;
12899 vinfos[4].foffset = j13;
12900 vinfos[4].indices[0] = _ij13[0];
12901 vinfos[4].indices[1] = _ij13[1];
12902 vinfos[4].maxsolutions = _nj13;
12903 vinfos[5].jointtype = 1;
12904 vinfos[5].foffset = j14;
12905 vinfos[5].indices[0] = _ij14[0];
12906 vinfos[5].indices[1] = _ij14[1];
12907 vinfos[5].maxsolutions = _nj14;
12908 std::vector<int> vfree(0);
12909 solutions.AddSolution(vinfos,vfree);
12910 }
12911 }
12912 }
12913 
12914 }
12915 
12916 }
12917 }
12918 }
12919 
12920 }
12921 
12922 }
12923 }
12924 }
12925 
12926 }
12927 
12928 }
12929 
12930 } else
12931 {
12932 {
12933 IkReal j9array[1], cj9array[1], sj9array[1];
12934 bool j9valid[1]={false};
12935 _nj9 = 1;
12936 IkReal x2911=((cj12)*(sj13));
12937 IkReal x2912=((cj12)*(cj13));
12938 IkReal x2913=((IkReal(1.00000000000000))*(sj14));
12939 if( IKabs(((gconst0)*(((((r12)*(x2911)))+(((cj14)*(r10)*(x2912)))+(((IkReal(-1.00000000000000))*(r11)*(x2912)*(x2913))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((cj14)*(r00)*(x2912)))+(((IkReal(-1.00000000000000))*(r01)*(x2912)*(x2913)))+(((r02)*(x2911))))))) < IKFAST_ATAN2_MAGTHRESH )
12940     continue;
12941 j9array[0]=IKatan2(((gconst0)*(((((r12)*(x2911)))+(((cj14)*(r10)*(x2912)))+(((IkReal(-1.00000000000000))*(r11)*(x2912)*(x2913)))))), ((gconst0)*(((((cj14)*(r00)*(x2912)))+(((IkReal(-1.00000000000000))*(r01)*(x2912)*(x2913)))+(((r02)*(x2911)))))));
12942 sj9array[0]=IKsin(j9array[0]);
12943 cj9array[0]=IKcos(j9array[0]);
12944 if( j9array[0] > IKPI )
12945 {
12946     j9array[0]-=IK2PI;
12947 }
12948 else if( j9array[0] < -IKPI )
12949 {    j9array[0]+=IK2PI;
12950 }
12951 j9valid[0] = true;
12952 for(int ij9 = 0; ij9 < 1; ++ij9)
12953 {
12954 if( !j9valid[ij9] )
12955 {
12956     continue;
12957 }
12958 _ij9[0] = ij9; _ij9[1] = -1;
12959 for(int iij9 = ij9+1; iij9 < 1; ++iij9)
12960 {
12961 if( j9valid[iij9] && IKabs(cj9array[ij9]-cj9array[iij9]) < IKFAST_SOLUTION_THRESH && IKabs(sj9array[ij9]-sj9array[iij9]) < IKFAST_SOLUTION_THRESH )
12962 {
12963     j9valid[iij9]=false; _ij9[1] = iij9; break; 
12964 }
12965 }
12966 j9 = j9array[ij9]; cj9 = cj9array[ij9]; sj9 = sj9array[ij9];
12967 {
12968 IkReal evalcond[3];
12969 IkReal x2914=IKsin(j9);
12970 IkReal x2915=IKcos(j9);
12971 IkReal x2916=((IkReal(1.00000000000000))*(sj14));
12972 IkReal x2917=((sj13)*(x2915));
12973 IkReal x2918=((cj13)*(x2914));
12974 IkReal x2919=((IkReal(1.00000000000000))*(cj14)*(r00));
12975 IkReal x2920=((r01)*(x2914));
12976 IkReal x2921=((r10)*(x2915));
12977 IkReal x2922=((sj13)*(x2914));
12978 IkReal x2923=((cj13)*(x2915));
12979 evalcond[0]=((((IkReal(-1.00000000000000))*(x2916)*(x2921)))+(cj12)+(((cj14)*(x2920)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x2915)))+(((r00)*(sj14)*(x2914))));
12980 evalcond[1]=((((r12)*(x2917)))+(((cj13)*(cj14)*(x2921)))+(((IkReal(-1.00000000000000))*(r11)*(x2916)*(x2923)))+(((r01)*(sj14)*(x2918)))+(((IkReal(-1.00000000000000))*(x2918)*(x2919)))+(((IkReal(-1.00000000000000))*(r02)*(x2922))));
12981 evalcond[2]=((((IkReal(-1.00000000000000))*(r11)*(x2916)*(x2917)))+(((cj14)*(r10)*(x2917)))+(((IkReal(-1.00000000000000))*(x2919)*(x2922)))+(((IkReal(-1.00000000000000))*(r12)*(x2923)))+(sj12)+(((r02)*(x2918)))+(((sj13)*(sj14)*(x2920))));
12982 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
12983 {
12984 continue;
12985 }
12986 }
12987 
12988 {
12989 IkReal dummyeval[1];
12990 dummyeval[0]=sj12;
12991 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12992 {
12993 {
12994 IkReal dummyeval[1];
12995 dummyeval[0]=cj12;
12996 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
12997 {
12998 {
12999 IkReal evalcond[7];
13000 IkReal x2924=((IkReal(1.00000000000000))*(sj13));
13001 IkReal x2925=((cj14)*(sj9));
13002 IkReal x2926=((cj9)*(sj14));
13003 IkReal x2927=((cj13)*(sj9));
13004 IkReal x2928=((sj13)*(sj14));
13005 IkReal x2929=((cj9)*(sj13));
13006 IkReal x2930=((IkReal(1.00000000000000))*(cj13));
13007 IkReal x2931=((cj14)*(r10));
13008 IkReal x2932=((sj14)*(sj9));
13009 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
13010 evalcond[1]=((((r00)*(x2932)))+(((IkReal(-1.00000000000000))*(cj14)*(cj9)*(r11)))+(((r01)*(x2925)))+(((IkReal(-1.00000000000000))*(r10)*(x2926))));
13011 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2924)))+(((r21)*(x2928)))+(((cj13)*(r22))));
13012 evalcond[3]=((IkReal(0.0950000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x2924)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((npy)*(x2928))));
13013 evalcond[4]=((((cj13)*(cj9)*(x2931)))+(((IkReal(-1.00000000000000))*(r11)*(x2926)*(x2930)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2924)))+(((r01)*(sj14)*(x2927)))+(((IkReal(-1.00000000000000))*(r00)*(x2925)*(x2930)))+(((r12)*(x2929))));
13014 evalcond[5]=((IkReal(1.00000000000000))+(((x2929)*(x2931)))+(((IkReal(-1.00000000000000))*(cj9)*(r12)*(x2930)))+(((IkReal(-1.00000000000000))*(r11)*(x2924)*(x2926)))+(((r01)*(sj9)*(x2928)))+(((IkReal(-1.00000000000000))*(r00)*(x2924)*(x2925)))+(((r02)*(x2927))));
13015 evalcond[6]=((((IkReal(-1.00000000000000))*(r01)*(x2924)*(x2926)))+(((IkReal(-1.00000000000000))*(r11)*(x2924)*(x2932)))+(((r10)*(sj13)*(x2925)))+(((IkReal(-1.00000000000000))*(cj9)*(r02)*(x2930)))+(((IkReal(-1.00000000000000))*(r12)*(x2927)))+(((cj14)*(r00)*(x2929))));
13016 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  )
13017 {
13018 {
13019 IkReal j11array[1], cj11array[1], sj11array[1];
13020 bool j11valid[1]={false};
13021 _nj11 = 1;
13022 IkReal x2933=((IkReal(4.00000000000000))*(sj14));
13023 IkReal x2934=((IkReal(4.00000000000000))*(cj14));
13024 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2934)))+(((IkReal(-1.00000000000000))*(npx)*(x2933))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x2934)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2933)))+(((IkReal(-0.360000000000000))*(cj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2934)))+(((IkReal(-1.00000000000000))*(npx)*(x2933)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x2934)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2933)))+(((IkReal(-0.360000000000000))*(cj13)))))-1) <= IKFAST_SINCOS_THRESH )
13025     continue;
13026 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npy)*(x2934)))+(((IkReal(-1.00000000000000))*(npx)*(x2933)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x2934)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2933)))+(((IkReal(-0.360000000000000))*(cj13)))));
13027 sj11array[0]=IKsin(j11array[0]);
13028 cj11array[0]=IKcos(j11array[0]);
13029 if( j11array[0] > IKPI )
13030 {
13031     j11array[0]-=IK2PI;
13032 }
13033 else if( j11array[0] < -IKPI )
13034 {    j11array[0]+=IK2PI;
13035 }
13036 j11valid[0] = true;
13037 for(int ij11 = 0; ij11 < 1; ++ij11)
13038 {
13039 if( !j11valid[ij11] )
13040 {
13041     continue;
13042 }
13043 _ij11[0] = ij11; _ij11[1] = -1;
13044 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
13045 {
13046 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
13047 {
13048     j11valid[iij11]=false; _ij11[1] = iij11; break; 
13049 }
13050 }
13051 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
13052 {
13053 IkReal evalcond[2];
13054 evalcond[0]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(IKsin(j11)))));
13055 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(npx)))+(((cj13)*(npy)*(sj14)))+(((IkReal(-1.00000000000000))*(npz)*(sj13))));
13056 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13057 {
13058 continue;
13059 }
13060 }
13061 
13062 {
13063 IkReal dummyeval[1];
13064 IkReal gconst56;
13065 gconst56=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
13066 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
13067 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13068 {
13069 {
13070 IkReal dummyeval[1];
13071 IkReal gconst57;
13072 gconst57=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
13073 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
13074 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13075 {
13076 continue;
13077 
13078 } else
13079 {
13080 {
13081 IkReal j10array[1], cj10array[1], sj10array[1];
13082 bool j10valid[1]={false};
13083 _nj10 = 1;
13084 IkReal x2935=((IkReal(1.00000000000000))*(cj11));
13085 IkReal x2936=((r20)*(sj14));
13086 IkReal x2937=((cj14)*(r21));
13087 IkReal x2938=((cj14)*(cj9)*(r01));
13088 IkReal x2939=((r10)*(sj14)*(sj9));
13089 IkReal x2940=((cj9)*(r00)*(sj14));
13090 IkReal x2941=((cj14)*(r11)*(sj9));
13091 if( IKabs(((gconst57)*(((((sj11)*(x2940)))+(((sj11)*(x2941)))+(((sj11)*(x2939)))+(((sj11)*(x2938)))+(((cj11)*(x2936)))+(((cj11)*(x2937))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst57)*(((((IkReal(-1.00000000000000))*(x2935)*(x2941)))+(((IkReal(-1.00000000000000))*(x2935)*(x2940)))+(((sj11)*(x2936)))+(((sj11)*(x2937)))+(((IkReal(-1.00000000000000))*(x2935)*(x2938)))+(((IkReal(-1.00000000000000))*(x2935)*(x2939))))))) < IKFAST_ATAN2_MAGTHRESH )
13092     continue;
13093 j10array[0]=IKatan2(((gconst57)*(((((sj11)*(x2940)))+(((sj11)*(x2941)))+(((sj11)*(x2939)))+(((sj11)*(x2938)))+(((cj11)*(x2936)))+(((cj11)*(x2937)))))), ((gconst57)*(((((IkReal(-1.00000000000000))*(x2935)*(x2941)))+(((IkReal(-1.00000000000000))*(x2935)*(x2940)))+(((sj11)*(x2936)))+(((sj11)*(x2937)))+(((IkReal(-1.00000000000000))*(x2935)*(x2938)))+(((IkReal(-1.00000000000000))*(x2935)*(x2939)))))));
13094 sj10array[0]=IKsin(j10array[0]);
13095 cj10array[0]=IKcos(j10array[0]);
13096 if( j10array[0] > IKPI )
13097 {
13098     j10array[0]-=IK2PI;
13099 }
13100 else if( j10array[0] < -IKPI )
13101 {    j10array[0]+=IK2PI;
13102 }
13103 j10valid[0] = true;
13104 for(int ij10 = 0; ij10 < 1; ++ij10)
13105 {
13106 if( !j10valid[ij10] )
13107 {
13108     continue;
13109 }
13110 _ij10[0] = ij10; _ij10[1] = -1;
13111 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13112 {
13113 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13114 {
13115     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13116 }
13117 }
13118 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13119 {
13120 IkReal evalcond[4];
13121 IkReal x2942=IKsin(j10);
13122 IkReal x2943=IKcos(j10);
13123 IkReal x2944=((cj13)*(sj14));
13124 IkReal x2945=((cj13)*(cj14));
13125 IkReal x2946=((r10)*(sj9));
13126 IkReal x2947=((IkReal(1.00000000000000))*(cj9));
13127 IkReal x2948=((sj11)*(x2942));
13128 IkReal x2949=((IkReal(1.00000000000000))*(x2943));
13129 IkReal x2950=((cj11)*(x2942));
13130 IkReal x2951=((IkReal(1.00000000000000))*(r11)*(sj9));
13131 IkReal x2952=((cj11)*(x2949));
13132 evalcond[0]=((((IkReal(-1.00000000000000))*(x2950)))+(((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x2949))));
13133 evalcond[1]=((((r21)*(x2944)))+(((IkReal(-1.00000000000000))*(x2952)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x2945)))+(x2948));
13134 evalcond[2]=((((IkReal(-1.00000000000000))*(x2952)))+(((IkReal(-1.00000000000000))*(sj14)*(x2946)))+(((IkReal(-1.00000000000000))*(cj14)*(x2951)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2947)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2947)))+(x2948));
13135 evalcond[3]=((((sj11)*(x2943)))+(((x2945)*(x2946)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(x2944)*(x2951)))+(((IkReal(-1.00000000000000))*(r01)*(x2944)*(x2947)))+(((cj9)*(r00)*(x2945)))+(x2950)+(((r12)*(sj13)*(sj9))));
13136 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13137 {
13138 continue;
13139 }
13140 }
13141 
13142 {
13143 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13144 vinfos[0].jointtype = 1;
13145 vinfos[0].foffset = j9;
13146 vinfos[0].indices[0] = _ij9[0];
13147 vinfos[0].indices[1] = _ij9[1];
13148 vinfos[0].maxsolutions = _nj9;
13149 vinfos[1].jointtype = 1;
13150 vinfos[1].foffset = j10;
13151 vinfos[1].indices[0] = _ij10[0];
13152 vinfos[1].indices[1] = _ij10[1];
13153 vinfos[1].maxsolutions = _nj10;
13154 vinfos[2].jointtype = 1;
13155 vinfos[2].foffset = j11;
13156 vinfos[2].indices[0] = _ij11[0];
13157 vinfos[2].indices[1] = _ij11[1];
13158 vinfos[2].maxsolutions = _nj11;
13159 vinfos[3].jointtype = 1;
13160 vinfos[3].foffset = j12;
13161 vinfos[3].indices[0] = _ij12[0];
13162 vinfos[3].indices[1] = _ij12[1];
13163 vinfos[3].maxsolutions = _nj12;
13164 vinfos[4].jointtype = 1;
13165 vinfos[4].foffset = j13;
13166 vinfos[4].indices[0] = _ij13[0];
13167 vinfos[4].indices[1] = _ij13[1];
13168 vinfos[4].maxsolutions = _nj13;
13169 vinfos[5].jointtype = 1;
13170 vinfos[5].foffset = j14;
13171 vinfos[5].indices[0] = _ij14[0];
13172 vinfos[5].indices[1] = _ij14[1];
13173 vinfos[5].maxsolutions = _nj14;
13174 std::vector<int> vfree(0);
13175 solutions.AddSolution(vinfos,vfree);
13176 }
13177 }
13178 }
13179 
13180 }
13181 
13182 }
13183 
13184 } else
13185 {
13186 {
13187 IkReal j10array[1], cj10array[1], sj10array[1];
13188 bool j10valid[1]={false};
13189 _nj10 = 1;
13190 IkReal x2953=((r20)*(sj14));
13191 IkReal x2954=((IkReal(1.00000000000000))*(cj13));
13192 IkReal x2955=((cj14)*(r20));
13193 IkReal x2956=((r21)*(sj14));
13194 IkReal x2957=((r22)*(sj13));
13195 IkReal x2958=((cj14)*(r21));
13196 if( IKabs(((gconst56)*(((((sj11)*(x2957)))+(((cj13)*(sj11)*(x2955)))+(((cj11)*(x2958)))+(((cj11)*(x2953)))+(((IkReal(-1.00000000000000))*(sj11)*(x2954)*(x2956))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst56)*(((((IkReal(-1.00000000000000))*(cj11)*(x2957)))+(((sj11)*(x2958)))+(((sj11)*(x2953)))+(((cj11)*(cj13)*(x2956)))+(((IkReal(-1.00000000000000))*(cj11)*(x2954)*(x2955))))))) < IKFAST_ATAN2_MAGTHRESH )
13197     continue;
13198 j10array[0]=IKatan2(((gconst56)*(((((sj11)*(x2957)))+(((cj13)*(sj11)*(x2955)))+(((cj11)*(x2958)))+(((cj11)*(x2953)))+(((IkReal(-1.00000000000000))*(sj11)*(x2954)*(x2956)))))), ((gconst56)*(((((IkReal(-1.00000000000000))*(cj11)*(x2957)))+(((sj11)*(x2958)))+(((sj11)*(x2953)))+(((cj11)*(cj13)*(x2956)))+(((IkReal(-1.00000000000000))*(cj11)*(x2954)*(x2955)))))));
13199 sj10array[0]=IKsin(j10array[0]);
13200 cj10array[0]=IKcos(j10array[0]);
13201 if( j10array[0] > IKPI )
13202 {
13203     j10array[0]-=IK2PI;
13204 }
13205 else if( j10array[0] < -IKPI )
13206 {    j10array[0]+=IK2PI;
13207 }
13208 j10valid[0] = true;
13209 for(int ij10 = 0; ij10 < 1; ++ij10)
13210 {
13211 if( !j10valid[ij10] )
13212 {
13213     continue;
13214 }
13215 _ij10[0] = ij10; _ij10[1] = -1;
13216 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13217 {
13218 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13219 {
13220     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13221 }
13222 }
13223 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13224 {
13225 IkReal evalcond[4];
13226 IkReal x2959=IKsin(j10);
13227 IkReal x2960=IKcos(j10);
13228 IkReal x2961=((cj13)*(sj14));
13229 IkReal x2962=((cj13)*(cj14));
13230 IkReal x2963=((r10)*(sj9));
13231 IkReal x2964=((IkReal(1.00000000000000))*(cj9));
13232 IkReal x2965=((sj11)*(x2959));
13233 IkReal x2966=((IkReal(1.00000000000000))*(x2960));
13234 IkReal x2967=((cj11)*(x2959));
13235 IkReal x2968=((IkReal(1.00000000000000))*(r11)*(sj9));
13236 IkReal x2969=((cj11)*(x2966));
13237 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x2967)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x2966))));
13238 evalcond[1]=((((r21)*(x2961)))+(((IkReal(-1.00000000000000))*(r20)*(x2962)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2969)))+(x2965));
13239 evalcond[2]=((((IkReal(-1.00000000000000))*(sj14)*(x2963)))+(((IkReal(-1.00000000000000))*(x2969)))+(((IkReal(-1.00000000000000))*(cj14)*(x2968)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2964)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2964)))+(x2965));
13240 evalcond[3]=((((sj11)*(x2960)))+(((cj9)*(r02)*(sj13)))+(((x2962)*(x2963)))+(((IkReal(-1.00000000000000))*(x2961)*(x2968)))+(((IkReal(-1.00000000000000))*(r01)*(x2961)*(x2964)))+(x2967)+(((r12)*(sj13)*(sj9)))+(((cj9)*(r00)*(x2962))));
13241 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13242 {
13243 continue;
13244 }
13245 }
13246 
13247 {
13248 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13249 vinfos[0].jointtype = 1;
13250 vinfos[0].foffset = j9;
13251 vinfos[0].indices[0] = _ij9[0];
13252 vinfos[0].indices[1] = _ij9[1];
13253 vinfos[0].maxsolutions = _nj9;
13254 vinfos[1].jointtype = 1;
13255 vinfos[1].foffset = j10;
13256 vinfos[1].indices[0] = _ij10[0];
13257 vinfos[1].indices[1] = _ij10[1];
13258 vinfos[1].maxsolutions = _nj10;
13259 vinfos[2].jointtype = 1;
13260 vinfos[2].foffset = j11;
13261 vinfos[2].indices[0] = _ij11[0];
13262 vinfos[2].indices[1] = _ij11[1];
13263 vinfos[2].maxsolutions = _nj11;
13264 vinfos[3].jointtype = 1;
13265 vinfos[3].foffset = j12;
13266 vinfos[3].indices[0] = _ij12[0];
13267 vinfos[3].indices[1] = _ij12[1];
13268 vinfos[3].maxsolutions = _nj12;
13269 vinfos[4].jointtype = 1;
13270 vinfos[4].foffset = j13;
13271 vinfos[4].indices[0] = _ij13[0];
13272 vinfos[4].indices[1] = _ij13[1];
13273 vinfos[4].maxsolutions = _nj13;
13274 vinfos[5].jointtype = 1;
13275 vinfos[5].foffset = j14;
13276 vinfos[5].indices[0] = _ij14[0];
13277 vinfos[5].indices[1] = _ij14[1];
13278 vinfos[5].maxsolutions = _nj14;
13279 std::vector<int> vfree(0);
13280 solutions.AddSolution(vinfos,vfree);
13281 }
13282 }
13283 }
13284 
13285 }
13286 
13287 }
13288 }
13289 }
13290 
13291 } else
13292 {
13293 IkReal x2970=((IkReal(1.00000000000000))*(sj13));
13294 IkReal x2971=((cj14)*(sj9));
13295 IkReal x2972=((cj9)*(sj14));
13296 IkReal x2973=((cj13)*(sj9));
13297 IkReal x2974=((sj13)*(sj14));
13298 IkReal x2975=((cj9)*(sj13));
13299 IkReal x2976=((IkReal(1.00000000000000))*(cj13));
13300 IkReal x2977=((cj14)*(r10));
13301 IkReal x2978=((sj14)*(sj9));
13302 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
13303 evalcond[1]=((((r01)*(x2971)))+(((IkReal(-1.00000000000000))*(cj14)*(cj9)*(r11)))+(((r00)*(x2978)))+(((IkReal(-1.00000000000000))*(r10)*(x2972))));
13304 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x2970)))+(((cj13)*(r22)))+(((r21)*(x2974))));
13305 evalcond[3]=((IkReal(-0.0950000000000000))+(((npy)*(x2974)))+(((cj13)*(npz)))+(((IkReal(-1.00000000000000))*(cj14)*(npx)*(x2970)))+(((IkReal(0.0900000000000000))*(sj13))));
13306 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x2972)*(x2976)))+(((cj13)*(cj9)*(x2977)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x2970)))+(((r12)*(x2975)))+(((IkReal(-1.00000000000000))*(r00)*(x2971)*(x2976)))+(((r01)*(sj14)*(x2973))));
13307 evalcond[5]=((IkReal(-1.00000000000000))+(((r02)*(x2973)))+(((IkReal(-1.00000000000000))*(cj9)*(r12)*(x2976)))+(((x2975)*(x2977)))+(((r01)*(sj9)*(x2974)))+(((IkReal(-1.00000000000000))*(r00)*(x2970)*(x2971)))+(((IkReal(-1.00000000000000))*(r11)*(x2970)*(x2972))));
13308 evalcond[6]=((((IkReal(-1.00000000000000))*(cj9)*(r02)*(x2976)))+(((r10)*(sj13)*(x2971)))+(((cj14)*(r00)*(x2975)))+(((IkReal(-1.00000000000000))*(r01)*(x2970)*(x2972)))+(((IkReal(-1.00000000000000))*(r12)*(x2973)))+(((IkReal(-1.00000000000000))*(r11)*(x2970)*(x2978))));
13309 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  )
13310 {
13311 {
13312 IkReal j11array[1], cj11array[1], sj11array[1];
13313 bool j11valid[1]={false};
13314 _nj11 = 1;
13315 IkReal x2979=((IkReal(4.00000000000000))*(sj14));
13316 IkReal x2980=((IkReal(4.00000000000000))*(cj14));
13317 if( IKabs(((IkReal(0.120000000000000))+(((npx)*(x2979)))+(((npy)*(x2980))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2979)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2980))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((npx)*(x2979)))+(((npy)*(x2980)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2979)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2980)))))-1) <= IKFAST_SINCOS_THRESH )
13318     continue;
13319 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((npx)*(x2979)))+(((npy)*(x2980)))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x2979)))+(((IkReal(-0.360000000000000))*(cj13)))+(((cj13)*(npx)*(x2980)))));
13320 sj11array[0]=IKsin(j11array[0]);
13321 cj11array[0]=IKcos(j11array[0]);
13322 if( j11array[0] > IKPI )
13323 {
13324     j11array[0]-=IK2PI;
13325 }
13326 else if( j11array[0] < -IKPI )
13327 {    j11array[0]+=IK2PI;
13328 }
13329 j11valid[0] = true;
13330 for(int ij11 = 0; ij11 < 1; ++ij11)
13331 {
13332 if( !j11valid[ij11] )
13333 {
13334     continue;
13335 }
13336 _ij11[0] = ij11; _ij11[1] = -1;
13337 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
13338 {
13339 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
13340 {
13341     j11valid[iij11]=false; _ij11[1] = iij11; break; 
13342 }
13343 }
13344 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
13345 {
13346 IkReal evalcond[2];
13347 evalcond[0]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(IKsin(j11))))+(((cj14)*(npy)))+(((npx)*(sj14))));
13348 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(npx)))+(((cj13)*(npy)*(sj14)))+(((IkReal(-1.00000000000000))*(npz)*(sj13))));
13349 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13350 {
13351 continue;
13352 }
13353 }
13354 
13355 {
13356 IkReal dummyeval[1];
13357 IkReal gconst58;
13358 gconst58=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
13359 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
13360 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13361 {
13362 {
13363 IkReal dummyeval[1];
13364 IkReal gconst59;
13365 gconst59=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
13366 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
13367 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13368 {
13369 continue;
13370 
13371 } else
13372 {
13373 {
13374 IkReal j10array[1], cj10array[1], sj10array[1];
13375 bool j10valid[1]={false};
13376 _nj10 = 1;
13377 IkReal x2981=((IkReal(1.00000000000000))*(sj11));
13378 IkReal x2982=((cj14)*(r21));
13379 IkReal x2983=((IkReal(1.00000000000000))*(cj11));
13380 IkReal x2984=((r20)*(sj14));
13381 IkReal x2985=((cj9)*(r00)*(sj14));
13382 IkReal x2986=((cj14)*(r11)*(sj9));
13383 IkReal x2987=((cj14)*(cj9)*(r01));
13384 IkReal x2988=((r10)*(sj14)*(sj9));
13385 if( IKabs(((gconst59)*(((((IkReal(-1.00000000000000))*(x2982)*(x2983)))+(((IkReal(-1.00000000000000))*(x2981)*(x2987)))+(((IkReal(-1.00000000000000))*(x2981)*(x2988)))+(((IkReal(-1.00000000000000))*(x2981)*(x2985)))+(((IkReal(-1.00000000000000))*(x2981)*(x2986)))+(((IkReal(-1.00000000000000))*(x2983)*(x2984))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst59)*(((((cj11)*(x2988)))+(((cj11)*(x2987)))+(((cj11)*(x2986)))+(((cj11)*(x2985)))+(((IkReal(-1.00000000000000))*(x2981)*(x2982)))+(((IkReal(-1.00000000000000))*(x2981)*(x2984))))))) < IKFAST_ATAN2_MAGTHRESH )
13386     continue;
13387 j10array[0]=IKatan2(((gconst59)*(((((IkReal(-1.00000000000000))*(x2982)*(x2983)))+(((IkReal(-1.00000000000000))*(x2981)*(x2987)))+(((IkReal(-1.00000000000000))*(x2981)*(x2988)))+(((IkReal(-1.00000000000000))*(x2981)*(x2985)))+(((IkReal(-1.00000000000000))*(x2981)*(x2986)))+(((IkReal(-1.00000000000000))*(x2983)*(x2984)))))), ((gconst59)*(((((cj11)*(x2988)))+(((cj11)*(x2987)))+(((cj11)*(x2986)))+(((cj11)*(x2985)))+(((IkReal(-1.00000000000000))*(x2981)*(x2982)))+(((IkReal(-1.00000000000000))*(x2981)*(x2984)))))));
13388 sj10array[0]=IKsin(j10array[0]);
13389 cj10array[0]=IKcos(j10array[0]);
13390 if( j10array[0] > IKPI )
13391 {
13392     j10array[0]-=IK2PI;
13393 }
13394 else if( j10array[0] < -IKPI )
13395 {    j10array[0]+=IK2PI;
13396 }
13397 j10valid[0] = true;
13398 for(int ij10 = 0; ij10 < 1; ++ij10)
13399 {
13400 if( !j10valid[ij10] )
13401 {
13402     continue;
13403 }
13404 _ij10[0] = ij10; _ij10[1] = -1;
13405 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13406 {
13407 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13408 {
13409     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13410 }
13411 }
13412 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13413 {
13414 IkReal evalcond[4];
13415 IkReal x2989=IKsin(j10);
13416 IkReal x2990=IKcos(j10);
13417 IkReal x2991=((cj14)*(sj9));
13418 IkReal x2992=((IkReal(1.00000000000000))*(r11));
13419 IkReal x2993=((cj13)*(sj14));
13420 IkReal x2994=((IkReal(1.00000000000000))*(cj9));
13421 IkReal x2995=((cj13)*(cj14));
13422 IkReal x2996=((cj11)*(x2989));
13423 IkReal x2997=((sj11)*(x2990));
13424 IkReal x2998=((cj11)*(x2990));
13425 IkReal x2999=((sj11)*(x2989));
13426 IkReal x3000=((x2996)+(x2997));
13427 evalcond[0]=((((cj14)*(r21)))+(x3000)+(((r20)*(sj14))));
13428 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x2998)))+(((r21)*(x2993)))+(((IkReal(-1.00000000000000))*(r20)*(x2995)))+(x2999));
13429 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(sj14)*(x2994)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x2994)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x2999)))+(((IkReal(-1.00000000000000))*(x2991)*(x2992)))+(x2998));
13430 evalcond[3]=((x3000)+(((IkReal(-1.00000000000000))*(r01)*(x2993)*(x2994)))+(((cj9)*(r02)*(sj13)))+(((cj9)*(r00)*(x2995)))+(((r12)*(sj13)*(sj9)))+(((IkReal(-1.00000000000000))*(sj9)*(x2992)*(x2993)))+(((cj13)*(r10)*(x2991))));
13431 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13432 {
13433 continue;
13434 }
13435 }
13436 
13437 {
13438 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13439 vinfos[0].jointtype = 1;
13440 vinfos[0].foffset = j9;
13441 vinfos[0].indices[0] = _ij9[0];
13442 vinfos[0].indices[1] = _ij9[1];
13443 vinfos[0].maxsolutions = _nj9;
13444 vinfos[1].jointtype = 1;
13445 vinfos[1].foffset = j10;
13446 vinfos[1].indices[0] = _ij10[0];
13447 vinfos[1].indices[1] = _ij10[1];
13448 vinfos[1].maxsolutions = _nj10;
13449 vinfos[2].jointtype = 1;
13450 vinfos[2].foffset = j11;
13451 vinfos[2].indices[0] = _ij11[0];
13452 vinfos[2].indices[1] = _ij11[1];
13453 vinfos[2].maxsolutions = _nj11;
13454 vinfos[3].jointtype = 1;
13455 vinfos[3].foffset = j12;
13456 vinfos[3].indices[0] = _ij12[0];
13457 vinfos[3].indices[1] = _ij12[1];
13458 vinfos[3].maxsolutions = _nj12;
13459 vinfos[4].jointtype = 1;
13460 vinfos[4].foffset = j13;
13461 vinfos[4].indices[0] = _ij13[0];
13462 vinfos[4].indices[1] = _ij13[1];
13463 vinfos[4].maxsolutions = _nj13;
13464 vinfos[5].jointtype = 1;
13465 vinfos[5].foffset = j14;
13466 vinfos[5].indices[0] = _ij14[0];
13467 vinfos[5].indices[1] = _ij14[1];
13468 vinfos[5].maxsolutions = _nj14;
13469 std::vector<int> vfree(0);
13470 solutions.AddSolution(vinfos,vfree);
13471 }
13472 }
13473 }
13474 
13475 }
13476 
13477 }
13478 
13479 } else
13480 {
13481 {
13482 IkReal j10array[1], cj10array[1], sj10array[1];
13483 bool j10valid[1]={false};
13484 _nj10 = 1;
13485 IkReal x3001=((cj13)*(sj11));
13486 IkReal x3002=((r21)*(sj14));
13487 IkReal x3003=((cj14)*(r20));
13488 IkReal x3004=((cj11)*(cj13));
13489 IkReal x3005=((r22)*(sj13));
13490 IkReal x3006=((r20)*(sj14));
13491 IkReal x3007=((cj14)*(r21));
13492 if( IKabs(((gconst58)*(((((IkReal(-1.00000000000000))*(sj11)*(x3005)))+(((cj11)*(x3007)))+(((cj11)*(x3006)))+(((IkReal(-1.00000000000000))*(x3001)*(x3003)))+(((x3001)*(x3002))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst58)*(((((sj11)*(x3006)))+(((sj11)*(x3007)))+(((IkReal(-1.00000000000000))*(x3002)*(x3004)))+(((cj11)*(x3005)))+(((x3003)*(x3004))))))) < IKFAST_ATAN2_MAGTHRESH )
13493     continue;
13494 j10array[0]=IKatan2(((gconst58)*(((((IkReal(-1.00000000000000))*(sj11)*(x3005)))+(((cj11)*(x3007)))+(((cj11)*(x3006)))+(((IkReal(-1.00000000000000))*(x3001)*(x3003)))+(((x3001)*(x3002)))))), ((gconst58)*(((((sj11)*(x3006)))+(((sj11)*(x3007)))+(((IkReal(-1.00000000000000))*(x3002)*(x3004)))+(((cj11)*(x3005)))+(((x3003)*(x3004)))))));
13495 sj10array[0]=IKsin(j10array[0]);
13496 cj10array[0]=IKcos(j10array[0]);
13497 if( j10array[0] > IKPI )
13498 {
13499     j10array[0]-=IK2PI;
13500 }
13501 else if( j10array[0] < -IKPI )
13502 {    j10array[0]+=IK2PI;
13503 }
13504 j10valid[0] = true;
13505 for(int ij10 = 0; ij10 < 1; ++ij10)
13506 {
13507 if( !j10valid[ij10] )
13508 {
13509     continue;
13510 }
13511 _ij10[0] = ij10; _ij10[1] = -1;
13512 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13513 {
13514 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13515 {
13516     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13517 }
13518 }
13519 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13520 {
13521 IkReal evalcond[4];
13522 IkReal x3008=IKsin(j10);
13523 IkReal x3009=IKcos(j10);
13524 IkReal x3010=((cj14)*(sj9));
13525 IkReal x3011=((IkReal(1.00000000000000))*(r11));
13526 IkReal x3012=((cj13)*(sj14));
13527 IkReal x3013=((IkReal(1.00000000000000))*(cj9));
13528 IkReal x3014=((cj13)*(cj14));
13529 IkReal x3015=((cj11)*(x3008));
13530 IkReal x3016=((sj11)*(x3009));
13531 IkReal x3017=((cj11)*(x3009));
13532 IkReal x3018=((sj11)*(x3008));
13533 IkReal x3019=((x3016)+(x3015));
13534 evalcond[0]=((((cj14)*(r21)))+(x3019)+(((r20)*(sj14))));
13535 evalcond[1]=((x3018)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x3014)))+(((r21)*(x3012)))+(((IkReal(-1.00000000000000))*(x3017))));
13536 evalcond[2]=((x3017)+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3013)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3013)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x3010)*(x3011)))+(((IkReal(-1.00000000000000))*(x3018))));
13537 evalcond[3]=((((cj9)*(r00)*(x3014)))+(x3019)+(((IkReal(-1.00000000000000))*(sj9)*(x3011)*(x3012)))+(((cj9)*(r02)*(sj13)))+(((IkReal(-1.00000000000000))*(r01)*(x3012)*(x3013)))+(((cj13)*(r10)*(x3010)))+(((r12)*(sj13)*(sj9))));
13538 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13539 {
13540 continue;
13541 }
13542 }
13543 
13544 {
13545 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13546 vinfos[0].jointtype = 1;
13547 vinfos[0].foffset = j9;
13548 vinfos[0].indices[0] = _ij9[0];
13549 vinfos[0].indices[1] = _ij9[1];
13550 vinfos[0].maxsolutions = _nj9;
13551 vinfos[1].jointtype = 1;
13552 vinfos[1].foffset = j10;
13553 vinfos[1].indices[0] = _ij10[0];
13554 vinfos[1].indices[1] = _ij10[1];
13555 vinfos[1].maxsolutions = _nj10;
13556 vinfos[2].jointtype = 1;
13557 vinfos[2].foffset = j11;
13558 vinfos[2].indices[0] = _ij11[0];
13559 vinfos[2].indices[1] = _ij11[1];
13560 vinfos[2].maxsolutions = _nj11;
13561 vinfos[3].jointtype = 1;
13562 vinfos[3].foffset = j12;
13563 vinfos[3].indices[0] = _ij12[0];
13564 vinfos[3].indices[1] = _ij12[1];
13565 vinfos[3].maxsolutions = _nj12;
13566 vinfos[4].jointtype = 1;
13567 vinfos[4].foffset = j13;
13568 vinfos[4].indices[0] = _ij13[0];
13569 vinfos[4].indices[1] = _ij13[1];
13570 vinfos[4].maxsolutions = _nj13;
13571 vinfos[5].jointtype = 1;
13572 vinfos[5].foffset = j14;
13573 vinfos[5].indices[0] = _ij14[0];
13574 vinfos[5].indices[1] = _ij14[1];
13575 vinfos[5].maxsolutions = _nj14;
13576 std::vector<int> vfree(0);
13577 solutions.AddSolution(vinfos,vfree);
13578 }
13579 }
13580 }
13581 
13582 }
13583 
13584 }
13585 }
13586 }
13587 
13588 } else
13589 {
13590 IkReal x3020=((cj13)*(sj9));
13591 IkReal x3021=((r01)*(sj14));
13592 IkReal x3022=((cj9)*(sj13));
13593 IkReal x3023=((sj13)*(sj9));
13594 IkReal x3024=((cj14)*(r01));
13595 IkReal x3025=((cj14)*(r10));
13596 IkReal x3026=((cj13)*(cj9));
13597 IkReal x3027=((IkReal(1.00000000000000))*(cj9));
13598 IkReal x3028=((sj14)*(sj9));
13599 IkReal x3029=((IkReal(1.00000000000000))*(cj14)*(sj9));
13600 IkReal x3030=((sj14)*(x3027));
13601 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
13602 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
13603 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
13604 evalcond[3]=((IkReal(1.00000000000000))+(((r00)*(x3028)))+(((sj9)*(x3024)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3027)))+(((IkReal(-1.00000000000000))*(r10)*(x3030))));
13605 evalcond[4]=((((IkReal(-1.00000000000000))*(r11)*(x3029)))+(((IkReal(-1.00000000000000))*(r00)*(x3030)))+(((IkReal(-1.00000000000000))*(x3024)*(x3027)))+(((IkReal(-1.00000000000000))*(r10)*(x3028))));
13606 evalcond[5]=((((r12)*(x3022)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(x3026)))+(((x3020)*(x3021)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x3020)))+(((x3025)*(x3026)))+(((IkReal(-1.00000000000000))*(r02)*(x3023))));
13607 evalcond[6]=((((r02)*(x3020)))+(((x3021)*(x3023)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(x3022)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x3023)))+(((IkReal(-1.00000000000000))*(r12)*(x3026)))+(((x3022)*(x3025))));
13608 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  )
13609 {
13610 {
13611 IkReal j11array[1], cj11array[1], sj11array[1];
13612 bool j11valid[1]={false};
13613 _nj11 = 1;
13614 IkReal x3031=((IkReal(4.00000000000000))*(cj13));
13615 IkReal x3032=((npy)*(sj14));
13616 IkReal x3033=((cj14)*(npx));
13617 IkReal x3034=((IkReal(4.00000000000000))*(sj13));
13618 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3033)*(x3034)))+(((x3032)*(x3034)))+(((npz)*(x3031))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x3034)))+(((x3031)*(x3033)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3033)*(x3034)))+(((x3032)*(x3034)))+(((npz)*(x3031)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x3034)))+(((x3031)*(x3033)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032)))))-1) <= IKFAST_SINCOS_THRESH )
13619     continue;
13620 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3033)*(x3034)))+(((x3032)*(x3034)))+(((npz)*(x3031)))), ((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((npz)*(x3034)))+(((x3031)*(x3033)))+(((IkReal(-1.00000000000000))*(x3031)*(x3032)))));
13621 sj11array[0]=IKsin(j11array[0]);
13622 cj11array[0]=IKcos(j11array[0]);
13623 if( j11array[0] > IKPI )
13624 {
13625     j11array[0]-=IK2PI;
13626 }
13627 else if( j11array[0] < -IKPI )
13628 {    j11array[0]+=IK2PI;
13629 }
13630 j11valid[0] = true;
13631 for(int ij11 = 0; ij11 < 1; ++ij11)
13632 {
13633 if( !j11valid[ij11] )
13634 {
13635     continue;
13636 }
13637 _ij11[0] = ij11; _ij11[1] = -1;
13638 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
13639 {
13640 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
13641 {
13642     j11valid[iij11]=false; _ij11[1] = iij11; break; 
13643 }
13644 }
13645 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
13646 {
13647 IkReal evalcond[2];
13648 IkReal x3035=((IkReal(1.00000000000000))*(sj13));
13649 IkReal x3036=((cj14)*(npx));
13650 IkReal x3037=((npy)*(sj14));
13651 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x3035)))+(((IkReal(-1.00000000000000))*(cj13)*(x3036)))+(((cj13)*(x3037))));
13652 evalcond[1]=((IkReal(0.0300000000000000))+(((sj13)*(x3037)))+(((IkReal(-0.250000000000000))*(IKsin(j11))))+(((IkReal(-1.00000000000000))*(x3035)*(x3036)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
13653 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13654 {
13655 continue;
13656 }
13657 }
13658 
13659 {
13660 IkReal dummyeval[1];
13661 IkReal gconst60;
13662 gconst60=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
13663 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
13664 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13665 {
13666 {
13667 IkReal dummyeval[1];
13668 IkReal gconst61;
13669 gconst61=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
13670 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
13671 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13672 {
13673 continue;
13674 
13675 } else
13676 {
13677 {
13678 IkReal j10array[1], cj10array[1], sj10array[1];
13679 bool j10valid[1]={false};
13680 _nj10 = 1;
13681 IkReal x3038=((cj13)*(sj14));
13682 IkReal x3039=((IkReal(1.00000000000000))*(cj11));
13683 IkReal x3040=((r11)*(sj9));
13684 IkReal x3041=((cj11)*(sj13));
13685 IkReal x3042=((r12)*(sj9));
13686 IkReal x3043=((cj9)*(r00));
13687 IkReal x3044=((sj11)*(sj13));
13688 IkReal x3045=((cj9)*(r02));
13689 IkReal x3046=((cj9)*(r01));
13690 IkReal x3047=((IkReal(1.00000000000000))*(sj11));
13691 IkReal x3048=((r10)*(sj9));
13692 IkReal x3049=((cj13)*(cj14)*(sj11));
13693 IkReal x3050=((cj11)*(cj13)*(cj14));
13694 if( IKabs(((gconst61)*(((((x3048)*(x3050)))+(((IkReal(-1.00000000000000))*(r22)*(x3044)))+(((IkReal(-1.00000000000000))*(x3038)*(x3039)*(x3040)))+(((IkReal(-1.00000000000000))*(x3038)*(x3039)*(x3046)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3047)))+(((x3043)*(x3050)))+(((r21)*(sj11)*(x3038)))+(((x3041)*(x3042)))+(((x3041)*(x3045))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst61)*(((((r22)*(x3041)))+(((x3043)*(x3049)))+(((x3042)*(x3044)))+(((IkReal(-1.00000000000000))*(x3038)*(x3040)*(x3047)))+(((IkReal(-1.00000000000000))*(x3038)*(x3046)*(x3047)))+(((IkReal(-1.00000000000000))*(r21)*(x3038)*(x3039)))+(((x3048)*(x3049)))+(((x3044)*(x3045)))+(((r20)*(x3050))))))) < IKFAST_ATAN2_MAGTHRESH )
13695     continue;
13696 j10array[0]=IKatan2(((gconst61)*(((((x3048)*(x3050)))+(((IkReal(-1.00000000000000))*(r22)*(x3044)))+(((IkReal(-1.00000000000000))*(x3038)*(x3039)*(x3040)))+(((IkReal(-1.00000000000000))*(x3038)*(x3039)*(x3046)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3047)))+(((x3043)*(x3050)))+(((r21)*(sj11)*(x3038)))+(((x3041)*(x3042)))+(((x3041)*(x3045)))))), ((gconst61)*(((((r22)*(x3041)))+(((x3043)*(x3049)))+(((x3042)*(x3044)))+(((IkReal(-1.00000000000000))*(x3038)*(x3040)*(x3047)))+(((IkReal(-1.00000000000000))*(x3038)*(x3046)*(x3047)))+(((IkReal(-1.00000000000000))*(r21)*(x3038)*(x3039)))+(((x3048)*(x3049)))+(((x3044)*(x3045)))+(((r20)*(x3050)))))));
13697 sj10array[0]=IKsin(j10array[0]);
13698 cj10array[0]=IKcos(j10array[0]);
13699 if( j10array[0] > IKPI )
13700 {
13701     j10array[0]-=IK2PI;
13702 }
13703 else if( j10array[0] < -IKPI )
13704 {    j10array[0]+=IK2PI;
13705 }
13706 j10valid[0] = true;
13707 for(int ij10 = 0; ij10 < 1; ++ij10)
13708 {
13709 if( !j10valid[ij10] )
13710 {
13711     continue;
13712 }
13713 _ij10[0] = ij10; _ij10[1] = -1;
13714 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13715 {
13716 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13717 {
13718     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13719 }
13720 }
13721 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13722 {
13723 IkReal evalcond[4];
13724 IkReal x3051=IKsin(j10);
13725 IkReal x3052=IKcos(j10);
13726 IkReal x3053=((IkReal(1.00000000000000))*(sj13));
13727 IkReal x3054=((r11)*(sj9));
13728 IkReal x3055=((cj9)*(r01));
13729 IkReal x3056=((r21)*(sj14));
13730 IkReal x3057=((cj9)*(r02));
13731 IkReal x3058=((sj13)*(sj9));
13732 IkReal x3059=((cj14)*(r10));
13733 IkReal x3060=((IkReal(1.00000000000000))*(cj13));
13734 IkReal x3061=((cj14)*(r20));
13735 IkReal x3062=((cj11)*(x3051));
13736 IkReal x3063=((sj11)*(x3052));
13737 IkReal x3064=((sj14)*(x3060));
13738 IkReal x3065=((sj11)*(x3051));
13739 IkReal x3066=((cj11)*(x3052));
13740 IkReal x3067=((cj14)*(cj9)*(r00));
13741 IkReal x3068=((x3063)+(x3062));
13742 evalcond[0]=((((IkReal(-1.00000000000000))*(x3066)))+(((IkReal(-1.00000000000000))*(x3060)*(x3061)))+(x3065)+(((cj13)*(x3056)))+(((IkReal(-1.00000000000000))*(r22)*(x3053))));
13743 evalcond[1]=((((sj13)*(x3056)))+(x3068)+(((IkReal(-1.00000000000000))*(x3053)*(x3061)))+(((cj13)*(r22))));
13744 evalcond[2]=((((cj13)*(x3067)))+(((sj13)*(x3057)))+(((IkReal(-1.00000000000000))*(x3054)*(x3064)))+(x3068)+(((r12)*(x3058)))+(((IkReal(-1.00000000000000))*(x3055)*(x3064)))+(((cj13)*(sj9)*(x3059))));
13745 evalcond[3]=((((IkReal(-1.00000000000000))*(x3065)))+(x3066)+(((IkReal(-1.00000000000000))*(sj14)*(x3053)*(x3054)))+(((IkReal(-1.00000000000000))*(sj14)*(x3053)*(x3055)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3060)))+(((sj13)*(x3067)))+(((x3058)*(x3059)))+(((IkReal(-1.00000000000000))*(x3057)*(x3060))));
13746 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13747 {
13748 continue;
13749 }
13750 }
13751 
13752 {
13753 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13754 vinfos[0].jointtype = 1;
13755 vinfos[0].foffset = j9;
13756 vinfos[0].indices[0] = _ij9[0];
13757 vinfos[0].indices[1] = _ij9[1];
13758 vinfos[0].maxsolutions = _nj9;
13759 vinfos[1].jointtype = 1;
13760 vinfos[1].foffset = j10;
13761 vinfos[1].indices[0] = _ij10[0];
13762 vinfos[1].indices[1] = _ij10[1];
13763 vinfos[1].maxsolutions = _nj10;
13764 vinfos[2].jointtype = 1;
13765 vinfos[2].foffset = j11;
13766 vinfos[2].indices[0] = _ij11[0];
13767 vinfos[2].indices[1] = _ij11[1];
13768 vinfos[2].maxsolutions = _nj11;
13769 vinfos[3].jointtype = 1;
13770 vinfos[3].foffset = j12;
13771 vinfos[3].indices[0] = _ij12[0];
13772 vinfos[3].indices[1] = _ij12[1];
13773 vinfos[3].maxsolutions = _nj12;
13774 vinfos[4].jointtype = 1;
13775 vinfos[4].foffset = j13;
13776 vinfos[4].indices[0] = _ij13[0];
13777 vinfos[4].indices[1] = _ij13[1];
13778 vinfos[4].maxsolutions = _nj13;
13779 vinfos[5].jointtype = 1;
13780 vinfos[5].foffset = j14;
13781 vinfos[5].indices[0] = _ij14[0];
13782 vinfos[5].indices[1] = _ij14[1];
13783 vinfos[5].maxsolutions = _nj14;
13784 std::vector<int> vfree(0);
13785 solutions.AddSolution(vinfos,vfree);
13786 }
13787 }
13788 }
13789 
13790 }
13791 
13792 }
13793 
13794 } else
13795 {
13796 {
13797 IkReal j10array[1], cj10array[1], sj10array[1];
13798 bool j10valid[1]={false};
13799 _nj10 = 1;
13800 IkReal x3069=((cj13)*(sj11));
13801 IkReal x3070=((r21)*(sj14));
13802 IkReal x3071=((cj11)*(cj13));
13803 IkReal x3072=((sj11)*(sj13));
13804 IkReal x3073=((cj11)*(sj13));
13805 IkReal x3074=((IkReal(1.00000000000000))*(cj14)*(r20));
13806 if( IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(x3073)*(x3074)))+(((r22)*(x3071)))+(((IkReal(-1.00000000000000))*(x3069)*(x3074)))+(((x3070)*(x3073)))+(((x3069)*(x3070)))+(((IkReal(-1.00000000000000))*(r22)*(x3072))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst60)*(((((IkReal(-1.00000000000000))*(x3072)*(x3074)))+(((r22)*(x3069)))+(((r22)*(x3073)))+(((x3070)*(x3072)))+(((IkReal(-1.00000000000000))*(x3070)*(x3071)))+(((cj14)*(r20)*(x3071))))))) < IKFAST_ATAN2_MAGTHRESH )
13807     continue;
13808 j10array[0]=IKatan2(((gconst60)*(((((IkReal(-1.00000000000000))*(x3073)*(x3074)))+(((r22)*(x3071)))+(((IkReal(-1.00000000000000))*(x3069)*(x3074)))+(((x3070)*(x3073)))+(((x3069)*(x3070)))+(((IkReal(-1.00000000000000))*(r22)*(x3072)))))), ((gconst60)*(((((IkReal(-1.00000000000000))*(x3072)*(x3074)))+(((r22)*(x3069)))+(((r22)*(x3073)))+(((x3070)*(x3072)))+(((IkReal(-1.00000000000000))*(x3070)*(x3071)))+(((cj14)*(r20)*(x3071)))))));
13809 sj10array[0]=IKsin(j10array[0]);
13810 cj10array[0]=IKcos(j10array[0]);
13811 if( j10array[0] > IKPI )
13812 {
13813     j10array[0]-=IK2PI;
13814 }
13815 else if( j10array[0] < -IKPI )
13816 {    j10array[0]+=IK2PI;
13817 }
13818 j10valid[0] = true;
13819 for(int ij10 = 0; ij10 < 1; ++ij10)
13820 {
13821 if( !j10valid[ij10] )
13822 {
13823     continue;
13824 }
13825 _ij10[0] = ij10; _ij10[1] = -1;
13826 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
13827 {
13828 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
13829 {
13830     j10valid[iij10]=false; _ij10[1] = iij10; break; 
13831 }
13832 }
13833 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
13834 {
13835 IkReal evalcond[4];
13836 IkReal x3075=IKsin(j10);
13837 IkReal x3076=IKcos(j10);
13838 IkReal x3077=((IkReal(1.00000000000000))*(sj13));
13839 IkReal x3078=((r11)*(sj9));
13840 IkReal x3079=((cj9)*(r01));
13841 IkReal x3080=((r21)*(sj14));
13842 IkReal x3081=((cj9)*(r02));
13843 IkReal x3082=((sj13)*(sj9));
13844 IkReal x3083=((cj14)*(r10));
13845 IkReal x3084=((IkReal(1.00000000000000))*(cj13));
13846 IkReal x3085=((cj14)*(r20));
13847 IkReal x3086=((cj11)*(x3075));
13848 IkReal x3087=((sj11)*(x3076));
13849 IkReal x3088=((sj14)*(x3084));
13850 IkReal x3089=((sj11)*(x3075));
13851 IkReal x3090=((cj11)*(x3076));
13852 IkReal x3091=((cj14)*(cj9)*(r00));
13853 IkReal x3092=((x3087)+(x3086));
13854 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3077)))+(x3089)+(((cj13)*(x3080)))+(((IkReal(-1.00000000000000))*(x3084)*(x3085)))+(((IkReal(-1.00000000000000))*(x3090))));
13855 evalcond[1]=((x3092)+(((sj13)*(x3080)))+(((IkReal(-1.00000000000000))*(x3077)*(x3085)))+(((cj13)*(r22))));
13856 evalcond[2]=((((IkReal(-1.00000000000000))*(x3079)*(x3088)))+(x3092)+(((r12)*(x3082)))+(((sj13)*(x3081)))+(((IkReal(-1.00000000000000))*(x3078)*(x3088)))+(((cj13)*(sj9)*(x3083)))+(((cj13)*(x3091))));
13857 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x3077)*(x3078)))+(((IkReal(-1.00000000000000))*(sj14)*(x3077)*(x3079)))+(x3090)+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3084)))+(((x3082)*(x3083)))+(((IkReal(-1.00000000000000))*(x3089)))+(((sj13)*(x3091)))+(((IkReal(-1.00000000000000))*(x3081)*(x3084))));
13858 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
13859 {
13860 continue;
13861 }
13862 }
13863 
13864 {
13865 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
13866 vinfos[0].jointtype = 1;
13867 vinfos[0].foffset = j9;
13868 vinfos[0].indices[0] = _ij9[0];
13869 vinfos[0].indices[1] = _ij9[1];
13870 vinfos[0].maxsolutions = _nj9;
13871 vinfos[1].jointtype = 1;
13872 vinfos[1].foffset = j10;
13873 vinfos[1].indices[0] = _ij10[0];
13874 vinfos[1].indices[1] = _ij10[1];
13875 vinfos[1].maxsolutions = _nj10;
13876 vinfos[2].jointtype = 1;
13877 vinfos[2].foffset = j11;
13878 vinfos[2].indices[0] = _ij11[0];
13879 vinfos[2].indices[1] = _ij11[1];
13880 vinfos[2].maxsolutions = _nj11;
13881 vinfos[3].jointtype = 1;
13882 vinfos[3].foffset = j12;
13883 vinfos[3].indices[0] = _ij12[0];
13884 vinfos[3].indices[1] = _ij12[1];
13885 vinfos[3].maxsolutions = _nj12;
13886 vinfos[4].jointtype = 1;
13887 vinfos[4].foffset = j13;
13888 vinfos[4].indices[0] = _ij13[0];
13889 vinfos[4].indices[1] = _ij13[1];
13890 vinfos[4].maxsolutions = _nj13;
13891 vinfos[5].jointtype = 1;
13892 vinfos[5].foffset = j14;
13893 vinfos[5].indices[0] = _ij14[0];
13894 vinfos[5].indices[1] = _ij14[1];
13895 vinfos[5].maxsolutions = _nj14;
13896 std::vector<int> vfree(0);
13897 solutions.AddSolution(vinfos,vfree);
13898 }
13899 }
13900 }
13901 
13902 }
13903 
13904 }
13905 }
13906 }
13907 
13908 } else
13909 {
13910 IkReal x3093=((cj13)*(sj9));
13911 IkReal x3094=((r01)*(sj14));
13912 IkReal x3095=((cj9)*(sj13));
13913 IkReal x3096=((sj13)*(sj9));
13914 IkReal x3097=((cj14)*(r01));
13915 IkReal x3098=((cj14)*(r10));
13916 IkReal x3099=((cj13)*(cj9));
13917 IkReal x3100=((IkReal(1.00000000000000))*(cj9));
13918 IkReal x3101=((sj14)*(sj9));
13919 IkReal x3102=((IkReal(1.00000000000000))*(cj14)*(sj9));
13920 IkReal x3103=((sj14)*(x3100));
13921 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
13922 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
13923 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
13924 evalcond[3]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r10)*(x3103)))+(((sj9)*(x3097)))+(((r00)*(x3101)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3100))));
13925 evalcond[4]=((((IkReal(-1.00000000000000))*(r10)*(x3101)))+(((IkReal(-1.00000000000000))*(r11)*(x3102)))+(((IkReal(-1.00000000000000))*(r00)*(x3103)))+(((IkReal(-1.00000000000000))*(x3097)*(x3100))));
13926 evalcond[5]=((((x3098)*(x3099)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(x3099)))+(((IkReal(-1.00000000000000))*(r02)*(x3096)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x3093)))+(((x3093)*(x3094)))+(((r12)*(x3095))));
13927 evalcond[6]=((((IkReal(-1.00000000000000))*(r11)*(sj14)*(x3095)))+(((IkReal(-1.00000000000000))*(r12)*(x3099)))+(((r02)*(x3093)))+(((IkReal(-1.00000000000000))*(cj14)*(r00)*(x3096)))+(((x3095)*(x3098)))+(((x3094)*(x3096))));
13928 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  )
13929 {
13930 {
13931 IkReal j11array[1], cj11array[1], sj11array[1];
13932 bool j11valid[1]={false};
13933 _nj11 = 1;
13934 IkReal x3104=((IkReal(4.00000000000000))*(cj13));
13935 IkReal x3105=((npy)*(sj14));
13936 IkReal x3106=((cj14)*(npx));
13937 IkReal x3107=((IkReal(4.00000000000000))*(sj13));
13938 if( IKabs(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3104)))+(((IkReal(-1.00000000000000))*(x3105)*(x3107)))+(((x3106)*(x3107)))+(((IkReal(-0.360000000000000))*(sj13))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x3104)*(x3105)))+(((npz)*(x3107)))+(((x3104)*(x3106))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3104)))+(((IkReal(-1.00000000000000))*(x3105)*(x3107)))+(((x3106)*(x3107)))+(((IkReal(-0.360000000000000))*(sj13)))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x3104)*(x3105)))+(((npz)*(x3107)))+(((x3104)*(x3106)))))-1) <= IKFAST_SINCOS_THRESH )
13939     continue;
13940 j11array[0]=IKatan2(((IkReal(0.120000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3104)))+(((IkReal(-1.00000000000000))*(x3105)*(x3107)))+(((x3106)*(x3107)))+(((IkReal(-0.360000000000000))*(sj13)))), ((IkReal(-0.940000000000000))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x3104)*(x3105)))+(((npz)*(x3107)))+(((x3104)*(x3106)))));
13941 sj11array[0]=IKsin(j11array[0]);
13942 cj11array[0]=IKcos(j11array[0]);
13943 if( j11array[0] > IKPI )
13944 {
13945     j11array[0]-=IK2PI;
13946 }
13947 else if( j11array[0] < -IKPI )
13948 {    j11array[0]+=IK2PI;
13949 }
13950 j11valid[0] = true;
13951 for(int ij11 = 0; ij11 < 1; ++ij11)
13952 {
13953 if( !j11valid[ij11] )
13954 {
13955     continue;
13956 }
13957 _ij11[0] = ij11; _ij11[1] = -1;
13958 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
13959 {
13960 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
13961 {
13962     j11valid[iij11]=false; _ij11[1] = iij11; break; 
13963 }
13964 }
13965 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
13966 {
13967 IkReal evalcond[2];
13968 IkReal x3108=((IkReal(1.00000000000000))*(sj13));
13969 IkReal x3109=((cj14)*(npx));
13970 IkReal x3110=((npy)*(sj14));
13971 evalcond[0]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x3110)))+(((IkReal(-1.00000000000000))*(npz)*(x3108)))+(((IkReal(-1.00000000000000))*(cj13)*(x3109))));
13972 evalcond[1]=((IkReal(-0.0300000000000000))+(((sj13)*(x3110)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3108)*(x3109)))+(((IkReal(0.250000000000000))*(IKsin(j11)))));
13973 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
13974 {
13975 continue;
13976 }
13977 }
13978 
13979 {
13980 IkReal dummyeval[1];
13981 IkReal gconst62;
13982 gconst62=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
13983 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
13984 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13985 {
13986 {
13987 IkReal dummyeval[1];
13988 IkReal gconst63;
13989 gconst63=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
13990 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
13991 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
13992 {
13993 continue;
13994 
13995 } else
13996 {
13997 {
13998 IkReal j10array[1], cj10array[1], sj10array[1];
13999 bool j10valid[1]={false};
14000 _nj10 = 1;
14001 IkReal x3111=((cj13)*(sj14));
14002 IkReal x3112=((IkReal(1.00000000000000))*(cj11));
14003 IkReal x3113=((r11)*(sj9));
14004 IkReal x3114=((IkReal(1.00000000000000))*(sj11));
14005 IkReal x3115=((cj13)*(cj14));
14006 IkReal x3116=((cj11)*(sj13));
14007 IkReal x3117=((r12)*(sj9));
14008 IkReal x3118=((sj11)*(sj13));
14009 IkReal x3119=((cj9)*(r02));
14010 IkReal x3120=((cj9)*(r01));
14011 IkReal x3121=((r10)*(sj9));
14012 IkReal x3122=((cj9)*(r00));
14013 if( IKabs(((gconst63)*(((((IkReal(-1.00000000000000))*(r20)*(x3114)*(x3115)))+(((cj11)*(x3115)*(x3121)))+(((cj11)*(x3115)*(x3122)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3114)))+(((IkReal(-1.00000000000000))*(x3111)*(x3112)*(x3113)))+(((r21)*(sj11)*(x3111)))+(((x3116)*(x3117)))+(((x3116)*(x3119)))+(((IkReal(-1.00000000000000))*(x3111)*(x3112)*(x3120))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst63)*(((((cj11)*(r20)*(x3115)))+(((r22)*(x3116)))+(((x3118)*(x3119)))+(((IkReal(-1.00000000000000))*(r21)*(x3111)*(x3112)))+(((sj11)*(x3115)*(x3121)))+(((sj11)*(x3115)*(x3122)))+(((IkReal(-1.00000000000000))*(x3111)*(x3113)*(x3114)))+(((IkReal(-1.00000000000000))*(x3111)*(x3114)*(x3120)))+(((x3117)*(x3118))))))) < IKFAST_ATAN2_MAGTHRESH )
14014     continue;
14015 j10array[0]=IKatan2(((gconst63)*(((((IkReal(-1.00000000000000))*(r20)*(x3114)*(x3115)))+(((cj11)*(x3115)*(x3121)))+(((cj11)*(x3115)*(x3122)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3114)))+(((IkReal(-1.00000000000000))*(x3111)*(x3112)*(x3113)))+(((r21)*(sj11)*(x3111)))+(((x3116)*(x3117)))+(((x3116)*(x3119)))+(((IkReal(-1.00000000000000))*(x3111)*(x3112)*(x3120)))))), ((gconst63)*(((((cj11)*(r20)*(x3115)))+(((r22)*(x3116)))+(((x3118)*(x3119)))+(((IkReal(-1.00000000000000))*(r21)*(x3111)*(x3112)))+(((sj11)*(x3115)*(x3121)))+(((sj11)*(x3115)*(x3122)))+(((IkReal(-1.00000000000000))*(x3111)*(x3113)*(x3114)))+(((IkReal(-1.00000000000000))*(x3111)*(x3114)*(x3120)))+(((x3117)*(x3118)))))));
14016 sj10array[0]=IKsin(j10array[0]);
14017 cj10array[0]=IKcos(j10array[0]);
14018 if( j10array[0] > IKPI )
14019 {
14020     j10array[0]-=IK2PI;
14021 }
14022 else if( j10array[0] < -IKPI )
14023 {    j10array[0]+=IK2PI;
14024 }
14025 j10valid[0] = true;
14026 for(int ij10 = 0; ij10 < 1; ++ij10)
14027 {
14028 if( !j10valid[ij10] )
14029 {
14030     continue;
14031 }
14032 _ij10[0] = ij10; _ij10[1] = -1;
14033 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14034 {
14035 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14036 {
14037     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14038 }
14039 }
14040 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14041 {
14042 IkReal evalcond[4];
14043 IkReal x3123=IKsin(j10);
14044 IkReal x3124=IKcos(j10);
14045 IkReal x3125=((IkReal(1.00000000000000))*(sj13));
14046 IkReal x3126=((r11)*(sj9));
14047 IkReal x3127=((cj9)*(r01));
14048 IkReal x3128=((IkReal(1.00000000000000))*(cj11));
14049 IkReal x3129=((r21)*(sj14));
14050 IkReal x3130=((cj9)*(r02));
14051 IkReal x3131=((sj13)*(sj9));
14052 IkReal x3132=((cj14)*(r10));
14053 IkReal x3133=((IkReal(1.00000000000000))*(cj13));
14054 IkReal x3134=((cj14)*(r20));
14055 IkReal x3135=((sj11)*(x3123));
14056 IkReal x3136=((sj14)*(x3133));
14057 IkReal x3137=((sj11)*(x3124));
14058 IkReal x3138=((cj14)*(cj9)*(r00));
14059 IkReal x3139=((x3124)*(x3128));
14060 evalcond[0]=((x3135)+(((cj13)*(x3129)))+(((IkReal(-1.00000000000000))*(x3133)*(x3134)))+(((IkReal(-1.00000000000000))*(r22)*(x3125)))+(((IkReal(-1.00000000000000))*(x3139))));
14061 evalcond[1]=((((IkReal(-1.00000000000000))*(x3125)*(x3134)))+(((IkReal(-1.00000000000000))*(x3137)))+(((sj13)*(x3129)))+(((IkReal(-1.00000000000000))*(x3123)*(x3128)))+(((cj13)*(r22))));
14062 evalcond[2]=((x3137)+(((cj13)*(x3138)))+(((cj13)*(sj9)*(x3132)))+(((sj13)*(x3130)))+(((cj11)*(x3123)))+(((r12)*(x3131)))+(((IkReal(-1.00000000000000))*(x3126)*(x3136)))+(((IkReal(-1.00000000000000))*(x3127)*(x3136))));
14063 evalcond[3]=((x3135)+(((x3131)*(x3132)))+(((IkReal(-1.00000000000000))*(x3130)*(x3133)))+(((sj13)*(x3138)))+(((IkReal(-1.00000000000000))*(sj14)*(x3125)*(x3127)))+(((IkReal(-1.00000000000000))*(sj14)*(x3125)*(x3126)))+(((IkReal(-1.00000000000000))*(x3139)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3133))));
14064 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14065 {
14066 continue;
14067 }
14068 }
14069 
14070 {
14071 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14072 vinfos[0].jointtype = 1;
14073 vinfos[0].foffset = j9;
14074 vinfos[0].indices[0] = _ij9[0];
14075 vinfos[0].indices[1] = _ij9[1];
14076 vinfos[0].maxsolutions = _nj9;
14077 vinfos[1].jointtype = 1;
14078 vinfos[1].foffset = j10;
14079 vinfos[1].indices[0] = _ij10[0];
14080 vinfos[1].indices[1] = _ij10[1];
14081 vinfos[1].maxsolutions = _nj10;
14082 vinfos[2].jointtype = 1;
14083 vinfos[2].foffset = j11;
14084 vinfos[2].indices[0] = _ij11[0];
14085 vinfos[2].indices[1] = _ij11[1];
14086 vinfos[2].maxsolutions = _nj11;
14087 vinfos[3].jointtype = 1;
14088 vinfos[3].foffset = j12;
14089 vinfos[3].indices[0] = _ij12[0];
14090 vinfos[3].indices[1] = _ij12[1];
14091 vinfos[3].maxsolutions = _nj12;
14092 vinfos[4].jointtype = 1;
14093 vinfos[4].foffset = j13;
14094 vinfos[4].indices[0] = _ij13[0];
14095 vinfos[4].indices[1] = _ij13[1];
14096 vinfos[4].maxsolutions = _nj13;
14097 vinfos[5].jointtype = 1;
14098 vinfos[5].foffset = j14;
14099 vinfos[5].indices[0] = _ij14[0];
14100 vinfos[5].indices[1] = _ij14[1];
14101 vinfos[5].maxsolutions = _nj14;
14102 std::vector<int> vfree(0);
14103 solutions.AddSolution(vinfos,vfree);
14104 }
14105 }
14106 }
14107 
14108 }
14109 
14110 }
14111 
14112 } else
14113 {
14114 {
14115 IkReal j10array[1], cj10array[1], sj10array[1];
14116 bool j10valid[1]={false};
14117 _nj10 = 1;
14118 IkReal x3140=((cj13)*(r22));
14119 IkReal x3141=((IkReal(1.00000000000000))*(sj11));
14120 IkReal x3142=((IkReal(1.00000000000000))*(cj11));
14121 IkReal x3143=((r22)*(sj13));
14122 IkReal x3144=((cj14)*(r20));
14123 IkReal x3145=((cj13)*(r21)*(sj14));
14124 IkReal x3146=((r21)*(sj13)*(sj14));
14125 if( IKabs(((gconst62)*(((((cj11)*(x3140)))+(((cj11)*(x3146)))+(((IkReal(-1.00000000000000))*(sj13)*(x3142)*(x3144)))+(((IkReal(-1.00000000000000))*(x3141)*(x3145)))+(((sj11)*(x3143)))+(((cj13)*(sj11)*(x3144))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst62)*(((((IkReal(-1.00000000000000))*(cj13)*(x3142)*(x3144)))+(((cj11)*(x3145)))+(((IkReal(-1.00000000000000))*(x3142)*(x3143)))+(((IkReal(-1.00000000000000))*(sj13)*(x3141)*(x3144)))+(((sj11)*(x3140)))+(((sj11)*(x3146))))))) < IKFAST_ATAN2_MAGTHRESH )
14126     continue;
14127 j10array[0]=IKatan2(((gconst62)*(((((cj11)*(x3140)))+(((cj11)*(x3146)))+(((IkReal(-1.00000000000000))*(sj13)*(x3142)*(x3144)))+(((IkReal(-1.00000000000000))*(x3141)*(x3145)))+(((sj11)*(x3143)))+(((cj13)*(sj11)*(x3144)))))), ((gconst62)*(((((IkReal(-1.00000000000000))*(cj13)*(x3142)*(x3144)))+(((cj11)*(x3145)))+(((IkReal(-1.00000000000000))*(x3142)*(x3143)))+(((IkReal(-1.00000000000000))*(sj13)*(x3141)*(x3144)))+(((sj11)*(x3140)))+(((sj11)*(x3146)))))));
14128 sj10array[0]=IKsin(j10array[0]);
14129 cj10array[0]=IKcos(j10array[0]);
14130 if( j10array[0] > IKPI )
14131 {
14132     j10array[0]-=IK2PI;
14133 }
14134 else if( j10array[0] < -IKPI )
14135 {    j10array[0]+=IK2PI;
14136 }
14137 j10valid[0] = true;
14138 for(int ij10 = 0; ij10 < 1; ++ij10)
14139 {
14140 if( !j10valid[ij10] )
14141 {
14142     continue;
14143 }
14144 _ij10[0] = ij10; _ij10[1] = -1;
14145 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14146 {
14147 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14148 {
14149     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14150 }
14151 }
14152 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14153 {
14154 IkReal evalcond[4];
14155 IkReal x3147=IKsin(j10);
14156 IkReal x3148=IKcos(j10);
14157 IkReal x3149=((IkReal(1.00000000000000))*(sj13));
14158 IkReal x3150=((r11)*(sj9));
14159 IkReal x3151=((cj9)*(r01));
14160 IkReal x3152=((IkReal(1.00000000000000))*(cj11));
14161 IkReal x3153=((r21)*(sj14));
14162 IkReal x3154=((cj9)*(r02));
14163 IkReal x3155=((sj13)*(sj9));
14164 IkReal x3156=((cj14)*(r10));
14165 IkReal x3157=((IkReal(1.00000000000000))*(cj13));
14166 IkReal x3158=((cj14)*(r20));
14167 IkReal x3159=((sj11)*(x3147));
14168 IkReal x3160=((sj14)*(x3157));
14169 IkReal x3161=((sj11)*(x3148));
14170 IkReal x3162=((cj14)*(cj9)*(r00));
14171 IkReal x3163=((x3148)*(x3152));
14172 evalcond[0]=((((IkReal(-1.00000000000000))*(x3157)*(x3158)))+(x3159)+(((IkReal(-1.00000000000000))*(r22)*(x3149)))+(((cj13)*(x3153)))+(((IkReal(-1.00000000000000))*(x3163))));
14173 evalcond[1]=((((IkReal(-1.00000000000000))*(x3161)))+(((IkReal(-1.00000000000000))*(x3149)*(x3158)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x3147)*(x3152)))+(((sj13)*(x3153))));
14174 evalcond[2]=((x3161)+(((IkReal(-1.00000000000000))*(x3150)*(x3160)))+(((cj11)*(x3147)))+(((r12)*(x3155)))+(((cj13)*(sj9)*(x3156)))+(((cj13)*(x3162)))+(((IkReal(-1.00000000000000))*(x3151)*(x3160)))+(((sj13)*(x3154))));
14175 evalcond[3]=((((sj13)*(x3162)))+(x3159)+(((x3155)*(x3156)))+(((IkReal(-1.00000000000000))*(sj14)*(x3149)*(x3151)))+(((IkReal(-1.00000000000000))*(sj14)*(x3149)*(x3150)))+(((IkReal(-1.00000000000000))*(x3154)*(x3157)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3157)))+(((IkReal(-1.00000000000000))*(x3163))));
14176 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14177 {
14178 continue;
14179 }
14180 }
14181 
14182 {
14183 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14184 vinfos[0].jointtype = 1;
14185 vinfos[0].foffset = j9;
14186 vinfos[0].indices[0] = _ij9[0];
14187 vinfos[0].indices[1] = _ij9[1];
14188 vinfos[0].maxsolutions = _nj9;
14189 vinfos[1].jointtype = 1;
14190 vinfos[1].foffset = j10;
14191 vinfos[1].indices[0] = _ij10[0];
14192 vinfos[1].indices[1] = _ij10[1];
14193 vinfos[1].maxsolutions = _nj10;
14194 vinfos[2].jointtype = 1;
14195 vinfos[2].foffset = j11;
14196 vinfos[2].indices[0] = _ij11[0];
14197 vinfos[2].indices[1] = _ij11[1];
14198 vinfos[2].maxsolutions = _nj11;
14199 vinfos[3].jointtype = 1;
14200 vinfos[3].foffset = j12;
14201 vinfos[3].indices[0] = _ij12[0];
14202 vinfos[3].indices[1] = _ij12[1];
14203 vinfos[3].maxsolutions = _nj12;
14204 vinfos[4].jointtype = 1;
14205 vinfos[4].foffset = j13;
14206 vinfos[4].indices[0] = _ij13[0];
14207 vinfos[4].indices[1] = _ij13[1];
14208 vinfos[4].maxsolutions = _nj13;
14209 vinfos[5].jointtype = 1;
14210 vinfos[5].foffset = j14;
14211 vinfos[5].indices[0] = _ij14[0];
14212 vinfos[5].indices[1] = _ij14[1];
14213 vinfos[5].maxsolutions = _nj14;
14214 std::vector<int> vfree(0);
14215 solutions.AddSolution(vinfos,vfree);
14216 }
14217 }
14218 }
14219 
14220 }
14221 
14222 }
14223 }
14224 }
14225 
14226 } else
14227 {
14228 if( 1 )
14229 {
14230 continue;
14231 
14232 } else
14233 {
14234 }
14235 }
14236 }
14237 }
14238 }
14239 }
14240 
14241 } else
14242 {
14243 {
14244 IkReal j11array[1], cj11array[1], sj11array[1];
14245 bool j11valid[1]={false};
14246 _nj11 = 1;
14247 IkReal x3164=((IkReal(4.00000000000000))*(cj13));
14248 IkReal x3165=((npy)*(sj14));
14249 IkReal x3166=((IkReal(4.00000000000000))*(sj13));
14250 IkReal x3167=((cj14)*(npx));
14251 if( IKabs(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x3164)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(x3166)*(x3167)))+(((x3165)*(x3166))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((npz)*(x3166)))+(((IkReal(-1.00000000000000))*(x3164)*(x3165)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x3164)*(x3167))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x3164)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(x3166)*(x3167)))+(((x3165)*(x3166)))))))+IKsqr(((IkReal(-0.940000000000000))+(((npz)*(x3166)))+(((IkReal(-1.00000000000000))*(x3164)*(x3165)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x3164)*(x3167)))))-1) <= IKFAST_SINCOS_THRESH )
14252     continue;
14253 j11array[0]=IKatan2(((((IKabs(cj12) != 0)?((IkReal)1/(cj12)):(IkReal)1.0e30))*(((((npz)*(x3164)))+(((IkReal(0.380000000000000))*(sj12)))+(((IkReal(0.360000000000000))*(sj13)))+(((IkReal(0.120000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(x3166)*(x3167)))+(((x3165)*(x3166)))))), ((IkReal(-0.940000000000000))+(((npz)*(x3166)))+(((IkReal(-1.00000000000000))*(x3164)*(x3165)))+(((IkReal(-0.360000000000000))*(cj13)))+(((x3164)*(x3167)))));
14254 sj11array[0]=IKsin(j11array[0]);
14255 cj11array[0]=IKcos(j11array[0]);
14256 if( j11array[0] > IKPI )
14257 {
14258     j11array[0]-=IK2PI;
14259 }
14260 else if( j11array[0] < -IKPI )
14261 {    j11array[0]+=IK2PI;
14262 }
14263 j11valid[0] = true;
14264 for(int ij11 = 0; ij11 < 1; ++ij11)
14265 {
14266 if( !j11valid[ij11] )
14267 {
14268     continue;
14269 }
14270 _ij11[0] = ij11; _ij11[1] = -1;
14271 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
14272 {
14273 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
14274 {
14275     j11valid[iij11]=false; _ij11[1] = iij11; break; 
14276 }
14277 }
14278 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
14279 {
14280 IkReal evalcond[3];
14281 IkReal x3168=IKsin(j11);
14282 IkReal x3169=((IkReal(1.00000000000000))*(sj13));
14283 IkReal x3170=((cj14)*(npx));
14284 IkReal x3171=((npy)*(sj14));
14285 IkReal x3172=((IkReal(0.250000000000000))*(x3168));
14286 evalcond[0]=((((IkReal(0.0950000000000000))*(cj12)))+(((sj12)*(x3172)))+(((cj14)*(npy)))+(((IkReal(-0.0300000000000000))*(sj12)))+(((npx)*(sj14))));
14287 evalcond[1]=((IkReal(0.235000000000000))+(((cj13)*(x3171)))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x3169)))+(((IkReal(-1.00000000000000))*(cj13)*(x3170))));
14288 evalcond[2]=((((IkReal(-1.00000000000000))*(x3169)*(x3170)))+(((IkReal(0.0950000000000000))*(sj12)))+(((sj13)*(x3171)))+(((cj13)*(npz)))+(((IkReal(0.0300000000000000))*(cj12)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(cj12)*(x3172))));
14289 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
14290 {
14291 continue;
14292 }
14293 }
14294 
14295 {
14296 IkReal dummyeval[1];
14297 IkReal gconst46;
14298 gconst46=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
14299 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
14300 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14301 {
14302 {
14303 IkReal dummyeval[1];
14304 IkReal gconst47;
14305 gconst47=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
14306 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
14307 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14308 {
14309 {
14310 IkReal evalcond[9];
14311 IkReal x3173=((r00)*(sj9));
14312 IkReal x3174=((IkReal(1.00000000000000))*(sj13));
14313 IkReal x3175=((cj13)*(sj14));
14314 IkReal x3176=((cj9)*(sj14));
14315 IkReal x3177=((cj13)*(r02));
14316 IkReal x3178=((sj13)*(sj14));
14317 IkReal x3179=((r01)*(sj9));
14318 IkReal x3180=((cj9)*(sj13));
14319 IkReal x3181=((IkReal(1.00000000000000))*(cj9));
14320 IkReal x3182=((cj14)*(r10));
14321 IkReal x3183=((cj14)*(npx));
14322 IkReal x3184=((IkReal(1.00000000000000))*(cj13));
14323 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
14324 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
14325 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x3174)))+(((IkReal(-1.00000000000000))*(x3183)*(x3184)))+(((IkReal(0.250000000000000))*(cj11)))+(((npy)*(x3175))));
14326 evalcond[3]=((((sj14)*(x3173)))+(((IkReal(-1.00000000000000))*(r10)*(x3176)))+(((cj14)*(x3179)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3181))));
14327 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x3174)))+(((r21)*(x3178)))+(((cj13)*(r22))));
14328 evalcond[5]=((IkReal(0.0950000000000000))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3174)*(x3183)))+(((npy)*(x3178))));
14329 evalcond[6]=((((IkReal(-1.00000000000000))*(cj14)*(x3173)*(x3184)))+(((IkReal(-1.00000000000000))*(r11)*(x3175)*(x3181)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x3174)))+(((r12)*(x3180)))+(((cj13)*(cj9)*(x3182)))+(((x3175)*(x3179))));
14330 evalcond[7]=((IkReal(1.00000000000000))+(((sj9)*(x3177)))+(((x3180)*(x3182)))+(((x3178)*(x3179)))+(((IkReal(-1.00000000000000))*(r11)*(x3174)*(x3176)))+(((IkReal(-1.00000000000000))*(cj14)*(x3173)*(x3174)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x3181))));
14331 evalcond[8]=((((cj14)*(r00)*(x3180)))+(((IkReal(-1.00000000000000))*(x3177)*(x3181)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x3174)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3184)))+(((IkReal(-1.00000000000000))*(r01)*(x3174)*(x3176)))+(((sj13)*(sj9)*(x3182))));
14332 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  )
14333 {
14334 {
14335 IkReal dummyeval[1];
14336 IkReal gconst48;
14337 gconst48=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
14338 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
14339 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14340 {
14341 {
14342 IkReal dummyeval[1];
14343 IkReal gconst49;
14344 gconst49=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
14345 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
14346 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14347 {
14348 continue;
14349 
14350 } else
14351 {
14352 {
14353 IkReal j10array[1], cj10array[1], sj10array[1];
14354 bool j10valid[1]={false};
14355 _nj10 = 1;
14356 IkReal x3185=((IkReal(1.00000000000000))*(cj11));
14357 IkReal x3186=((sj11)*(sj14));
14358 IkReal x3187=((r10)*(sj9));
14359 IkReal x3188=((cj9)*(r00));
14360 IkReal x3189=((cj14)*(sj11));
14361 IkReal x3190=((r11)*(sj9));
14362 IkReal x3191=((cj14)*(cj9)*(r01));
14363 if( IKabs(((gconst49)*(((((cj9)*(r01)*(x3189)))+(((cj11)*(cj14)*(r21)))+(((cj11)*(r20)*(sj14)))+(((x3186)*(x3188)))+(((x3186)*(x3187)))+(((x3189)*(x3190))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(x3185)*(x3191)))+(((IkReal(-1.00000000000000))*(sj14)*(x3185)*(x3187)))+(((IkReal(-1.00000000000000))*(sj14)*(x3185)*(x3188)))+(((r20)*(x3186)))+(((IkReal(-1.00000000000000))*(cj14)*(x3185)*(x3190)))+(((r21)*(x3189))))))) < IKFAST_ATAN2_MAGTHRESH )
14364     continue;
14365 j10array[0]=IKatan2(((gconst49)*(((((cj9)*(r01)*(x3189)))+(((cj11)*(cj14)*(r21)))+(((cj11)*(r20)*(sj14)))+(((x3186)*(x3188)))+(((x3186)*(x3187)))+(((x3189)*(x3190)))))), ((gconst49)*(((((IkReal(-1.00000000000000))*(x3185)*(x3191)))+(((IkReal(-1.00000000000000))*(sj14)*(x3185)*(x3187)))+(((IkReal(-1.00000000000000))*(sj14)*(x3185)*(x3188)))+(((r20)*(x3186)))+(((IkReal(-1.00000000000000))*(cj14)*(x3185)*(x3190)))+(((r21)*(x3189)))))));
14366 sj10array[0]=IKsin(j10array[0]);
14367 cj10array[0]=IKcos(j10array[0]);
14368 if( j10array[0] > IKPI )
14369 {
14370     j10array[0]-=IK2PI;
14371 }
14372 else if( j10array[0] < -IKPI )
14373 {    j10array[0]+=IK2PI;
14374 }
14375 j10valid[0] = true;
14376 for(int ij10 = 0; ij10 < 1; ++ij10)
14377 {
14378 if( !j10valid[ij10] )
14379 {
14380     continue;
14381 }
14382 _ij10[0] = ij10; _ij10[1] = -1;
14383 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14384 {
14385 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14386 {
14387     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14388 }
14389 }
14390 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14391 {
14392 IkReal evalcond[4];
14393 IkReal x3192=IKsin(j10);
14394 IkReal x3193=IKcos(j10);
14395 IkReal x3194=((cj13)*(sj14));
14396 IkReal x3195=((cj13)*(cj14));
14397 IkReal x3196=((r10)*(sj9));
14398 IkReal x3197=((IkReal(1.00000000000000))*(cj9));
14399 IkReal x3198=((sj11)*(x3192));
14400 IkReal x3199=((IkReal(1.00000000000000))*(x3193));
14401 IkReal x3200=((cj11)*(x3192));
14402 IkReal x3201=((IkReal(1.00000000000000))*(r11)*(sj9));
14403 IkReal x3202=((cj11)*(x3199));
14404 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(sj11)*(x3199)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x3200))));
14405 evalcond[1]=((x3198)+(((r21)*(x3194)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x3202)))+(((IkReal(-1.00000000000000))*(r20)*(x3195))));
14406 evalcond[2]=((x3198)+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3197)))+(((IkReal(-1.00000000000000))*(sj14)*(x3196)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3197)))+(((IkReal(-1.00000000000000))*(x3202)))+(((IkReal(-1.00000000000000))*(cj14)*(x3201))));
14407 evalcond[3]=((((IkReal(-1.00000000000000))*(x3194)*(x3201)))+(((IkReal(-1.00000000000000))*(r01)*(x3194)*(x3197)))+(((cj9)*(r02)*(sj13)))+(x3200)+(((x3195)*(x3196)))+(((sj11)*(x3193)))+(((r12)*(sj13)*(sj9)))+(((cj9)*(r00)*(x3195))));
14408 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14409 {
14410 continue;
14411 }
14412 }
14413 
14414 {
14415 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14416 vinfos[0].jointtype = 1;
14417 vinfos[0].foffset = j9;
14418 vinfos[0].indices[0] = _ij9[0];
14419 vinfos[0].indices[1] = _ij9[1];
14420 vinfos[0].maxsolutions = _nj9;
14421 vinfos[1].jointtype = 1;
14422 vinfos[1].foffset = j10;
14423 vinfos[1].indices[0] = _ij10[0];
14424 vinfos[1].indices[1] = _ij10[1];
14425 vinfos[1].maxsolutions = _nj10;
14426 vinfos[2].jointtype = 1;
14427 vinfos[2].foffset = j11;
14428 vinfos[2].indices[0] = _ij11[0];
14429 vinfos[2].indices[1] = _ij11[1];
14430 vinfos[2].maxsolutions = _nj11;
14431 vinfos[3].jointtype = 1;
14432 vinfos[3].foffset = j12;
14433 vinfos[3].indices[0] = _ij12[0];
14434 vinfos[3].indices[1] = _ij12[1];
14435 vinfos[3].maxsolutions = _nj12;
14436 vinfos[4].jointtype = 1;
14437 vinfos[4].foffset = j13;
14438 vinfos[4].indices[0] = _ij13[0];
14439 vinfos[4].indices[1] = _ij13[1];
14440 vinfos[4].maxsolutions = _nj13;
14441 vinfos[5].jointtype = 1;
14442 vinfos[5].foffset = j14;
14443 vinfos[5].indices[0] = _ij14[0];
14444 vinfos[5].indices[1] = _ij14[1];
14445 vinfos[5].maxsolutions = _nj14;
14446 std::vector<int> vfree(0);
14447 solutions.AddSolution(vinfos,vfree);
14448 }
14449 }
14450 }
14451 
14452 }
14453 
14454 }
14455 
14456 } else
14457 {
14458 {
14459 IkReal j10array[1], cj10array[1], sj10array[1];
14460 bool j10valid[1]={false};
14461 _nj10 = 1;
14462 IkReal x3203=((cj11)*(r20));
14463 IkReal x3204=((IkReal(1.00000000000000))*(cj13));
14464 IkReal x3205=((r21)*(sj14));
14465 IkReal x3206=((r22)*(sj13));
14466 IkReal x3207=((r20)*(sj11));
14467 IkReal x3208=((cj14)*(r21));
14468 if( IKabs(((gconst48)*(((((sj11)*(x3206)))+(((sj14)*(x3203)))+(((cj13)*(cj14)*(x3207)))+(((cj11)*(x3208)))+(((IkReal(-1.00000000000000))*(sj11)*(x3204)*(x3205))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((sj11)*(x3208)))+(((sj14)*(x3207)))+(((IkReal(-1.00000000000000))*(cj11)*(x3206)))+(((cj11)*(cj13)*(x3205)))+(((IkReal(-1.00000000000000))*(cj14)*(x3203)*(x3204))))))) < IKFAST_ATAN2_MAGTHRESH )
14469     continue;
14470 j10array[0]=IKatan2(((gconst48)*(((((sj11)*(x3206)))+(((sj14)*(x3203)))+(((cj13)*(cj14)*(x3207)))+(((cj11)*(x3208)))+(((IkReal(-1.00000000000000))*(sj11)*(x3204)*(x3205)))))), ((gconst48)*(((((sj11)*(x3208)))+(((sj14)*(x3207)))+(((IkReal(-1.00000000000000))*(cj11)*(x3206)))+(((cj11)*(cj13)*(x3205)))+(((IkReal(-1.00000000000000))*(cj14)*(x3203)*(x3204)))))));
14471 sj10array[0]=IKsin(j10array[0]);
14472 cj10array[0]=IKcos(j10array[0]);
14473 if( j10array[0] > IKPI )
14474 {
14475     j10array[0]-=IK2PI;
14476 }
14477 else if( j10array[0] < -IKPI )
14478 {    j10array[0]+=IK2PI;
14479 }
14480 j10valid[0] = true;
14481 for(int ij10 = 0; ij10 < 1; ++ij10)
14482 {
14483 if( !j10valid[ij10] )
14484 {
14485     continue;
14486 }
14487 _ij10[0] = ij10; _ij10[1] = -1;
14488 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14489 {
14490 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14491 {
14492     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14493 }
14494 }
14495 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14496 {
14497 IkReal evalcond[4];
14498 IkReal x3209=IKsin(j10);
14499 IkReal x3210=IKcos(j10);
14500 IkReal x3211=((cj13)*(sj14));
14501 IkReal x3212=((cj13)*(cj14));
14502 IkReal x3213=((r10)*(sj9));
14503 IkReal x3214=((IkReal(1.00000000000000))*(cj9));
14504 IkReal x3215=((sj11)*(x3209));
14505 IkReal x3216=((IkReal(1.00000000000000))*(x3210));
14506 IkReal x3217=((cj11)*(x3209));
14507 IkReal x3218=((IkReal(1.00000000000000))*(r11)*(sj9));
14508 IkReal x3219=((cj11)*(x3216));
14509 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x3217)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x3216))));
14510 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3212)))+(x3215)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x3219)))+(((r21)*(x3211))));
14511 evalcond[2]=((x3215)+(((IkReal(-1.00000000000000))*(cj14)*(x3218)))+(((IkReal(-1.00000000000000))*(x3219)))+(((IkReal(-1.00000000000000))*(sj14)*(x3213)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3214)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3214))));
14512 evalcond[3]=((((x3212)*(x3213)))+(((IkReal(-1.00000000000000))*(r01)*(x3211)*(x3214)))+(((IkReal(-1.00000000000000))*(x3211)*(x3218)))+(((sj11)*(x3210)))+(((cj9)*(r02)*(sj13)))+(x3217)+(((cj9)*(r00)*(x3212)))+(((r12)*(sj13)*(sj9))));
14513 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14514 {
14515 continue;
14516 }
14517 }
14518 
14519 {
14520 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14521 vinfos[0].jointtype = 1;
14522 vinfos[0].foffset = j9;
14523 vinfos[0].indices[0] = _ij9[0];
14524 vinfos[0].indices[1] = _ij9[1];
14525 vinfos[0].maxsolutions = _nj9;
14526 vinfos[1].jointtype = 1;
14527 vinfos[1].foffset = j10;
14528 vinfos[1].indices[0] = _ij10[0];
14529 vinfos[1].indices[1] = _ij10[1];
14530 vinfos[1].maxsolutions = _nj10;
14531 vinfos[2].jointtype = 1;
14532 vinfos[2].foffset = j11;
14533 vinfos[2].indices[0] = _ij11[0];
14534 vinfos[2].indices[1] = _ij11[1];
14535 vinfos[2].maxsolutions = _nj11;
14536 vinfos[3].jointtype = 1;
14537 vinfos[3].foffset = j12;
14538 vinfos[3].indices[0] = _ij12[0];
14539 vinfos[3].indices[1] = _ij12[1];
14540 vinfos[3].maxsolutions = _nj12;
14541 vinfos[4].jointtype = 1;
14542 vinfos[4].foffset = j13;
14543 vinfos[4].indices[0] = _ij13[0];
14544 vinfos[4].indices[1] = _ij13[1];
14545 vinfos[4].maxsolutions = _nj13;
14546 vinfos[5].jointtype = 1;
14547 vinfos[5].foffset = j14;
14548 vinfos[5].indices[0] = _ij14[0];
14549 vinfos[5].indices[1] = _ij14[1];
14550 vinfos[5].maxsolutions = _nj14;
14551 std::vector<int> vfree(0);
14552 solutions.AddSolution(vinfos,vfree);
14553 }
14554 }
14555 }
14556 
14557 }
14558 
14559 }
14560 
14561 } else
14562 {
14563 IkReal x3220=((r00)*(sj9));
14564 IkReal x3221=((IkReal(1.00000000000000))*(sj13));
14565 IkReal x3222=((cj13)*(sj14));
14566 IkReal x3223=((cj9)*(sj14));
14567 IkReal x3224=((cj13)*(r02));
14568 IkReal x3225=((sj13)*(sj14));
14569 IkReal x3226=((r01)*(sj9));
14570 IkReal x3227=((cj9)*(sj13));
14571 IkReal x3228=((IkReal(1.00000000000000))*(cj9));
14572 IkReal x3229=((cj14)*(r10));
14573 IkReal x3230=((cj14)*(npx));
14574 IkReal x3231=((IkReal(1.00000000000000))*(cj13));
14575 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
14576 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
14577 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((npy)*(x3222)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(x3230)*(x3231)))+(((IkReal(-1.00000000000000))*(npz)*(x3221))));
14578 evalcond[3]=((((cj14)*(x3226)))+(((IkReal(-1.00000000000000))*(r10)*(x3223)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3228)))+(((sj14)*(x3220))));
14579 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x3221)))+(((r21)*(x3225)))+(((cj13)*(r22))));
14580 evalcond[5]=((IkReal(-0.0950000000000000))+(((npy)*(x3225)))+(((IkReal(-1.00000000000000))*(x3221)*(x3230)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
14581 evalcond[6]=((((r12)*(x3227)))+(((x3222)*(x3226)))+(((cj13)*(cj9)*(x3229)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x3221)))+(((IkReal(-1.00000000000000))*(cj14)*(x3220)*(x3231)))+(((IkReal(-1.00000000000000))*(r11)*(x3222)*(x3228))));
14582 evalcond[7]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(cj14)*(x3220)*(x3221)))+(((x3227)*(x3229)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x3228)))+(((x3225)*(x3226)))+(((IkReal(-1.00000000000000))*(r11)*(x3221)*(x3223)))+(((sj9)*(x3224))));
14583 evalcond[8]=((((sj13)*(sj9)*(x3229)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3231)))+(((cj14)*(r00)*(x3227)))+(((IkReal(-1.00000000000000))*(x3224)*(x3228)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x3221)))+(((IkReal(-1.00000000000000))*(r01)*(x3221)*(x3223))));
14584 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  )
14585 {
14586 {
14587 IkReal dummyeval[1];
14588 IkReal gconst50;
14589 gconst50=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
14590 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
14591 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14592 {
14593 {
14594 IkReal dummyeval[1];
14595 IkReal gconst51;
14596 gconst51=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
14597 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
14598 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14599 {
14600 continue;
14601 
14602 } else
14603 {
14604 {
14605 IkReal j10array[1], cj10array[1], sj10array[1];
14606 bool j10valid[1]={false};
14607 _nj10 = 1;
14608 IkReal x3232=((IkReal(1.00000000000000))*(sj11));
14609 IkReal x3233=((cj14)*(r21));
14610 IkReal x3234=((IkReal(1.00000000000000))*(cj11));
14611 IkReal x3235=((r20)*(sj14));
14612 IkReal x3236=((cj9)*(r00)*(sj14));
14613 IkReal x3237=((cj14)*(r11)*(sj9));
14614 IkReal x3238=((cj14)*(cj9)*(r01));
14615 IkReal x3239=((r10)*(sj14)*(sj9));
14616 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x3233)*(x3234)))+(((IkReal(-1.00000000000000))*(x3232)*(x3239)))+(((IkReal(-1.00000000000000))*(x3232)*(x3238)))+(((IkReal(-1.00000000000000))*(x3232)*(x3236)))+(((IkReal(-1.00000000000000))*(x3232)*(x3237)))+(((IkReal(-1.00000000000000))*(x3234)*(x3235))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((cj11)*(x3236)))+(((cj11)*(x3237)))+(((cj11)*(x3238)))+(((cj11)*(x3239)))+(((IkReal(-1.00000000000000))*(x3232)*(x3233)))+(((IkReal(-1.00000000000000))*(x3232)*(x3235))))))) < IKFAST_ATAN2_MAGTHRESH )
14617     continue;
14618 j10array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x3233)*(x3234)))+(((IkReal(-1.00000000000000))*(x3232)*(x3239)))+(((IkReal(-1.00000000000000))*(x3232)*(x3238)))+(((IkReal(-1.00000000000000))*(x3232)*(x3236)))+(((IkReal(-1.00000000000000))*(x3232)*(x3237)))+(((IkReal(-1.00000000000000))*(x3234)*(x3235)))))), ((gconst51)*(((((cj11)*(x3236)))+(((cj11)*(x3237)))+(((cj11)*(x3238)))+(((cj11)*(x3239)))+(((IkReal(-1.00000000000000))*(x3232)*(x3233)))+(((IkReal(-1.00000000000000))*(x3232)*(x3235)))))));
14619 sj10array[0]=IKsin(j10array[0]);
14620 cj10array[0]=IKcos(j10array[0]);
14621 if( j10array[0] > IKPI )
14622 {
14623     j10array[0]-=IK2PI;
14624 }
14625 else if( j10array[0] < -IKPI )
14626 {    j10array[0]+=IK2PI;
14627 }
14628 j10valid[0] = true;
14629 for(int ij10 = 0; ij10 < 1; ++ij10)
14630 {
14631 if( !j10valid[ij10] )
14632 {
14633     continue;
14634 }
14635 _ij10[0] = ij10; _ij10[1] = -1;
14636 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14637 {
14638 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14639 {
14640     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14641 }
14642 }
14643 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14644 {
14645 IkReal evalcond[4];
14646 IkReal x3240=IKsin(j10);
14647 IkReal x3241=IKcos(j10);
14648 IkReal x3242=((cj14)*(sj9));
14649 IkReal x3243=((IkReal(1.00000000000000))*(r11));
14650 IkReal x3244=((cj13)*(sj14));
14651 IkReal x3245=((IkReal(1.00000000000000))*(cj9));
14652 IkReal x3246=((cj13)*(cj14));
14653 IkReal x3247=((cj11)*(x3240));
14654 IkReal x3248=((sj11)*(x3241));
14655 IkReal x3249=((cj11)*(x3241));
14656 IkReal x3250=((sj11)*(x3240));
14657 IkReal x3251=((x3248)+(x3247));
14658 evalcond[0]=((((cj14)*(r21)))+(x3251)+(((r20)*(sj14))));
14659 evalcond[1]=((((r21)*(x3244)))+(((IkReal(-1.00000000000000))*(x3249)))+(((IkReal(-1.00000000000000))*(r20)*(x3246)))+(x3250)+(((IkReal(-1.00000000000000))*(r22)*(sj13))));
14660 evalcond[2]=((x3249)+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3245)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3245)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x3250)))+(((IkReal(-1.00000000000000))*(x3242)*(x3243))));
14661 evalcond[3]=((((cj9)*(r00)*(x3246)))+(((cj9)*(r02)*(sj13)))+(x3251)+(((IkReal(-1.00000000000000))*(sj9)*(x3243)*(x3244)))+(((cj13)*(r10)*(x3242)))+(((IkReal(-1.00000000000000))*(r01)*(x3244)*(x3245)))+(((r12)*(sj13)*(sj9))));
14662 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14663 {
14664 continue;
14665 }
14666 }
14667 
14668 {
14669 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14670 vinfos[0].jointtype = 1;
14671 vinfos[0].foffset = j9;
14672 vinfos[0].indices[0] = _ij9[0];
14673 vinfos[0].indices[1] = _ij9[1];
14674 vinfos[0].maxsolutions = _nj9;
14675 vinfos[1].jointtype = 1;
14676 vinfos[1].foffset = j10;
14677 vinfos[1].indices[0] = _ij10[0];
14678 vinfos[1].indices[1] = _ij10[1];
14679 vinfos[1].maxsolutions = _nj10;
14680 vinfos[2].jointtype = 1;
14681 vinfos[2].foffset = j11;
14682 vinfos[2].indices[0] = _ij11[0];
14683 vinfos[2].indices[1] = _ij11[1];
14684 vinfos[2].maxsolutions = _nj11;
14685 vinfos[3].jointtype = 1;
14686 vinfos[3].foffset = j12;
14687 vinfos[3].indices[0] = _ij12[0];
14688 vinfos[3].indices[1] = _ij12[1];
14689 vinfos[3].maxsolutions = _nj12;
14690 vinfos[4].jointtype = 1;
14691 vinfos[4].foffset = j13;
14692 vinfos[4].indices[0] = _ij13[0];
14693 vinfos[4].indices[1] = _ij13[1];
14694 vinfos[4].maxsolutions = _nj13;
14695 vinfos[5].jointtype = 1;
14696 vinfos[5].foffset = j14;
14697 vinfos[5].indices[0] = _ij14[0];
14698 vinfos[5].indices[1] = _ij14[1];
14699 vinfos[5].maxsolutions = _nj14;
14700 std::vector<int> vfree(0);
14701 solutions.AddSolution(vinfos,vfree);
14702 }
14703 }
14704 }
14705 
14706 }
14707 
14708 }
14709 
14710 } else
14711 {
14712 {
14713 IkReal j10array[1], cj10array[1], sj10array[1];
14714 bool j10valid[1]={false};
14715 _nj10 = 1;
14716 IkReal x3252=((cj13)*(sj11));
14717 IkReal x3253=((r21)*(sj14));
14718 IkReal x3254=((cj14)*(r20));
14719 IkReal x3255=((cj11)*(cj13));
14720 IkReal x3256=((r22)*(sj13));
14721 IkReal x3257=((r20)*(sj14));
14722 IkReal x3258=((cj14)*(r21));
14723 if( IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(x3252)*(x3254)))+(((cj11)*(x3258)))+(((cj11)*(x3257)))+(((x3252)*(x3253)))+(((IkReal(-1.00000000000000))*(sj11)*(x3256))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((sj11)*(x3257)))+(((sj11)*(x3258)))+(((cj11)*(x3256)))+(((IkReal(-1.00000000000000))*(x3253)*(x3255)))+(((x3254)*(x3255))))))) < IKFAST_ATAN2_MAGTHRESH )
14724     continue;
14725 j10array[0]=IKatan2(((gconst50)*(((((IkReal(-1.00000000000000))*(x3252)*(x3254)))+(((cj11)*(x3258)))+(((cj11)*(x3257)))+(((x3252)*(x3253)))+(((IkReal(-1.00000000000000))*(sj11)*(x3256)))))), ((gconst50)*(((((sj11)*(x3257)))+(((sj11)*(x3258)))+(((cj11)*(x3256)))+(((IkReal(-1.00000000000000))*(x3253)*(x3255)))+(((x3254)*(x3255)))))));
14726 sj10array[0]=IKsin(j10array[0]);
14727 cj10array[0]=IKcos(j10array[0]);
14728 if( j10array[0] > IKPI )
14729 {
14730     j10array[0]-=IK2PI;
14731 }
14732 else if( j10array[0] < -IKPI )
14733 {    j10array[0]+=IK2PI;
14734 }
14735 j10valid[0] = true;
14736 for(int ij10 = 0; ij10 < 1; ++ij10)
14737 {
14738 if( !j10valid[ij10] )
14739 {
14740     continue;
14741 }
14742 _ij10[0] = ij10; _ij10[1] = -1;
14743 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14744 {
14745 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14746 {
14747     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14748 }
14749 }
14750 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14751 {
14752 IkReal evalcond[4];
14753 IkReal x3259=IKsin(j10);
14754 IkReal x3260=IKcos(j10);
14755 IkReal x3261=((cj14)*(sj9));
14756 IkReal x3262=((IkReal(1.00000000000000))*(r11));
14757 IkReal x3263=((cj13)*(sj14));
14758 IkReal x3264=((IkReal(1.00000000000000))*(cj9));
14759 IkReal x3265=((cj13)*(cj14));
14760 IkReal x3266=((cj11)*(x3259));
14761 IkReal x3267=((sj11)*(x3260));
14762 IkReal x3268=((cj11)*(x3260));
14763 IkReal x3269=((sj11)*(x3259));
14764 IkReal x3270=((x3267)+(x3266));
14765 evalcond[0]=((((cj14)*(r21)))+(x3270)+(((r20)*(sj14))));
14766 evalcond[1]=((((r21)*(x3263)))+(((IkReal(-1.00000000000000))*(x3268)))+(x3269)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x3265))));
14767 evalcond[2]=((((IkReal(-1.00000000000000))*(x3261)*(x3262)))+(((IkReal(-1.00000000000000))*(x3269)))+(x3268)+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3264)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3264))));
14768 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3263)*(x3264)))+(((cj9)*(r02)*(sj13)))+(x3270)+(((cj9)*(r00)*(x3265)))+(((cj13)*(r10)*(x3261)))+(((r12)*(sj13)*(sj9)))+(((IkReal(-1.00000000000000))*(sj9)*(x3262)*(x3263))));
14769 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14770 {
14771 continue;
14772 }
14773 }
14774 
14775 {
14776 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14777 vinfos[0].jointtype = 1;
14778 vinfos[0].foffset = j9;
14779 vinfos[0].indices[0] = _ij9[0];
14780 vinfos[0].indices[1] = _ij9[1];
14781 vinfos[0].maxsolutions = _nj9;
14782 vinfos[1].jointtype = 1;
14783 vinfos[1].foffset = j10;
14784 vinfos[1].indices[0] = _ij10[0];
14785 vinfos[1].indices[1] = _ij10[1];
14786 vinfos[1].maxsolutions = _nj10;
14787 vinfos[2].jointtype = 1;
14788 vinfos[2].foffset = j11;
14789 vinfos[2].indices[0] = _ij11[0];
14790 vinfos[2].indices[1] = _ij11[1];
14791 vinfos[2].maxsolutions = _nj11;
14792 vinfos[3].jointtype = 1;
14793 vinfos[3].foffset = j12;
14794 vinfos[3].indices[0] = _ij12[0];
14795 vinfos[3].indices[1] = _ij12[1];
14796 vinfos[3].maxsolutions = _nj12;
14797 vinfos[4].jointtype = 1;
14798 vinfos[4].foffset = j13;
14799 vinfos[4].indices[0] = _ij13[0];
14800 vinfos[4].indices[1] = _ij13[1];
14801 vinfos[4].maxsolutions = _nj13;
14802 vinfos[5].jointtype = 1;
14803 vinfos[5].foffset = j14;
14804 vinfos[5].indices[0] = _ij14[0];
14805 vinfos[5].indices[1] = _ij14[1];
14806 vinfos[5].maxsolutions = _nj14;
14807 std::vector<int> vfree(0);
14808 solutions.AddSolution(vinfos,vfree);
14809 }
14810 }
14811 }
14812 
14813 }
14814 
14815 }
14816 
14817 } else
14818 {
14819 IkReal x3271=((cj9)*(r10));
14820 IkReal x3272=((cj13)*(cj14));
14821 IkReal x3273=((sj14)*(sj9));
14822 IkReal x3274=((IkReal(1.00000000000000))*(sj14));
14823 IkReal x3275=((cj9)*(sj13));
14824 IkReal x3276=((r02)*(sj9));
14825 IkReal x3277=((cj13)*(cj9));
14826 IkReal x3278=((cj14)*(r01));
14827 IkReal x3279=((IkReal(1.00000000000000))*(npx));
14828 IkReal x3280=((cj14)*(sj13));
14829 IkReal x3281=((IkReal(1.00000000000000))*(cj9));
14830 IkReal x3282=((npy)*(sj14));
14831 IkReal x3283=((IkReal(1.00000000000000))*(sj13));
14832 IkReal x3284=((IkReal(1.00000000000000))*(cj14)*(sj9));
14833 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
14834 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
14835 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
14836 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(npz)*(x3283)))+(((IkReal(-1.00000000000000))*(x3272)*(x3279)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x3282))));
14837 evalcond[4]=((IkReal(1.00000000000000))+(((r00)*(x3273)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3281)))+(((sj9)*(x3278)))+(((IkReal(-1.00000000000000))*(x3271)*(x3274))));
14838 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((IkReal(-1.00000000000000))*(x3279)*(x3280)))+(((sj13)*(x3282)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
14839 evalcond[6]=((((IkReal(-1.00000000000000))*(cj9)*(r00)*(x3274)))+(((IkReal(-1.00000000000000))*(r10)*(x3273)))+(((IkReal(-1.00000000000000))*(x3278)*(x3281)))+(((IkReal(-1.00000000000000))*(r11)*(x3284))));
14840 evalcond[7]=((((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3272)))+(((cj13)*(r01)*(x3273)))+(((IkReal(-1.00000000000000))*(x3276)*(x3283)))+(((IkReal(-1.00000000000000))*(r11)*(x3274)*(x3277)))+(((r12)*(x3275)))+(((x3271)*(x3272))));
14841 evalcond[8]=((((cj13)*(x3276)))+(((IkReal(-1.00000000000000))*(r12)*(x3277)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3280)))+(((r01)*(sj13)*(x3273)))+(((IkReal(-1.00000000000000))*(r11)*(x3274)*(x3275)))+(((x3271)*(x3280))));
14842 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  )
14843 {
14844 {
14845 IkReal dummyeval[1];
14846 IkReal gconst52;
14847 gconst52=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
14848 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
14849 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14850 {
14851 {
14852 IkReal dummyeval[1];
14853 IkReal gconst53;
14854 gconst53=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
14855 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
14856 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
14857 {
14858 continue;
14859 
14860 } else
14861 {
14862 {
14863 IkReal j10array[1], cj10array[1], sj10array[1];
14864 bool j10valid[1]={false};
14865 _nj10 = 1;
14866 IkReal x3285=((cj13)*(sj14));
14867 IkReal x3286=((IkReal(1.00000000000000))*(cj11));
14868 IkReal x3287=((r11)*(sj9));
14869 IkReal x3288=((IkReal(1.00000000000000))*(sj11));
14870 IkReal x3289=((cj13)*(cj14));
14871 IkReal x3290=((cj11)*(sj13));
14872 IkReal x3291=((r12)*(sj9));
14873 IkReal x3292=((sj11)*(sj13));
14874 IkReal x3293=((cj9)*(r02));
14875 IkReal x3294=((cj9)*(r01));
14876 IkReal x3295=((r10)*(sj9));
14877 IkReal x3296=((cj9)*(r00));
14878 if( IKabs(((gconst53)*(((((r21)*(sj11)*(x3285)))+(((IkReal(-1.00000000000000))*(x3285)*(x3286)*(x3287)))+(((IkReal(-1.00000000000000))*(x3285)*(x3286)*(x3294)))+(((x3290)*(x3293)))+(((x3290)*(x3291)))+(((cj11)*(x3289)*(x3295)))+(((cj11)*(x3289)*(x3296)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3288)))+(((IkReal(-1.00000000000000))*(r20)*(x3288)*(x3289))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((sj11)*(x3289)*(x3295)))+(((sj11)*(x3289)*(x3296)))+(((x3292)*(x3293)))+(((x3291)*(x3292)))+(((r22)*(x3290)))+(((IkReal(-1.00000000000000))*(x3285)*(x3288)*(x3294)))+(((IkReal(-1.00000000000000))*(r21)*(x3285)*(x3286)))+(((IkReal(-1.00000000000000))*(x3285)*(x3287)*(x3288)))+(((cj11)*(r20)*(x3289))))))) < IKFAST_ATAN2_MAGTHRESH )
14879     continue;
14880 j10array[0]=IKatan2(((gconst53)*(((((r21)*(sj11)*(x3285)))+(((IkReal(-1.00000000000000))*(x3285)*(x3286)*(x3287)))+(((IkReal(-1.00000000000000))*(x3285)*(x3286)*(x3294)))+(((x3290)*(x3293)))+(((x3290)*(x3291)))+(((cj11)*(x3289)*(x3295)))+(((cj11)*(x3289)*(x3296)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3288)))+(((IkReal(-1.00000000000000))*(r20)*(x3288)*(x3289)))))), ((gconst53)*(((((sj11)*(x3289)*(x3295)))+(((sj11)*(x3289)*(x3296)))+(((x3292)*(x3293)))+(((x3291)*(x3292)))+(((r22)*(x3290)))+(((IkReal(-1.00000000000000))*(x3285)*(x3288)*(x3294)))+(((IkReal(-1.00000000000000))*(r21)*(x3285)*(x3286)))+(((IkReal(-1.00000000000000))*(x3285)*(x3287)*(x3288)))+(((cj11)*(r20)*(x3289)))))));
14881 sj10array[0]=IKsin(j10array[0]);
14882 cj10array[0]=IKcos(j10array[0]);
14883 if( j10array[0] > IKPI )
14884 {
14885     j10array[0]-=IK2PI;
14886 }
14887 else if( j10array[0] < -IKPI )
14888 {    j10array[0]+=IK2PI;
14889 }
14890 j10valid[0] = true;
14891 for(int ij10 = 0; ij10 < 1; ++ij10)
14892 {
14893 if( !j10valid[ij10] )
14894 {
14895     continue;
14896 }
14897 _ij10[0] = ij10; _ij10[1] = -1;
14898 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
14899 {
14900 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
14901 {
14902     j10valid[iij10]=false; _ij10[1] = iij10; break; 
14903 }
14904 }
14905 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
14906 {
14907 IkReal evalcond[4];
14908 IkReal x3297=IKsin(j10);
14909 IkReal x3298=IKcos(j10);
14910 IkReal x3299=((IkReal(1.00000000000000))*(sj13));
14911 IkReal x3300=((r11)*(sj9));
14912 IkReal x3301=((cj9)*(r01));
14913 IkReal x3302=((r21)*(sj14));
14914 IkReal x3303=((cj9)*(r02));
14915 IkReal x3304=((sj13)*(sj9));
14916 IkReal x3305=((cj14)*(r10));
14917 IkReal x3306=((IkReal(1.00000000000000))*(cj13));
14918 IkReal x3307=((cj14)*(r20));
14919 IkReal x3308=((cj11)*(x3297));
14920 IkReal x3309=((sj11)*(x3298));
14921 IkReal x3310=((sj14)*(x3306));
14922 IkReal x3311=((sj11)*(x3297));
14923 IkReal x3312=((cj11)*(x3298));
14924 IkReal x3313=((cj14)*(cj9)*(r00));
14925 IkReal x3314=((x3308)+(x3309));
14926 evalcond[0]=((x3311)+(((IkReal(-1.00000000000000))*(r22)*(x3299)))+(((IkReal(-1.00000000000000))*(x3306)*(x3307)))+(((cj13)*(x3302)))+(((IkReal(-1.00000000000000))*(x3312))));
14927 evalcond[1]=((x3314)+(((IkReal(-1.00000000000000))*(x3299)*(x3307)))+(((cj13)*(r22)))+(((sj13)*(x3302))));
14928 evalcond[2]=((((cj13)*(sj9)*(x3305)))+(x3314)+(((cj13)*(x3313)))+(((r12)*(x3304)))+(((IkReal(-1.00000000000000))*(x3301)*(x3310)))+(((IkReal(-1.00000000000000))*(x3300)*(x3310)))+(((sj13)*(x3303))));
14929 evalcond[3]=((x3312)+(((x3304)*(x3305)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3306)))+(((IkReal(-1.00000000000000))*(x3311)))+(((IkReal(-1.00000000000000))*(sj14)*(x3299)*(x3300)))+(((IkReal(-1.00000000000000))*(sj14)*(x3299)*(x3301)))+(((IkReal(-1.00000000000000))*(x3303)*(x3306)))+(((sj13)*(x3313))));
14930 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
14931 {
14932 continue;
14933 }
14934 }
14935 
14936 {
14937 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
14938 vinfos[0].jointtype = 1;
14939 vinfos[0].foffset = j9;
14940 vinfos[0].indices[0] = _ij9[0];
14941 vinfos[0].indices[1] = _ij9[1];
14942 vinfos[0].maxsolutions = _nj9;
14943 vinfos[1].jointtype = 1;
14944 vinfos[1].foffset = j10;
14945 vinfos[1].indices[0] = _ij10[0];
14946 vinfos[1].indices[1] = _ij10[1];
14947 vinfos[1].maxsolutions = _nj10;
14948 vinfos[2].jointtype = 1;
14949 vinfos[2].foffset = j11;
14950 vinfos[2].indices[0] = _ij11[0];
14951 vinfos[2].indices[1] = _ij11[1];
14952 vinfos[2].maxsolutions = _nj11;
14953 vinfos[3].jointtype = 1;
14954 vinfos[3].foffset = j12;
14955 vinfos[3].indices[0] = _ij12[0];
14956 vinfos[3].indices[1] = _ij12[1];
14957 vinfos[3].maxsolutions = _nj12;
14958 vinfos[4].jointtype = 1;
14959 vinfos[4].foffset = j13;
14960 vinfos[4].indices[0] = _ij13[0];
14961 vinfos[4].indices[1] = _ij13[1];
14962 vinfos[4].maxsolutions = _nj13;
14963 vinfos[5].jointtype = 1;
14964 vinfos[5].foffset = j14;
14965 vinfos[5].indices[0] = _ij14[0];
14966 vinfos[5].indices[1] = _ij14[1];
14967 vinfos[5].maxsolutions = _nj14;
14968 std::vector<int> vfree(0);
14969 solutions.AddSolution(vinfos,vfree);
14970 }
14971 }
14972 }
14973 
14974 }
14975 
14976 }
14977 
14978 } else
14979 {
14980 {
14981 IkReal j10array[1], cj10array[1], sj10array[1];
14982 bool j10valid[1]={false};
14983 _nj10 = 1;
14984 IkReal x3315=((cj13)*(sj11));
14985 IkReal x3316=((r21)*(sj14));
14986 IkReal x3317=((cj11)*(cj13));
14987 IkReal x3318=((cj11)*(sj13));
14988 IkReal x3319=((sj11)*(sj13));
14989 IkReal x3320=((IkReal(1.00000000000000))*(cj14)*(r20));
14990 if( IKabs(((gconst52)*(((((x3316)*(x3318)))+(((IkReal(-1.00000000000000))*(r22)*(x3319)))+(((x3315)*(x3316)))+(((r22)*(x3317)))+(((IkReal(-1.00000000000000))*(x3318)*(x3320)))+(((IkReal(-1.00000000000000))*(x3315)*(x3320))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((x3316)*(x3319)))+(((IkReal(-1.00000000000000))*(x3316)*(x3317)))+(((IkReal(-1.00000000000000))*(x3319)*(x3320)))+(((r22)*(x3315)))+(((r22)*(x3318)))+(((cj14)*(r20)*(x3317))))))) < IKFAST_ATAN2_MAGTHRESH )
14991     continue;
14992 j10array[0]=IKatan2(((gconst52)*(((((x3316)*(x3318)))+(((IkReal(-1.00000000000000))*(r22)*(x3319)))+(((x3315)*(x3316)))+(((r22)*(x3317)))+(((IkReal(-1.00000000000000))*(x3318)*(x3320)))+(((IkReal(-1.00000000000000))*(x3315)*(x3320)))))), ((gconst52)*(((((x3316)*(x3319)))+(((IkReal(-1.00000000000000))*(x3316)*(x3317)))+(((IkReal(-1.00000000000000))*(x3319)*(x3320)))+(((r22)*(x3315)))+(((r22)*(x3318)))+(((cj14)*(r20)*(x3317)))))));
14993 sj10array[0]=IKsin(j10array[0]);
14994 cj10array[0]=IKcos(j10array[0]);
14995 if( j10array[0] > IKPI )
14996 {
14997     j10array[0]-=IK2PI;
14998 }
14999 else if( j10array[0] < -IKPI )
15000 {    j10array[0]+=IK2PI;
15001 }
15002 j10valid[0] = true;
15003 for(int ij10 = 0; ij10 < 1; ++ij10)
15004 {
15005 if( !j10valid[ij10] )
15006 {
15007     continue;
15008 }
15009 _ij10[0] = ij10; _ij10[1] = -1;
15010 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15011 {
15012 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15013 {
15014     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15015 }
15016 }
15017 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15018 {
15019 IkReal evalcond[4];
15020 IkReal x3321=IKsin(j10);
15021 IkReal x3322=IKcos(j10);
15022 IkReal x3323=((IkReal(1.00000000000000))*(sj13));
15023 IkReal x3324=((r11)*(sj9));
15024 IkReal x3325=((cj9)*(r01));
15025 IkReal x3326=((r21)*(sj14));
15026 IkReal x3327=((cj9)*(r02));
15027 IkReal x3328=((sj13)*(sj9));
15028 IkReal x3329=((cj14)*(r10));
15029 IkReal x3330=((IkReal(1.00000000000000))*(cj13));
15030 IkReal x3331=((cj14)*(r20));
15031 IkReal x3332=((cj11)*(x3321));
15032 IkReal x3333=((sj11)*(x3322));
15033 IkReal x3334=((sj14)*(x3330));
15034 IkReal x3335=((sj11)*(x3321));
15035 IkReal x3336=((cj11)*(x3322));
15036 IkReal x3337=((cj14)*(cj9)*(r00));
15037 IkReal x3338=((x3333)+(x3332));
15038 evalcond[0]=((((IkReal(-1.00000000000000))*(x3330)*(x3331)))+(x3335)+(((IkReal(-1.00000000000000))*(x3336)))+(((IkReal(-1.00000000000000))*(r22)*(x3323)))+(((cj13)*(x3326))));
15039 evalcond[1]=((x3338)+(((IkReal(-1.00000000000000))*(x3323)*(x3331)))+(((sj13)*(x3326)))+(((cj13)*(r22))));
15040 evalcond[2]=((((r12)*(x3328)))+(x3338)+(((cj13)*(x3337)))+(((sj13)*(x3327)))+(((IkReal(-1.00000000000000))*(x3324)*(x3334)))+(((cj13)*(sj9)*(x3329)))+(((IkReal(-1.00000000000000))*(x3325)*(x3334))));
15041 evalcond[3]=((((x3328)*(x3329)))+(((IkReal(-1.00000000000000))*(sj14)*(x3323)*(x3324)))+(((IkReal(-1.00000000000000))*(sj14)*(x3323)*(x3325)))+(((sj13)*(x3337)))+(x3336)+(((IkReal(-1.00000000000000))*(x3335)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3330)))+(((IkReal(-1.00000000000000))*(x3327)*(x3330))));
15042 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15043 {
15044 continue;
15045 }
15046 }
15047 
15048 {
15049 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15050 vinfos[0].jointtype = 1;
15051 vinfos[0].foffset = j9;
15052 vinfos[0].indices[0] = _ij9[0];
15053 vinfos[0].indices[1] = _ij9[1];
15054 vinfos[0].maxsolutions = _nj9;
15055 vinfos[1].jointtype = 1;
15056 vinfos[1].foffset = j10;
15057 vinfos[1].indices[0] = _ij10[0];
15058 vinfos[1].indices[1] = _ij10[1];
15059 vinfos[1].maxsolutions = _nj10;
15060 vinfos[2].jointtype = 1;
15061 vinfos[2].foffset = j11;
15062 vinfos[2].indices[0] = _ij11[0];
15063 vinfos[2].indices[1] = _ij11[1];
15064 vinfos[2].maxsolutions = _nj11;
15065 vinfos[3].jointtype = 1;
15066 vinfos[3].foffset = j12;
15067 vinfos[3].indices[0] = _ij12[0];
15068 vinfos[3].indices[1] = _ij12[1];
15069 vinfos[3].maxsolutions = _nj12;
15070 vinfos[4].jointtype = 1;
15071 vinfos[4].foffset = j13;
15072 vinfos[4].indices[0] = _ij13[0];
15073 vinfos[4].indices[1] = _ij13[1];
15074 vinfos[4].maxsolutions = _nj13;
15075 vinfos[5].jointtype = 1;
15076 vinfos[5].foffset = j14;
15077 vinfos[5].indices[0] = _ij14[0];
15078 vinfos[5].indices[1] = _ij14[1];
15079 vinfos[5].maxsolutions = _nj14;
15080 std::vector<int> vfree(0);
15081 solutions.AddSolution(vinfos,vfree);
15082 }
15083 }
15084 }
15085 
15086 }
15087 
15088 }
15089 
15090 } else
15091 {
15092 IkReal x3339=((cj9)*(r10));
15093 IkReal x3340=((cj13)*(cj14));
15094 IkReal x3341=((sj14)*(sj9));
15095 IkReal x3342=((IkReal(1.00000000000000))*(sj14));
15096 IkReal x3343=((cj9)*(sj13));
15097 IkReal x3344=((r02)*(sj9));
15098 IkReal x3345=((cj13)*(cj9));
15099 IkReal x3346=((cj14)*(r01));
15100 IkReal x3347=((IkReal(1.00000000000000))*(npx));
15101 IkReal x3348=((cj14)*(sj13));
15102 IkReal x3349=((IkReal(1.00000000000000))*(cj9));
15103 IkReal x3350=((npy)*(sj14));
15104 IkReal x3351=((IkReal(1.00000000000000))*(sj13));
15105 IkReal x3352=((IkReal(1.00000000000000))*(cj14)*(sj9));
15106 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
15107 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
15108 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
15109 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(-1.00000000000000))*(x3340)*(x3347)))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x3351)))+(((cj13)*(x3350))));
15110 evalcond[4]=((IkReal(-1.00000000000000))+(((r00)*(x3341)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3349)))+(((sj9)*(x3346)))+(((IkReal(-1.00000000000000))*(x3339)*(x3342))));
15111 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x3347)*(x3348)))+(((sj13)*(x3350)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(0.250000000000000))*(sj11))));
15112 evalcond[6]=((((IkReal(-1.00000000000000))*(x3346)*(x3349)))+(((IkReal(-1.00000000000000))*(cj9)*(r00)*(x3342)))+(((IkReal(-1.00000000000000))*(r11)*(x3352)))+(((IkReal(-1.00000000000000))*(r10)*(x3341))));
15113 evalcond[7]=((((cj13)*(r01)*(x3341)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3340)))+(((IkReal(-1.00000000000000))*(x3344)*(x3351)))+(((IkReal(-1.00000000000000))*(r11)*(x3342)*(x3345)))+(((x3339)*(x3340)))+(((r12)*(x3343))));
15114 evalcond[8]=((((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3348)))+(((IkReal(-1.00000000000000))*(r12)*(x3345)))+(((cj13)*(x3344)))+(((r01)*(sj13)*(x3341)))+(((IkReal(-1.00000000000000))*(r11)*(x3342)*(x3343)))+(((x3339)*(x3348))));
15115 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  )
15116 {
15117 {
15118 IkReal dummyeval[1];
15119 IkReal gconst54;
15120 gconst54=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
15121 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
15122 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15123 {
15124 {
15125 IkReal dummyeval[1];
15126 IkReal gconst55;
15127 gconst55=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
15128 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
15129 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15130 {
15131 continue;
15132 
15133 } else
15134 {
15135 {
15136 IkReal j10array[1], cj10array[1], sj10array[1];
15137 bool j10valid[1]={false};
15138 _nj10 = 1;
15139 IkReal x3353=((cj13)*(sj14));
15140 IkReal x3354=((IkReal(1.00000000000000))*(cj11));
15141 IkReal x3355=((r11)*(sj9));
15142 IkReal x3356=((cj11)*(sj13));
15143 IkReal x3357=((r12)*(sj9));
15144 IkReal x3358=((r10)*(sj9));
15145 IkReal x3359=((sj11)*(sj13));
15146 IkReal x3360=((cj9)*(r02));
15147 IkReal x3361=((IkReal(1.00000000000000))*(sj11));
15148 IkReal x3362=((cj9)*(r01));
15149 IkReal x3363=((cj9)*(r00));
15150 IkReal x3364=((cj13)*(cj14)*(sj11));
15151 IkReal x3365=((cj11)*(cj13)*(cj14));
15152 if( IKabs(((gconst55)*(((((x3356)*(x3360)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)*(x3362)))+(((x3363)*(x3365)))+(((IkReal(-1.00000000000000))*(r22)*(x3359)))+(((x3358)*(x3365)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3361)))+(((x3356)*(x3357)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)*(x3355)))+(((r21)*(sj11)*(x3353))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((x3363)*(x3364)))+(((IkReal(-1.00000000000000))*(x3353)*(x3355)*(x3361)))+(((IkReal(-1.00000000000000))*(x3353)*(x3361)*(x3362)))+(((x3358)*(x3364)))+(((r20)*(x3365)))+(((x3359)*(x3360)))+(((IkReal(-1.00000000000000))*(r21)*(x3353)*(x3354)))+(((x3357)*(x3359)))+(((r22)*(x3356))))))) < IKFAST_ATAN2_MAGTHRESH )
15153     continue;
15154 j10array[0]=IKatan2(((gconst55)*(((((x3356)*(x3360)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)*(x3362)))+(((x3363)*(x3365)))+(((IkReal(-1.00000000000000))*(r22)*(x3359)))+(((x3358)*(x3365)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3361)))+(((x3356)*(x3357)))+(((IkReal(-1.00000000000000))*(x3353)*(x3354)*(x3355)))+(((r21)*(sj11)*(x3353)))))), ((gconst55)*(((((x3363)*(x3364)))+(((IkReal(-1.00000000000000))*(x3353)*(x3355)*(x3361)))+(((IkReal(-1.00000000000000))*(x3353)*(x3361)*(x3362)))+(((x3358)*(x3364)))+(((r20)*(x3365)))+(((x3359)*(x3360)))+(((IkReal(-1.00000000000000))*(r21)*(x3353)*(x3354)))+(((x3357)*(x3359)))+(((r22)*(x3356)))))));
15155 sj10array[0]=IKsin(j10array[0]);
15156 cj10array[0]=IKcos(j10array[0]);
15157 if( j10array[0] > IKPI )
15158 {
15159     j10array[0]-=IK2PI;
15160 }
15161 else if( j10array[0] < -IKPI )
15162 {    j10array[0]+=IK2PI;
15163 }
15164 j10valid[0] = true;
15165 for(int ij10 = 0; ij10 < 1; ++ij10)
15166 {
15167 if( !j10valid[ij10] )
15168 {
15169     continue;
15170 }
15171 _ij10[0] = ij10; _ij10[1] = -1;
15172 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15173 {
15174 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15175 {
15176     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15177 }
15178 }
15179 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15180 {
15181 IkReal evalcond[4];
15182 IkReal x3366=IKsin(j10);
15183 IkReal x3367=IKcos(j10);
15184 IkReal x3368=((IkReal(1.00000000000000))*(sj13));
15185 IkReal x3369=((r11)*(sj9));
15186 IkReal x3370=((cj9)*(r01));
15187 IkReal x3371=((IkReal(1.00000000000000))*(cj11));
15188 IkReal x3372=((r21)*(sj14));
15189 IkReal x3373=((cj9)*(r02));
15190 IkReal x3374=((sj13)*(sj9));
15191 IkReal x3375=((cj14)*(r10));
15192 IkReal x3376=((IkReal(1.00000000000000))*(cj13));
15193 IkReal x3377=((cj14)*(r20));
15194 IkReal x3378=((sj11)*(x3366));
15195 IkReal x3379=((sj14)*(x3376));
15196 IkReal x3380=((sj11)*(x3367));
15197 IkReal x3381=((cj14)*(cj9)*(r00));
15198 IkReal x3382=((x3367)*(x3371));
15199 evalcond[0]=((x3378)+(((IkReal(-1.00000000000000))*(r22)*(x3368)))+(((cj13)*(x3372)))+(((IkReal(-1.00000000000000))*(x3376)*(x3377)))+(((IkReal(-1.00000000000000))*(x3382))));
15200 evalcond[1]=((((IkReal(-1.00000000000000))*(x3366)*(x3371)))+(((IkReal(-1.00000000000000))*(x3380)))+(((sj13)*(x3372)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x3368)*(x3377))));
15201 evalcond[2]=((((r12)*(x3374)))+(((cj13)*(sj9)*(x3375)))+(x3380)+(((IkReal(-1.00000000000000))*(x3370)*(x3379)))+(((cj13)*(x3381)))+(((sj13)*(x3373)))+(((IkReal(-1.00000000000000))*(x3369)*(x3379)))+(((cj11)*(x3366))));
15202 evalcond[3]=((((IkReal(-1.00000000000000))*(sj14)*(x3368)*(x3369)))+(((IkReal(-1.00000000000000))*(x3373)*(x3376)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3376)))+(x3378)+(((IkReal(-1.00000000000000))*(sj14)*(x3368)*(x3370)))+(((x3374)*(x3375)))+(((IkReal(-1.00000000000000))*(x3382)))+(((sj13)*(x3381))));
15203 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15204 {
15205 continue;
15206 }
15207 }
15208 
15209 {
15210 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15211 vinfos[0].jointtype = 1;
15212 vinfos[0].foffset = j9;
15213 vinfos[0].indices[0] = _ij9[0];
15214 vinfos[0].indices[1] = _ij9[1];
15215 vinfos[0].maxsolutions = _nj9;
15216 vinfos[1].jointtype = 1;
15217 vinfos[1].foffset = j10;
15218 vinfos[1].indices[0] = _ij10[0];
15219 vinfos[1].indices[1] = _ij10[1];
15220 vinfos[1].maxsolutions = _nj10;
15221 vinfos[2].jointtype = 1;
15222 vinfos[2].foffset = j11;
15223 vinfos[2].indices[0] = _ij11[0];
15224 vinfos[2].indices[1] = _ij11[1];
15225 vinfos[2].maxsolutions = _nj11;
15226 vinfos[3].jointtype = 1;
15227 vinfos[3].foffset = j12;
15228 vinfos[3].indices[0] = _ij12[0];
15229 vinfos[3].indices[1] = _ij12[1];
15230 vinfos[3].maxsolutions = _nj12;
15231 vinfos[4].jointtype = 1;
15232 vinfos[4].foffset = j13;
15233 vinfos[4].indices[0] = _ij13[0];
15234 vinfos[4].indices[1] = _ij13[1];
15235 vinfos[4].maxsolutions = _nj13;
15236 vinfos[5].jointtype = 1;
15237 vinfos[5].foffset = j14;
15238 vinfos[5].indices[0] = _ij14[0];
15239 vinfos[5].indices[1] = _ij14[1];
15240 vinfos[5].maxsolutions = _nj14;
15241 std::vector<int> vfree(0);
15242 solutions.AddSolution(vinfos,vfree);
15243 }
15244 }
15245 }
15246 
15247 }
15248 
15249 }
15250 
15251 } else
15252 {
15253 {
15254 IkReal j10array[1], cj10array[1], sj10array[1];
15255 bool j10valid[1]={false};
15256 _nj10 = 1;
15257 IkReal x3383=((r22)*(sj11));
15258 IkReal x3384=((IkReal(1.00000000000000))*(sj11));
15259 IkReal x3385=((IkReal(1.00000000000000))*(cj11));
15260 IkReal x3386=((cj14)*(r20));
15261 IkReal x3387=((cj13)*(r21)*(sj14));
15262 IkReal x3388=((r21)*(sj13)*(sj14));
15263 if( IKabs(((gconst54)*(((((cj13)*(sj11)*(x3386)))+(((IkReal(-1.00000000000000))*(x3384)*(x3387)))+(((IkReal(-1.00000000000000))*(sj13)*(x3385)*(x3386)))+(((cj11)*(cj13)*(r22)))+(((sj13)*(x3383)))+(((cj11)*(x3388))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((IkReal(-1.00000000000000))*(sj13)*(x3384)*(x3386)))+(((sj11)*(x3388)))+(((IkReal(-1.00000000000000))*(cj13)*(x3385)*(x3386)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3385)))+(((cj13)*(x3383)))+(((cj11)*(x3387))))))) < IKFAST_ATAN2_MAGTHRESH )
15264     continue;
15265 j10array[0]=IKatan2(((gconst54)*(((((cj13)*(sj11)*(x3386)))+(((IkReal(-1.00000000000000))*(x3384)*(x3387)))+(((IkReal(-1.00000000000000))*(sj13)*(x3385)*(x3386)))+(((cj11)*(cj13)*(r22)))+(((sj13)*(x3383)))+(((cj11)*(x3388)))))), ((gconst54)*(((((IkReal(-1.00000000000000))*(sj13)*(x3384)*(x3386)))+(((sj11)*(x3388)))+(((IkReal(-1.00000000000000))*(cj13)*(x3385)*(x3386)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3385)))+(((cj13)*(x3383)))+(((cj11)*(x3387)))))));
15266 sj10array[0]=IKsin(j10array[0]);
15267 cj10array[0]=IKcos(j10array[0]);
15268 if( j10array[0] > IKPI )
15269 {
15270     j10array[0]-=IK2PI;
15271 }
15272 else if( j10array[0] < -IKPI )
15273 {    j10array[0]+=IK2PI;
15274 }
15275 j10valid[0] = true;
15276 for(int ij10 = 0; ij10 < 1; ++ij10)
15277 {
15278 if( !j10valid[ij10] )
15279 {
15280     continue;
15281 }
15282 _ij10[0] = ij10; _ij10[1] = -1;
15283 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15284 {
15285 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15286 {
15287     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15288 }
15289 }
15290 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15291 {
15292 IkReal evalcond[4];
15293 IkReal x3389=IKsin(j10);
15294 IkReal x3390=IKcos(j10);
15295 IkReal x3391=((IkReal(1.00000000000000))*(sj13));
15296 IkReal x3392=((r11)*(sj9));
15297 IkReal x3393=((cj9)*(r01));
15298 IkReal x3394=((IkReal(1.00000000000000))*(cj11));
15299 IkReal x3395=((r21)*(sj14));
15300 IkReal x3396=((cj9)*(r02));
15301 IkReal x3397=((sj13)*(sj9));
15302 IkReal x3398=((cj14)*(r10));
15303 IkReal x3399=((IkReal(1.00000000000000))*(cj13));
15304 IkReal x3400=((cj14)*(r20));
15305 IkReal x3401=((sj11)*(x3389));
15306 IkReal x3402=((sj14)*(x3399));
15307 IkReal x3403=((sj11)*(x3390));
15308 IkReal x3404=((cj14)*(cj9)*(r00));
15309 IkReal x3405=((x3390)*(x3394));
15310 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3391)))+(((IkReal(-1.00000000000000))*(x3399)*(x3400)))+(x3401)+(((cj13)*(x3395)))+(((IkReal(-1.00000000000000))*(x3405))));
15311 evalcond[1]=((((IkReal(-1.00000000000000))*(x3403)))+(((IkReal(-1.00000000000000))*(x3389)*(x3394)))+(((sj13)*(x3395)))+(((IkReal(-1.00000000000000))*(x3391)*(x3400)))+(((cj13)*(r22))));
15312 evalcond[2]=((((IkReal(-1.00000000000000))*(x3392)*(x3402)))+(x3403)+(((cj13)*(sj9)*(x3398)))+(((cj13)*(x3404)))+(((sj13)*(x3396)))+(((r12)*(x3397)))+(((IkReal(-1.00000000000000))*(x3393)*(x3402)))+(((cj11)*(x3389))));
15313 evalcond[3]=((((IkReal(-1.00000000000000))*(x3396)*(x3399)))+(x3401)+(((IkReal(-1.00000000000000))*(sj14)*(x3391)*(x3392)))+(((IkReal(-1.00000000000000))*(sj14)*(x3391)*(x3393)))+(((sj13)*(x3404)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3399)))+(((x3397)*(x3398)))+(((IkReal(-1.00000000000000))*(x3405))));
15314 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15315 {
15316 continue;
15317 }
15318 }
15319 
15320 {
15321 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15322 vinfos[0].jointtype = 1;
15323 vinfos[0].foffset = j9;
15324 vinfos[0].indices[0] = _ij9[0];
15325 vinfos[0].indices[1] = _ij9[1];
15326 vinfos[0].maxsolutions = _nj9;
15327 vinfos[1].jointtype = 1;
15328 vinfos[1].foffset = j10;
15329 vinfos[1].indices[0] = _ij10[0];
15330 vinfos[1].indices[1] = _ij10[1];
15331 vinfos[1].maxsolutions = _nj10;
15332 vinfos[2].jointtype = 1;
15333 vinfos[2].foffset = j11;
15334 vinfos[2].indices[0] = _ij11[0];
15335 vinfos[2].indices[1] = _ij11[1];
15336 vinfos[2].maxsolutions = _nj11;
15337 vinfos[3].jointtype = 1;
15338 vinfos[3].foffset = j12;
15339 vinfos[3].indices[0] = _ij12[0];
15340 vinfos[3].indices[1] = _ij12[1];
15341 vinfos[3].maxsolutions = _nj12;
15342 vinfos[4].jointtype = 1;
15343 vinfos[4].foffset = j13;
15344 vinfos[4].indices[0] = _ij13[0];
15345 vinfos[4].indices[1] = _ij13[1];
15346 vinfos[4].maxsolutions = _nj13;
15347 vinfos[5].jointtype = 1;
15348 vinfos[5].foffset = j14;
15349 vinfos[5].indices[0] = _ij14[0];
15350 vinfos[5].indices[1] = _ij14[1];
15351 vinfos[5].maxsolutions = _nj14;
15352 std::vector<int> vfree(0);
15353 solutions.AddSolution(vinfos,vfree);
15354 }
15355 }
15356 }
15357 
15358 }
15359 
15360 }
15361 
15362 } else
15363 {
15364 if( 1 )
15365 {
15366 continue;
15367 
15368 } else
15369 {
15370 }
15371 }
15372 }
15373 }
15374 }
15375 }
15376 
15377 } else
15378 {
15379 {
15380 IkReal j10array[1], cj10array[1], sj10array[1];
15381 bool j10valid[1]={false};
15382 _nj10 = 1;
15383 IkReal x3406=((r21)*(sj14));
15384 IkReal x3407=((cj12)*(cj13));
15385 IkReal x3408=((sj11)*(sj13));
15386 IkReal x3409=((cj14)*(r20));
15387 IkReal x3410=((IkReal(1.00000000000000))*(sj11));
15388 IkReal x3411=((cj12)*(r22));
15389 IkReal x3412=((IkReal(1.00000000000000))*(cj11));
15390 IkReal x3413=((cj13)*(r22));
15391 IkReal x3414=((sj13)*(x3412));
15392 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3412)*(x3413)))+(((x3408)*(x3411)))+(((IkReal(-1.00000000000000))*(x3406)*(x3407)*(x3410)))+(((sj11)*(x3407)*(x3409)))+(((cj11)*(sj13)*(x3409)))+(((IkReal(-1.00000000000000))*(x3406)*(x3414))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((x3408)*(x3409)))+(((IkReal(-1.00000000000000))*(x3407)*(x3409)*(x3412)))+(((IkReal(-1.00000000000000))*(x3406)*(x3408)))+(((IkReal(-1.00000000000000))*(x3411)*(x3414)))+(((cj11)*(x3406)*(x3407)))+(((IkReal(-1.00000000000000))*(x3410)*(x3413))))))) < IKFAST_ATAN2_MAGTHRESH )
15393     continue;
15394 j10array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(x3412)*(x3413)))+(((x3408)*(x3411)))+(((IkReal(-1.00000000000000))*(x3406)*(x3407)*(x3410)))+(((sj11)*(x3407)*(x3409)))+(((cj11)*(sj13)*(x3409)))+(((IkReal(-1.00000000000000))*(x3406)*(x3414)))))), ((gconst47)*(((((x3408)*(x3409)))+(((IkReal(-1.00000000000000))*(x3407)*(x3409)*(x3412)))+(((IkReal(-1.00000000000000))*(x3406)*(x3408)))+(((IkReal(-1.00000000000000))*(x3411)*(x3414)))+(((cj11)*(x3406)*(x3407)))+(((IkReal(-1.00000000000000))*(x3410)*(x3413)))))));
15395 sj10array[0]=IKsin(j10array[0]);
15396 cj10array[0]=IKcos(j10array[0]);
15397 if( j10array[0] > IKPI )
15398 {
15399     j10array[0]-=IK2PI;
15400 }
15401 else if( j10array[0] < -IKPI )
15402 {    j10array[0]+=IK2PI;
15403 }
15404 j10valid[0] = true;
15405 for(int ij10 = 0; ij10 < 1; ++ij10)
15406 {
15407 if( !j10valid[ij10] )
15408 {
15409     continue;
15410 }
15411 _ij10[0] = ij10; _ij10[1] = -1;
15412 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15413 {
15414 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15415 {
15416     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15417 }
15418 }
15419 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15420 {
15421 IkReal evalcond[6];
15422 IkReal x3415=IKsin(j10);
15423 IkReal x3416=IKcos(j10);
15424 IkReal x3417=((IkReal(1.00000000000000))*(cj13));
15425 IkReal x3418=((cj9)*(r02));
15426 IkReal x3419=((IkReal(1.00000000000000))*(sj13));
15427 IkReal x3420=((r11)*(sj9));
15428 IkReal x3421=((IkReal(1.00000000000000))*(cj14));
15429 IkReal x3422=((cj9)*(r01));
15430 IkReal x3423=((r21)*(sj14));
15431 IkReal x3424=((IkReal(1.00000000000000))*(sj12));
15432 IkReal x3425=((r10)*(sj9));
15433 IkReal x3426=((cj14)*(sj13));
15434 IkReal x3427=((cj14)*(r20));
15435 IkReal x3428=((IkReal(1.00000000000000))*(sj14));
15436 IkReal x3429=((r12)*(sj9));
15437 IkReal x3430=((cj13)*(cj14));
15438 IkReal x3431=((cj9)*(r00));
15439 IkReal x3432=((sj11)*(x3415));
15440 IkReal x3433=((cj11)*(x3415));
15441 IkReal x3434=((sj11)*(x3416));
15442 IkReal x3435=((cj11)*(x3416));
15443 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x3424)*(x3434)))+(((IkReal(-1.00000000000000))*(x3424)*(x3433))));
15444 evalcond[1]=((((IkReal(-1.00000000000000))*(r22)*(x3419)))+(((cj13)*(x3423)))+(((IkReal(-1.00000000000000))*(x3417)*(x3427)))+(x3432)+(((IkReal(-1.00000000000000))*(x3435))));
15445 evalcond[2]=((((sj13)*(x3423)))+(((cj12)*(x3434)))+(((cj12)*(x3433)))+(((IkReal(-1.00000000000000))*(x3419)*(x3427)))+(((cj13)*(r22))));
15446 evalcond[3]=((((IkReal(-1.00000000000000))*(x3428)*(x3431)))+(((IkReal(-1.00000000000000))*(x3420)*(x3421)))+(((sj12)*(x3432)))+(((IkReal(-1.00000000000000))*(x3424)*(x3435)))+(((IkReal(-1.00000000000000))*(x3425)*(x3428)))+(((IkReal(-1.00000000000000))*(x3421)*(x3422))));
15447 evalcond[4]=((((x3425)*(x3430)))+(((sj13)*(x3429)))+(((x3430)*(x3431)))+(x3433)+(x3434)+(((sj13)*(x3418)))+(((IkReal(-1.00000000000000))*(sj14)*(x3417)*(x3422)))+(((IkReal(-1.00000000000000))*(sj14)*(x3417)*(x3420))));
15448 evalcond[5]=((((x3425)*(x3426)))+(((cj12)*(x3435)))+(((IkReal(-1.00000000000000))*(x3417)*(x3429)))+(((IkReal(-1.00000000000000))*(cj12)*(x3432)))+(((IkReal(-1.00000000000000))*(sj14)*(x3419)*(x3422)))+(((IkReal(-1.00000000000000))*(sj14)*(x3419)*(x3420)))+(((IkReal(-1.00000000000000))*(x3417)*(x3418)))+(((x3426)*(x3431))));
15449 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  )
15450 {
15451 continue;
15452 }
15453 }
15454 
15455 {
15456 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15457 vinfos[0].jointtype = 1;
15458 vinfos[0].foffset = j9;
15459 vinfos[0].indices[0] = _ij9[0];
15460 vinfos[0].indices[1] = _ij9[1];
15461 vinfos[0].maxsolutions = _nj9;
15462 vinfos[1].jointtype = 1;
15463 vinfos[1].foffset = j10;
15464 vinfos[1].indices[0] = _ij10[0];
15465 vinfos[1].indices[1] = _ij10[1];
15466 vinfos[1].maxsolutions = _nj10;
15467 vinfos[2].jointtype = 1;
15468 vinfos[2].foffset = j11;
15469 vinfos[2].indices[0] = _ij11[0];
15470 vinfos[2].indices[1] = _ij11[1];
15471 vinfos[2].maxsolutions = _nj11;
15472 vinfos[3].jointtype = 1;
15473 vinfos[3].foffset = j12;
15474 vinfos[3].indices[0] = _ij12[0];
15475 vinfos[3].indices[1] = _ij12[1];
15476 vinfos[3].maxsolutions = _nj12;
15477 vinfos[4].jointtype = 1;
15478 vinfos[4].foffset = j13;
15479 vinfos[4].indices[0] = _ij13[0];
15480 vinfos[4].indices[1] = _ij13[1];
15481 vinfos[4].maxsolutions = _nj13;
15482 vinfos[5].jointtype = 1;
15483 vinfos[5].foffset = j14;
15484 vinfos[5].indices[0] = _ij14[0];
15485 vinfos[5].indices[1] = _ij14[1];
15486 vinfos[5].maxsolutions = _nj14;
15487 std::vector<int> vfree(0);
15488 solutions.AddSolution(vinfos,vfree);
15489 }
15490 }
15491 }
15492 
15493 }
15494 
15495 }
15496 
15497 } else
15498 {
15499 {
15500 IkReal j10array[1], cj10array[1], sj10array[1];
15501 bool j10valid[1]={false};
15502 _nj10 = 1;
15503 IkReal x3436=((cj11)*(sj12));
15504 IkReal x3437=((r22)*(sj13));
15505 IkReal x3438=((r20)*(sj14));
15506 IkReal x3439=((cj14)*(sj11));
15507 IkReal x3440=((cj13)*(r20));
15508 IkReal x3441=((sj11)*(sj12));
15509 IkReal x3442=((cj13)*(r21)*(sj14));
15510 if( IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(x3441)*(x3442)))+(((cj11)*(x3438)))+(((cj11)*(cj14)*(r21)))+(((sj12)*(x3439)*(x3440)))+(((x3437)*(x3441))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x3436)*(x3440)))+(((IkReal(-1.00000000000000))*(x3436)*(x3437)))+(((x3436)*(x3442)))+(((r21)*(x3439)))+(((sj11)*(x3438))))))) < IKFAST_ATAN2_MAGTHRESH )
15511     continue;
15512 j10array[0]=IKatan2(((gconst46)*(((((IkReal(-1.00000000000000))*(x3441)*(x3442)))+(((cj11)*(x3438)))+(((cj11)*(cj14)*(r21)))+(((sj12)*(x3439)*(x3440)))+(((x3437)*(x3441)))))), ((gconst46)*(((((IkReal(-1.00000000000000))*(cj14)*(x3436)*(x3440)))+(((IkReal(-1.00000000000000))*(x3436)*(x3437)))+(((x3436)*(x3442)))+(((r21)*(x3439)))+(((sj11)*(x3438)))))));
15513 sj10array[0]=IKsin(j10array[0]);
15514 cj10array[0]=IKcos(j10array[0]);
15515 if( j10array[0] > IKPI )
15516 {
15517     j10array[0]-=IK2PI;
15518 }
15519 else if( j10array[0] < -IKPI )
15520 {    j10array[0]+=IK2PI;
15521 }
15522 j10valid[0] = true;
15523 for(int ij10 = 0; ij10 < 1; ++ij10)
15524 {
15525 if( !j10valid[ij10] )
15526 {
15527     continue;
15528 }
15529 _ij10[0] = ij10; _ij10[1] = -1;
15530 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15531 {
15532 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15533 {
15534     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15535 }
15536 }
15537 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15538 {
15539 IkReal evalcond[6];
15540 IkReal x3443=IKsin(j10);
15541 IkReal x3444=IKcos(j10);
15542 IkReal x3445=((IkReal(1.00000000000000))*(cj13));
15543 IkReal x3446=((cj9)*(r02));
15544 IkReal x3447=((IkReal(1.00000000000000))*(sj13));
15545 IkReal x3448=((r11)*(sj9));
15546 IkReal x3449=((IkReal(1.00000000000000))*(cj14));
15547 IkReal x3450=((cj9)*(r01));
15548 IkReal x3451=((r21)*(sj14));
15549 IkReal x3452=((IkReal(1.00000000000000))*(sj12));
15550 IkReal x3453=((r10)*(sj9));
15551 IkReal x3454=((cj14)*(sj13));
15552 IkReal x3455=((cj14)*(r20));
15553 IkReal x3456=((IkReal(1.00000000000000))*(sj14));
15554 IkReal x3457=((r12)*(sj9));
15555 IkReal x3458=((cj13)*(cj14));
15556 IkReal x3459=((cj9)*(r00));
15557 IkReal x3460=((sj11)*(x3443));
15558 IkReal x3461=((cj11)*(x3443));
15559 IkReal x3462=((sj11)*(x3444));
15560 IkReal x3463=((cj11)*(x3444));
15561 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x3452)*(x3462)))+(((IkReal(-1.00000000000000))*(x3452)*(x3461))));
15562 evalcond[1]=((((cj13)*(x3451)))+(x3460)+(((IkReal(-1.00000000000000))*(x3445)*(x3455)))+(((IkReal(-1.00000000000000))*(x3463)))+(((IkReal(-1.00000000000000))*(r22)*(x3447))));
15563 evalcond[2]=((((IkReal(-1.00000000000000))*(x3447)*(x3455)))+(((cj12)*(x3462)))+(((cj12)*(x3461)))+(((sj13)*(x3451)))+(((cj13)*(r22))));
15564 evalcond[3]=((((IkReal(-1.00000000000000))*(x3453)*(x3456)))+(((sj12)*(x3460)))+(((IkReal(-1.00000000000000))*(x3452)*(x3463)))+(((IkReal(-1.00000000000000))*(x3448)*(x3449)))+(((IkReal(-1.00000000000000))*(x3449)*(x3450)))+(((IkReal(-1.00000000000000))*(x3456)*(x3459))));
15565 evalcond[4]=((((x3453)*(x3458)))+(((IkReal(-1.00000000000000))*(sj14)*(x3445)*(x3448)))+(((IkReal(-1.00000000000000))*(sj14)*(x3445)*(x3450)))+(x3462)+(x3461)+(((x3458)*(x3459)))+(((sj13)*(x3457)))+(((sj13)*(x3446))));
15566 evalcond[5]=((((x3453)*(x3454)))+(((cj12)*(x3463)))+(((IkReal(-1.00000000000000))*(cj12)*(x3460)))+(((IkReal(-1.00000000000000))*(x3445)*(x3457)))+(((IkReal(-1.00000000000000))*(x3445)*(x3446)))+(((x3454)*(x3459)))+(((IkReal(-1.00000000000000))*(sj14)*(x3447)*(x3450)))+(((IkReal(-1.00000000000000))*(sj14)*(x3447)*(x3448))));
15567 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  )
15568 {
15569 continue;
15570 }
15571 }
15572 
15573 {
15574 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15575 vinfos[0].jointtype = 1;
15576 vinfos[0].foffset = j9;
15577 vinfos[0].indices[0] = _ij9[0];
15578 vinfos[0].indices[1] = _ij9[1];
15579 vinfos[0].maxsolutions = _nj9;
15580 vinfos[1].jointtype = 1;
15581 vinfos[1].foffset = j10;
15582 vinfos[1].indices[0] = _ij10[0];
15583 vinfos[1].indices[1] = _ij10[1];
15584 vinfos[1].maxsolutions = _nj10;
15585 vinfos[2].jointtype = 1;
15586 vinfos[2].foffset = j11;
15587 vinfos[2].indices[0] = _ij11[0];
15588 vinfos[2].indices[1] = _ij11[1];
15589 vinfos[2].maxsolutions = _nj11;
15590 vinfos[3].jointtype = 1;
15591 vinfos[3].foffset = j12;
15592 vinfos[3].indices[0] = _ij12[0];
15593 vinfos[3].indices[1] = _ij12[1];
15594 vinfos[3].maxsolutions = _nj12;
15595 vinfos[4].jointtype = 1;
15596 vinfos[4].foffset = j13;
15597 vinfos[4].indices[0] = _ij13[0];
15598 vinfos[4].indices[1] = _ij13[1];
15599 vinfos[4].maxsolutions = _nj13;
15600 vinfos[5].jointtype = 1;
15601 vinfos[5].foffset = j14;
15602 vinfos[5].indices[0] = _ij14[0];
15603 vinfos[5].indices[1] = _ij14[1];
15604 vinfos[5].maxsolutions = _nj14;
15605 std::vector<int> vfree(0);
15606 solutions.AddSolution(vinfos,vfree);
15607 }
15608 }
15609 }
15610 
15611 }
15612 
15613 }
15614 }
15615 }
15616 
15617 }
15618 
15619 }
15620 
15621 } else
15622 {
15623 {
15624 IkReal j11array[1], cj11array[1], sj11array[1];
15625 bool j11valid[1]={false};
15626 _nj11 = 1;
15627 IkReal x3464=((IkReal(4.00000000000000))*(sj14));
15628 IkReal x3465=((IkReal(4.00000000000000))*(cj14));
15629 if( IKabs(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x3465)))+(((IkReal(-1.00000000000000))*(npx)*(x3464))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x3465)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x3464))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x3465)))+(((IkReal(-1.00000000000000))*(npx)*(x3464)))))))+IKsqr(((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x3465)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x3464)))))-1) <= IKFAST_SINCOS_THRESH )
15630     continue;
15631 j11array[0]=IKatan2(((((IKabs(sj12) != 0)?((IkReal)1/(sj12)):(IkReal)1.0e30))*(((((IkReal(0.120000000000000))*(sj12)))+(((IkReal(-0.380000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(npy)*(x3465)))+(((IkReal(-1.00000000000000))*(npx)*(x3464)))))), ((IkReal(-0.940000000000000))+(((IkReal(4.00000000000000))*(npz)*(sj13)))+(((cj13)*(npx)*(x3465)))+(((IkReal(-0.360000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(cj13)*(npy)*(x3464)))));
15632 sj11array[0]=IKsin(j11array[0]);
15633 cj11array[0]=IKcos(j11array[0]);
15634 if( j11array[0] > IKPI )
15635 {
15636     j11array[0]-=IK2PI;
15637 }
15638 else if( j11array[0] < -IKPI )
15639 {    j11array[0]+=IK2PI;
15640 }
15641 j11valid[0] = true;
15642 for(int ij11 = 0; ij11 < 1; ++ij11)
15643 {
15644 if( !j11valid[ij11] )
15645 {
15646     continue;
15647 }
15648 _ij11[0] = ij11; _ij11[1] = -1;
15649 for(int iij11 = ij11+1; iij11 < 1; ++iij11)
15650 {
15651 if( j11valid[iij11] && IKabs(cj11array[ij11]-cj11array[iij11]) < IKFAST_SOLUTION_THRESH && IKabs(sj11array[ij11]-sj11array[iij11]) < IKFAST_SOLUTION_THRESH )
15652 {
15653     j11valid[iij11]=false; _ij11[1] = iij11; break; 
15654 }
15655 }
15656 j11 = j11array[ij11]; cj11 = cj11array[ij11]; sj11 = sj11array[ij11];
15657 {
15658 IkReal evalcond[3];
15659 IkReal x3466=IKsin(j11);
15660 IkReal x3467=((IkReal(1.00000000000000))*(sj13));
15661 IkReal x3468=((cj14)*(npx));
15662 IkReal x3469=((npy)*(sj14));
15663 IkReal x3470=((IkReal(0.250000000000000))*(x3466));
15664 evalcond[0]=((((IkReal(0.0950000000000000))*(cj12)))+(((sj12)*(x3470)))+(((cj14)*(npy)))+(((IkReal(-0.0300000000000000))*(sj12)))+(((npx)*(sj14))));
15665 evalcond[1]=((IkReal(0.235000000000000))+(((IkReal(0.250000000000000))*(IKcos(j11))))+(((IkReal(0.0900000000000000))*(cj13)))+(((cj13)*(x3469)))+(((IkReal(-1.00000000000000))*(npz)*(x3467)))+(((IkReal(-1.00000000000000))*(cj13)*(x3468))));
15666 evalcond[2]=((((IkReal(-1.00000000000000))*(x3467)*(x3468)))+(((IkReal(0.0950000000000000))*(sj12)))+(((sj13)*(x3469)))+(((cj13)*(npz)))+(((IkReal(0.0300000000000000))*(cj12)))+(((IkReal(-1.00000000000000))*(cj12)*(x3470)))+(((IkReal(0.0900000000000000))*(sj13))));
15667 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  )
15668 {
15669 continue;
15670 }
15671 }
15672 
15673 {
15674 IkReal dummyeval[1];
15675 IkReal gconst46;
15676 gconst46=IKsign(((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11))))));
15677 dummyeval[0]=((((sj12)*((sj11)*(sj11))))+(((sj12)*((cj11)*(cj11)))));
15678 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15679 {
15680 {
15681 IkReal dummyeval[1];
15682 IkReal gconst47;
15683 gconst47=IKsign(((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11))))));
15684 dummyeval[0]=((((cj12)*((sj11)*(sj11))))+(((cj12)*((cj11)*(cj11)))));
15685 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15686 {
15687 {
15688 IkReal evalcond[9];
15689 IkReal x3471=((r00)*(sj9));
15690 IkReal x3472=((IkReal(1.00000000000000))*(sj13));
15691 IkReal x3473=((cj13)*(sj14));
15692 IkReal x3474=((cj9)*(sj14));
15693 IkReal x3475=((cj13)*(r02));
15694 IkReal x3476=((sj13)*(sj14));
15695 IkReal x3477=((r01)*(sj9));
15696 IkReal x3478=((cj9)*(sj13));
15697 IkReal x3479=((IkReal(1.00000000000000))*(cj9));
15698 IkReal x3480=((cj14)*(r10));
15699 IkReal x3481=((cj14)*(npx));
15700 IkReal x3482=((IkReal(1.00000000000000))*(cj13));
15701 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j12)), IkReal(6.28318530717959))));
15702 evalcond[1]=((IkReal(-0.0300000000000000))+(((cj14)*(npy)))+(((npx)*(sj14)))+(((IkReal(0.250000000000000))*(sj11))));
15703 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(x3481)*(x3482)))+(((IkReal(0.250000000000000))*(cj11)))+(((npy)*(x3473)))+(((IkReal(-1.00000000000000))*(npz)*(x3472))));
15704 evalcond[3]=((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3479)))+(((IkReal(-1.00000000000000))*(r10)*(x3474)))+(((cj14)*(x3477)))+(((sj14)*(x3471))));
15705 evalcond[4]=((((IkReal(-1.00000000000000))*(cj14)*(r20)*(x3472)))+(((r21)*(x3476)))+(((cj13)*(r22))));
15706 evalcond[5]=((IkReal(0.0950000000000000))+(((IkReal(-1.00000000000000))*(x3472)*(x3481)))+(((npy)*(x3476)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13))));
15707 evalcond[6]=((((x3473)*(x3477)))+(((r12)*(x3478)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x3472)))+(((IkReal(-1.00000000000000))*(r11)*(x3473)*(x3479)))+(((IkReal(-1.00000000000000))*(cj14)*(x3471)*(x3482)))+(((cj13)*(cj9)*(x3480))));
15708 evalcond[7]=((IkReal(1.00000000000000))+(((sj9)*(x3475)))+(((x3476)*(x3477)))+(((IkReal(-1.00000000000000))*(cj14)*(x3471)*(x3472)))+(((x3478)*(x3480)))+(((IkReal(-1.00000000000000))*(r11)*(x3472)*(x3474)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x3479))));
15709 evalcond[8]=((((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3482)))+(((cj14)*(r00)*(x3478)))+(((sj13)*(sj9)*(x3480)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x3472)))+(((IkReal(-1.00000000000000))*(x3475)*(x3479)))+(((IkReal(-1.00000000000000))*(r01)*(x3472)*(x3474))));
15710 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  )
15711 {
15712 {
15713 IkReal dummyeval[1];
15714 IkReal gconst48;
15715 gconst48=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
15716 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
15717 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15718 {
15719 {
15720 IkReal dummyeval[1];
15721 IkReal gconst49;
15722 gconst49=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
15723 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
15724 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15725 {
15726 continue;
15727 
15728 } else
15729 {
15730 {
15731 IkReal j10array[1], cj10array[1], sj10array[1];
15732 bool j10valid[1]={false};
15733 _nj10 = 1;
15734 IkReal x3483=((IkReal(1.00000000000000))*(cj11));
15735 IkReal x3484=((sj11)*(sj14));
15736 IkReal x3485=((r10)*(sj9));
15737 IkReal x3486=((cj9)*(r00));
15738 IkReal x3487=((cj14)*(sj11));
15739 IkReal x3488=((r11)*(sj9));
15740 IkReal x3489=((cj14)*(cj9)*(r01));
15741 if( IKabs(((gconst49)*(((((x3484)*(x3486)))+(((x3484)*(x3485)))+(((cj11)*(cj14)*(r21)))+(((x3487)*(x3488)))+(((cj11)*(r20)*(sj14)))+(((cj9)*(r01)*(x3487))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst49)*(((((IkReal(-1.00000000000000))*(x3483)*(x3489)))+(((IkReal(-1.00000000000000))*(cj14)*(x3483)*(x3488)))+(((IkReal(-1.00000000000000))*(sj14)*(x3483)*(x3486)))+(((IkReal(-1.00000000000000))*(sj14)*(x3483)*(x3485)))+(((r20)*(x3484)))+(((r21)*(x3487))))))) < IKFAST_ATAN2_MAGTHRESH )
15742     continue;
15743 j10array[0]=IKatan2(((gconst49)*(((((x3484)*(x3486)))+(((x3484)*(x3485)))+(((cj11)*(cj14)*(r21)))+(((x3487)*(x3488)))+(((cj11)*(r20)*(sj14)))+(((cj9)*(r01)*(x3487)))))), ((gconst49)*(((((IkReal(-1.00000000000000))*(x3483)*(x3489)))+(((IkReal(-1.00000000000000))*(cj14)*(x3483)*(x3488)))+(((IkReal(-1.00000000000000))*(sj14)*(x3483)*(x3486)))+(((IkReal(-1.00000000000000))*(sj14)*(x3483)*(x3485)))+(((r20)*(x3484)))+(((r21)*(x3487)))))));
15744 sj10array[0]=IKsin(j10array[0]);
15745 cj10array[0]=IKcos(j10array[0]);
15746 if( j10array[0] > IKPI )
15747 {
15748     j10array[0]-=IK2PI;
15749 }
15750 else if( j10array[0] < -IKPI )
15751 {    j10array[0]+=IK2PI;
15752 }
15753 j10valid[0] = true;
15754 for(int ij10 = 0; ij10 < 1; ++ij10)
15755 {
15756 if( !j10valid[ij10] )
15757 {
15758     continue;
15759 }
15760 _ij10[0] = ij10; _ij10[1] = -1;
15761 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15762 {
15763 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15764 {
15765     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15766 }
15767 }
15768 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15769 {
15770 IkReal evalcond[4];
15771 IkReal x3490=IKsin(j10);
15772 IkReal x3491=IKcos(j10);
15773 IkReal x3492=((cj13)*(sj14));
15774 IkReal x3493=((cj13)*(cj14));
15775 IkReal x3494=((r10)*(sj9));
15776 IkReal x3495=((IkReal(1.00000000000000))*(cj9));
15777 IkReal x3496=((sj11)*(x3490));
15778 IkReal x3497=((IkReal(1.00000000000000))*(x3491));
15779 IkReal x3498=((cj11)*(x3490));
15780 IkReal x3499=((IkReal(1.00000000000000))*(r11)*(sj9));
15781 IkReal x3500=((cj11)*(x3497));
15782 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x3497)))+(((IkReal(-1.00000000000000))*(x3498))));
15783 evalcond[1]=((((IkReal(-1.00000000000000))*(x3500)))+(x3496)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(r20)*(x3493)))+(((r21)*(x3492))));
15784 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(x3499)))+(((IkReal(-1.00000000000000))*(x3500)))+(x3496)+(((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3495)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3495)))+(((IkReal(-1.00000000000000))*(sj14)*(x3494))));
15785 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(x3492)*(x3495)))+(((cj9)*(r02)*(sj13)))+(((cj9)*(r00)*(x3493)))+(x3498)+(((IkReal(-1.00000000000000))*(x3492)*(x3499)))+(((sj11)*(x3491)))+(((x3493)*(x3494)))+(((r12)*(sj13)*(sj9))));
15786 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15787 {
15788 continue;
15789 }
15790 }
15791 
15792 {
15793 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15794 vinfos[0].jointtype = 1;
15795 vinfos[0].foffset = j9;
15796 vinfos[0].indices[0] = _ij9[0];
15797 vinfos[0].indices[1] = _ij9[1];
15798 vinfos[0].maxsolutions = _nj9;
15799 vinfos[1].jointtype = 1;
15800 vinfos[1].foffset = j10;
15801 vinfos[1].indices[0] = _ij10[0];
15802 vinfos[1].indices[1] = _ij10[1];
15803 vinfos[1].maxsolutions = _nj10;
15804 vinfos[2].jointtype = 1;
15805 vinfos[2].foffset = j11;
15806 vinfos[2].indices[0] = _ij11[0];
15807 vinfos[2].indices[1] = _ij11[1];
15808 vinfos[2].maxsolutions = _nj11;
15809 vinfos[3].jointtype = 1;
15810 vinfos[3].foffset = j12;
15811 vinfos[3].indices[0] = _ij12[0];
15812 vinfos[3].indices[1] = _ij12[1];
15813 vinfos[3].maxsolutions = _nj12;
15814 vinfos[4].jointtype = 1;
15815 vinfos[4].foffset = j13;
15816 vinfos[4].indices[0] = _ij13[0];
15817 vinfos[4].indices[1] = _ij13[1];
15818 vinfos[4].maxsolutions = _nj13;
15819 vinfos[5].jointtype = 1;
15820 vinfos[5].foffset = j14;
15821 vinfos[5].indices[0] = _ij14[0];
15822 vinfos[5].indices[1] = _ij14[1];
15823 vinfos[5].maxsolutions = _nj14;
15824 std::vector<int> vfree(0);
15825 solutions.AddSolution(vinfos,vfree);
15826 }
15827 }
15828 }
15829 
15830 }
15831 
15832 }
15833 
15834 } else
15835 {
15836 {
15837 IkReal j10array[1], cj10array[1], sj10array[1];
15838 bool j10valid[1]={false};
15839 _nj10 = 1;
15840 IkReal x3501=((cj11)*(r20));
15841 IkReal x3502=((IkReal(1.00000000000000))*(cj13));
15842 IkReal x3503=((r21)*(sj14));
15843 IkReal x3504=((r22)*(sj13));
15844 IkReal x3505=((r20)*(sj11));
15845 IkReal x3506=((cj14)*(r21));
15846 if( IKabs(((gconst48)*(((((cj13)*(cj14)*(x3505)))+(((IkReal(-1.00000000000000))*(sj11)*(x3502)*(x3503)))+(((cj11)*(x3506)))+(((sj14)*(x3501)))+(((sj11)*(x3504))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst48)*(((((IkReal(-1.00000000000000))*(cj11)*(x3504)))+(((IkReal(-1.00000000000000))*(cj14)*(x3501)*(x3502)))+(((sj14)*(x3505)))+(((sj11)*(x3506)))+(((cj11)*(cj13)*(x3503))))))) < IKFAST_ATAN2_MAGTHRESH )
15847     continue;
15848 j10array[0]=IKatan2(((gconst48)*(((((cj13)*(cj14)*(x3505)))+(((IkReal(-1.00000000000000))*(sj11)*(x3502)*(x3503)))+(((cj11)*(x3506)))+(((sj14)*(x3501)))+(((sj11)*(x3504)))))), ((gconst48)*(((((IkReal(-1.00000000000000))*(cj11)*(x3504)))+(((IkReal(-1.00000000000000))*(cj14)*(x3501)*(x3502)))+(((sj14)*(x3505)))+(((sj11)*(x3506)))+(((cj11)*(cj13)*(x3503)))))));
15849 sj10array[0]=IKsin(j10array[0]);
15850 cj10array[0]=IKcos(j10array[0]);
15851 if( j10array[0] > IKPI )
15852 {
15853     j10array[0]-=IK2PI;
15854 }
15855 else if( j10array[0] < -IKPI )
15856 {    j10array[0]+=IK2PI;
15857 }
15858 j10valid[0] = true;
15859 for(int ij10 = 0; ij10 < 1; ++ij10)
15860 {
15861 if( !j10valid[ij10] )
15862 {
15863     continue;
15864 }
15865 _ij10[0] = ij10; _ij10[1] = -1;
15866 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
15867 {
15868 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
15869 {
15870     j10valid[iij10]=false; _ij10[1] = iij10; break; 
15871 }
15872 }
15873 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
15874 {
15875 IkReal evalcond[4];
15876 IkReal x3507=IKsin(j10);
15877 IkReal x3508=IKcos(j10);
15878 IkReal x3509=((cj13)*(sj14));
15879 IkReal x3510=((cj13)*(cj14));
15880 IkReal x3511=((r10)*(sj9));
15881 IkReal x3512=((IkReal(1.00000000000000))*(cj9));
15882 IkReal x3513=((sj11)*(x3507));
15883 IkReal x3514=((IkReal(1.00000000000000))*(x3508));
15884 IkReal x3515=((cj11)*(x3507));
15885 IkReal x3516=((IkReal(1.00000000000000))*(r11)*(sj9));
15886 IkReal x3517=((cj11)*(x3514));
15887 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(sj11)*(x3514)))+(((IkReal(-1.00000000000000))*(x3515))));
15888 evalcond[1]=((((IkReal(-1.00000000000000))*(x3517)))+(x3513)+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((r21)*(x3509)))+(((IkReal(-1.00000000000000))*(r20)*(x3510))));
15889 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3512)))+(((IkReal(-1.00000000000000))*(x3517)))+(x3513)+(((IkReal(-1.00000000000000))*(sj14)*(x3511)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3512)))+(((IkReal(-1.00000000000000))*(cj14)*(x3516))));
15890 evalcond[3]=((((IkReal(-1.00000000000000))*(x3509)*(x3516)))+(((x3510)*(x3511)))+(((cj9)*(r02)*(sj13)))+(x3515)+(((IkReal(-1.00000000000000))*(r01)*(x3509)*(x3512)))+(((cj9)*(r00)*(x3510)))+(((sj11)*(x3508)))+(((r12)*(sj13)*(sj9))));
15891 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
15892 {
15893 continue;
15894 }
15895 }
15896 
15897 {
15898 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
15899 vinfos[0].jointtype = 1;
15900 vinfos[0].foffset = j9;
15901 vinfos[0].indices[0] = _ij9[0];
15902 vinfos[0].indices[1] = _ij9[1];
15903 vinfos[0].maxsolutions = _nj9;
15904 vinfos[1].jointtype = 1;
15905 vinfos[1].foffset = j10;
15906 vinfos[1].indices[0] = _ij10[0];
15907 vinfos[1].indices[1] = _ij10[1];
15908 vinfos[1].maxsolutions = _nj10;
15909 vinfos[2].jointtype = 1;
15910 vinfos[2].foffset = j11;
15911 vinfos[2].indices[0] = _ij11[0];
15912 vinfos[2].indices[1] = _ij11[1];
15913 vinfos[2].maxsolutions = _nj11;
15914 vinfos[3].jointtype = 1;
15915 vinfos[3].foffset = j12;
15916 vinfos[3].indices[0] = _ij12[0];
15917 vinfos[3].indices[1] = _ij12[1];
15918 vinfos[3].maxsolutions = _nj12;
15919 vinfos[4].jointtype = 1;
15920 vinfos[4].foffset = j13;
15921 vinfos[4].indices[0] = _ij13[0];
15922 vinfos[4].indices[1] = _ij13[1];
15923 vinfos[4].maxsolutions = _nj13;
15924 vinfos[5].jointtype = 1;
15925 vinfos[5].foffset = j14;
15926 vinfos[5].indices[0] = _ij14[0];
15927 vinfos[5].indices[1] = _ij14[1];
15928 vinfos[5].maxsolutions = _nj14;
15929 std::vector<int> vfree(0);
15930 solutions.AddSolution(vinfos,vfree);
15931 }
15932 }
15933 }
15934 
15935 }
15936 
15937 }
15938 
15939 } else
15940 {
15941 IkReal x3518=((r00)*(sj9));
15942 IkReal x3519=((IkReal(1.00000000000000))*(sj13));
15943 IkReal x3520=((cj13)*(sj14));
15944 IkReal x3521=((cj9)*(sj14));
15945 IkReal x3522=((cj13)*(r02));
15946 IkReal x3523=((sj13)*(sj14));
15947 IkReal x3524=((r01)*(sj9));
15948 IkReal x3525=((cj9)*(sj13));
15949 IkReal x3526=((IkReal(1.00000000000000))*(cj9));
15950 IkReal x3527=((cj14)*(r10));
15951 IkReal x3528=((cj14)*(npx));
15952 IkReal x3529=((IkReal(1.00000000000000))*(cj13));
15953 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j12)), IkReal(6.28318530717959))));
15954 evalcond[1]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((cj14)*(npy)))+(((npx)*(sj14))));
15955 evalcond[2]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x3519)))+(((IkReal(0.250000000000000))*(cj11)))+(((npy)*(x3520)))+(((IkReal(-1.00000000000000))*(x3528)*(x3529))));
15956 evalcond[3]=((((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3526)))+(((cj14)*(x3524)))+(((sj14)*(x3518)))+(((IkReal(-1.00000000000000))*(r10)*(x3521))));
15957 evalcond[4]=((((r21)*(x3523)))+(((IkReal(-1.00000000000000))*(cj14)*(r20)*(x3519)))+(((cj13)*(r22))));
15958 evalcond[5]=((IkReal(-0.0950000000000000))+(((IkReal(-1.00000000000000))*(x3519)*(x3528)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((npy)*(x3523))));
15959 evalcond[6]=((((cj13)*(cj9)*(x3527)))+(((r12)*(x3525)))+(((IkReal(-1.00000000000000))*(r11)*(x3520)*(x3526)))+(((x3520)*(x3524)))+(((IkReal(-1.00000000000000))*(r02)*(sj9)*(x3519)))+(((IkReal(-1.00000000000000))*(cj14)*(x3518)*(x3529))));
15960 evalcond[7]=((IkReal(-1.00000000000000))+(((x3525)*(x3527)))+(((IkReal(-1.00000000000000))*(cj13)*(r12)*(x3526)))+(((sj9)*(x3522)))+(((x3523)*(x3524)))+(((IkReal(-1.00000000000000))*(r11)*(x3519)*(x3521)))+(((IkReal(-1.00000000000000))*(cj14)*(x3518)*(x3519))));
15961 evalcond[8]=((((IkReal(-1.00000000000000))*(x3522)*(x3526)))+(((IkReal(-1.00000000000000))*(r01)*(x3519)*(x3521)))+(((IkReal(-1.00000000000000))*(r11)*(sj14)*(sj9)*(x3519)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3529)))+(((sj13)*(sj9)*(x3527)))+(((cj14)*(r00)*(x3525))));
15962 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  )
15963 {
15964 {
15965 IkReal dummyeval[1];
15966 IkReal gconst50;
15967 gconst50=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
15968 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
15969 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15970 {
15971 {
15972 IkReal dummyeval[1];
15973 IkReal gconst51;
15974 gconst51=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
15975 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
15976 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
15977 {
15978 continue;
15979 
15980 } else
15981 {
15982 {
15983 IkReal j10array[1], cj10array[1], sj10array[1];
15984 bool j10valid[1]={false};
15985 _nj10 = 1;
15986 IkReal x3530=((IkReal(1.00000000000000))*(sj11));
15987 IkReal x3531=((cj14)*(r21));
15988 IkReal x3532=((IkReal(1.00000000000000))*(cj11));
15989 IkReal x3533=((r20)*(sj14));
15990 IkReal x3534=((cj9)*(r00)*(sj14));
15991 IkReal x3535=((cj14)*(r11)*(sj9));
15992 IkReal x3536=((cj14)*(cj9)*(r01));
15993 IkReal x3537=((r10)*(sj14)*(sj9));
15994 if( IKabs(((gconst51)*(((((IkReal(-1.00000000000000))*(x3531)*(x3532)))+(((IkReal(-1.00000000000000))*(x3530)*(x3535)))+(((IkReal(-1.00000000000000))*(x3530)*(x3534)))+(((IkReal(-1.00000000000000))*(x3530)*(x3537)))+(((IkReal(-1.00000000000000))*(x3530)*(x3536)))+(((IkReal(-1.00000000000000))*(x3532)*(x3533))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst51)*(((((cj11)*(x3535)))+(((cj11)*(x3534)))+(((cj11)*(x3537)))+(((cj11)*(x3536)))+(((IkReal(-1.00000000000000))*(x3530)*(x3531)))+(((IkReal(-1.00000000000000))*(x3530)*(x3533))))))) < IKFAST_ATAN2_MAGTHRESH )
15995     continue;
15996 j10array[0]=IKatan2(((gconst51)*(((((IkReal(-1.00000000000000))*(x3531)*(x3532)))+(((IkReal(-1.00000000000000))*(x3530)*(x3535)))+(((IkReal(-1.00000000000000))*(x3530)*(x3534)))+(((IkReal(-1.00000000000000))*(x3530)*(x3537)))+(((IkReal(-1.00000000000000))*(x3530)*(x3536)))+(((IkReal(-1.00000000000000))*(x3532)*(x3533)))))), ((gconst51)*(((((cj11)*(x3535)))+(((cj11)*(x3534)))+(((cj11)*(x3537)))+(((cj11)*(x3536)))+(((IkReal(-1.00000000000000))*(x3530)*(x3531)))+(((IkReal(-1.00000000000000))*(x3530)*(x3533)))))));
15997 sj10array[0]=IKsin(j10array[0]);
15998 cj10array[0]=IKcos(j10array[0]);
15999 if( j10array[0] > IKPI )
16000 {
16001     j10array[0]-=IK2PI;
16002 }
16003 else if( j10array[0] < -IKPI )
16004 {    j10array[0]+=IK2PI;
16005 }
16006 j10valid[0] = true;
16007 for(int ij10 = 0; ij10 < 1; ++ij10)
16008 {
16009 if( !j10valid[ij10] )
16010 {
16011     continue;
16012 }
16013 _ij10[0] = ij10; _ij10[1] = -1;
16014 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16015 {
16016 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16017 {
16018     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16019 }
16020 }
16021 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16022 {
16023 IkReal evalcond[4];
16024 IkReal x3538=IKsin(j10);
16025 IkReal x3539=IKcos(j10);
16026 IkReal x3540=((cj14)*(sj9));
16027 IkReal x3541=((IkReal(1.00000000000000))*(r11));
16028 IkReal x3542=((cj13)*(sj14));
16029 IkReal x3543=((IkReal(1.00000000000000))*(cj9));
16030 IkReal x3544=((cj13)*(cj14));
16031 IkReal x3545=((cj11)*(x3538));
16032 IkReal x3546=((sj11)*(x3539));
16033 IkReal x3547=((cj11)*(x3539));
16034 IkReal x3548=((sj11)*(x3538));
16035 IkReal x3549=((x3545)+(x3546));
16036 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x3549));
16037 evalcond[1]=((((r21)*(x3542)))+(x3548)+(((IkReal(-1.00000000000000))*(r20)*(x3544)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x3547))));
16038 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3543)))+(x3547)+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x3548)))+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3543)))+(((IkReal(-1.00000000000000))*(x3540)*(x3541))));
16039 evalcond[3]=((((cj9)*(r02)*(sj13)))+(x3549)+(((cj9)*(r00)*(x3544)))+(((IkReal(-1.00000000000000))*(r01)*(x3542)*(x3543)))+(((IkReal(-1.00000000000000))*(sj9)*(x3541)*(x3542)))+(((cj13)*(r10)*(x3540)))+(((r12)*(sj13)*(sj9))));
16040 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16041 {
16042 continue;
16043 }
16044 }
16045 
16046 {
16047 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16048 vinfos[0].jointtype = 1;
16049 vinfos[0].foffset = j9;
16050 vinfos[0].indices[0] = _ij9[0];
16051 vinfos[0].indices[1] = _ij9[1];
16052 vinfos[0].maxsolutions = _nj9;
16053 vinfos[1].jointtype = 1;
16054 vinfos[1].foffset = j10;
16055 vinfos[1].indices[0] = _ij10[0];
16056 vinfos[1].indices[1] = _ij10[1];
16057 vinfos[1].maxsolutions = _nj10;
16058 vinfos[2].jointtype = 1;
16059 vinfos[2].foffset = j11;
16060 vinfos[2].indices[0] = _ij11[0];
16061 vinfos[2].indices[1] = _ij11[1];
16062 vinfos[2].maxsolutions = _nj11;
16063 vinfos[3].jointtype = 1;
16064 vinfos[3].foffset = j12;
16065 vinfos[3].indices[0] = _ij12[0];
16066 vinfos[3].indices[1] = _ij12[1];
16067 vinfos[3].maxsolutions = _nj12;
16068 vinfos[4].jointtype = 1;
16069 vinfos[4].foffset = j13;
16070 vinfos[4].indices[0] = _ij13[0];
16071 vinfos[4].indices[1] = _ij13[1];
16072 vinfos[4].maxsolutions = _nj13;
16073 vinfos[5].jointtype = 1;
16074 vinfos[5].foffset = j14;
16075 vinfos[5].indices[0] = _ij14[0];
16076 vinfos[5].indices[1] = _ij14[1];
16077 vinfos[5].maxsolutions = _nj14;
16078 std::vector<int> vfree(0);
16079 solutions.AddSolution(vinfos,vfree);
16080 }
16081 }
16082 }
16083 
16084 }
16085 
16086 }
16087 
16088 } else
16089 {
16090 {
16091 IkReal j10array[1], cj10array[1], sj10array[1];
16092 bool j10valid[1]={false};
16093 _nj10 = 1;
16094 IkReal x3550=((cj13)*(sj11));
16095 IkReal x3551=((r21)*(sj14));
16096 IkReal x3552=((cj14)*(r20));
16097 IkReal x3553=((cj11)*(cj13));
16098 IkReal x3554=((r22)*(sj13));
16099 IkReal x3555=((r20)*(sj14));
16100 IkReal x3556=((cj14)*(r21));
16101 if( IKabs(((gconst50)*(((((IkReal(-1.00000000000000))*(sj11)*(x3554)))+(((IkReal(-1.00000000000000))*(x3550)*(x3552)))+(((cj11)*(x3556)))+(((cj11)*(x3555)))+(((x3550)*(x3551))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst50)*(((((sj11)*(x3555)))+(((sj11)*(x3556)))+(((x3552)*(x3553)))+(((cj11)*(x3554)))+(((IkReal(-1.00000000000000))*(x3551)*(x3553))))))) < IKFAST_ATAN2_MAGTHRESH )
16102     continue;
16103 j10array[0]=IKatan2(((gconst50)*(((((IkReal(-1.00000000000000))*(sj11)*(x3554)))+(((IkReal(-1.00000000000000))*(x3550)*(x3552)))+(((cj11)*(x3556)))+(((cj11)*(x3555)))+(((x3550)*(x3551)))))), ((gconst50)*(((((sj11)*(x3555)))+(((sj11)*(x3556)))+(((x3552)*(x3553)))+(((cj11)*(x3554)))+(((IkReal(-1.00000000000000))*(x3551)*(x3553)))))));
16104 sj10array[0]=IKsin(j10array[0]);
16105 cj10array[0]=IKcos(j10array[0]);
16106 if( j10array[0] > IKPI )
16107 {
16108     j10array[0]-=IK2PI;
16109 }
16110 else if( j10array[0] < -IKPI )
16111 {    j10array[0]+=IK2PI;
16112 }
16113 j10valid[0] = true;
16114 for(int ij10 = 0; ij10 < 1; ++ij10)
16115 {
16116 if( !j10valid[ij10] )
16117 {
16118     continue;
16119 }
16120 _ij10[0] = ij10; _ij10[1] = -1;
16121 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16122 {
16123 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16124 {
16125     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16126 }
16127 }
16128 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16129 {
16130 IkReal evalcond[4];
16131 IkReal x3557=IKsin(j10);
16132 IkReal x3558=IKcos(j10);
16133 IkReal x3559=((cj14)*(sj9));
16134 IkReal x3560=((IkReal(1.00000000000000))*(r11));
16135 IkReal x3561=((cj13)*(sj14));
16136 IkReal x3562=((IkReal(1.00000000000000))*(cj9));
16137 IkReal x3563=((cj13)*(cj14));
16138 IkReal x3564=((cj11)*(x3557));
16139 IkReal x3565=((sj11)*(x3558));
16140 IkReal x3566=((cj11)*(x3558));
16141 IkReal x3567=((sj11)*(x3557));
16142 IkReal x3568=((x3564)+(x3565));
16143 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(x3568));
16144 evalcond[1]=((((IkReal(-1.00000000000000))*(r20)*(x3563)))+(x3567)+(((r21)*(x3561)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)))+(((IkReal(-1.00000000000000))*(x3566))));
16145 evalcond[2]=((((IkReal(-1.00000000000000))*(cj14)*(r01)*(x3562)))+(x3566)+(((IkReal(-1.00000000000000))*(r00)*(sj14)*(x3562)))+(((IkReal(-1.00000000000000))*(r10)*(sj14)*(sj9)))+(((IkReal(-1.00000000000000))*(x3559)*(x3560)))+(((IkReal(-1.00000000000000))*(x3567))));
16146 evalcond[3]=((((cj9)*(r02)*(sj13)))+(x3568)+(((IkReal(-1.00000000000000))*(r01)*(x3561)*(x3562)))+(((cj13)*(r10)*(x3559)))+(((cj9)*(r00)*(x3563)))+(((IkReal(-1.00000000000000))*(sj9)*(x3560)*(x3561)))+(((r12)*(sj13)*(sj9))));
16147 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16148 {
16149 continue;
16150 }
16151 }
16152 
16153 {
16154 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16155 vinfos[0].jointtype = 1;
16156 vinfos[0].foffset = j9;
16157 vinfos[0].indices[0] = _ij9[0];
16158 vinfos[0].indices[1] = _ij9[1];
16159 vinfos[0].maxsolutions = _nj9;
16160 vinfos[1].jointtype = 1;
16161 vinfos[1].foffset = j10;
16162 vinfos[1].indices[0] = _ij10[0];
16163 vinfos[1].indices[1] = _ij10[1];
16164 vinfos[1].maxsolutions = _nj10;
16165 vinfos[2].jointtype = 1;
16166 vinfos[2].foffset = j11;
16167 vinfos[2].indices[0] = _ij11[0];
16168 vinfos[2].indices[1] = _ij11[1];
16169 vinfos[2].maxsolutions = _nj11;
16170 vinfos[3].jointtype = 1;
16171 vinfos[3].foffset = j12;
16172 vinfos[3].indices[0] = _ij12[0];
16173 vinfos[3].indices[1] = _ij12[1];
16174 vinfos[3].maxsolutions = _nj12;
16175 vinfos[4].jointtype = 1;
16176 vinfos[4].foffset = j13;
16177 vinfos[4].indices[0] = _ij13[0];
16178 vinfos[4].indices[1] = _ij13[1];
16179 vinfos[4].maxsolutions = _nj13;
16180 vinfos[5].jointtype = 1;
16181 vinfos[5].foffset = j14;
16182 vinfos[5].indices[0] = _ij14[0];
16183 vinfos[5].indices[1] = _ij14[1];
16184 vinfos[5].maxsolutions = _nj14;
16185 std::vector<int> vfree(0);
16186 solutions.AddSolution(vinfos,vfree);
16187 }
16188 }
16189 }
16190 
16191 }
16192 
16193 }
16194 
16195 } else
16196 {
16197 IkReal x3569=((cj9)*(r10));
16198 IkReal x3570=((cj13)*(cj14));
16199 IkReal x3571=((sj14)*(sj9));
16200 IkReal x3572=((IkReal(1.00000000000000))*(sj14));
16201 IkReal x3573=((cj9)*(sj13));
16202 IkReal x3574=((r02)*(sj9));
16203 IkReal x3575=((cj13)*(cj9));
16204 IkReal x3576=((cj14)*(r01));
16205 IkReal x3577=((IkReal(1.00000000000000))*(npx));
16206 IkReal x3578=((cj14)*(sj13));
16207 IkReal x3579=((IkReal(1.00000000000000))*(cj9));
16208 IkReal x3580=((npy)*(sj14));
16209 IkReal x3581=((IkReal(1.00000000000000))*(sj13));
16210 IkReal x3582=((IkReal(1.00000000000000))*(cj14)*(sj9));
16211 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(3.14159265358979))+(j12)), IkReal(6.28318530717959))));
16212 evalcond[1]=((IkReal(0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
16213 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
16214 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(-1.00000000000000))*(npz)*(x3581)))+(((IkReal(0.250000000000000))*(cj11)))+(((cj13)*(x3580)))+(((IkReal(-1.00000000000000))*(x3570)*(x3577))));
16215 evalcond[4]=((IkReal(1.00000000000000))+(((r00)*(x3571)))+(((sj9)*(x3576)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3579)))+(((IkReal(-1.00000000000000))*(x3569)*(x3572))));
16216 evalcond[5]=((IkReal(0.0300000000000000))+(((IkReal(-0.250000000000000))*(sj11)))+(((sj13)*(x3580)))+(((cj13)*(npz)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(-1.00000000000000))*(x3577)*(x3578))));
16217 evalcond[6]=((((IkReal(-1.00000000000000))*(cj9)*(r00)*(x3572)))+(((IkReal(-1.00000000000000))*(x3576)*(x3579)))+(((IkReal(-1.00000000000000))*(r10)*(x3571)))+(((IkReal(-1.00000000000000))*(r11)*(x3582))));
16218 evalcond[7]=((((IkReal(-1.00000000000000))*(x3574)*(x3581)))+(((IkReal(-1.00000000000000))*(r11)*(x3572)*(x3575)))+(((x3569)*(x3570)))+(((r12)*(x3573)))+(((cj13)*(r01)*(x3571)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3570))));
16219 evalcond[8]=((((IkReal(-1.00000000000000))*(r11)*(x3572)*(x3573)))+(((r01)*(sj13)*(x3571)))+(((x3569)*(x3578)))+(((IkReal(-1.00000000000000))*(r12)*(x3575)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3578)))+(((cj13)*(x3574))));
16220 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  )
16221 {
16222 {
16223 IkReal dummyeval[1];
16224 IkReal gconst52;
16225 gconst52=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
16226 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
16227 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16228 {
16229 {
16230 IkReal dummyeval[1];
16231 IkReal gconst53;
16232 gconst53=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
16233 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
16234 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16235 {
16236 continue;
16237 
16238 } else
16239 {
16240 {
16241 IkReal j10array[1], cj10array[1], sj10array[1];
16242 bool j10valid[1]={false};
16243 _nj10 = 1;
16244 IkReal x3583=((cj13)*(sj14));
16245 IkReal x3584=((IkReal(1.00000000000000))*(cj11));
16246 IkReal x3585=((r11)*(sj9));
16247 IkReal x3586=((IkReal(1.00000000000000))*(sj11));
16248 IkReal x3587=((cj13)*(cj14));
16249 IkReal x3588=((cj11)*(sj13));
16250 IkReal x3589=((r12)*(sj9));
16251 IkReal x3590=((sj11)*(sj13));
16252 IkReal x3591=((cj9)*(r02));
16253 IkReal x3592=((cj9)*(r01));
16254 IkReal x3593=((r10)*(sj9));
16255 IkReal x3594=((cj9)*(r00));
16256 if( IKabs(((gconst53)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3586)))+(((r21)*(sj11)*(x3583)))+(((x3588)*(x3589)))+(((IkReal(-1.00000000000000))*(r20)*(x3586)*(x3587)))+(((x3588)*(x3591)))+(((cj11)*(x3587)*(x3593)))+(((cj11)*(x3587)*(x3594)))+(((IkReal(-1.00000000000000))*(x3583)*(x3584)*(x3592)))+(((IkReal(-1.00000000000000))*(x3583)*(x3584)*(x3585))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst53)*(((((sj11)*(x3587)*(x3594)))+(((sj11)*(x3587)*(x3593)))+(((x3589)*(x3590)))+(((cj11)*(r20)*(x3587)))+(((x3590)*(x3591)))+(((IkReal(-1.00000000000000))*(x3583)*(x3586)*(x3592)))+(((IkReal(-1.00000000000000))*(x3583)*(x3585)*(x3586)))+(((IkReal(-1.00000000000000))*(r21)*(x3583)*(x3584)))+(((r22)*(x3588))))))) < IKFAST_ATAN2_MAGTHRESH )
16257     continue;
16258 j10array[0]=IKatan2(((gconst53)*(((((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3586)))+(((r21)*(sj11)*(x3583)))+(((x3588)*(x3589)))+(((IkReal(-1.00000000000000))*(r20)*(x3586)*(x3587)))+(((x3588)*(x3591)))+(((cj11)*(x3587)*(x3593)))+(((cj11)*(x3587)*(x3594)))+(((IkReal(-1.00000000000000))*(x3583)*(x3584)*(x3592)))+(((IkReal(-1.00000000000000))*(x3583)*(x3584)*(x3585)))))), ((gconst53)*(((((sj11)*(x3587)*(x3594)))+(((sj11)*(x3587)*(x3593)))+(((x3589)*(x3590)))+(((cj11)*(r20)*(x3587)))+(((x3590)*(x3591)))+(((IkReal(-1.00000000000000))*(x3583)*(x3586)*(x3592)))+(((IkReal(-1.00000000000000))*(x3583)*(x3585)*(x3586)))+(((IkReal(-1.00000000000000))*(r21)*(x3583)*(x3584)))+(((r22)*(x3588)))))));
16259 sj10array[0]=IKsin(j10array[0]);
16260 cj10array[0]=IKcos(j10array[0]);
16261 if( j10array[0] > IKPI )
16262 {
16263     j10array[0]-=IK2PI;
16264 }
16265 else if( j10array[0] < -IKPI )
16266 {    j10array[0]+=IK2PI;
16267 }
16268 j10valid[0] = true;
16269 for(int ij10 = 0; ij10 < 1; ++ij10)
16270 {
16271 if( !j10valid[ij10] )
16272 {
16273     continue;
16274 }
16275 _ij10[0] = ij10; _ij10[1] = -1;
16276 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16277 {
16278 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16279 {
16280     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16281 }
16282 }
16283 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16284 {
16285 IkReal evalcond[4];
16286 IkReal x3595=IKsin(j10);
16287 IkReal x3596=IKcos(j10);
16288 IkReal x3597=((IkReal(1.00000000000000))*(sj13));
16289 IkReal x3598=((r11)*(sj9));
16290 IkReal x3599=((cj9)*(r01));
16291 IkReal x3600=((r21)*(sj14));
16292 IkReal x3601=((cj9)*(r02));
16293 IkReal x3602=((sj13)*(sj9));
16294 IkReal x3603=((cj14)*(r10));
16295 IkReal x3604=((IkReal(1.00000000000000))*(cj13));
16296 IkReal x3605=((cj14)*(r20));
16297 IkReal x3606=((cj11)*(x3595));
16298 IkReal x3607=((sj11)*(x3596));
16299 IkReal x3608=((sj14)*(x3604));
16300 IkReal x3609=((sj11)*(x3595));
16301 IkReal x3610=((cj11)*(x3596));
16302 IkReal x3611=((cj14)*(cj9)*(r00));
16303 IkReal x3612=((x3607)+(x3606));
16304 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3597)))+(((IkReal(-1.00000000000000))*(x3610)))+(x3609)+(((cj13)*(x3600)))+(((IkReal(-1.00000000000000))*(x3604)*(x3605))));
16305 evalcond[1]=((((sj13)*(x3600)))+(x3612)+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x3597)*(x3605))));
16306 evalcond[2]=((((sj13)*(x3601)))+(((IkReal(-1.00000000000000))*(x3598)*(x3608)))+(x3612)+(((cj13)*(x3611)))+(((IkReal(-1.00000000000000))*(x3599)*(x3608)))+(((cj13)*(sj9)*(x3603)))+(((r12)*(x3602))));
16307 evalcond[3]=((((sj13)*(x3611)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3604)))+(((IkReal(-1.00000000000000))*(x3601)*(x3604)))+(((IkReal(-1.00000000000000))*(x3609)))+(x3610)+(((x3602)*(x3603)))+(((IkReal(-1.00000000000000))*(sj14)*(x3597)*(x3598)))+(((IkReal(-1.00000000000000))*(sj14)*(x3597)*(x3599))));
16308 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16309 {
16310 continue;
16311 }
16312 }
16313 
16314 {
16315 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16316 vinfos[0].jointtype = 1;
16317 vinfos[0].foffset = j9;
16318 vinfos[0].indices[0] = _ij9[0];
16319 vinfos[0].indices[1] = _ij9[1];
16320 vinfos[0].maxsolutions = _nj9;
16321 vinfos[1].jointtype = 1;
16322 vinfos[1].foffset = j10;
16323 vinfos[1].indices[0] = _ij10[0];
16324 vinfos[1].indices[1] = _ij10[1];
16325 vinfos[1].maxsolutions = _nj10;
16326 vinfos[2].jointtype = 1;
16327 vinfos[2].foffset = j11;
16328 vinfos[2].indices[0] = _ij11[0];
16329 vinfos[2].indices[1] = _ij11[1];
16330 vinfos[2].maxsolutions = _nj11;
16331 vinfos[3].jointtype = 1;
16332 vinfos[3].foffset = j12;
16333 vinfos[3].indices[0] = _ij12[0];
16334 vinfos[3].indices[1] = _ij12[1];
16335 vinfos[3].maxsolutions = _nj12;
16336 vinfos[4].jointtype = 1;
16337 vinfos[4].foffset = j13;
16338 vinfos[4].indices[0] = _ij13[0];
16339 vinfos[4].indices[1] = _ij13[1];
16340 vinfos[4].maxsolutions = _nj13;
16341 vinfos[5].jointtype = 1;
16342 vinfos[5].foffset = j14;
16343 vinfos[5].indices[0] = _ij14[0];
16344 vinfos[5].indices[1] = _ij14[1];
16345 vinfos[5].maxsolutions = _nj14;
16346 std::vector<int> vfree(0);
16347 solutions.AddSolution(vinfos,vfree);
16348 }
16349 }
16350 }
16351 
16352 }
16353 
16354 }
16355 
16356 } else
16357 {
16358 {
16359 IkReal j10array[1], cj10array[1], sj10array[1];
16360 bool j10valid[1]={false};
16361 _nj10 = 1;
16362 IkReal x3613=((cj13)*(sj11));
16363 IkReal x3614=((r21)*(sj14));
16364 IkReal x3615=((cj11)*(cj13));
16365 IkReal x3616=((cj11)*(sj13));
16366 IkReal x3617=((sj11)*(sj13));
16367 IkReal x3618=((IkReal(1.00000000000000))*(cj14)*(r20));
16368 if( IKabs(((gconst52)*(((((IkReal(-1.00000000000000))*(x3616)*(x3618)))+(((IkReal(-1.00000000000000))*(r22)*(x3617)))+(((x3613)*(x3614)))+(((r22)*(x3615)))+(((IkReal(-1.00000000000000))*(x3613)*(x3618)))+(((x3614)*(x3616))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst52)*(((((cj14)*(r20)*(x3615)))+(((IkReal(-1.00000000000000))*(x3617)*(x3618)))+(((r22)*(x3613)))+(((r22)*(x3616)))+(((IkReal(-1.00000000000000))*(x3614)*(x3615)))+(((x3614)*(x3617))))))) < IKFAST_ATAN2_MAGTHRESH )
16369     continue;
16370 j10array[0]=IKatan2(((gconst52)*(((((IkReal(-1.00000000000000))*(x3616)*(x3618)))+(((IkReal(-1.00000000000000))*(r22)*(x3617)))+(((x3613)*(x3614)))+(((r22)*(x3615)))+(((IkReal(-1.00000000000000))*(x3613)*(x3618)))+(((x3614)*(x3616)))))), ((gconst52)*(((((cj14)*(r20)*(x3615)))+(((IkReal(-1.00000000000000))*(x3617)*(x3618)))+(((r22)*(x3613)))+(((r22)*(x3616)))+(((IkReal(-1.00000000000000))*(x3614)*(x3615)))+(((x3614)*(x3617)))))));
16371 sj10array[0]=IKsin(j10array[0]);
16372 cj10array[0]=IKcos(j10array[0]);
16373 if( j10array[0] > IKPI )
16374 {
16375     j10array[0]-=IK2PI;
16376 }
16377 else if( j10array[0] < -IKPI )
16378 {    j10array[0]+=IK2PI;
16379 }
16380 j10valid[0] = true;
16381 for(int ij10 = 0; ij10 < 1; ++ij10)
16382 {
16383 if( !j10valid[ij10] )
16384 {
16385     continue;
16386 }
16387 _ij10[0] = ij10; _ij10[1] = -1;
16388 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16389 {
16390 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16391 {
16392     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16393 }
16394 }
16395 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16396 {
16397 IkReal evalcond[4];
16398 IkReal x3619=IKsin(j10);
16399 IkReal x3620=IKcos(j10);
16400 IkReal x3621=((IkReal(1.00000000000000))*(sj13));
16401 IkReal x3622=((r11)*(sj9));
16402 IkReal x3623=((cj9)*(r01));
16403 IkReal x3624=((r21)*(sj14));
16404 IkReal x3625=((cj9)*(r02));
16405 IkReal x3626=((sj13)*(sj9));
16406 IkReal x3627=((cj14)*(r10));
16407 IkReal x3628=((IkReal(1.00000000000000))*(cj13));
16408 IkReal x3629=((cj14)*(r20));
16409 IkReal x3630=((cj11)*(x3619));
16410 IkReal x3631=((sj11)*(x3620));
16411 IkReal x3632=((sj14)*(x3628));
16412 IkReal x3633=((sj11)*(x3619));
16413 IkReal x3634=((cj11)*(x3620));
16414 IkReal x3635=((cj14)*(cj9)*(r00));
16415 IkReal x3636=((x3630)+(x3631));
16416 evalcond[0]=((((cj13)*(x3624)))+(x3633)+(((IkReal(-1.00000000000000))*(x3628)*(x3629)))+(((IkReal(-1.00000000000000))*(x3634)))+(((IkReal(-1.00000000000000))*(r22)*(x3621))));
16417 evalcond[1]=((((IkReal(-1.00000000000000))*(x3621)*(x3629)))+(x3636)+(((sj13)*(x3624)))+(((cj13)*(r22))));
16418 evalcond[2]=((((cj13)*(sj9)*(x3627)))+(x3636)+(((sj13)*(x3625)))+(((r12)*(x3626)))+(((cj13)*(x3635)))+(((IkReal(-1.00000000000000))*(x3623)*(x3632)))+(((IkReal(-1.00000000000000))*(x3622)*(x3632))));
16419 evalcond[3]=((((sj13)*(x3635)))+(((x3626)*(x3627)))+(((IkReal(-1.00000000000000))*(x3625)*(x3628)))+(((IkReal(-1.00000000000000))*(sj14)*(x3621)*(x3623)))+(((IkReal(-1.00000000000000))*(sj14)*(x3621)*(x3622)))+(x3634)+(((IkReal(-1.00000000000000))*(x3633)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3628))));
16420 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16421 {
16422 continue;
16423 }
16424 }
16425 
16426 {
16427 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16428 vinfos[0].jointtype = 1;
16429 vinfos[0].foffset = j9;
16430 vinfos[0].indices[0] = _ij9[0];
16431 vinfos[0].indices[1] = _ij9[1];
16432 vinfos[0].maxsolutions = _nj9;
16433 vinfos[1].jointtype = 1;
16434 vinfos[1].foffset = j10;
16435 vinfos[1].indices[0] = _ij10[0];
16436 vinfos[1].indices[1] = _ij10[1];
16437 vinfos[1].maxsolutions = _nj10;
16438 vinfos[2].jointtype = 1;
16439 vinfos[2].foffset = j11;
16440 vinfos[2].indices[0] = _ij11[0];
16441 vinfos[2].indices[1] = _ij11[1];
16442 vinfos[2].maxsolutions = _nj11;
16443 vinfos[3].jointtype = 1;
16444 vinfos[3].foffset = j12;
16445 vinfos[3].indices[0] = _ij12[0];
16446 vinfos[3].indices[1] = _ij12[1];
16447 vinfos[3].maxsolutions = _nj12;
16448 vinfos[4].jointtype = 1;
16449 vinfos[4].foffset = j13;
16450 vinfos[4].indices[0] = _ij13[0];
16451 vinfos[4].indices[1] = _ij13[1];
16452 vinfos[4].maxsolutions = _nj13;
16453 vinfos[5].jointtype = 1;
16454 vinfos[5].foffset = j14;
16455 vinfos[5].indices[0] = _ij14[0];
16456 vinfos[5].indices[1] = _ij14[1];
16457 vinfos[5].maxsolutions = _nj14;
16458 std::vector<int> vfree(0);
16459 solutions.AddSolution(vinfos,vfree);
16460 }
16461 }
16462 }
16463 
16464 }
16465 
16466 }
16467 
16468 } else
16469 {
16470 IkReal x3637=((cj9)*(r10));
16471 IkReal x3638=((cj13)*(cj14));
16472 IkReal x3639=((sj14)*(sj9));
16473 IkReal x3640=((IkReal(1.00000000000000))*(sj14));
16474 IkReal x3641=((cj9)*(sj13));
16475 IkReal x3642=((r02)*(sj9));
16476 IkReal x3643=((cj13)*(cj9));
16477 IkReal x3644=((cj14)*(r01));
16478 IkReal x3645=((IkReal(1.00000000000000))*(npx));
16479 IkReal x3646=((cj14)*(sj13));
16480 IkReal x3647=((IkReal(1.00000000000000))*(cj9));
16481 IkReal x3648=((npy)*(sj14));
16482 IkReal x3649=((IkReal(1.00000000000000))*(sj13));
16483 IkReal x3650=((IkReal(1.00000000000000))*(cj14)*(sj9));
16484 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(j12, IkReal(6.28318530717959))));
16485 evalcond[1]=((IkReal(-0.0950000000000000))+(((cj14)*(npy)))+(((npx)*(sj14))));
16486 evalcond[2]=((((cj14)*(r21)))+(((r20)*(sj14))));
16487 evalcond[3]=((IkReal(0.235000000000000))+(((IkReal(0.0900000000000000))*(cj13)))+(((IkReal(0.250000000000000))*(cj11)))+(((IkReal(-1.00000000000000))*(npz)*(x3649)))+(((cj13)*(x3648)))+(((IkReal(-1.00000000000000))*(x3638)*(x3645))));
16488 evalcond[4]=((IkReal(-1.00000000000000))+(((sj9)*(x3644)))+(((IkReal(-1.00000000000000))*(cj14)*(r11)*(x3647)))+(((IkReal(-1.00000000000000))*(x3637)*(x3640)))+(((r00)*(x3639))));
16489 evalcond[5]=((IkReal(-0.0300000000000000))+(((IkReal(-1.00000000000000))*(x3645)*(x3646)))+(((cj13)*(npz)))+(((sj13)*(x3648)))+(((IkReal(0.0900000000000000))*(sj13)))+(((IkReal(0.250000000000000))*(sj11))));
16490 evalcond[6]=((((IkReal(-1.00000000000000))*(cj9)*(r00)*(x3640)))+(((IkReal(-1.00000000000000))*(x3644)*(x3647)))+(((IkReal(-1.00000000000000))*(r11)*(x3650)))+(((IkReal(-1.00000000000000))*(r10)*(x3639))));
16491 evalcond[7]=((((IkReal(-1.00000000000000))*(r11)*(x3640)*(x3643)))+(((r12)*(x3641)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3638)))+(((x3637)*(x3638)))+(((cj13)*(r01)*(x3639)))+(((IkReal(-1.00000000000000))*(x3642)*(x3649))));
16492 evalcond[8]=((((IkReal(-1.00000000000000))*(r11)*(x3640)*(x3641)))+(((cj13)*(x3642)))+(((x3637)*(x3646)))+(((IkReal(-1.00000000000000))*(r12)*(x3643)))+(((IkReal(-1.00000000000000))*(r00)*(sj9)*(x3646)))+(((r01)*(sj13)*(x3639))));
16493 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  )
16494 {
16495 {
16496 IkReal dummyeval[1];
16497 IkReal gconst54;
16498 gconst54=IKsign((((sj11)*(sj11))+((cj11)*(cj11))));
16499 dummyeval[0]=(((sj11)*(sj11))+((cj11)*(cj11)));
16500 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16501 {
16502 {
16503 IkReal dummyeval[1];
16504 IkReal gconst55;
16505 gconst55=IKsign(((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11))))));
16506 dummyeval[0]=((((IkReal(-1.00000000000000))*((sj11)*(sj11))))+(((IkReal(-1.00000000000000))*((cj11)*(cj11)))));
16507 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
16508 {
16509 continue;
16510 
16511 } else
16512 {
16513 {
16514 IkReal j10array[1], cj10array[1], sj10array[1];
16515 bool j10valid[1]={false};
16516 _nj10 = 1;
16517 IkReal x3651=((cj13)*(sj14));
16518 IkReal x3652=((IkReal(1.00000000000000))*(cj11));
16519 IkReal x3653=((r11)*(sj9));
16520 IkReal x3654=((cj11)*(sj13));
16521 IkReal x3655=((r12)*(sj9));
16522 IkReal x3656=((r10)*(sj9));
16523 IkReal x3657=((sj11)*(sj13));
16524 IkReal x3658=((cj9)*(r02));
16525 IkReal x3659=((IkReal(1.00000000000000))*(sj11));
16526 IkReal x3660=((cj9)*(r01));
16527 IkReal x3661=((cj9)*(r00));
16528 IkReal x3662=((cj13)*(cj14)*(sj11));
16529 IkReal x3663=((cj11)*(cj13)*(cj14));
16530 if( IKabs(((gconst55)*(((((IkReal(-1.00000000000000))*(x3651)*(x3652)*(x3653)))+(((x3656)*(x3663)))+(((IkReal(-1.00000000000000))*(r22)*(x3657)))+(((IkReal(-1.00000000000000))*(x3651)*(x3652)*(x3660)))+(((r21)*(sj11)*(x3651)))+(((x3654)*(x3658)))+(((x3654)*(x3655)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3659)))+(((x3661)*(x3663))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst55)*(((((IkReal(-1.00000000000000))*(r21)*(x3651)*(x3652)))+(((x3656)*(x3662)))+(((IkReal(-1.00000000000000))*(x3651)*(x3653)*(x3659)))+(((x3657)*(x3658)))+(((r20)*(x3663)))+(((x3655)*(x3657)))+(((IkReal(-1.00000000000000))*(x3651)*(x3659)*(x3660)))+(((x3661)*(x3662)))+(((r22)*(x3654))))))) < IKFAST_ATAN2_MAGTHRESH )
16531     continue;
16532 j10array[0]=IKatan2(((gconst55)*(((((IkReal(-1.00000000000000))*(x3651)*(x3652)*(x3653)))+(((x3656)*(x3663)))+(((IkReal(-1.00000000000000))*(r22)*(x3657)))+(((IkReal(-1.00000000000000))*(x3651)*(x3652)*(x3660)))+(((r21)*(sj11)*(x3651)))+(((x3654)*(x3658)))+(((x3654)*(x3655)))+(((IkReal(-1.00000000000000))*(cj13)*(cj14)*(r20)*(x3659)))+(((x3661)*(x3663)))))), ((gconst55)*(((((IkReal(-1.00000000000000))*(r21)*(x3651)*(x3652)))+(((x3656)*(x3662)))+(((IkReal(-1.00000000000000))*(x3651)*(x3653)*(x3659)))+(((x3657)*(x3658)))+(((r20)*(x3663)))+(((x3655)*(x3657)))+(((IkReal(-1.00000000000000))*(x3651)*(x3659)*(x3660)))+(((x3661)*(x3662)))+(((r22)*(x3654)))))));
16533 sj10array[0]=IKsin(j10array[0]);
16534 cj10array[0]=IKcos(j10array[0]);
16535 if( j10array[0] > IKPI )
16536 {
16537     j10array[0]-=IK2PI;
16538 }
16539 else if( j10array[0] < -IKPI )
16540 {    j10array[0]+=IK2PI;
16541 }
16542 j10valid[0] = true;
16543 for(int ij10 = 0; ij10 < 1; ++ij10)
16544 {
16545 if( !j10valid[ij10] )
16546 {
16547     continue;
16548 }
16549 _ij10[0] = ij10; _ij10[1] = -1;
16550 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16551 {
16552 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16553 {
16554     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16555 }
16556 }
16557 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16558 {
16559 IkReal evalcond[4];
16560 IkReal x3664=IKsin(j10);
16561 IkReal x3665=IKcos(j10);
16562 IkReal x3666=((IkReal(1.00000000000000))*(sj13));
16563 IkReal x3667=((r11)*(sj9));
16564 IkReal x3668=((cj9)*(r01));
16565 IkReal x3669=((IkReal(1.00000000000000))*(cj11));
16566 IkReal x3670=((r21)*(sj14));
16567 IkReal x3671=((cj9)*(r02));
16568 IkReal x3672=((sj13)*(sj9));
16569 IkReal x3673=((cj14)*(r10));
16570 IkReal x3674=((IkReal(1.00000000000000))*(cj13));
16571 IkReal x3675=((cj14)*(r20));
16572 IkReal x3676=((sj11)*(x3664));
16573 IkReal x3677=((sj14)*(x3674));
16574 IkReal x3678=((sj11)*(x3665));
16575 IkReal x3679=((cj14)*(cj9)*(r00));
16576 IkReal x3680=((x3665)*(x3669));
16577 evalcond[0]=((((IkReal(-1.00000000000000))*(x3680)))+(((cj13)*(x3670)))+(x3676)+(((IkReal(-1.00000000000000))*(r22)*(x3666)))+(((IkReal(-1.00000000000000))*(x3674)*(x3675))));
16578 evalcond[1]=((((IkReal(-1.00000000000000))*(x3664)*(x3669)))+(((sj13)*(x3670)))+(((IkReal(-1.00000000000000))*(x3678)))+(((IkReal(-1.00000000000000))*(x3666)*(x3675)))+(((cj13)*(r22))));
16579 evalcond[2]=((((cj13)*(sj9)*(x3673)))+(((r12)*(x3672)))+(((cj13)*(x3679)))+(x3678)+(((IkReal(-1.00000000000000))*(x3667)*(x3677)))+(((sj13)*(x3671)))+(((cj11)*(x3664)))+(((IkReal(-1.00000000000000))*(x3668)*(x3677))));
16580 evalcond[3]=((((IkReal(-1.00000000000000))*(x3671)*(x3674)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3674)))+(((IkReal(-1.00000000000000))*(x3680)))+(x3676)+(((sj13)*(x3679)))+(((IkReal(-1.00000000000000))*(sj14)*(x3666)*(x3667)))+(((IkReal(-1.00000000000000))*(sj14)*(x3666)*(x3668)))+(((x3672)*(x3673))));
16581 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16582 {
16583 continue;
16584 }
16585 }
16586 
16587 {
16588 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16589 vinfos[0].jointtype = 1;
16590 vinfos[0].foffset = j9;
16591 vinfos[0].indices[0] = _ij9[0];
16592 vinfos[0].indices[1] = _ij9[1];
16593 vinfos[0].maxsolutions = _nj9;
16594 vinfos[1].jointtype = 1;
16595 vinfos[1].foffset = j10;
16596 vinfos[1].indices[0] = _ij10[0];
16597 vinfos[1].indices[1] = _ij10[1];
16598 vinfos[1].maxsolutions = _nj10;
16599 vinfos[2].jointtype = 1;
16600 vinfos[2].foffset = j11;
16601 vinfos[2].indices[0] = _ij11[0];
16602 vinfos[2].indices[1] = _ij11[1];
16603 vinfos[2].maxsolutions = _nj11;
16604 vinfos[3].jointtype = 1;
16605 vinfos[3].foffset = j12;
16606 vinfos[3].indices[0] = _ij12[0];
16607 vinfos[3].indices[1] = _ij12[1];
16608 vinfos[3].maxsolutions = _nj12;
16609 vinfos[4].jointtype = 1;
16610 vinfos[4].foffset = j13;
16611 vinfos[4].indices[0] = _ij13[0];
16612 vinfos[4].indices[1] = _ij13[1];
16613 vinfos[4].maxsolutions = _nj13;
16614 vinfos[5].jointtype = 1;
16615 vinfos[5].foffset = j14;
16616 vinfos[5].indices[0] = _ij14[0];
16617 vinfos[5].indices[1] = _ij14[1];
16618 vinfos[5].maxsolutions = _nj14;
16619 std::vector<int> vfree(0);
16620 solutions.AddSolution(vinfos,vfree);
16621 }
16622 }
16623 }
16624 
16625 }
16626 
16627 }
16628 
16629 } else
16630 {
16631 {
16632 IkReal j10array[1], cj10array[1], sj10array[1];
16633 bool j10valid[1]={false};
16634 _nj10 = 1;
16635 IkReal x3681=((r22)*(sj11));
16636 IkReal x3682=((IkReal(1.00000000000000))*(sj11));
16637 IkReal x3683=((IkReal(1.00000000000000))*(cj11));
16638 IkReal x3684=((cj14)*(r20));
16639 IkReal x3685=((cj13)*(r21)*(sj14));
16640 IkReal x3686=((r21)*(sj13)*(sj14));
16641 if( IKabs(((gconst54)*(((((cj11)*(x3686)))+(((IkReal(-1.00000000000000))*(x3682)*(x3685)))+(((cj11)*(cj13)*(r22)))+(((sj13)*(x3681)))+(((IkReal(-1.00000000000000))*(sj13)*(x3683)*(x3684)))+(((cj13)*(sj11)*(x3684))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst54)*(((((cj11)*(x3685)))+(((cj13)*(x3681)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3683)))+(((sj11)*(x3686)))+(((IkReal(-1.00000000000000))*(cj13)*(x3683)*(x3684)))+(((IkReal(-1.00000000000000))*(sj13)*(x3682)*(x3684))))))) < IKFAST_ATAN2_MAGTHRESH )
16642     continue;
16643 j10array[0]=IKatan2(((gconst54)*(((((cj11)*(x3686)))+(((IkReal(-1.00000000000000))*(x3682)*(x3685)))+(((cj11)*(cj13)*(r22)))+(((sj13)*(x3681)))+(((IkReal(-1.00000000000000))*(sj13)*(x3683)*(x3684)))+(((cj13)*(sj11)*(x3684)))))), ((gconst54)*(((((cj11)*(x3685)))+(((cj13)*(x3681)))+(((IkReal(-1.00000000000000))*(r22)*(sj13)*(x3683)))+(((sj11)*(x3686)))+(((IkReal(-1.00000000000000))*(cj13)*(x3683)*(x3684)))+(((IkReal(-1.00000000000000))*(sj13)*(x3682)*(x3684)))))));
16644 sj10array[0]=IKsin(j10array[0]);
16645 cj10array[0]=IKcos(j10array[0]);
16646 if( j10array[0] > IKPI )
16647 {
16648     j10array[0]-=IK2PI;
16649 }
16650 else if( j10array[0] < -IKPI )
16651 {    j10array[0]+=IK2PI;
16652 }
16653 j10valid[0] = true;
16654 for(int ij10 = 0; ij10 < 1; ++ij10)
16655 {
16656 if( !j10valid[ij10] )
16657 {
16658     continue;
16659 }
16660 _ij10[0] = ij10; _ij10[1] = -1;
16661 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16662 {
16663 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16664 {
16665     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16666 }
16667 }
16668 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16669 {
16670 IkReal evalcond[4];
16671 IkReal x3687=IKsin(j10);
16672 IkReal x3688=IKcos(j10);
16673 IkReal x3689=((IkReal(1.00000000000000))*(sj13));
16674 IkReal x3690=((r11)*(sj9));
16675 IkReal x3691=((cj9)*(r01));
16676 IkReal x3692=((IkReal(1.00000000000000))*(cj11));
16677 IkReal x3693=((r21)*(sj14));
16678 IkReal x3694=((cj9)*(r02));
16679 IkReal x3695=((sj13)*(sj9));
16680 IkReal x3696=((cj14)*(r10));
16681 IkReal x3697=((IkReal(1.00000000000000))*(cj13));
16682 IkReal x3698=((cj14)*(r20));
16683 IkReal x3699=((sj11)*(x3687));
16684 IkReal x3700=((sj14)*(x3697));
16685 IkReal x3701=((sj11)*(x3688));
16686 IkReal x3702=((cj14)*(cj9)*(r00));
16687 IkReal x3703=((x3688)*(x3692));
16688 evalcond[0]=((((IkReal(-1.00000000000000))*(r22)*(x3689)))+(((IkReal(-1.00000000000000))*(x3703)))+(x3699)+(((IkReal(-1.00000000000000))*(x3697)*(x3698)))+(((cj13)*(x3693))));
16689 evalcond[1]=((((IkReal(-1.00000000000000))*(x3689)*(x3698)))+(((sj13)*(x3693)))+(((IkReal(-1.00000000000000))*(x3687)*(x3692)))+(((IkReal(-1.00000000000000))*(x3701)))+(((cj13)*(r22))));
16690 evalcond[2]=((((cj11)*(x3687)))+(((cj13)*(x3702)))+(((sj13)*(x3694)))+(((IkReal(-1.00000000000000))*(x3690)*(x3700)))+(x3701)+(((IkReal(-1.00000000000000))*(x3691)*(x3700)))+(((cj13)*(sj9)*(x3696)))+(((r12)*(x3695))));
16691 evalcond[3]=((((sj13)*(x3702)))+(((x3695)*(x3696)))+(((IkReal(-1.00000000000000))*(sj14)*(x3689)*(x3691)))+(((IkReal(-1.00000000000000))*(sj14)*(x3689)*(x3690)))+(((IkReal(-1.00000000000000))*(x3703)))+(x3699)+(((IkReal(-1.00000000000000))*(x3694)*(x3697)))+(((IkReal(-1.00000000000000))*(r12)*(sj9)*(x3697))));
16692 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
16693 {
16694 continue;
16695 }
16696 }
16697 
16698 {
16699 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16700 vinfos[0].jointtype = 1;
16701 vinfos[0].foffset = j9;
16702 vinfos[0].indices[0] = _ij9[0];
16703 vinfos[0].indices[1] = _ij9[1];
16704 vinfos[0].maxsolutions = _nj9;
16705 vinfos[1].jointtype = 1;
16706 vinfos[1].foffset = j10;
16707 vinfos[1].indices[0] = _ij10[0];
16708 vinfos[1].indices[1] = _ij10[1];
16709 vinfos[1].maxsolutions = _nj10;
16710 vinfos[2].jointtype = 1;
16711 vinfos[2].foffset = j11;
16712 vinfos[2].indices[0] = _ij11[0];
16713 vinfos[2].indices[1] = _ij11[1];
16714 vinfos[2].maxsolutions = _nj11;
16715 vinfos[3].jointtype = 1;
16716 vinfos[3].foffset = j12;
16717 vinfos[3].indices[0] = _ij12[0];
16718 vinfos[3].indices[1] = _ij12[1];
16719 vinfos[3].maxsolutions = _nj12;
16720 vinfos[4].jointtype = 1;
16721 vinfos[4].foffset = j13;
16722 vinfos[4].indices[0] = _ij13[0];
16723 vinfos[4].indices[1] = _ij13[1];
16724 vinfos[4].maxsolutions = _nj13;
16725 vinfos[5].jointtype = 1;
16726 vinfos[5].foffset = j14;
16727 vinfos[5].indices[0] = _ij14[0];
16728 vinfos[5].indices[1] = _ij14[1];
16729 vinfos[5].maxsolutions = _nj14;
16730 std::vector<int> vfree(0);
16731 solutions.AddSolution(vinfos,vfree);
16732 }
16733 }
16734 }
16735 
16736 }
16737 
16738 }
16739 
16740 } else
16741 {
16742 if( 1 )
16743 {
16744 continue;
16745 
16746 } else
16747 {
16748 }
16749 }
16750 }
16751 }
16752 }
16753 }
16754 
16755 } else
16756 {
16757 {
16758 IkReal j10array[1], cj10array[1], sj10array[1];
16759 bool j10valid[1]={false};
16760 _nj10 = 1;
16761 IkReal x3704=((r21)*(sj14));
16762 IkReal x3705=((cj12)*(cj13));
16763 IkReal x3706=((sj11)*(sj13));
16764 IkReal x3707=((cj14)*(r20));
16765 IkReal x3708=((IkReal(1.00000000000000))*(sj11));
16766 IkReal x3709=((cj12)*(r22));
16767 IkReal x3710=((IkReal(1.00000000000000))*(cj11));
16768 IkReal x3711=((cj13)*(r22));
16769 IkReal x3712=((sj13)*(x3710));
16770 if( IKabs(((gconst47)*(((((IkReal(-1.00000000000000))*(x3704)*(x3712)))+(((IkReal(-1.00000000000000))*(x3710)*(x3711)))+(((cj11)*(sj13)*(x3707)))+(((IkReal(-1.00000000000000))*(x3704)*(x3705)*(x3708)))+(((sj11)*(x3705)*(x3707)))+(((x3706)*(x3709))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst47)*(((((cj11)*(x3704)*(x3705)))+(((IkReal(-1.00000000000000))*(x3705)*(x3707)*(x3710)))+(((IkReal(-1.00000000000000))*(x3709)*(x3712)))+(((IkReal(-1.00000000000000))*(x3708)*(x3711)))+(((IkReal(-1.00000000000000))*(x3704)*(x3706)))+(((x3706)*(x3707))))))) < IKFAST_ATAN2_MAGTHRESH )
16771     continue;
16772 j10array[0]=IKatan2(((gconst47)*(((((IkReal(-1.00000000000000))*(x3704)*(x3712)))+(((IkReal(-1.00000000000000))*(x3710)*(x3711)))+(((cj11)*(sj13)*(x3707)))+(((IkReal(-1.00000000000000))*(x3704)*(x3705)*(x3708)))+(((sj11)*(x3705)*(x3707)))+(((x3706)*(x3709)))))), ((gconst47)*(((((cj11)*(x3704)*(x3705)))+(((IkReal(-1.00000000000000))*(x3705)*(x3707)*(x3710)))+(((IkReal(-1.00000000000000))*(x3709)*(x3712)))+(((IkReal(-1.00000000000000))*(x3708)*(x3711)))+(((IkReal(-1.00000000000000))*(x3704)*(x3706)))+(((x3706)*(x3707)))))));
16773 sj10array[0]=IKsin(j10array[0]);
16774 cj10array[0]=IKcos(j10array[0]);
16775 if( j10array[0] > IKPI )
16776 {
16777     j10array[0]-=IK2PI;
16778 }
16779 else if( j10array[0] < -IKPI )
16780 {    j10array[0]+=IK2PI;
16781 }
16782 j10valid[0] = true;
16783 for(int ij10 = 0; ij10 < 1; ++ij10)
16784 {
16785 if( !j10valid[ij10] )
16786 {
16787     continue;
16788 }
16789 _ij10[0] = ij10; _ij10[1] = -1;
16790 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16791 {
16792 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16793 {
16794     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16795 }
16796 }
16797 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16798 {
16799 IkReal evalcond[6];
16800 IkReal x3713=IKsin(j10);
16801 IkReal x3714=IKcos(j10);
16802 IkReal x3715=((IkReal(1.00000000000000))*(cj13));
16803 IkReal x3716=((cj9)*(r02));
16804 IkReal x3717=((IkReal(1.00000000000000))*(sj13));
16805 IkReal x3718=((r11)*(sj9));
16806 IkReal x3719=((IkReal(1.00000000000000))*(cj14));
16807 IkReal x3720=((cj9)*(r01));
16808 IkReal x3721=((r21)*(sj14));
16809 IkReal x3722=((IkReal(1.00000000000000))*(sj12));
16810 IkReal x3723=((r10)*(sj9));
16811 IkReal x3724=((cj14)*(sj13));
16812 IkReal x3725=((cj14)*(r20));
16813 IkReal x3726=((IkReal(1.00000000000000))*(sj14));
16814 IkReal x3727=((r12)*(sj9));
16815 IkReal x3728=((cj13)*(cj14));
16816 IkReal x3729=((cj9)*(r00));
16817 IkReal x3730=((sj11)*(x3713));
16818 IkReal x3731=((cj11)*(x3713));
16819 IkReal x3732=((sj11)*(x3714));
16820 IkReal x3733=((cj11)*(x3714));
16821 evalcond[0]=((((cj14)*(r21)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x3722)*(x3731)))+(((IkReal(-1.00000000000000))*(x3722)*(x3732))));
16822 evalcond[1]=((((cj13)*(x3721)))+(x3730)+(((IkReal(-1.00000000000000))*(x3733)))+(((IkReal(-1.00000000000000))*(r22)*(x3717)))+(((IkReal(-1.00000000000000))*(x3715)*(x3725))));
16823 evalcond[2]=((((sj13)*(x3721)))+(((cj13)*(r22)))+(((IkReal(-1.00000000000000))*(x3717)*(x3725)))+(((cj12)*(x3731)))+(((cj12)*(x3732))));
16824 evalcond[3]=((((IkReal(-1.00000000000000))*(x3726)*(x3729)))+(((IkReal(-1.00000000000000))*(x3723)*(x3726)))+(((IkReal(-1.00000000000000))*(x3719)*(x3720)))+(((IkReal(-1.00000000000000))*(x3722)*(x3733)))+(((sj12)*(x3730)))+(((IkReal(-1.00000000000000))*(x3718)*(x3719))));
16825 evalcond[4]=((x3732)+(x3731)+(((IkReal(-1.00000000000000))*(sj14)*(x3715)*(x3718)))+(((IkReal(-1.00000000000000))*(sj14)*(x3715)*(x3720)))+(((x3723)*(x3728)))+(((sj13)*(x3727)))+(((x3728)*(x3729)))+(((sj13)*(x3716))));
16826 evalcond[5]=((((IkReal(-1.00000000000000))*(x3715)*(x3716)))+(((x3724)*(x3729)))+(((IkReal(-1.00000000000000))*(sj14)*(x3717)*(x3720)))+(((IkReal(-1.00000000000000))*(cj12)*(x3730)))+(((IkReal(-1.00000000000000))*(sj14)*(x3717)*(x3718)))+(((x3723)*(x3724)))+(((cj12)*(x3733)))+(((IkReal(-1.00000000000000))*(x3715)*(x3727))));
16827 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  )
16828 {
16829 continue;
16830 }
16831 }
16832 
16833 {
16834 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16835 vinfos[0].jointtype = 1;
16836 vinfos[0].foffset = j9;
16837 vinfos[0].indices[0] = _ij9[0];
16838 vinfos[0].indices[1] = _ij9[1];
16839 vinfos[0].maxsolutions = _nj9;
16840 vinfos[1].jointtype = 1;
16841 vinfos[1].foffset = j10;
16842 vinfos[1].indices[0] = _ij10[0];
16843 vinfos[1].indices[1] = _ij10[1];
16844 vinfos[1].maxsolutions = _nj10;
16845 vinfos[2].jointtype = 1;
16846 vinfos[2].foffset = j11;
16847 vinfos[2].indices[0] = _ij11[0];
16848 vinfos[2].indices[1] = _ij11[1];
16849 vinfos[2].maxsolutions = _nj11;
16850 vinfos[3].jointtype = 1;
16851 vinfos[3].foffset = j12;
16852 vinfos[3].indices[0] = _ij12[0];
16853 vinfos[3].indices[1] = _ij12[1];
16854 vinfos[3].maxsolutions = _nj12;
16855 vinfos[4].jointtype = 1;
16856 vinfos[4].foffset = j13;
16857 vinfos[4].indices[0] = _ij13[0];
16858 vinfos[4].indices[1] = _ij13[1];
16859 vinfos[4].maxsolutions = _nj13;
16860 vinfos[5].jointtype = 1;
16861 vinfos[5].foffset = j14;
16862 vinfos[5].indices[0] = _ij14[0];
16863 vinfos[5].indices[1] = _ij14[1];
16864 vinfos[5].maxsolutions = _nj14;
16865 std::vector<int> vfree(0);
16866 solutions.AddSolution(vinfos,vfree);
16867 }
16868 }
16869 }
16870 
16871 }
16872 
16873 }
16874 
16875 } else
16876 {
16877 {
16878 IkReal j10array[1], cj10array[1], sj10array[1];
16879 bool j10valid[1]={false};
16880 _nj10 = 1;
16881 IkReal x3734=((cj11)*(sj12));
16882 IkReal x3735=((r22)*(sj13));
16883 IkReal x3736=((r20)*(sj14));
16884 IkReal x3737=((cj14)*(sj11));
16885 IkReal x3738=((cj13)*(r20));
16886 IkReal x3739=((sj11)*(sj12));
16887 IkReal x3740=((cj13)*(r21)*(sj14));
16888 if( IKabs(((gconst46)*(((((cj11)*(cj14)*(r21)))+(((x3735)*(x3739)))+(((cj11)*(x3736)))+(((sj12)*(x3737)*(x3738)))+(((IkReal(-1.00000000000000))*(x3739)*(x3740))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst46)*(((((sj11)*(x3736)))+(((x3734)*(x3740)))+(((IkReal(-1.00000000000000))*(x3734)*(x3735)))+(((IkReal(-1.00000000000000))*(cj14)*(x3734)*(x3738)))+(((r21)*(x3737))))))) < IKFAST_ATAN2_MAGTHRESH )
16889     continue;
16890 j10array[0]=IKatan2(((gconst46)*(((((cj11)*(cj14)*(r21)))+(((x3735)*(x3739)))+(((cj11)*(x3736)))+(((sj12)*(x3737)*(x3738)))+(((IkReal(-1.00000000000000))*(x3739)*(x3740)))))), ((gconst46)*(((((sj11)*(x3736)))+(((x3734)*(x3740)))+(((IkReal(-1.00000000000000))*(x3734)*(x3735)))+(((IkReal(-1.00000000000000))*(cj14)*(x3734)*(x3738)))+(((r21)*(x3737)))))));
16891 sj10array[0]=IKsin(j10array[0]);
16892 cj10array[0]=IKcos(j10array[0]);
16893 if( j10array[0] > IKPI )
16894 {
16895     j10array[0]-=IK2PI;
16896 }
16897 else if( j10array[0] < -IKPI )
16898 {    j10array[0]+=IK2PI;
16899 }
16900 j10valid[0] = true;
16901 for(int ij10 = 0; ij10 < 1; ++ij10)
16902 {
16903 if( !j10valid[ij10] )
16904 {
16905     continue;
16906 }
16907 _ij10[0] = ij10; _ij10[1] = -1;
16908 for(int iij10 = ij10+1; iij10 < 1; ++iij10)
16909 {
16910 if( j10valid[iij10] && IKabs(cj10array[ij10]-cj10array[iij10]) < IKFAST_SOLUTION_THRESH && IKabs(sj10array[ij10]-sj10array[iij10]) < IKFAST_SOLUTION_THRESH )
16911 {
16912     j10valid[iij10]=false; _ij10[1] = iij10; break; 
16913 }
16914 }
16915 j10 = j10array[ij10]; cj10 = cj10array[ij10]; sj10 = sj10array[ij10];
16916 {
16917 IkReal evalcond[6];
16918 IkReal x3741=IKsin(j10);
16919 IkReal x3742=IKcos(j10);
16920 IkReal x3743=((IkReal(1.00000000000000))*(cj13));
16921 IkReal x3744=((cj9)*(r02));
16922 IkReal x3745=((IkReal(1.00000000000000))*(sj13));
16923 IkReal x3746=((r11)*(sj9));
16924 IkReal x3747=((IkReal(1.00000000000000))*(cj14));
16925 IkReal x3748=((cj9)*(r01));
16926 IkReal x3749=((r21)*(sj14));
16927 IkReal x3750=((IkReal(1.00000000000000))*(sj12));
16928 IkReal x3751=((r10)*(sj9));
16929 IkReal x3752=((cj14)*(sj13));
16930 IkReal x3753=((cj14)*(r20));
16931 IkReal x3754=((IkReal(1.00000000000000))*(sj14));
16932 IkReal x3755=((r12)*(sj9));
16933 IkReal x3756=((cj13)*(cj14));
16934 IkReal x3757=((cj9)*(r00));
16935 IkReal x3758=((sj11)*(x3741));
16936 IkReal x3759=((cj11)*(x3741));
16937 IkReal x3760=((sj11)*(x3742));
16938 IkReal x3761=((cj11)*(x3742));
16939 evalcond[0]=((((cj14)*(r21)))+(((IkReal(-1.00000000000000))*(x3750)*(x3759)))+(((r20)*(sj14)))+(((IkReal(-1.00000000000000))*(x3750)*(x3760))));
16940 evalcond[1]=((((cj13)*(x3749)))+(((IkReal(-1.00000000000000))*(r22)*(x3745)))+(((IkReal(-1.00000000000000))*(x3743)*(x3753)))+(((IkReal(-1.00000000000000))*(x3761)))+(x3758));
16941 evalcond[2]=((((cj12)*(x3759)))+(((IkReal(-1.00000000000000))*(x3745)*(x3753)))+(((cj12)*(x3760)))+(((sj13)*(x3749)))+(((cj13)*(r22))));
16942 evalcond[3]=((((IkReal(-1.00000000000000))*(x3746)*(x3747)))+(((IkReal(-1.00000000000000))*(x3747)*(x3748)))+(((IkReal(-1.00000000000000))*(x3754)*(x3757)))+(((IkReal(-1.00000000000000))*(x3751)*(x3754)))+(((IkReal(-1.00000000000000))*(x3750)*(x3761)))+(((sj12)*(x3758))));
16943 evalcond[4]=((((x3751)*(x3756)))+(((IkReal(-1.00000000000000))*(sj14)*(x3743)*(x3746)))+(((IkReal(-1.00000000000000))*(sj14)*(x3743)*(x3748)))+(x3760)+(x3759)+(((x3756)*(x3757)))+(((sj13)*(x3755)))+(((sj13)*(x3744))));
16944 evalcond[5]=((((IkReal(-1.00000000000000))*(x3743)*(x3755)))+(((x3751)*(x3752)))+(((IkReal(-1.00000000000000))*(x3743)*(x3744)))+(((IkReal(-1.00000000000000))*(sj14)*(x3745)*(x3746)))+(((IkReal(-1.00000000000000))*(sj14)*(x3745)*(x3748)))+(((x3752)*(x3757)))+(((IkReal(-1.00000000000000))*(cj12)*(x3758)))+(((cj12)*(x3761))));
16945 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  )
16946 {
16947 continue;
16948 }
16949 }
16950 
16951 {
16952 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6);
16953 vinfos[0].jointtype = 1;
16954 vinfos[0].foffset = j9;
16955 vinfos[0].indices[0] = _ij9[0];
16956 vinfos[0].indices[1] = _ij9[1];
16957 vinfos[0].maxsolutions = _nj9;
16958 vinfos[1].jointtype = 1;
16959 vinfos[1].foffset = j10;
16960 vinfos[1].indices[0] = _ij10[0];
16961 vinfos[1].indices[1] = _ij10[1];
16962 vinfos[1].maxsolutions = _nj10;
16963 vinfos[2].jointtype = 1;
16964 vinfos[2].foffset = j11;
16965 vinfos[2].indices[0] = _ij11[0];
16966 vinfos[2].indices[1] = _ij11[1];
16967 vinfos[2].maxsolutions = _nj11;
16968 vinfos[3].jointtype = 1;
16969 vinfos[3].foffset = j12;
16970 vinfos[3].indices[0] = _ij12[0];
16971 vinfos[3].indices[1] = _ij12[1];
16972 vinfos[3].maxsolutions = _nj12;
16973 vinfos[4].jointtype = 1;
16974 vinfos[4].foffset = j13;
16975 vinfos[4].indices[0] = _ij13[0];
16976 vinfos[4].indices[1] = _ij13[1];
16977 vinfos[4].maxsolutions = _nj13;
16978 vinfos[5].jointtype = 1;
16979 vinfos[5].foffset = j14;
16980 vinfos[5].indices[0] = _ij14[0];
16981 vinfos[5].indices[1] = _ij14[1];
16982 vinfos[5].maxsolutions = _nj14;
16983 std::vector<int> vfree(0);
16984 solutions.AddSolution(vinfos,vfree);
16985 }
16986 }
16987 }
16988 
16989 }
16990 
16991 }
16992 }
16993 }
16994 
16995 }
16996 
16997 }
16998 }
16999 }
17000 
17001 }
17002 
17003 }
17004     }
17005 }
17006 return solutions.GetNumSolutions()>0;
17007 }
17008 
17009 static inline bool checkconsistency8(const IkReal* Breal)
17010 {
17011     IkReal norm = 0.1;
17012     for(int i = 0; i < 7; ++i) {
17013         norm += IKabs(Breal[i]);
17014     }
17015     IkReal tol = 1e-5*norm; // have to increase the threshold since many computations are involved
17016     return IKabs(Breal[0]*Breal[1]-Breal[2]) < tol && IKabs(Breal[1]*Breal[1]-Breal[3]) < tol && IKabs(Breal[0]*Breal[3]-Breal[4]) < tol && IKabs(Breal[1]*Breal[3]-Breal[5]) < tol && IKabs(Breal[0]*Breal[5]-Breal[6]) < tol;
17017 }
17021 static inline void solvedialyticpoly8qep(const IkReal* matcoeffs, IkReal* rawroots, int& numroots)
17022 {
17023     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
17024     IkReal IKFAST_ALIGNED16(M[16*16]) = {0};
17025     IkReal IKFAST_ALIGNED16(A[8*8]);
17026     IkReal IKFAST_ALIGNED16(work[16*16*15]);
17027     int ipiv[8];
17028     int info, coeffindex;
17029     const int worksize=16*16*15;
17030     const int matrixdim = 8;
17031     const int matrixdim2 = 16;
17032     numroots = 0;
17033     // first setup M = [0 I; -C -B] and A
17034     coeffindex = 0;
17035     for(int j = 0; j < 4; ++j) {
17036         for(int k = 0; k < 6; ++k) {
17037             M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -matcoeffs[coeffindex++];
17038         }
17039     }
17040     for(int j = 0; j < 4; ++j) {
17041         for(int k = 0; k < 6; ++k) {
17042             M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -matcoeffs[coeffindex++];
17043         }
17044     }
17045     for(int j = 0; j < 4; ++j) {
17046         for(int k = 0; k < 6; ++k) {
17047             A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = matcoeffs[coeffindex++];
17048         }
17049         for(int k = 0; k < 2; ++k) {
17050             A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
17051         }
17052     }
17053     const IkReal lfpossibilities[4][4] = {{1,-1,1,1},{1,0,-2,1},{1,1,2,0},{1,-1,4,1}};
17054     int lfindex = -1;
17055     bool bsingular = true;
17056     do {
17057         dgetrf_(&matrixdim,&matrixdim,A,&matrixdim,&ipiv[0],&info);
17058         if( info == 0 ) {
17059             bsingular = false;
17060             for(int j = 0; j < matrixdim; ++j) {
17061                 if( IKabs(A[j*matrixdim+j]) < 100*tol ) {
17062                     bsingular = true;
17063                     break;
17064                 }
17065             }
17066             if( !bsingular ) {
17067                 break;
17068             }
17069         }
17070         if( lfindex == 3 ) {
17071             break;
17072         }
17073         // transform by the linear functional
17074         lfindex++;
17075         const IkReal* lf = lfpossibilities[lfindex];
17076         // have to reinitialize A
17077         coeffindex = 0;
17078         for(int j = 0; j < 4; ++j) {
17079             for(int k = 0; k < 6; ++k) {
17080                 IkReal a = matcoeffs[coeffindex+48], b = matcoeffs[coeffindex+24], c = matcoeffs[coeffindex];
17081                 A[(j+4)+matrixdim*k] = A[j+matrixdim*(k+2)] = lf[0]*lf[0]*a+lf[0]*lf[2]*b+lf[2]*lf[2]*c;
17082                 M[matrixdim+(j+4)+2*matrixdim*k] = M[matrixdim+j+2*matrixdim*(k+2)] = -(lf[1]*lf[1]*a + lf[1]*lf[3]*b + lf[3]*lf[3]*c);
17083                 M[matrixdim+(j+4)+2*matrixdim*k+matrixdim*2*matrixdim] = M[matrixdim+j+2*matrixdim*(k+2)+matrixdim*2*matrixdim] = -(2*lf[0]*lf[1]*a + (lf[0]*lf[3]+lf[1]*lf[2])*b + 2*lf[2]*lf[3]*c);
17084                 coeffindex++;
17085             }
17086             for(int k = 0; k < 2; ++k) {
17087                 A[j+matrixdim*k] = A[(j+4)+matrixdim*(k+6)] = 0;
17088             }
17089         }
17090     } while(lfindex<4);
17091 
17092     if( bsingular ) {
17093         return;
17094     }
17095     dgetrs_("No transpose", &matrixdim, &matrixdim2, A, &matrixdim, &ipiv[0], &M[matrixdim], &matrixdim2, &info);
17096     if( info != 0 ) {
17097         return;
17098     }
17099 
17100     // set identity in upper corner
17101     for(int j = 0; j < matrixdim; ++j) {
17102         M[matrixdim*2*matrixdim+j+matrixdim*2*j] = 1;
17103     }
17104     IkReal IKFAST_ALIGNED16(wr[16]);
17105     IkReal IKFAST_ALIGNED16(wi[16]);
17106     IkReal IKFAST_ALIGNED16(vr[16*16]);
17107     int one=1;
17108     dgeev_("N", "V", &matrixdim2, M, &matrixdim2, wr, wi,NULL, &one, vr, &matrixdim2, work, &worksize, &info);
17109     if( info != 0 ) {
17110         return;
17111     }
17112     IkReal Breal[matrixdim-1];
17113     for(int i = 0; i < matrixdim2; ++i) {
17114         if( IKabs(wi[i]) < tol*100 ) {
17115             IkReal* ev = vr+matrixdim2*i;
17116             if( IKabs(wr[i]) > 1 ) {
17117                 ev += matrixdim;
17118             }
17119             // consistency has to be checked!!
17120             if( IKabs(ev[0]) < tol ) {
17121                 continue;
17122             }
17123             IkReal iconst = 1/ev[0];
17124             for(int j = 1; j < matrixdim; ++j) {
17125                 Breal[j-1] = ev[j]*iconst;
17126             }
17127             if( checkconsistency8(Breal) ) {
17128                 if( lfindex >= 0 ) {
17129                     const IkReal* lf = lfpossibilities[lfindex];
17130                     rawroots[numroots++] = (wr[i]*lf[0]+lf[1])/(wr[i]*lf[2]+lf[3]);
17131                 }
17132                 else {
17133                     rawroots[numroots++] = wr[i];
17134                 }
17135                 bool bsmall0=IKabs(ev[0]) > IKabs(ev[2]);
17136                 bool bsmall1=IKabs(ev[0]) > IKabs(ev[1]);
17137                 if( bsmall0 && bsmall1 ) {
17138                     rawroots[numroots++] = ev[2]/ev[0];
17139                     rawroots[numroots++] = ev[1]/ev[0];
17140                 }
17141                 else if( bsmall0 && !bsmall1 ) {
17142                     rawroots[numroots++] = ev[3]/ev[1];
17143                     rawroots[numroots++] = ev[1]/ev[0];
17144                 }
17145                 else if( !bsmall0 && bsmall1 ) {
17146                     rawroots[numroots++] = ev[6]/ev[4];
17147                     rawroots[numroots++] = ev[7]/ev[6];
17148                 }
17149                 else if( !bsmall0 && !bsmall1 ) {
17150                     rawroots[numroots++] = ev[7]/ev[5];
17151                     rawroots[numroots++] = ev[7]/ev[6];
17152                 }
17153             }
17154         }
17155     }
17156 }};
17157 
17158 
17161 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
17162 IKSolver solver;
17163 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
17164 }
17165 
17166 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - NextageOpen (53b6c6feea19292c552a263dfc45aa26)>"; }
17167 
17168 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
17169 
17170 #ifdef IKFAST_NAMESPACE
17171 } // end namespace
17172 #endif
17173 
17174 #ifndef IKFAST_NO_MAIN
17175 #include <stdio.h>
17176 #include <stdlib.h>
17177 #ifdef IKFAST_NAMESPACE
17178 using namespace IKFAST_NAMESPACE;
17179 #endif
17180 int main(int argc, char** argv)
17181 {
17182     if( argc != 12+GetNumFreeParameters()+1 ) {
17183         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
17184                "Returns the ik solutions given the transformation of the end effector specified by\n"
17185                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
17186                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
17187         return 1;
17188     }
17189 
17190     IkSolutionList<IkReal> solutions;
17191     std::vector<IkReal> vfree(GetNumFreeParameters());
17192     IkReal eerot[9],eetrans[3];
17193     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
17194     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
17195     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
17196     for(std::size_t i = 0; i < vfree.size(); ++i)
17197         vfree[i] = atof(argv[13+i]);
17198     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
17199 
17200     if( !bSuccess ) {
17201         fprintf(stderr,"Failed to get ik solution\n");
17202         return -1;
17203     }
17204 
17205     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
17206     std::vector<IkReal> solvalues(GetNumJoints());
17207     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
17208         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
17209         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
17210         std::vector<IkReal> vsolfree(sol.GetFree().size());
17211         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
17212         for( std::size_t j = 0; j < solvalues.size(); ++j)
17213             printf("%.15f, ", solvalues[j]);
17214         printf("\n");
17215     }
17216     return 0;
17217 }
17218 
17219 #endif


nextage_ik_plugin
Author(s): TORK Developer 534o <534o@opensouce-robotics.tokyo.jp>
autogenerated on Wed May 15 2019 04:45:06