fanuc_lrmate200ic5h_manipulator_ikfast_solver.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 #define IKFAST_HAS_LIBRARY
00021 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
00022 using namespace ikfast;
00023 
00024 // check if the included ikfast version matches what this file was compiled with
00025 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
00026 IKFAST_COMPILE_ASSERT(IKFAST_VERSION==61);
00027 
00028 #include <cmath>
00029 #include <vector>
00030 #include <limits>
00031 #include <algorithm>
00032 #include <complex>
00033 
00034 #define IKFAST_STRINGIZE2(s) #s
00035 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
00036 
00037 #ifndef IKFAST_ASSERT
00038 #include <stdexcept>
00039 #include <sstream>
00040 #include <iostream>
00041 
00042 #ifdef _MSC_VER
00043 #ifndef __PRETTY_FUNCTION__
00044 #define __PRETTY_FUNCTION__ __FUNCDNAME__
00045 #endif
00046 #endif
00047 
00048 #ifndef __PRETTY_FUNCTION__
00049 #define __PRETTY_FUNCTION__ __func__
00050 #endif
00051 
00052 #define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } }
00053 
00054 #endif
00055 
00056 #if defined(_MSC_VER)
00057 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
00058 #else
00059 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
00060 #endif
00061 
00062 #define IK2PI  ((IkReal)6.28318530717959)
00063 #define IKPI  ((IkReal)3.14159265358979)
00064 #define IKPI_2  ((IkReal)1.57079632679490)
00065 
00066 #ifdef _MSC_VER
00067 #ifndef isnan
00068 #define isnan _isnan
00069 #endif
00070 #endif // _MSC_VER
00071 
00072 // lapack routines
00073 extern "C" {
00074   void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
00075   void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
00076   void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
00077   void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
00078   void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info);
00079   void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info);
00080 }
00081 
00082 using namespace std; // necessary to get std math routines
00083 
00084 #ifdef IKFAST_NAMESPACE
00085 namespace IKFAST_NAMESPACE {
00086 #endif
00087 
00088 inline float IKabs(float f) { return fabsf(f); }
00089 inline double IKabs(double f) { return fabs(f); }
00090 
00091 inline float IKsqr(float f) { return f*f; }
00092 inline double IKsqr(double f) { return f*f; }
00093 
00094 inline float IKlog(float f) { return logf(f); }
00095 inline double IKlog(double f) { return log(f); }
00096 
00097 // allows asin and acos to exceed 1
00098 #ifndef IKFAST_SINCOS_THRESH
00099 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
00100 #endif
00101 
00102 // used to check input to atan2 for degenerate cases
00103 #ifndef IKFAST_ATAN2_MAGTHRESH
00104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
00105 #endif
00106 
00107 // minimum distance of separate solutions
00108 #ifndef IKFAST_SOLUTION_THRESH
00109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
00110 #endif
00111 
00112 inline float IKasin(float f)
00113 {
00114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00115 if( f <= -1 ) return float(-IKPI_2);
00116 else if( f >= 1 ) return float(IKPI_2);
00117 return asinf(f);
00118 }
00119 inline double IKasin(double f)
00120 {
00121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00122 if( f <= -1 ) return -IKPI_2;
00123 else if( f >= 1 ) return IKPI_2;
00124 return asin(f);
00125 }
00126 
00127 // return positive value in [0,y)
00128 inline float IKfmod(float x, float y)
00129 {
00130     while(x < 0) {
00131         x += y;
00132     }
00133     return fmodf(x,y);
00134 }
00135 
00136 // return positive value in [0,y)
00137 inline double IKfmod(double x, double y)
00138 {
00139     while(x < 0) {
00140         x += y;
00141     }
00142     return fmod(x,y);
00143 }
00144 
00145 inline float IKacos(float f)
00146 {
00147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00148 if( f <= -1 ) return float(IKPI);
00149 else if( f >= 1 ) return float(0);
00150 return acosf(f);
00151 }
00152 inline double IKacos(double f)
00153 {
00154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00155 if( f <= -1 ) return IKPI;
00156 else if( f >= 1 ) return 0;
00157 return acos(f);
00158 }
00159 inline float IKsin(float f) { return sinf(f); }
00160 inline double IKsin(double f) { return sin(f); }
00161 inline float IKcos(float f) { return cosf(f); }
00162 inline double IKcos(double f) { return cos(f); }
00163 inline float IKtan(float f) { return tanf(f); }
00164 inline double IKtan(double f) { return tan(f); }
00165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
00166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
00167 inline float IKatan2(float fy, float fx) {
00168     if( isnan(fy) ) {
00169         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00170         return float(IKPI_2);
00171     }
00172     else if( isnan(fx) ) {
00173         return 0;
00174     }
00175     return atan2f(fy,fx);
00176 }
00177 inline double IKatan2(double fy, double fx) {
00178     if( isnan(fy) ) {
00179         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00180         return IKPI_2;
00181     }
00182     else if( isnan(fx) ) {
00183         return 0;
00184     }
00185     return atan2(fy,fx);
00186 }
00187 
00188 inline float IKsign(float f) {
00189     if( f > 0 ) {
00190         return float(1);
00191     }
00192     else if( f < 0 ) {
00193         return float(-1);
00194     }
00195     return 0;
00196 }
00197 
00198 inline double IKsign(double f) {
00199     if( f > 0 ) {
00200         return 1.0;
00201     }
00202     else if( f < 0 ) {
00203         return -1.0;
00204     }
00205     return 0;
00206 }
00207 
00210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
00211 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24;
00212 x0=IKcos(j[0]);
00213 x1=IKsin(j[1]);
00214 x2=IKcos(j[2]);
00215 x3=IKcos(j[1]);
00216 x4=IKsin(j[2]);
00217 x5=IKsin(j[0]);
00218 x6=IKsin(j[3]);
00219 x7=IKcos(j[3]);
00220 x8=IKcos(j[4]);
00221 x9=IKsin(j[4]);
00222 x10=((IkReal(0.0750000000000000))*(x0));
00223 x11=((IkReal(0.0800000000000000))*(x5));
00224 x12=((IkReal(0.320000000000000))*(x0));
00225 x13=((IkReal(0.0800000000000000))*(x1));
00226 x14=((IkReal(1.00000000000000))*(x0));
00227 x15=((IkReal(1.00000000000000))*(x5));
00228 x16=((IkReal(0.0800000000000000))*(x0));
00229 x17=((IkReal(0.0750000000000000))*(x5));
00230 x18=((x3)*(x4));
00231 x19=((x1)*(x5));
00232 x20=((x2)*(x3));
00233 x21=((x1)*(x4));
00234 x22=((x1)*(x2));
00235 x23=((IkReal(0.0750000000000000))*(x22));
00236 x24=((x1)*(x11));
00237 IkReal x25=((x0)*(x13));
00238 IkReal x26=((IkReal(1.00000000000000))*(x18));
00239 eetrans[0]=((((x10)*(x22)))+(x10)+(((x6)*(((((IkReal(-1.00000000000000))*(x16)*(x26)))+(((x2)*(x25)))))))+(((x12)*(x20)))+(((IkReal(0.300000000000000))*(x0)*(x1)))+(((x12)*(x21)))+(((x7)*(((((x16)*(x20)))+(((x25)*(x4)))))))+(((IkReal(-1.00000000000000))*(x10)*(x26))));
00240 IkReal x27=((IkReal(1.00000000000000))*(x18));
00241 eetrans[1]=((((IkReal(0.320000000000000))*(x19)*(x4)))+(((IkReal(0.320000000000000))*(x20)*(x5)))+(((x6)*(((((IkReal(-1.00000000000000))*(x11)*(x27)))+(((x11)*(x22)))))))+(((IkReal(-1.00000000000000))*(x17)*(x27)))+(((IkReal(0.300000000000000))*(x19)))+(x17)+(((x17)*(x22)))+(((x7)*(((((x11)*(x21)))+(((x11)*(x20))))))));
00242 eetrans[2]=((IkReal(0.330000000000000))+(((x6)*(((((x13)*(x4)))+(((IkReal(0.0800000000000000))*(x20)))))))+(((IkReal(0.320000000000000))*(x18)))+(((IkReal(0.0750000000000000))*(x21)))+(((IkReal(0.300000000000000))*(x3)))+(((IkReal(-0.320000000000000))*(x22)))+(((x7)*(((((IkReal(0.0800000000000000))*(x18)))+(((IkReal(-1.00000000000000))*(x13)*(x2)))))))+(((IkReal(0.0750000000000000))*(x20))));
00243 IkReal x28=((IkReal(1.00000000000000))*(x14));
00244 eerot[0]=((((x8)*(((((x6)*(((((IkReal(-1.00000000000000))*(x21)*(x28)))+(((IkReal(-1.00000000000000))*(x20)*(x28)))))))+(((x7)*(((((IkReal(-1.00000000000000))*(x18)*(x28)))+(((x0)*(x22)))))))))))+(((IkReal(-1.00000000000000))*(x15)*(x9))));
00245 IkReal x29=((IkReal(1.00000000000000))*(x15));
00246 eerot[1]=((((x8)*(((((x6)*(((((IkReal(-1.00000000000000))*(x20)*(x29)))+(((IkReal(-1.00000000000000))*(x21)*(x29)))))))+(((x7)*(((((IkReal(-1.00000000000000))*(x18)*(x29)))+(((x19)*(x2)))))))))))+(((x0)*(x9))));
00247 eerot[2]=((x8)*(((((x6)*(((((IkReal(-1.00000000000000))*(x18)))+(((IkReal(1.00000000000000))*(x22)))))))+(((x7)*(((x20)+(x21))))))));
00248 }
00249 
00250 IKFAST_API int GetNumFreeParameters() { return 0; }
00251 IKFAST_API int* GetFreeParameters() { return NULL; }
00252 IKFAST_API int GetNumJoints() { return 5; }
00253 
00254 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00255 
00256 IKFAST_API int GetIkType() { return 0x56000007; }
00257 
00258 class IKSolver {
00259 public:
00260 IkReal j0,cj0,sj0,htj0,j1,cj1,sj1,htj1,j2,cj2,sj2,htj2,j3,cj3,sj3,htj3,j4,cj4,sj4,htj4,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp;
00261 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4;
00262 
00263 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00264 j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1; 
00265 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00266     solutions.Clear();
00267 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00268 
00269 r00 = eerot[0];
00270 r01 = eerot[1];
00271 r02 = eerot[2];
00272 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00273 new_r00=r00;
00274 new_px=px;
00275 new_r01=r01;
00276 new_py=py;
00277 new_r02=r02;
00278 new_pz=((IkReal(-0.330000000000000))+(pz));
00279 r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz;
00280 
00281 pp=(((px)*(px))+((pz)*(pz))+((py)*(py)));
00282 {
00283 IkReal j0array[2], cj0array[2], sj0array[2];
00284 bool j0valid[2]={false};
00285 _nj0 = 2;
00286 if( IKabs(((IkReal(-1.00000000000000))*(py))) < IKFAST_ATAN2_MAGTHRESH && IKabs(px) < IKFAST_ATAN2_MAGTHRESH )
00287     continue;
00288 IkReal x30=IKatan2(((IkReal(-1.00000000000000))*(py)), px);
00289 j0array[0]=((IkReal(-1.00000000000000))*(x30));
00290 sj0array[0]=IKsin(j0array[0]);
00291 cj0array[0]=IKcos(j0array[0]);
00292 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x30))));
00293 sj0array[1]=IKsin(j0array[1]);
00294 cj0array[1]=IKcos(j0array[1]);
00295 if( j0array[0] > IKPI )
00296 {
00297     j0array[0]-=IK2PI;
00298 }
00299 else if( j0array[0] < -IKPI )
00300 {    j0array[0]+=IK2PI;
00301 }
00302 j0valid[0] = true;
00303 if( j0array[1] > IKPI )
00304 {
00305     j0array[1]-=IK2PI;
00306 }
00307 else if( j0array[1] < -IKPI )
00308 {    j0array[1]+=IK2PI;
00309 }
00310 j0valid[1] = true;
00311 for(int ij0 = 0; ij0 < 2; ++ij0)
00312 {
00313 if( !j0valid[ij0] )
00314 {
00315     continue;
00316 }
00317 _ij0[0] = ij0; _ij0[1] = -1;
00318 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
00319 {
00320 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00321 {
00322     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00323 }
00324 }
00325 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00326 
00327 IkReal op[4+1], zeror[4];
00328 int numroots;
00329 op[0]=((((IkReal(-2.40000000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.313500000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.00564000000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00180000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(1.20000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(-2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.644800000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.180000000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.600000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.0225600000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-0.0225600000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(0.00720000000000000))*(pz)*((r02)*(r02))))+(((IkReal(-4.80000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-4.80000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.372000000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0225600000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.180000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.00564000000000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-8.00000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.0496000000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(0.180000000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.382500000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-8.00000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.00720000000000000))*(py)*(r01)*(r02)))+(((IkReal(-0.600000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.644800000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.180000000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.600000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.600000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.00453600000000000))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.744000000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-1.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-0.765000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(1.20000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-4.80000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.744000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(4.00000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-2.40000000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.40000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.00180000000000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.372000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.600000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-2.40000000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-4.80000000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-0.180000000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(0.00384000000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(0.00115200000000000))*(r01)*(r02)*(sj0)))+(((IkReal(2.40000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(2.40000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-0.600000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-2.40000000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.744000000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-4.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.600000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.00720000000000000))*(px)*(r00)*(r02)))+(((IkReal(-0.180000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-0.0345000000000000))*(pp)*((r02)*(r02))))+(((IkReal(0.000108000000000000))*((r02)*(r02))))+(((IkReal(0.600000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-2.40000000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.00180000000000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(1.20000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.0451200000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.20000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.600000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(2.40000000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.300000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00180000000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.744000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.180000000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.180000000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.180000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.744000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(0.0992000000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-4.80000000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.644800000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.696000000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(2.40000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-1.20000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(1.20000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.0225600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(1.20000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(0.00226800000000000))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(0.180000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-8.00000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.0496000000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.00384000000000000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(0.600000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(2.40000000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.180000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-4.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.20000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.382500000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(0.0496000000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.0992000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.300000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.0496000000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-2.40000000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.696000000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.300000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.600000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.40000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-2.40000000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.644800000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.180000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(0.744000000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.180000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.20000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.00115200000000000))*(cj0)*(r00)*(r02)))+(((IkReal(0.744000000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.744000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0225600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.180000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.300000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(1.20000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.600000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.00226800000000000))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-4.80000000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.0225600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.744000000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00)))));
00330 op[1]=((((IkReal(0.360000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.360000000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.108000000000000))*(px)*(r00)*(r02)))+(((IkReal(-4.80000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.0307200000000000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(2.40000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.360000000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.180000000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00921600000000000))*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(9.60000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.108000000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00216000000000000))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.360000000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.108000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.360000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.00108000000000000))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.180000000000000))*(pp)*((r02)*(r02))))+(((IkReal(-0.720000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(1.44000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(1.44000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.360000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(0.0126000000000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.0181200000000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.0126000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-1.44000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(1.44000000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.720000000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.360000000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-4.80000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(1.44000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(1.44000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(4.80000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(4.80000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.00921600000000000))*(cj0)*(r00)*(r02)))+(((IkReal(4.80000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.0126000000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.108000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-1.44000000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(0.108000000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.0307200000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(1.44000000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.0181200000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.360000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.0126000000000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(4.80000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.80000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.360000000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(9.60000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-0.360000000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-2.40000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.00108000000000000))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.44000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.360000000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.360000000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(1.44000000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(4.80000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(1.44000000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(1.44000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(1.44000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.720000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.360000000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.108000000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.108000000000000))*(py)*(r01)*(r02)))+(((IkReal(0.360000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.108000000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(4.80000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.216000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.108000000000000))*(pz)*((r02)*(r02))))+(((IkReal(0.00338400000000000))*((r02)*(r02))))+(((IkReal(0.180000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(1.44000000000000))*(cj0)*(px)*(pz)*((r00)*(r00)))));
00331 op[2]=((((IkReal(-16.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(1.20000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(8.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.39200000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.20000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-1.50900000000000))*(pp)*((r02)*(r02))))+(((IkReal(0.600000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(8.00000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.00768000000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.0255600000000000))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(0.0992000000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.39200000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.39200000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(0.0992000000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-1.39200000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(1.39200000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(0.696000000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(1.20000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.204720000000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-1.39200000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-32.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.0992000000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-2.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(0.212400000000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(0.00133200000000000))*((r02)*(r02))))+(((IkReal(2.25300000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.198400000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-4.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(1.20000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.59040000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.59040000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.765000000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(1.20000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.212400000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(0.212400000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(1.20000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.53000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(1.48800000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.204720000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.198400000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(2.40000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-0.765000000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.39200000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.600000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-8.00000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.212400000000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(1.48800000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.600000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.0127800000000000))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(1.20000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(1.20000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.600000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.0992000000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(8.00000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-1.59040000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.600000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.00768000000000000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.20000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.696000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-0.0127800000000000))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-8.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.600000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(1.20000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-1.59040000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(2.40000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.39200000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-1.39200000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.20000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02))));
00332 op[3]=((((IkReal(0.360000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.360000000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-4.80000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.108000000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-1.44000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.0307200000000000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(2.40000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.360000000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.180000000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(9.60000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.00216000000000000))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.360000000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.108000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.360000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.00108000000000000))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.180000000000000))*(pp)*((r02)*(r02))))+(((IkReal(0.108000000000000))*(px)*(r00)*(r02)))+(((IkReal(-0.720000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(0.216000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-1.44000000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.0126000000000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.0181200000000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.0126000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-1.44000000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.108000000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.108000000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(1.44000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.720000000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(1.44000000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(-0.360000000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-4.80000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-1.44000000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(4.80000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(4.80000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.44000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.360000000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.44000000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(4.80000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.0126000000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.00921600000000000))*(cj0)*(r00)*(r02)))+(((IkReal(-1.44000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0307200000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.0181200000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.108000000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.360000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.0126000000000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(4.80000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.80000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.360000000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(9.60000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-0.360000000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-2.40000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.108000000000000))*(py)*(r01)*(r02)))+(((IkReal(-1.44000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-1.44000000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.00108000000000000))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.360000000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.44000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-0.360000000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(4.80000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.108000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-0.720000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.360000000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.00921600000000000))*(r01)*(r02)*(sj0)))+(((IkReal(0.360000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.108000000000000))*(pz)*((r02)*(r02))))+(((IkReal(4.80000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.00338400000000000))*((r02)*(r02))))+(((IkReal(-1.44000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-1.44000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(0.180000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00)))));
00333 op[4]=((((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.313500000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.20000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.00564000000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00180000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(2.40000000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.644800000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-2.40000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00720000000000000))*(px)*(r00)*(r02)))+(((IkReal(0.600000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-0.372000000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.00564000000000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-8.00000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.0496000000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-1.20000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.180000000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.382500000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.180000000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.40000000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.600000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(0.644800000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.180000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.600000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(2.40000000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.180000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0225600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-4.00000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.600000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.600000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(-2.40000000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.00453600000000000))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-1.20000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.744000000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-1.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.765000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(0.600000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(2.40000000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.744000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(4.00000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.180000000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-0.00115200000000000))*(cj0)*(r00)*(r02)))+(((IkReal(1.20000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.00180000000000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.372000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.600000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(0.0225600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(4.80000000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00384000000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.600000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-0.180000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.744000000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-2.40000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-4.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.600000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.00720000000000000))*(pz)*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-2.40000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.0345000000000000))*(pp)*((r02)*(r02))))+(((IkReal(0.000108000000000000))*((r02)*(r02))))+(((IkReal(-0.180000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(0.600000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.00180000000000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.600000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.300000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00180000000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-2.40000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0225600000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(2.40000000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.744000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.744000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(4.80000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.0992000000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.644800000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.696000000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.180000000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-2.40000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-2.40000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(0.00226800000000000))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.180000000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(-8.00000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.0496000000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.00384000000000000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(0.600000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.382500000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.0225600000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(2.40000000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.40000000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.180000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(0.0496000000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.180000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(0.0992000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.300000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.0496000000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.20000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(2.40000000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.20000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.696000000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.300000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.600000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.0451200000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.644800000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(1.20000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.744000000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(1.20000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.744000000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.180000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.744000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.180000000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.00720000000000000))*(py)*(r01)*(r02)))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.300000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(-0.0225600000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.180000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(0.0225600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.600000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.00226800000000000))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.744000000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(4.80000000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.00115200000000000))*(r01)*(r02)*(sj0)))+(((IkReal(2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02)))));
00334 polyroots4(op,zeror,numroots);
00335 IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1];
00336 int numsolutions = 0;
00337 for(int ij1 = 0; ij1 < numroots; ++ij1)
00338 {
00339 IkReal htj1 = zeror[ij1];
00340 tempj1array[0]=((IkReal(2.00000000000000))*(atan(htj1)));
00341 for(int kj1 = 0; kj1 < 1; ++kj1)
00342 {
00343 j1array[numsolutions] = tempj1array[kj1];
00344 if( j1array[numsolutions] > IKPI )
00345 {
00346     j1array[numsolutions]-=IK2PI;
00347 }
00348 else if( j1array[numsolutions] < -IKPI )
00349 {
00350     j1array[numsolutions]+=IK2PI;
00351 }
00352 sj1array[numsolutions] = IKsin(j1array[numsolutions]);
00353 cj1array[numsolutions] = IKcos(j1array[numsolutions]);
00354 numsolutions++;
00355 }
00356 }
00357 bool j1valid[4]={true,true,true,true};
00358 _nj1 = 4;
00359 for(int ij1 = 0; ij1 < numsolutions; ++ij1)
00360     {
00361 if( !j1valid[ij1] )
00362 {
00363     continue;
00364 }
00365     j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00366 htj1 = IKtan(j1/2);
00367 
00368 _ij1[0] = ij1; _ij1[1] = -1;
00369 for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1)
00370 {
00371 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00372 {
00373     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00374 }
00375 }
00376 {
00377 IkReal j4array[2], cj4array[2], sj4array[2];
00378 bool j4valid[2]={false};
00379 _nj4 = 2;
00380 sj4array[0]=((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00381 if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH )
00382 {
00383     j4valid[0] = j4valid[1] = true;
00384     j4array[0] = IKasin(sj4array[0]);
00385     cj4array[0] = IKcos(j4array[0]);
00386     sj4array[1] = sj4array[0];
00387     j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]);
00388     cj4array[1] = -cj4array[0];
00389 }
00390 else if( isnan(sj4array[0]) )
00391 {
00392     // probably any value will work
00393     j4valid[0] = true;
00394     cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0;
00395 }
00396 for(int ij4 = 0; ij4 < 2; ++ij4)
00397 {
00398 if( !j4valid[ij4] )
00399 {
00400     continue;
00401 }
00402 _ij4[0] = ij4; _ij4[1] = -1;
00403 for(int iij4 = ij4+1; iij4 < 2; ++iij4)
00404 {
00405 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
00406 {
00407     j4valid[iij4]=false; _ij4[1] = iij4; break; 
00408 }
00409 }
00410 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
00411 
00412 {
00413 IkReal dummyeval[1];
00414 IkReal gconst0;
00415 gconst0=IKsign(cj4);
00416 dummyeval[0]=cj4;
00417 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00418 {
00419 {
00420 IkReal dummyeval[1];
00421 IkReal gconst1;
00422 gconst1=IKsign(cj4);
00423 dummyeval[0]=cj4;
00424 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00425 {
00426 {
00427 IkReal evalcond[9];
00428 IkReal x31=(py)*(py);
00429 IkReal x32=(px)*(px);
00430 IkReal x33=(pz)*(pz);
00431 IkReal x34=((r02)*(sj1));
00432 IkReal x35=((cj1)*(pz));
00433 IkReal x36=((IkReal(0.150000000000000))*(r00));
00434 IkReal x37=((IkReal(0.600000000000000))*(r02));
00435 IkReal x38=((cj0)*(px));
00436 IkReal x39=((r01)*(sj0));
00437 IkReal x40=((IkReal(1.00000000000000))*(cj1));
00438 IkReal x41=((py)*(sj0));
00439 IkReal x42=((py)*(r01));
00440 IkReal x43=((IkReal(0.150000000000000))*(sj1));
00441 IkReal x44=((IkReal(1.00000000000000))*(pz));
00442 IkReal x45=((px)*(sj1));
00443 IkReal x46=((IkReal(0.600000000000000))*(r00));
00444 IkReal x47=((cj0)*(r00));
00445 IkReal x48=((IkReal(0.0843750000000000))*(cj1));
00446 IkReal x49=((IkReal(2.00000000000000))*(pz));
00447 IkReal x50=((cj1)*(px));
00448 IkReal x51=((IkReal(1.00000000000000))*(px));
00449 IkReal x52=((IkReal(0.300000000000000))*(cj1));
00450 IkReal x53=((IkReal(0.0956250000000000))*(sj1));
00451 IkReal x54=((IkReal(1.00000000000000))*(sj1));
00452 IkReal x55=((cj0)*(pz));
00453 IkReal x56=((IkReal(0.150000000000000))*(cj1));
00454 IkReal x57=((IkReal(2.00000000000000))*(sj1));
00455 IkReal x58=((IkReal(2.00000000000000))*(cj1));
00456 IkReal x59=((IkReal(2.00000000000000))*(r00));
00457 IkReal x60=((IkReal(0.300000000000000))*(sj1));
00458 IkReal x61=((r02)*(x41));
00459 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
00460 evalcond[1]=((((IkReal(-1.00000000000000))*(sj0)*(x51)))+(((cj0)*(py))));
00461 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00462 evalcond[3]=((((IkReal(-1.00000000000000))*(x40)*(x47)))+(x34)+(((IkReal(-1.00000000000000))*(x39)*(x40))));
00463 evalcond[4]=((((IkReal(-1.00000000000000))*(r02)*(x40)))+(((IkReal(-1.00000000000000))*(x39)*(x54)))+(((IkReal(-1.00000000000000))*(x47)*(x54))));
00464 evalcond[5]=((((IkReal(0.0750000000000000))*(x39)))+(((r02)*(x52)))+(((IkReal(-1.00000000000000))*(r00)*(x51)))+(((IkReal(0.0750000000000000))*(x47)))+(((x39)*(x60)))+(((IkReal(-1.00000000000000))*(x42)))+(((IkReal(-1.00000000000000))*(r02)*(x44)))+(((x47)*(x60))));
00465 evalcond[6]=((x61)+(((r02)*(x38)))+(((IkReal(-1.00000000000000))*(x39)*(x44)))+(((x47)*(x52)))+(((IkReal(-1.00000000000000))*(x44)*(x47)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(-0.300000000000000))*(x34)))+(((x39)*(x52))));
00466 evalcond[7]=((((r02)*(x33)*(x58)))+(((IkReal(-1.00000000000000))*(x42)*(x43)))+(((x39)*(x53)))+(((x34)*(x41)*(x49)))+(((x34)*(x38)*(x49)))+(((px)*(x35)*(x59)))+(((x41)*(x45)*(x59)))+(((IkReal(-1.00000000000000))*(pp)*(x47)*(x54)))+(((x56)*(x61)))+(((x38)*(x42)*(x57)))+(((IkReal(-1.00000000000000))*(x36)*(x45)))+(((IkReal(-1.00000000000000))*(cj0)*(x35)*(x36)))+(((IkReal(-1.00000000000000))*(pp)*(x39)*(x54)))+(((IkReal(-0.600000000000000))*(x42)))+(((x32)*(x47)*(x57)))+(((IkReal(-0.150000000000000))*(pz)*(x34)))+(((IkReal(-1.00000000000000))*(pz)*(x37)))+(((IkReal(-1.00000000000000))*(px)*(x46)))+(((r02)*(x38)*(x56)))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(x40)))+(((r02)*(x48)))+(((x47)*(x53)))+(((x31)*(x39)*(x57)))+(((IkReal(0.0450000000000000))*(x39)))+(((IkReal(2.00000000000000))*(x35)*(x42)))+(((IkReal(-0.150000000000000))*(x35)*(x39)))+(((IkReal(0.0450000000000000))*(x47))));
00467 evalcond[8]=((((pz)*(x39)*(x43)))+(((IkReal(-1.00000000000000))*(pp)*(x40)*(x47)))+(((IkReal(0.600000000000000))*(pz)*(x39)))+(((IkReal(0.0450000000000000))*(r02)))+(((pp)*(x34)))+(((x41)*(x50)*(x59)))+(((IkReal(-0.150000000000000))*(x34)*(x41)))+(((IkReal(-2.00000000000000))*(x33)*(x34)))+(((x31)*(x39)*(x58)))+(((IkReal(-1.00000000000000))*(x47)*(x48)))+(((sj1)*(x36)*(x55)))+(((IkReal(2.00000000000000))*(r02)*(x35)*(x38)))+(((x32)*(x47)*(x58)))+(((IkReal(-1.00000000000000))*(x39)*(x48)))+(((IkReal(-1.00000000000000))*(r00)*(x45)*(x49)))+(((IkReal(-1.00000000000000))*(sj1)*(x42)*(x49)))+(((IkReal(-1.00000000000000))*(pp)*(x39)*(x40)))+(((IkReal(-1.00000000000000))*(x37)*(x41)))+(((IkReal(-1.00000000000000))*(x42)*(x56)))+(((IkReal(-1.00000000000000))*(x36)*(x50)))+(((IkReal(0.0956250000000000))*(x34)))+(((IkReal(-0.150000000000000))*(r02)*(x35)))+(((IkReal(-0.150000000000000))*(x34)*(x38)))+(((x46)*(x55)))+(((x38)*(x42)*(x58)))+(((IkReal(-1.00000000000000))*(x37)*(x38)))+(((IkReal(2.00000000000000))*(x35)*(x61))));
00468 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  )
00469 {
00470 {
00471 IkReal j3array[2], cj3array[2], sj3array[2];
00472 bool j3valid[2]={false};
00473 _nj3 = 2;
00474 IkReal x62=((IkReal(11.4095661394664))*(sj1));
00475 IkReal x63=((cj0)*(px));
00476 IkReal x64=((py)*(sj0));
00477 if( (((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((IkReal(2.85239153486660))*(x63)))+(((x62)*(x64)))+(((x62)*(x63)))+(((IkReal(2.85239153486660))*(x64)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1))))) < -1-IKFAST_SINCOS_THRESH || (((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((IkReal(2.85239153486660))*(x63)))+(((x62)*(x64)))+(((x62)*(x63)))+(((IkReal(2.85239153486660))*(x64)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1))))) > 1+IKFAST_SINCOS_THRESH )
00478     continue;
00479 IkReal x65=IKasin(((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((IkReal(2.85239153486660))*(x63)))+(((x62)*(x64)))+(((x62)*(x63)))+(((IkReal(2.85239153486660))*(x64)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1)))));
00480 j3array[0]=((IkReal(-1.34057673951805))+(((IkReal(-1.00000000000000))*(x65))));
00481 sj3array[0]=IKsin(j3array[0]);
00482 cj3array[0]=IKcos(j3array[0]);
00483 j3array[1]=((IkReal(1.80101591407174))+(x65));
00484 sj3array[1]=IKsin(j3array[1]);
00485 cj3array[1]=IKcos(j3array[1]);
00486 if( j3array[0] > IKPI )
00487 {
00488     j3array[0]-=IK2PI;
00489 }
00490 else if( j3array[0] < -IKPI )
00491 {    j3array[0]+=IK2PI;
00492 }
00493 j3valid[0] = true;
00494 if( j3array[1] > IKPI )
00495 {
00496     j3array[1]-=IK2PI;
00497 }
00498 else if( j3array[1] < -IKPI )
00499 {    j3array[1]+=IK2PI;
00500 }
00501 j3valid[1] = true;
00502 for(int ij3 = 0; ij3 < 2; ++ij3)
00503 {
00504 if( !j3valid[ij3] )
00505 {
00506     continue;
00507 }
00508 _ij3[0] = ij3; _ij3[1] = -1;
00509 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00510 {
00511 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00512 {
00513     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00514 }
00515 }
00516 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00517 {
00518 IkReal evalcond[1];
00519 IkReal x66=((IkReal(2.00000000000000))*(sj0));
00520 IkReal x67=((px)*(py));
00521 IkReal x68=((r00)*(sj0));
00522 IkReal x69=((cj0)*(r01));
00523 IkReal x70=((py)*(r00));
00524 IkReal x71=((IkReal(2.00000000000000))*(cj0));
00525 IkReal x72=((px)*(r01));
00526 IkReal x73=((IkReal(0.600000000000000))*(cj1));
00527 IkReal x74=((py)*(r02));
00528 IkReal x75=((IkReal(0.600000000000000))*(sj1));
00529 IkReal x76=((IkReal(0.0450000000000000))*(sj1));
00530 IkReal x77=((px)*(r02));
00531 evalcond[0]=((IkReal(-0.114425000000000))+(((IkReal(-1.00000000000000))*(pz)*(x71)*(x74)))+(((IkReal(0.150000000000000))*(x70)))+(((IkReal(-1.00000000000000))*(sj0)*(x73)*(x77)))+(((IkReal(-1.00000000000000))*(x68)*(x76)))+(((IkReal(0.0956250000000000))*(x69)))+(((cj0)*(x73)*(x74)))+(((IkReal(-2.00000000000000))*(x69)*((py)*(py))))+(((IkReal(-1.00000000000000))*(pz)*(x69)*(x73)))+(((IkReal(-1.00000000000000))*(x72)*(x75)))+(((r00)*(x66)*((px)*(px))))+(((pz)*(x68)*(x73)))+(((IkReal(-0.150000000000000))*(x72)))+(((pz)*(x66)*(x77)))+(((pp)*(x69)))+(((IkReal(-0.0120000000000000))*(IKsin(j3))))+(((x70)*(x75)))+(((IkReal(-0.0512000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(pp)*(x68)))+(((r01)*(x66)*(x67)))+(((IkReal(-0.0956250000000000))*(x68)))+(((IkReal(-1.00000000000000))*(r00)*(x67)*(x71)))+(((x69)*(x76))));
00532 if( IKabs(evalcond[0]) > 0.000001  )
00533 {
00534 continue;
00535 }
00536 }
00537 
00538 {
00539 IkReal dummyeval[1];
00540 IkReal gconst8;
00541 gconst8=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00542 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
00543 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00544 {
00545 {
00546 IkReal dummyeval[1];
00547 IkReal gconst9;
00548 gconst9=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00549 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
00550 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00551 {
00552 continue;
00553 
00554 } else
00555 {
00556 {
00557 IkReal j2array[1], cj2array[1], sj2array[1];
00558 bool j2valid[1]={false};
00559 _nj2 = 1;
00560 IkReal x78=((r02)*(sj0));
00561 IkReal x79=((IkReal(0.0800000000000000))*(sj1));
00562 IkReal x80=((cj3)*(px));
00563 IkReal x81=((cj0)*(r01));
00564 IkReal x82=((IkReal(0.0240000000000000))*(cj1));
00565 IkReal x83=((pz)*(sj3));
00566 IkReal x84=((IkReal(0.00600000000000000))*(cj1));
00567 IkReal x85=((IkReal(0.00562500000000000))*(cj1));
00568 IkReal x86=((IkReal(0.0750000000000000))*(sj1));
00569 IkReal x87=((r00)*(sj0));
00570 IkReal x88=((cj3)*(pz));
00571 IkReal x89=((IkReal(0.320000000000000))*(py));
00572 IkReal x90=((IkReal(0.0800000000000000))*(cj1));
00573 IkReal x91=((IkReal(0.0750000000000000))*(cj1));
00574 IkReal x92=((py)*(sj0));
00575 IkReal x93=((IkReal(0.320000000000000))*(sj1));
00576 IkReal x94=((cj0)*(px));
00577 IkReal x95=((py)*(r00));
00578 IkReal x96=((IkReal(0.00600000000000000))*(sj1));
00579 IkReal x97=((cj1)*(px)*(r01));
00580 IkReal x98=((cj0)*(py)*(r02));
00581 IkReal x99=((px)*(sj3)*(x79));
00582 if( IKabs(((gconst9)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj3)*(x79)*(x98)))+(((sj0)*(sj1)*(x89)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x90)))+(((cj3)*(x79)*(x92)))+(((sj3)*(x81)*(x84)))+(((px)*(x78)*(x86)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x93)*(x94)))+(((x79)*(x81)*(x83)))+(((IkReal(-1.00000000000000))*(x85)*(x87)))+(((IkReal(-1.00000000000000))*(x86)*(x98)))+(((sj3)*(x90)*(x95)))+(((IkReal(-1.00000000000000))*(x79)*(x83)*(x87)))+(((cj0)*(x79)*(x80)))+(((IkReal(-1.00000000000000))*(sj3)*(x84)*(x87)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((pz)*(x81)*(x86)))+(((x88)*(x90)))+(((IkReal(-1.00000000000000))*(pz)*(x86)*(x87)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x91)))+(((x78)*(x99)))+(((x81)*(x85)))+(((IkReal(-1.00000000000000))*(cj3)*(x96)))+(((x91)*(x95))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((cj0)*(r02)*(sj1)*(x89)))+(((x79)*(x87)*(x88)))+(((cj3)*(x79)*(x98)))+(((IkReal(-1.00000000000000))*(pz)*(x81)*(x93)))+(((IkReal(-1.00000000000000))*(px)*(x78)*(x93)))+(((IkReal(-1.00000000000000))*(cj1)*(r00)*(x89)))+(((IkReal(-1.00000000000000))*(x78)*(x79)*(x80)))+(((pz)*(x91)))+(((IkReal(-1.00000000000000))*(x79)*(x81)*(x88)))+(((x82)*(x87)))+(((IkReal(-1.00000000000000))*(cj3)*(x90)*(x95)))+(((sj3)*(x79)*(x92)))+(((IkReal(-1.00000000000000))*(sj3)*(x96)))+(((cj3)*(x84)*(x87)))+(((pz)*(x87)*(x93)))+(((r01)*(x80)*(x90)))+(((x83)*(x90)))+(((IkReal(-1.00000000000000))*(cj3)*(x81)*(x84)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x86)*(x94)))+(((sj3)*(x79)*(x94)))+(((IkReal(0.320000000000000))*(x97)))+(((x86)*(x92)))+(((IkReal(-1.00000000000000))*(x81)*(x82))))))) < IKFAST_ATAN2_MAGTHRESH )
00583     continue;
00584 j2array[0]=IKatan2(((gconst9)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj3)*(x79)*(x98)))+(((sj0)*(sj1)*(x89)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x90)))+(((cj3)*(x79)*(x92)))+(((sj3)*(x81)*(x84)))+(((px)*(x78)*(x86)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x93)*(x94)))+(((x79)*(x81)*(x83)))+(((IkReal(-1.00000000000000))*(x85)*(x87)))+(((IkReal(-1.00000000000000))*(x86)*(x98)))+(((sj3)*(x90)*(x95)))+(((IkReal(-1.00000000000000))*(x79)*(x83)*(x87)))+(((cj0)*(x79)*(x80)))+(((IkReal(-1.00000000000000))*(sj3)*(x84)*(x87)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((pz)*(x81)*(x86)))+(((x88)*(x90)))+(((IkReal(-1.00000000000000))*(pz)*(x86)*(x87)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x91)))+(((x78)*(x99)))+(((x81)*(x85)))+(((IkReal(-1.00000000000000))*(cj3)*(x96)))+(((x91)*(x95)))))), ((gconst9)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((cj0)*(r02)*(sj1)*(x89)))+(((x79)*(x87)*(x88)))+(((cj3)*(x79)*(x98)))+(((IkReal(-1.00000000000000))*(pz)*(x81)*(x93)))+(((IkReal(-1.00000000000000))*(px)*(x78)*(x93)))+(((IkReal(-1.00000000000000))*(cj1)*(r00)*(x89)))+(((IkReal(-1.00000000000000))*(x78)*(x79)*(x80)))+(((pz)*(x91)))+(((IkReal(-1.00000000000000))*(x79)*(x81)*(x88)))+(((x82)*(x87)))+(((IkReal(-1.00000000000000))*(cj3)*(x90)*(x95)))+(((sj3)*(x79)*(x92)))+(((IkReal(-1.00000000000000))*(sj3)*(x96)))+(((cj3)*(x84)*(x87)))+(((pz)*(x87)*(x93)))+(((r01)*(x80)*(x90)))+(((x83)*(x90)))+(((IkReal(-1.00000000000000))*(cj3)*(x81)*(x84)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x86)*(x94)))+(((sj3)*(x79)*(x94)))+(((IkReal(0.320000000000000))*(x97)))+(((x86)*(x92)))+(((IkReal(-1.00000000000000))*(x81)*(x82)))))));
00585 sj2array[0]=IKsin(j2array[0]);
00586 cj2array[0]=IKcos(j2array[0]);
00587 if( j2array[0] > IKPI )
00588 {
00589     j2array[0]-=IK2PI;
00590 }
00591 else if( j2array[0] < -IKPI )
00592 {    j2array[0]+=IK2PI;
00593 }
00594 j2valid[0] = true;
00595 for(int ij2 = 0; ij2 < 1; ++ij2)
00596 {
00597 if( !j2valid[ij2] )
00598 {
00599     continue;
00600 }
00601 _ij2[0] = ij2; _ij2[1] = -1;
00602 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00603 {
00604 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00605 {
00606     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00607 }
00608 }
00609 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00610 {
00611 IkReal evalcond[4];
00612 IkReal x100=IKcos(j2);
00613 IkReal x101=IKsin(j2);
00614 IkReal x102=((IkReal(0.0800000000000000))*(sj3));
00615 IkReal x103=((cj0)*(r01));
00616 IkReal x104=((IkReal(1.00000000000000))*(px));
00617 IkReal x105=((py)*(sj1));
00618 IkReal x106=((cj0)*(r02));
00619 IkReal x107=((IkReal(0.0750000000000000))*(cj1));
00620 IkReal x108=((r02)*(sj0));
00621 IkReal x109=((IkReal(0.0750000000000000))*(sj1));
00622 IkReal x110=((cj1)*(pz));
00623 IkReal x111=((r00)*(sj0));
00624 IkReal x112=((IkReal(0.0800000000000000))*(cj3));
00625 IkReal x113=((pz)*(sj1));
00626 IkReal x114=((IkReal(1.00000000000000))*(sj0));
00627 IkReal x115=((cj1)*(py));
00628 IkReal x116=((IkReal(0.0750000000000000))*(x101));
00629 IkReal x117=((IkReal(0.320000000000000))*(x100));
00630 IkReal x118=((IkReal(0.320000000000000))*(x101));
00631 IkReal x119=((IkReal(0.0750000000000000))*(x100));
00632 IkReal x120=((sj1)*(x111));
00633 IkReal x121=((x101)*(x102));
00634 IkReal x122=((x100)*(x112));
00635 IkReal x123=((x100)*(x102));
00636 IkReal x124=((x101)*(x112));
00637 IkReal x125=((x121)+(x116));
00638 IkReal x126=((x122)+(x117));
00639 IkReal x127=((x124)+(x123)+(x119)+(x118));
00640 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x104)))+(((IkReal(-1.00000000000000))*(x114)*(x115)))+(x126)+(((IkReal(-1.00000000000000))*(x125)))+(x107)+(x113));
00641 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x105)*(x114)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x104)))+(x127)+(x109)+(((IkReal(-1.00000000000000))*(x110))));
00642 evalcond[2]=((((IkReal(-1.00000000000000))*(sj1)*(x104)*(x108)))+(((x111)*(x113)))+(((x107)*(x111)))+(((x105)*(x106)))+(((IkReal(-1.00000000000000))*(x126)))+(((IkReal(-1.00000000000000))*(r00)*(x115)))+(((cj1)*(px)*(r01)))+(x125)+(((IkReal(-1.00000000000000))*(x103)*(x113)))+(((IkReal(-1.00000000000000))*(x103)*(x107))));
00643 evalcond[3]=((((IkReal(-1.00000000000000))*(x109)*(x111)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x104)))+(((x110)*(x111)))+(((IkReal(-1.00000000000000))*(cj1)*(x104)*(x108)))+(((IkReal(-1.00000000000000))*(x103)*(x110)))+(x127)+(((IkReal(0.300000000000000))*(x103)))+(((x106)*(x115)))+(((IkReal(-0.300000000000000))*(x111)))+(((r00)*(x105)))+(((x103)*(x109))));
00644 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00645 {
00646 continue;
00647 }
00648 }
00649 
00650 {
00651 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00652 vinfos[0].jointtype = 1;
00653 vinfos[0].foffset = j0;
00654 vinfos[0].indices[0] = _ij0[0];
00655 vinfos[0].indices[1] = _ij0[1];
00656 vinfos[0].maxsolutions = _nj0;
00657 vinfos[1].jointtype = 1;
00658 vinfos[1].foffset = j1;
00659 vinfos[1].indices[0] = _ij1[0];
00660 vinfos[1].indices[1] = _ij1[1];
00661 vinfos[1].maxsolutions = _nj1;
00662 vinfos[2].jointtype = 1;
00663 vinfos[2].foffset = j2;
00664 vinfos[2].indices[0] = _ij2[0];
00665 vinfos[2].indices[1] = _ij2[1];
00666 vinfos[2].maxsolutions = _nj2;
00667 vinfos[3].jointtype = 1;
00668 vinfos[3].foffset = j3;
00669 vinfos[3].indices[0] = _ij3[0];
00670 vinfos[3].indices[1] = _ij3[1];
00671 vinfos[3].maxsolutions = _nj3;
00672 vinfos[4].jointtype = 1;
00673 vinfos[4].foffset = j4;
00674 vinfos[4].indices[0] = _ij4[0];
00675 vinfos[4].indices[1] = _ij4[1];
00676 vinfos[4].maxsolutions = _nj4;
00677 std::vector<int> vfree(0);
00678 solutions.AddSolution(vinfos,vfree);
00679 }
00680 }
00681 }
00682 
00683 }
00684 
00685 }
00686 
00687 } else
00688 {
00689 {
00690 IkReal j2array[1], cj2array[1], sj2array[1];
00691 bool j2valid[1]={false};
00692 _nj2 = 1;
00693 IkReal x128=((IkReal(0.0800000000000000))*(cj1));
00694 IkReal x129=((cj0)*(px));
00695 IkReal x130=((py)*(sj0));
00696 IkReal x131=((IkReal(0.320000000000000))*(sj1));
00697 IkReal x132=((IkReal(0.00600000000000000))*(cj3));
00698 IkReal x133=((pz)*(sj3));
00699 IkReal x134=((IkReal(0.0750000000000000))*(cj1));
00700 IkReal x135=((IkReal(0.0800000000000000))*(sj1));
00701 IkReal x136=((IkReal(0.0750000000000000))*(sj1));
00702 IkReal x137=((IkReal(0.00600000000000000))*(sj3));
00703 IkReal x138=((cj3)*(pz));
00704 IkReal x139=((IkReal(0.320000000000000))*(cj1));
00705 if( IKabs(((gconst8)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x132)))+(((IkReal(-1.00000000000000))*(x130)*(x134)))+(((IkReal(-1.00000000000000))*(sj3)*(x128)*(x130)))+(((cj3)*(x129)*(x135)))+(((cj3)*(x130)*(x135)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x133)*(x135)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x128)*(x129)))+(((x128)*(x138)))+(((IkReal(-1.00000000000000))*(x129)*(x134)))+(((x130)*(x131)))+(((cj1)*(x137)))+(((pz)*(x136)))+(((pz)*(x139)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x129)*(x131))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((sj3)*(x129)*(x135)))+(((x129)*(x139)))+(((pz)*(x134)))+(((x130)*(x139)))+(((IkReal(-1.00000000000000))*(x135)*(x138)))+(((IkReal(-1.00000000000000))*(pz)*(x131)))+(((x130)*(x136)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((sj3)*(x130)*(x135)))+(((cj3)*(x128)*(x130)))+(((IkReal(-1.00000000000000))*(cj1)*(x132)))+(((x128)*(x133)))+(((x129)*(x136)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x137)))+(((cj3)*(x128)*(x129))))))) < IKFAST_ATAN2_MAGTHRESH )
00706     continue;
00707 j2array[0]=IKatan2(((gconst8)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x132)))+(((IkReal(-1.00000000000000))*(x130)*(x134)))+(((IkReal(-1.00000000000000))*(sj3)*(x128)*(x130)))+(((cj3)*(x129)*(x135)))+(((cj3)*(x130)*(x135)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x133)*(x135)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x128)*(x129)))+(((x128)*(x138)))+(((IkReal(-1.00000000000000))*(x129)*(x134)))+(((x130)*(x131)))+(((cj1)*(x137)))+(((pz)*(x136)))+(((pz)*(x139)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x129)*(x131)))))), ((gconst8)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((sj3)*(x129)*(x135)))+(((x129)*(x139)))+(((pz)*(x134)))+(((x130)*(x139)))+(((IkReal(-1.00000000000000))*(x135)*(x138)))+(((IkReal(-1.00000000000000))*(pz)*(x131)))+(((x130)*(x136)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((sj3)*(x130)*(x135)))+(((cj3)*(x128)*(x130)))+(((IkReal(-1.00000000000000))*(cj1)*(x132)))+(((x128)*(x133)))+(((x129)*(x136)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x137)))+(((cj3)*(x128)*(x129)))))));
00708 sj2array[0]=IKsin(j2array[0]);
00709 cj2array[0]=IKcos(j2array[0]);
00710 if( j2array[0] > IKPI )
00711 {
00712     j2array[0]-=IK2PI;
00713 }
00714 else if( j2array[0] < -IKPI )
00715 {    j2array[0]+=IK2PI;
00716 }
00717 j2valid[0] = true;
00718 for(int ij2 = 0; ij2 < 1; ++ij2)
00719 {
00720 if( !j2valid[ij2] )
00721 {
00722     continue;
00723 }
00724 _ij2[0] = ij2; _ij2[1] = -1;
00725 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00726 {
00727 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00728 {
00729     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00730 }
00731 }
00732 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00733 {
00734 IkReal evalcond[4];
00735 IkReal x140=IKcos(j2);
00736 IkReal x141=IKsin(j2);
00737 IkReal x142=((IkReal(0.0800000000000000))*(sj3));
00738 IkReal x143=((cj0)*(r01));
00739 IkReal x144=((IkReal(1.00000000000000))*(px));
00740 IkReal x145=((py)*(sj1));
00741 IkReal x146=((cj0)*(r02));
00742 IkReal x147=((IkReal(0.0750000000000000))*(cj1));
00743 IkReal x148=((r02)*(sj0));
00744 IkReal x149=((IkReal(0.0750000000000000))*(sj1));
00745 IkReal x150=((cj1)*(pz));
00746 IkReal x151=((r00)*(sj0));
00747 IkReal x152=((IkReal(0.0800000000000000))*(cj3));
00748 IkReal x153=((pz)*(sj1));
00749 IkReal x154=((IkReal(1.00000000000000))*(sj0));
00750 IkReal x155=((cj1)*(py));
00751 IkReal x156=((IkReal(0.0750000000000000))*(x141));
00752 IkReal x157=((IkReal(0.320000000000000))*(x140));
00753 IkReal x158=((IkReal(0.320000000000000))*(x141));
00754 IkReal x159=((IkReal(0.0750000000000000))*(x140));
00755 IkReal x160=((sj1)*(x151));
00756 IkReal x161=((x141)*(x142));
00757 IkReal x162=((x140)*(x152));
00758 IkReal x163=((x140)*(x142));
00759 IkReal x164=((x141)*(x152));
00760 IkReal x165=((x156)+(x161));
00761 IkReal x166=((x157)+(x162));
00762 IkReal x167=((x159)+(x158)+(x163)+(x164));
00763 evalcond[0]=((((IkReal(-1.00000000000000))*(x154)*(x155)))+(x153)+(((IkReal(-1.00000000000000))*(x165)))+(x166)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x144)))+(x147));
00764 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x150)))+(x167)+(((IkReal(-1.00000000000000))*(x145)*(x154)))+(x149)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x144))));
00765 evalcond[2]=((((x151)*(x153)))+(((IkReal(-1.00000000000000))*(x143)*(x147)))+(((IkReal(-1.00000000000000))*(x166)))+(((cj1)*(px)*(r01)))+(x165)+(((x147)*(x151)))+(((IkReal(-1.00000000000000))*(sj1)*(x144)*(x148)))+(((IkReal(-1.00000000000000))*(x143)*(x153)))+(((x145)*(x146)))+(((IkReal(-1.00000000000000))*(r00)*(x155))));
00766 evalcond[3]=((((IkReal(-1.00000000000000))*(r01)*(sj1)*(x144)))+(((r00)*(x145)))+(((x143)*(x149)))+(((IkReal(0.300000000000000))*(x143)))+(((x150)*(x151)))+(x167)+(((IkReal(-0.300000000000000))*(x151)))+(((IkReal(-1.00000000000000))*(x143)*(x150)))+(((IkReal(-1.00000000000000))*(cj1)*(x144)*(x148)))+(((IkReal(-1.00000000000000))*(x149)*(x151)))+(((x146)*(x155))));
00767 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00768 {
00769 continue;
00770 }
00771 }
00772 
00773 {
00774 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00775 vinfos[0].jointtype = 1;
00776 vinfos[0].foffset = j0;
00777 vinfos[0].indices[0] = _ij0[0];
00778 vinfos[0].indices[1] = _ij0[1];
00779 vinfos[0].maxsolutions = _nj0;
00780 vinfos[1].jointtype = 1;
00781 vinfos[1].foffset = j1;
00782 vinfos[1].indices[0] = _ij1[0];
00783 vinfos[1].indices[1] = _ij1[1];
00784 vinfos[1].maxsolutions = _nj1;
00785 vinfos[2].jointtype = 1;
00786 vinfos[2].foffset = j2;
00787 vinfos[2].indices[0] = _ij2[0];
00788 vinfos[2].indices[1] = _ij2[1];
00789 vinfos[2].maxsolutions = _nj2;
00790 vinfos[3].jointtype = 1;
00791 vinfos[3].foffset = j3;
00792 vinfos[3].indices[0] = _ij3[0];
00793 vinfos[3].indices[1] = _ij3[1];
00794 vinfos[3].maxsolutions = _nj3;
00795 vinfos[4].jointtype = 1;
00796 vinfos[4].foffset = j4;
00797 vinfos[4].indices[0] = _ij4[0];
00798 vinfos[4].indices[1] = _ij4[1];
00799 vinfos[4].maxsolutions = _nj4;
00800 std::vector<int> vfree(0);
00801 solutions.AddSolution(vinfos,vfree);
00802 }
00803 }
00804 }
00805 
00806 }
00807 
00808 }
00809 }
00810 }
00811 
00812 } else
00813 {
00814 IkReal x168=(py)*(py);
00815 IkReal x169=(px)*(px);
00816 IkReal x170=(pz)*(pz);
00817 IkReal x171=((r02)*(sj1));
00818 IkReal x172=((cj1)*(pz));
00819 IkReal x173=((IkReal(0.150000000000000))*(r00));
00820 IkReal x174=((IkReal(0.600000000000000))*(r02));
00821 IkReal x175=((cj0)*(px));
00822 IkReal x176=((r01)*(sj0));
00823 IkReal x177=((IkReal(1.00000000000000))*(cj1));
00824 IkReal x178=((py)*(sj0));
00825 IkReal x179=((py)*(r01));
00826 IkReal x180=((IkReal(0.150000000000000))*(sj1));
00827 IkReal x181=((IkReal(1.00000000000000))*(pz));
00828 IkReal x182=((px)*(sj1));
00829 IkReal x183=((IkReal(0.600000000000000))*(r00));
00830 IkReal x184=((cj0)*(r00));
00831 IkReal x185=((IkReal(0.0843750000000000))*(cj1));
00832 IkReal x186=((IkReal(2.00000000000000))*(pz));
00833 IkReal x187=((cj1)*(px));
00834 IkReal x188=((IkReal(1.00000000000000))*(px));
00835 IkReal x189=((IkReal(0.300000000000000))*(cj1));
00836 IkReal x190=((IkReal(0.0956250000000000))*(sj1));
00837 IkReal x191=((IkReal(1.00000000000000))*(sj1));
00838 IkReal x192=((cj0)*(pz));
00839 IkReal x193=((IkReal(0.150000000000000))*(cj1));
00840 IkReal x194=((IkReal(2.00000000000000))*(sj1));
00841 IkReal x195=((IkReal(2.00000000000000))*(cj1));
00842 IkReal x196=((IkReal(2.00000000000000))*(r00));
00843 IkReal x197=((IkReal(0.300000000000000))*(sj1));
00844 IkReal x198=((r02)*(x178));
00845 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
00846 evalcond[1]=((((IkReal(-1.00000000000000))*(sj0)*(x188)))+(((cj0)*(py))));
00847 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00848 evalcond[3]=((x171)+(((IkReal(-1.00000000000000))*(x177)*(x184)))+(((IkReal(-1.00000000000000))*(x176)*(x177))));
00849 evalcond[4]=((((IkReal(-1.00000000000000))*(x176)*(x191)))+(((IkReal(-1.00000000000000))*(r02)*(x177)))+(((IkReal(-1.00000000000000))*(x184)*(x191))));
00850 evalcond[5]=((((x184)*(x197)))+(((IkReal(-1.00000000000000))*(r02)*(x181)))+(((IkReal(-1.00000000000000))*(r00)*(x188)))+(((IkReal(0.0750000000000000))*(x184)))+(((r02)*(x189)))+(((x176)*(x197)))+(((IkReal(-1.00000000000000))*(x179)))+(((IkReal(0.0750000000000000))*(x176))));
00851 evalcond[6]=((((IkReal(-1.00000000000000))*(x181)*(x184)))+(((x184)*(x189)))+(((IkReal(-0.300000000000000))*(x171)))+(((IkReal(-1.00000000000000))*(x176)*(x181)))+(x198)+(((r02)*(x175)))+(((IkReal(-0.0750000000000000))*(r02)))+(((x176)*(x189))));
00852 evalcond[7]=((((IkReal(2.00000000000000))*(x172)*(x179)))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(x177)))+(((r02)*(x185)))+(((x178)*(x182)*(x196)))+(((x171)*(x178)*(x186)))+(((IkReal(-1.00000000000000))*(x173)*(x182)))+(((IkReal(-0.600000000000000))*(x179)))+(((IkReal(-0.150000000000000))*(x172)*(x176)))+(((IkReal(-1.00000000000000))*(pp)*(x184)*(x191)))+(((x168)*(x176)*(x194)))+(((x176)*(x190)))+(((IkReal(-1.00000000000000))*(pz)*(x174)))+(((x193)*(x198)))+(((x175)*(x179)*(x194)))+(((IkReal(-1.00000000000000))*(px)*(x183)))+(((x184)*(x190)))+(((r02)*(x170)*(x195)))+(((x171)*(x175)*(x186)))+(((px)*(x172)*(x196)))+(((IkReal(0.0450000000000000))*(x184)))+(((IkReal(-1.00000000000000))*(pp)*(x176)*(x191)))+(((IkReal(-1.00000000000000))*(cj0)*(x172)*(x173)))+(((IkReal(-1.00000000000000))*(x179)*(x180)))+(((IkReal(-0.150000000000000))*(pz)*(x171)))+(((x169)*(x184)*(x194)))+(((r02)*(x175)*(x193)))+(((IkReal(0.0450000000000000))*(x176))));
00853 evalcond[8]=((((IkReal(0.0956250000000000))*(x171)))+(((IkReal(0.600000000000000))*(pz)*(x176)))+(((x168)*(x176)*(x195)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-0.150000000000000))*(x171)*(x178)))+(((IkReal(-1.00000000000000))*(r00)*(x182)*(x186)))+(((IkReal(-1.00000000000000))*(x174)*(x178)))+(((x169)*(x184)*(x195)))+(((IkReal(-0.150000000000000))*(r02)*(x172)))+(((IkReal(-1.00000000000000))*(pp)*(x177)*(x184)))+(((IkReal(2.00000000000000))*(r02)*(x172)*(x175)))+(((IkReal(-1.00000000000000))*(x174)*(x175)))+(((IkReal(-1.00000000000000))*(pp)*(x176)*(x177)))+(((x183)*(x192)))+(((IkReal(-1.00000000000000))*(x176)*(x185)))+(((pp)*(x171)))+(((IkReal(-2.00000000000000))*(x170)*(x171)))+(((IkReal(-1.00000000000000))*(x184)*(x185)))+(((IkReal(-1.00000000000000))*(x173)*(x187)))+(((sj1)*(x173)*(x192)))+(((IkReal(-0.150000000000000))*(x171)*(x175)))+(((x175)*(x179)*(x195)))+(((IkReal(-1.00000000000000))*(sj1)*(x179)*(x186)))+(((IkReal(2.00000000000000))*(x172)*(x198)))+(((x178)*(x187)*(x196)))+(((pz)*(x176)*(x180)))+(((IkReal(-1.00000000000000))*(x179)*(x193))));
00854 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  )
00855 {
00856 {
00857 IkReal j3array[2], cj3array[2], sj3array[2];
00858 bool j3valid[2]={false};
00859 _nj3 = 2;
00860 IkReal x199=((IkReal(11.4095661394664))*(sj1));
00861 IkReal x200=((cj0)*(px));
00862 IkReal x201=((py)*(sj0));
00863 if( (((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((x199)*(x201)))+(((IkReal(2.85239153486660))*(x200)))+(((x199)*(x200)))+(((IkReal(2.85239153486660))*(x201)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1))))) < -1-IKFAST_SINCOS_THRESH || (((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((x199)*(x201)))+(((IkReal(2.85239153486660))*(x200)))+(((x199)*(x200)))+(((IkReal(2.85239153486660))*(x201)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1))))) > 1+IKFAST_SINCOS_THRESH )
00864     continue;
00865 IkReal x202=IKasin(((IkReal(0.357499739036614))+(((IkReal(-19.0159435657774))*(pp)))+(((x199)*(x201)))+(((IkReal(2.85239153486660))*(x200)))+(((x199)*(x200)))+(((IkReal(2.85239153486660))*(x201)))+(((IkReal(11.4095661394664))*(cj1)*(pz)))+(((IkReal(-0.855717460459981))*(sj1)))));
00866 j3array[0]=((IkReal(-1.34057673951805))+(((IkReal(-1.00000000000000))*(x202))));
00867 sj3array[0]=IKsin(j3array[0]);
00868 cj3array[0]=IKcos(j3array[0]);
00869 j3array[1]=((IkReal(1.80101591407174))+(x202));
00870 sj3array[1]=IKsin(j3array[1]);
00871 cj3array[1]=IKcos(j3array[1]);
00872 if( j3array[0] > IKPI )
00873 {
00874     j3array[0]-=IK2PI;
00875 }
00876 else if( j3array[0] < -IKPI )
00877 {    j3array[0]+=IK2PI;
00878 }
00879 j3valid[0] = true;
00880 if( j3array[1] > IKPI )
00881 {
00882     j3array[1]-=IK2PI;
00883 }
00884 else if( j3array[1] < -IKPI )
00885 {    j3array[1]+=IK2PI;
00886 }
00887 j3valid[1] = true;
00888 for(int ij3 = 0; ij3 < 2; ++ij3)
00889 {
00890 if( !j3valid[ij3] )
00891 {
00892     continue;
00893 }
00894 _ij3[0] = ij3; _ij3[1] = -1;
00895 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00896 {
00897 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00898 {
00899     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00900 }
00901 }
00902 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00903 {
00904 IkReal evalcond[1];
00905 IkReal x203=((IkReal(2.00000000000000))*(sj0));
00906 IkReal x204=((px)*(py));
00907 IkReal x205=((r00)*(sj0));
00908 IkReal x206=((cj0)*(r01));
00909 IkReal x207=((py)*(r00));
00910 IkReal x208=((IkReal(2.00000000000000))*(cj0));
00911 IkReal x209=((px)*(r01));
00912 IkReal x210=((IkReal(0.600000000000000))*(cj1));
00913 IkReal x211=((py)*(r02));
00914 IkReal x212=((IkReal(0.600000000000000))*(sj1));
00915 IkReal x213=((IkReal(0.0450000000000000))*(sj1));
00916 IkReal x214=((px)*(r02));
00917 evalcond[0]=((IkReal(0.114425000000000))+(((IkReal(0.0956250000000000))*(x206)))+(((IkReal(0.150000000000000))*(x207)))+(((IkReal(-0.0956250000000000))*(x205)))+(((IkReal(-1.00000000000000))*(pz)*(x208)*(x211)))+(((IkReal(-1.00000000000000))*(x205)*(x213)))+(((pz)*(x203)*(x214)))+(((r00)*(x203)*((px)*(px))))+(((IkReal(-0.150000000000000))*(x209)))+(((IkReal(-1.00000000000000))*(x209)*(x212)))+(((pp)*(x206)))+(((IkReal(-1.00000000000000))*(r00)*(x204)*(x208)))+(((cj0)*(x210)*(x211)))+(((IkReal(-1.00000000000000))*(pz)*(x206)*(x210)))+(((IkReal(0.0512000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(sj0)*(x210)*(x214)))+(((r01)*(x203)*(x204)))+(((IkReal(-1.00000000000000))*(pp)*(x205)))+(((x206)*(x213)))+(((IkReal(0.0120000000000000))*(IKsin(j3))))+(((pz)*(x205)*(x210)))+(((IkReal(-2.00000000000000))*(x206)*((py)*(py))))+(((x207)*(x212))));
00918 if( IKabs(evalcond[0]) > 0.000001  )
00919 {
00920 continue;
00921 }
00922 }
00923 
00924 {
00925 IkReal dummyeval[1];
00926 IkReal gconst10;
00927 gconst10=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00928 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
00929 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00930 {
00931 {
00932 IkReal dummyeval[1];
00933 IkReal gconst11;
00934 gconst11=IKsign(((IkReal(-0.108025000000000))+(((IkReal(-0.0512000000000000))*(cj3)))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))));
00935 dummyeval[0]=((IkReal(-16.8789062500000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
00936 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00937 {
00938 continue;
00939 
00940 } else
00941 {
00942 {
00943 IkReal j2array[1], cj2array[1], sj2array[1];
00944 bool j2valid[1]={false};
00945 _nj2 = 1;
00946 IkReal x215=((r02)*(sj0));
00947 IkReal x216=((IkReal(0.0800000000000000))*(sj1));
00948 IkReal x217=((cj3)*(px));
00949 IkReal x218=((cj0)*(r01));
00950 IkReal x219=((IkReal(0.0240000000000000))*(cj1));
00951 IkReal x220=((pz)*(sj3));
00952 IkReal x221=((IkReal(0.00600000000000000))*(cj1));
00953 IkReal x222=((IkReal(0.0750000000000000))*(sj1));
00954 IkReal x223=((py)*(sj0));
00955 IkReal x224=((IkReal(0.00562500000000000))*(cj1));
00956 IkReal x225=((r00)*(sj0));
00957 IkReal x226=((cj3)*(pz));
00958 IkReal x227=((IkReal(0.320000000000000))*(sj1));
00959 IkReal x228=((IkReal(0.0800000000000000))*(cj1));
00960 IkReal x229=((IkReal(0.0750000000000000))*(cj1));
00961 IkReal x230=((py)*(r00));
00962 IkReal x231=((IkReal(0.320000000000000))*(cj1));
00963 IkReal x232=((cj0)*(px));
00964 IkReal x233=((IkReal(0.00600000000000000))*(sj1));
00965 IkReal x234=((cj1)*(px)*(r01));
00966 IkReal x235=((cj0)*(py)*(r02));
00967 IkReal x236=((px)*(sj3)*(x216));
00968 if( IKabs(((gconst11)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x222)*(x225)))+(((IkReal(-1.00000000000000))*(pz)*(x231)))+(((pz)*(x218)*(x222)))+(((IkReal(-1.00000000000000))*(x223)*(x227)))+(((x215)*(x236)))+(((cj3)*(x233)))+(((x216)*(x218)*(x220)))+(((IkReal(-1.00000000000000))*(sj3)*(x221)*(x225)))+(((px)*(x215)*(x222)))+(((sj3)*(x228)*(x230)))+(((x229)*(x230)))+(((IkReal(-1.00000000000000))*(x216)*(x220)*(x225)))+(((IkReal(-1.00000000000000))*(cj3)*(x216)*(x223)))+(((IkReal(-1.00000000000000))*(x227)*(x232)))+(((sj3)*(x218)*(x221)))+(((IkReal(0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x228)))+(((IkReal(-1.00000000000000))*(x226)*(x228)))+(((IkReal(-1.00000000000000))*(x222)*(x235)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x235)))+(((IkReal(-1.00000000000000))*(cj0)*(x216)*(x217)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x229)))+(((IkReal(-1.00000000000000))*(x224)*(x225)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x218)*(x224))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((IkReal(0.0225000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x218)*(x227)))+(((x216)*(x225)*(x226)))+(((IkReal(-1.00000000000000))*(x222)*(x232)))+(((IkReal(0.00562500000000000))*(sj1)))+(((cj3)*(x221)*(x225)))+(((IkReal(-1.00000000000000))*(x222)*(x223)))+(((IkReal(-1.00000000000000))*(cj3)*(x218)*(x221)))+(((x219)*(x225)))+(((r01)*(x217)*(x228)))+(((sj3)*(x233)))+(((IkReal(-1.00000000000000))*(x218)*(x219)))+(((IkReal(-1.00000000000000))*(x230)*(x231)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x232)))+(((IkReal(-1.00000000000000))*(x215)*(x216)*(x217)))+(((px)*(r01)*(x231)))+(((IkReal(-1.00000000000000))*(x220)*(x228)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x223)))+(((x227)*(x235)))+(((IkReal(-1.00000000000000))*(pz)*(x229)))+(((IkReal(-1.00000000000000))*(x216)*(x218)*(x226)))+(((IkReal(-1.00000000000000))*(cj3)*(x228)*(x230)))+(((cj3)*(x216)*(x235)))+(((IkReal(-1.00000000000000))*(px)*(x215)*(x227)))+(((IkReal(0.0240000000000000))*(sj3)))+(((pz)*(x225)*(x227))))))) < IKFAST_ATAN2_MAGTHRESH )
00969     continue;
00970 j2array[0]=IKatan2(((gconst11)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x222)*(x225)))+(((IkReal(-1.00000000000000))*(pz)*(x231)))+(((pz)*(x218)*(x222)))+(((IkReal(-1.00000000000000))*(x223)*(x227)))+(((x215)*(x236)))+(((cj3)*(x233)))+(((x216)*(x218)*(x220)))+(((IkReal(-1.00000000000000))*(sj3)*(x221)*(x225)))+(((px)*(x215)*(x222)))+(((sj3)*(x228)*(x230)))+(((x229)*(x230)))+(((IkReal(-1.00000000000000))*(x216)*(x220)*(x225)))+(((IkReal(-1.00000000000000))*(cj3)*(x216)*(x223)))+(((IkReal(-1.00000000000000))*(x227)*(x232)))+(((sj3)*(x218)*(x221)))+(((IkReal(0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x228)))+(((IkReal(-1.00000000000000))*(x226)*(x228)))+(((IkReal(-1.00000000000000))*(x222)*(x235)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x235)))+(((IkReal(-1.00000000000000))*(cj0)*(x216)*(x217)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x229)))+(((IkReal(-1.00000000000000))*(x224)*(x225)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x218)*(x224)))))), ((gconst11)*(((IkReal(0.0225000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x218)*(x227)))+(((x216)*(x225)*(x226)))+(((IkReal(-1.00000000000000))*(x222)*(x232)))+(((IkReal(0.00562500000000000))*(sj1)))+(((cj3)*(x221)*(x225)))+(((IkReal(-1.00000000000000))*(x222)*(x223)))+(((IkReal(-1.00000000000000))*(cj3)*(x218)*(x221)))+(((x219)*(x225)))+(((r01)*(x217)*(x228)))+(((sj3)*(x233)))+(((IkReal(-1.00000000000000))*(x218)*(x219)))+(((IkReal(-1.00000000000000))*(x230)*(x231)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x232)))+(((IkReal(-1.00000000000000))*(x215)*(x216)*(x217)))+(((px)*(r01)*(x231)))+(((IkReal(-1.00000000000000))*(x220)*(x228)))+(((IkReal(-1.00000000000000))*(sj3)*(x216)*(x223)))+(((x227)*(x235)))+(((IkReal(-1.00000000000000))*(pz)*(x229)))+(((IkReal(-1.00000000000000))*(x216)*(x218)*(x226)))+(((IkReal(-1.00000000000000))*(cj3)*(x228)*(x230)))+(((cj3)*(x216)*(x235)))+(((IkReal(-1.00000000000000))*(px)*(x215)*(x227)))+(((IkReal(0.0240000000000000))*(sj3)))+(((pz)*(x225)*(x227)))))));
00971 sj2array[0]=IKsin(j2array[0]);
00972 cj2array[0]=IKcos(j2array[0]);
00973 if( j2array[0] > IKPI )
00974 {
00975     j2array[0]-=IK2PI;
00976 }
00977 else if( j2array[0] < -IKPI )
00978 {    j2array[0]+=IK2PI;
00979 }
00980 j2valid[0] = true;
00981 for(int ij2 = 0; ij2 < 1; ++ij2)
00982 {
00983 if( !j2valid[ij2] )
00984 {
00985     continue;
00986 }
00987 _ij2[0] = ij2; _ij2[1] = -1;
00988 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00989 {
00990 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00991 {
00992     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00993 }
00994 }
00995 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00996 {
00997 IkReal evalcond[4];
00998 IkReal x237=IKcos(j2);
00999 IkReal x238=IKsin(j2);
01000 IkReal x239=((IkReal(0.0800000000000000))*(sj3));
01001 IkReal x240=((cj0)*(r01));
01002 IkReal x241=((IkReal(1.00000000000000))*(px));
01003 IkReal x242=((py)*(sj1));
01004 IkReal x243=((cj0)*(r02));
01005 IkReal x244=((IkReal(0.0750000000000000))*(cj1));
01006 IkReal x245=((r02)*(sj0));
01007 IkReal x246=((IkReal(0.0750000000000000))*(sj1));
01008 IkReal x247=((cj1)*(pz));
01009 IkReal x248=((r00)*(sj0));
01010 IkReal x249=((IkReal(0.0800000000000000))*(cj3));
01011 IkReal x250=((pz)*(sj1));
01012 IkReal x251=((IkReal(1.00000000000000))*(sj0));
01013 IkReal x252=((cj1)*(py));
01014 IkReal x253=((IkReal(0.320000000000000))*(x237));
01015 IkReal x254=((IkReal(0.0750000000000000))*(x238));
01016 IkReal x255=((IkReal(0.320000000000000))*(x238));
01017 IkReal x256=((IkReal(0.0750000000000000))*(x237));
01018 IkReal x257=((sj1)*(x248));
01019 IkReal x258=((x237)*(x249));
01020 IkReal x259=((x238)*(x239));
01021 IkReal x260=((x237)*(x239));
01022 IkReal x261=((x238)*(x249));
01023 IkReal x262=((x259)+(x254));
01024 IkReal x263=((x258)+(x253));
01025 IkReal x264=((x255)+(x256)+(x261)+(x260));
01026 evalcond[0]=((x250)+(((IkReal(-1.00000000000000))*(x251)*(x252)))+(x244)+(((IkReal(-1.00000000000000))*(x262)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x241)))+(x263));
01027 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x247)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x241)))+(((IkReal(-1.00000000000000))*(x242)*(x251)))+(x246)+(x264));
01028 evalcond[2]=((((x244)*(x248)))+(((IkReal(-1.00000000000000))*(x240)*(x244)))+(((IkReal(-1.00000000000000))*(x240)*(x250)))+(((IkReal(-1.00000000000000))*(r00)*(x252)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(sj1)*(x241)*(x245)))+(((x248)*(x250)))+(((x242)*(x243)))+(((IkReal(-1.00000000000000))*(x262)))+(x263));
01029 evalcond[3]=((((IkReal(-1.00000000000000))*(x240)*(x247)))+(((x247)*(x248)))+(((IkReal(-1.00000000000000))*(cj1)*(x241)*(x245)))+(((x243)*(x252)))+(((r00)*(x242)))+(((IkReal(-1.00000000000000))*(x264)))+(((IkReal(-0.300000000000000))*(x248)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x241)))+(((IkReal(0.300000000000000))*(x240)))+(((x240)*(x246)))+(((IkReal(-1.00000000000000))*(x246)*(x248))));
01030 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01031 {
01032 continue;
01033 }
01034 }
01035 
01036 {
01037 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01038 vinfos[0].jointtype = 1;
01039 vinfos[0].foffset = j0;
01040 vinfos[0].indices[0] = _ij0[0];
01041 vinfos[0].indices[1] = _ij0[1];
01042 vinfos[0].maxsolutions = _nj0;
01043 vinfos[1].jointtype = 1;
01044 vinfos[1].foffset = j1;
01045 vinfos[1].indices[0] = _ij1[0];
01046 vinfos[1].indices[1] = _ij1[1];
01047 vinfos[1].maxsolutions = _nj1;
01048 vinfos[2].jointtype = 1;
01049 vinfos[2].foffset = j2;
01050 vinfos[2].indices[0] = _ij2[0];
01051 vinfos[2].indices[1] = _ij2[1];
01052 vinfos[2].maxsolutions = _nj2;
01053 vinfos[3].jointtype = 1;
01054 vinfos[3].foffset = j3;
01055 vinfos[3].indices[0] = _ij3[0];
01056 vinfos[3].indices[1] = _ij3[1];
01057 vinfos[3].maxsolutions = _nj3;
01058 vinfos[4].jointtype = 1;
01059 vinfos[4].foffset = j4;
01060 vinfos[4].indices[0] = _ij4[0];
01061 vinfos[4].indices[1] = _ij4[1];
01062 vinfos[4].maxsolutions = _nj4;
01063 std::vector<int> vfree(0);
01064 solutions.AddSolution(vinfos,vfree);
01065 }
01066 }
01067 }
01068 
01069 }
01070 
01071 }
01072 
01073 } else
01074 {
01075 {
01076 IkReal j2array[1], cj2array[1], sj2array[1];
01077 bool j2valid[1]={false};
01078 _nj2 = 1;
01079 IkReal x265=((IkReal(0.0800000000000000))*(cj1));
01080 IkReal x266=((cj0)*(px));
01081 IkReal x267=((py)*(sj0));
01082 IkReal x268=((IkReal(0.320000000000000))*(sj1));
01083 IkReal x269=((IkReal(0.00600000000000000))*(cj3));
01084 IkReal x270=((pz)*(sj3));
01085 IkReal x271=((IkReal(0.0750000000000000))*(cj1));
01086 IkReal x272=((IkReal(0.0800000000000000))*(sj1));
01087 IkReal x273=((IkReal(0.0750000000000000))*(sj1));
01088 IkReal x274=((IkReal(0.00600000000000000))*(sj3));
01089 IkReal x275=((cj3)*(pz));
01090 IkReal x276=((IkReal(0.320000000000000))*(cj1));
01091 if( IKabs(((gconst10)*(((IkReal(-0.0960000000000000))+(((cj3)*(x266)*(x272)))+(((cj3)*(x267)*(x272)))+(((x266)*(x268)))+(((IkReal(-1.00000000000000))*(sj3)*(x265)*(x266)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x265)*(x267)))+(((x270)*(x272)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x267)*(x271)))+(((pz)*(x273)))+(((IkReal(-1.00000000000000))*(x266)*(x271)))+(((pz)*(x276)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x269)))+(((x265)*(x275)))+(((x267)*(x268)))+(((cj1)*(x274))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((IkReal(-0.0225000000000000))+(((sj3)*(x266)*(x272)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x267)*(x273)))+(((x267)*(x276)))+(((x266)*(x276)))+(((IkReal(-1.00000000000000))*(pz)*(x268)))+(((x266)*(x273)))+(((x265)*(x270)))+(((IkReal(-1.00000000000000))*(sj1)*(x274)))+(((cj3)*(x265)*(x267)))+(((sj3)*(x267)*(x272)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((cj3)*(x265)*(x266)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x272)*(x275)))+(((IkReal(-1.00000000000000))*(cj1)*(x269)))+(((pz)*(x271))))))) < IKFAST_ATAN2_MAGTHRESH )
01092     continue;
01093 j2array[0]=IKatan2(((gconst10)*(((IkReal(-0.0960000000000000))+(((cj3)*(x266)*(x272)))+(((cj3)*(x267)*(x272)))+(((x266)*(x268)))+(((IkReal(-1.00000000000000))*(sj3)*(x265)*(x266)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x265)*(x267)))+(((x270)*(x272)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x267)*(x271)))+(((pz)*(x273)))+(((IkReal(-1.00000000000000))*(x266)*(x271)))+(((pz)*(x276)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x269)))+(((x265)*(x275)))+(((x267)*(x268)))+(((cj1)*(x274)))))), ((gconst10)*(((IkReal(-0.0225000000000000))+(((sj3)*(x266)*(x272)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x267)*(x273)))+(((x267)*(x276)))+(((x266)*(x276)))+(((IkReal(-1.00000000000000))*(pz)*(x268)))+(((x266)*(x273)))+(((x265)*(x270)))+(((IkReal(-1.00000000000000))*(sj1)*(x274)))+(((cj3)*(x265)*(x267)))+(((sj3)*(x267)*(x272)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((cj3)*(x265)*(x266)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x272)*(x275)))+(((IkReal(-1.00000000000000))*(cj1)*(x269)))+(((pz)*(x271)))))));
01094 sj2array[0]=IKsin(j2array[0]);
01095 cj2array[0]=IKcos(j2array[0]);
01096 if( j2array[0] > IKPI )
01097 {
01098     j2array[0]-=IK2PI;
01099 }
01100 else if( j2array[0] < -IKPI )
01101 {    j2array[0]+=IK2PI;
01102 }
01103 j2valid[0] = true;
01104 for(int ij2 = 0; ij2 < 1; ++ij2)
01105 {
01106 if( !j2valid[ij2] )
01107 {
01108     continue;
01109 }
01110 _ij2[0] = ij2; _ij2[1] = -1;
01111 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01112 {
01113 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01114 {
01115     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01116 }
01117 }
01118 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01119 {
01120 IkReal evalcond[4];
01121 IkReal x277=IKcos(j2);
01122 IkReal x278=IKsin(j2);
01123 IkReal x279=((IkReal(0.0800000000000000))*(sj3));
01124 IkReal x280=((cj0)*(r01));
01125 IkReal x281=((IkReal(1.00000000000000))*(px));
01126 IkReal x282=((py)*(sj1));
01127 IkReal x283=((cj0)*(r02));
01128 IkReal x284=((IkReal(0.0750000000000000))*(cj1));
01129 IkReal x285=((r02)*(sj0));
01130 IkReal x286=((IkReal(0.0750000000000000))*(sj1));
01131 IkReal x287=((cj1)*(pz));
01132 IkReal x288=((r00)*(sj0));
01133 IkReal x289=((IkReal(0.0800000000000000))*(cj3));
01134 IkReal x290=((pz)*(sj1));
01135 IkReal x291=((IkReal(1.00000000000000))*(sj0));
01136 IkReal x292=((cj1)*(py));
01137 IkReal x293=((IkReal(0.320000000000000))*(x277));
01138 IkReal x294=((IkReal(0.0750000000000000))*(x278));
01139 IkReal x295=((IkReal(0.320000000000000))*(x278));
01140 IkReal x296=((IkReal(0.0750000000000000))*(x277));
01141 IkReal x297=((sj1)*(x288));
01142 IkReal x298=((x277)*(x289));
01143 IkReal x299=((x278)*(x279));
01144 IkReal x300=((x277)*(x279));
01145 IkReal x301=((x278)*(x289));
01146 IkReal x302=((x299)+(x294));
01147 IkReal x303=((x298)+(x293));
01148 IkReal x304=((x300)+(x301)+(x295)+(x296));
01149 evalcond[0]=((((IkReal(-1.00000000000000))*(x302)))+(x284)+(x303)+(((IkReal(-1.00000000000000))*(x291)*(x292)))+(x290)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x281))));
01150 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x282)*(x291)))+(x286)+(x304)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x281)))+(((IkReal(-1.00000000000000))*(x287))));
01151 evalcond[2]=((((IkReal(-1.00000000000000))*(x302)))+(((x288)*(x290)))+(x303)+(((x282)*(x283)))+(((IkReal(-1.00000000000000))*(sj1)*(x281)*(x285)))+(((IkReal(-1.00000000000000))*(x280)*(x284)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x280)*(x290)))+(((x284)*(x288)))+(((IkReal(-1.00000000000000))*(r00)*(x292))));
01152 evalcond[3]=((((x280)*(x286)))+(((IkReal(-1.00000000000000))*(x280)*(x287)))+(((IkReal(-1.00000000000000))*(x286)*(x288)))+(((IkReal(-1.00000000000000))*(x304)))+(((IkReal(0.300000000000000))*(x280)))+(((x283)*(x292)))+(((r00)*(x282)))+(((IkReal(-1.00000000000000))*(cj1)*(x281)*(x285)))+(((x287)*(x288)))+(((IkReal(-0.300000000000000))*(x288)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x281))));
01153 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01154 {
01155 continue;
01156 }
01157 }
01158 
01159 {
01160 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01161 vinfos[0].jointtype = 1;
01162 vinfos[0].foffset = j0;
01163 vinfos[0].indices[0] = _ij0[0];
01164 vinfos[0].indices[1] = _ij0[1];
01165 vinfos[0].maxsolutions = _nj0;
01166 vinfos[1].jointtype = 1;
01167 vinfos[1].foffset = j1;
01168 vinfos[1].indices[0] = _ij1[0];
01169 vinfos[1].indices[1] = _ij1[1];
01170 vinfos[1].maxsolutions = _nj1;
01171 vinfos[2].jointtype = 1;
01172 vinfos[2].foffset = j2;
01173 vinfos[2].indices[0] = _ij2[0];
01174 vinfos[2].indices[1] = _ij2[1];
01175 vinfos[2].maxsolutions = _nj2;
01176 vinfos[3].jointtype = 1;
01177 vinfos[3].foffset = j3;
01178 vinfos[3].indices[0] = _ij3[0];
01179 vinfos[3].indices[1] = _ij3[1];
01180 vinfos[3].maxsolutions = _nj3;
01181 vinfos[4].jointtype = 1;
01182 vinfos[4].foffset = j4;
01183 vinfos[4].indices[0] = _ij4[0];
01184 vinfos[4].indices[1] = _ij4[1];
01185 vinfos[4].maxsolutions = _nj4;
01186 std::vector<int> vfree(0);
01187 solutions.AddSolution(vinfos,vfree);
01188 }
01189 }
01190 }
01191 
01192 }
01193 
01194 }
01195 }
01196 }
01197 
01198 } else
01199 {
01200 if( 1 )
01201 {
01202 continue;
01203 
01204 } else
01205 {
01206 }
01207 }
01208 }
01209 }
01210 
01211 } else
01212 {
01213 {
01214 IkReal j3array[1], cj3array[1], sj3array[1];
01215 bool j3valid[1]={false};
01216 _nj3 = 1;
01217 IkReal x305=((r01)*(sj0));
01218 IkReal x306=((cj0)*(r00));
01219 IkReal x307=((IkReal(12800.0000000000))*(pz));
01220 IkReal x308=((IkReal(900.000000000000))*(cj1));
01221 IkReal x309=((IkReal(3000.00000000000))*(pz));
01222 IkReal x310=((IkReal(3840.00000000000))*(sj1));
01223 IkReal x311=((IkReal(900.000000000000))*(sj1));
01224 IkReal x312=((px)*(r00));
01225 IkReal x313=((IkReal(3840.00000000000))*(cj1));
01226 IkReal x314=((py)*(r01));
01227 IkReal x315=((py)*(r02)*(sj0));
01228 IkReal x316=((cj0)*(px)*(r02));
01229 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(r02)*(x307)))+(((x306)*(x310)))+(((IkReal(-1.00000000000000))*(r02)*(x311)))+(((x305)*(x310)))+(((IkReal(-1.00000000000000))*(x305)*(x309)))+(((IkReal(3000.00000000000))*(x315)))+(((IkReal(-12800.0000000000))*(x314)))+(((x305)*(x308)))+(((IkReal(3000.00000000000))*(x316)))+(((IkReal(-12800.0000000000))*(x312)))+(((IkReal(960.000000000000))*(x306)))+(((IkReal(-225.000000000000))*(r02)))+(((r02)*(x313)))+(((x306)*(x308)))+(((IkReal(960.000000000000))*(x305)))+(((IkReal(-1.00000000000000))*(x306)*(x309)))+(((IkReal(-240.000000000000))*(cj4))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(x306)*(x307)))+(((IkReal(-1.00000000000000))*(x305)*(x307)))+(((IkReal(-960.000000000000))*(r02)))+(((IkReal(3000.00000000000))*(x314)))+(((x305)*(x313)))+(((IkReal(-225.000000000000))*(x306)))+(((IkReal(-1.00000000000000))*(r02)*(x308)))+(((IkReal(3000.00000000000))*(x312)))+(((IkReal(-225.000000000000))*(x305)))+(((IkReal(12800.0000000000))*(x316)))+(((r02)*(x309)))+(((IkReal(12800.0000000000))*(x315)))+(((IkReal(-1.00000000000000))*(r02)*(x310)))+(((IkReal(-1024.00000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x305)*(x311)))+(((IkReal(-1.00000000000000))*(x306)*(x311)))+(((x306)*(x313))))))) < IKFAST_ATAN2_MAGTHRESH )
01230     continue;
01231 j3array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(r02)*(x307)))+(((x306)*(x310)))+(((IkReal(-1.00000000000000))*(r02)*(x311)))+(((x305)*(x310)))+(((IkReal(-1.00000000000000))*(x305)*(x309)))+(((IkReal(3000.00000000000))*(x315)))+(((IkReal(-12800.0000000000))*(x314)))+(((x305)*(x308)))+(((IkReal(3000.00000000000))*(x316)))+(((IkReal(-12800.0000000000))*(x312)))+(((IkReal(960.000000000000))*(x306)))+(((IkReal(-225.000000000000))*(r02)))+(((r02)*(x313)))+(((x306)*(x308)))+(((IkReal(960.000000000000))*(x305)))+(((IkReal(-1.00000000000000))*(x306)*(x309)))+(((IkReal(-240.000000000000))*(cj4)))))), ((gconst1)*(((((IkReal(-1.00000000000000))*(x306)*(x307)))+(((IkReal(-1.00000000000000))*(x305)*(x307)))+(((IkReal(-960.000000000000))*(r02)))+(((IkReal(3000.00000000000))*(x314)))+(((x305)*(x313)))+(((IkReal(-225.000000000000))*(x306)))+(((IkReal(-1.00000000000000))*(r02)*(x308)))+(((IkReal(3000.00000000000))*(x312)))+(((IkReal(-225.000000000000))*(x305)))+(((IkReal(12800.0000000000))*(x316)))+(((r02)*(x309)))+(((IkReal(12800.0000000000))*(x315)))+(((IkReal(-1.00000000000000))*(r02)*(x310)))+(((IkReal(-1024.00000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x305)*(x311)))+(((IkReal(-1.00000000000000))*(x306)*(x311)))+(((x306)*(x313)))))));
01232 sj3array[0]=IKsin(j3array[0]);
01233 cj3array[0]=IKcos(j3array[0]);
01234 if( j3array[0] > IKPI )
01235 {
01236     j3array[0]-=IK2PI;
01237 }
01238 else if( j3array[0] < -IKPI )
01239 {    j3array[0]+=IK2PI;
01240 }
01241 j3valid[0] = true;
01242 for(int ij3 = 0; ij3 < 1; ++ij3)
01243 {
01244 if( !j3valid[ij3] )
01245 {
01246     continue;
01247 }
01248 _ij3[0] = ij3; _ij3[1] = -1;
01249 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01250 {
01251 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01252 {
01253     j3valid[iij3]=false; _ij3[1] = iij3; break; 
01254 }
01255 }
01256 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01257 {
01258 IkReal evalcond[4];
01259 IkReal x317=IKcos(j3);
01260 IkReal x318=IKsin(j3);
01261 IkReal x319=((r01)*(sj0));
01262 IkReal x320=((IkReal(0.300000000000000))*(r02));
01263 IkReal x321=((r00)*(sj0));
01264 IkReal x322=((py)*(sj0));
01265 IkReal x323=((IkReal(0.600000000000000))*(cj1));
01266 IkReal x324=((IkReal(0.150000000000000))*(px));
01267 IkReal x325=((IkReal(0.320000000000000))*(cj4));
01268 IkReal x326=((IkReal(1.00000000000000))*(pz));
01269 IkReal x327=((py)*(r00));
01270 IkReal x328=((IkReal(0.300000000000000))*(cj1));
01271 IkReal x329=((IkReal(1.00000000000000))*(pp));
01272 IkReal x330=((cj0)*(r00));
01273 IkReal x331=((IkReal(0.0450000000000000))*(sj1));
01274 IkReal x332=((IkReal(0.600000000000000))*(sj1));
01275 IkReal x333=((IkReal(0.0750000000000000))*(cj4));
01276 IkReal x334=((cj0)*(r01));
01277 IkReal x335=((IkReal(2.00000000000000))*(pz));
01278 IkReal x336=((cj0)*(px));
01279 IkReal x337=((IkReal(0.300000000000000))*(sj1));
01280 IkReal x338=((IkReal(2.00000000000000))*(px)*(py));
01281 IkReal x339=((IkReal(0.0120000000000000))*(x318));
01282 IkReal x340=((IkReal(0.0512000000000000))*(x317));
01283 IkReal x341=((cj0)*(py)*(r02));
01284 IkReal x342=((px)*(r02)*(sj0));
01285 evalcond[0]=((IkReal(0.0188000000000000))+(((IkReal(-1.00000000000000))*(x329)))+(((pz)*(x323)))+(((cj0)*(x324)))+(((IkReal(0.150000000000000))*(x322)))+(((IkReal(-1.00000000000000))*(x331)))+(x339)+(((x332)*(x336)))+(x340)+(((x322)*(x332))));
01286 evalcond[1]=((((IkReal(-1.00000000000000))*(py)*(r01)))+(((IkReal(-1.00000000000000))*(r02)*(x326)))+(((IkReal(0.0750000000000000))*(x319)))+(((cj1)*(x320)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((x330)*(x337)))+(((IkReal(0.0750000000000000))*(x330)))+(((IkReal(-1.00000000000000))*(x318)*(x325)))+(((x317)*(x333)))+(((x319)*(x337))));
01287 evalcond[2]=((((IkReal(-1.00000000000000))*(x318)*(x333)))+(((x319)*(x328)))+(((IkReal(-0.0800000000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(sj1)*(x320)))+(((IkReal(-1.00000000000000))*(x326)*(x330)))+(((r02)*(x322)))+(((IkReal(-0.0750000000000000))*(r02)))+(((r02)*(x336)))+(((IkReal(-1.00000000000000))*(x319)*(x326)))+(((x328)*(x330)))+(((IkReal(-1.00000000000000))*(x317)*(x325))));
01288 evalcond[3]=((((IkReal(0.150000000000000))*(x327)))+(((x335)*(x342)))+(((IkReal(2.00000000000000))*(x321)*((px)*(px))))+(((IkReal(-2.00000000000000))*(x334)*((py)*(py))))+(((pp)*(x334)))+(((IkReal(-1.00000000000000))*(sj4)*(x340)))+(((IkReal(-0.0956250000000000))*(x321)))+(((IkReal(-1.00000000000000))*(x321)*(x329)))+(((IkReal(-1.00000000000000))*(x321)*(x331)))+(((pz)*(x321)*(x323)))+(((x323)*(x341)))+(((x331)*(x334)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x332)))+(((x327)*(x332)))+(((IkReal(0.0956250000000000))*(x334)))+(((IkReal(-0.114425000000000))*(sj4)))+(((IkReal(-1.00000000000000))*(pz)*(x323)*(x334)))+(((IkReal(-1.00000000000000))*(x335)*(x341)))+(((IkReal(-1.00000000000000))*(sj4)*(x339)))+(((IkReal(-1.00000000000000))*(x323)*(x342)))+(((IkReal(-2.00000000000000))*(x327)*(x336)))+(((IkReal(-1.00000000000000))*(r01)*(x324)))+(((x319)*(x338))));
01289 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01290 {
01291 continue;
01292 }
01293 }
01294 
01295 {
01296 IkReal dummyeval[1];
01297 IkReal gconst2;
01298 gconst2=IKsign(((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3))))));
01299 dummyeval[0]=((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3)))));
01300 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01301 {
01302 {
01303 IkReal dummyeval[1];
01304 IkReal gconst3;
01305 IkReal x343=((IkReal(0.0800000000000000))*(cj4));
01306 gconst3=IKsign(((((IkReal(0.320000000000000))*(cj3)*(cj4)))+(((IkReal(0.0750000000000000))*(cj4)*(sj3)))+(((x343)*((cj3)*(cj3))))+(((x343)*((sj3)*(sj3))))));
01307 IkReal x344=((IkReal(1.06666666666667))*(cj4));
01308 dummyeval[0]=((((IkReal(4.26666666666667))*(cj3)*(cj4)))+(((x344)*((sj3)*(sj3))))+(((x344)*((cj3)*(cj3))))+(((cj4)*(sj3))));
01309 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01310 {
01311 {
01312 IkReal evalcond[11];
01313 IkReal x345=((IkReal(0.0512000000000000))*(cj3));
01314 IkReal x346=((IkReal(0.0120000000000000))*(sj3));
01315 IkReal x347=(py)*(py);
01316 IkReal x348=(px)*(px);
01317 IkReal x349=(pz)*(pz);
01318 IkReal x350=((r01)*(sj0));
01319 IkReal x351=((py)*(r00));
01320 IkReal x352=((pz)*(sj1));
01321 IkReal x353=((py)*(r01));
01322 IkReal x354=((px)*(sj0));
01323 IkReal x355=((IkReal(0.600000000000000))*(r02));
01324 IkReal x356=((IkReal(0.150000000000000))*(cj1));
01325 IkReal x357=((cj0)*(sj1));
01326 IkReal x358=((IkReal(0.150000000000000))*(px));
01327 IkReal x359=((IkReal(2.00000000000000))*(cj1));
01328 IkReal x360=((cj0)*(r01));
01329 IkReal x361=((r02)*(sj1));
01330 IkReal x362=((px)*(r00));
01331 IkReal x363=((IkReal(0.300000000000000))*(r00));
01332 IkReal x364=((IkReal(1.00000000000000))*(pz));
01333 IkReal x365=((r00)*(sj1));
01334 IkReal x366=((cj0)*(r00));
01335 IkReal x367=((cj0)*(cj1));
01336 IkReal x368=((IkReal(1.00000000000000))*(sj1));
01337 IkReal x369=((IkReal(0.0956250000000000))*(r00));
01338 IkReal x370=((IkReal(0.600000000000000))*(pz));
01339 IkReal x371=((IkReal(0.600000000000000))*(sj1));
01340 IkReal x372=((IkReal(2.00000000000000))*(px));
01341 IkReal x373=((IkReal(2.00000000000000))*(sj1));
01342 IkReal x374=((IkReal(0.150000000000000))*(sj1));
01343 IkReal x375=((cj1)*(r02));
01344 IkReal x376=((cj0)*(px));
01345 IkReal x377=((IkReal(0.0843750000000000))*(cj1));
01346 IkReal x378=((py)*(sj0));
01347 IkReal x379=((pz)*(r02));
01348 IkReal x380=((IkReal(1.00000000000000))*(cj1));
01349 IkReal x381=((cj0)*(py));
01350 IkReal x382=((r00)*(sj0));
01351 IkReal x383=((r02)*(x378));
01352 IkReal x384=((pp)*(x380));
01353 IkReal x385=((IkReal(1.00000000000000))*(pp)*(r00));
01354 IkReal x386=((x346)+(x345));
01355 IkReal x387=((IkReal(2.00000000000000))*(r00)*(x348));
01356 IkReal x388=((cj0)*(x372)*(x379));
01357 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
01358 evalcond[1]=((x381)+(((IkReal(-1.00000000000000))*(x354))));
01359 evalcond[2]=((IkReal(-1.00000000000000))+(x360)+(((IkReal(-1.00000000000000))*(x382))));
01360 evalcond[3]=((((IkReal(-1.00000000000000))*(x366)*(x380)))+(x361)+(((IkReal(-1.00000000000000))*(x350)*(x380))));
01361 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x357)))+(((IkReal(-1.00000000000000))*(x375)))+(((IkReal(-1.00000000000000))*(x350)*(x368))));
01362 evalcond[5]=((IkReal(0.0188000000000000))+(x386)+(((IkReal(0.600000000000000))*(px)*(x357)))+(((IkReal(0.150000000000000))*(x378)))+(((IkReal(-1.00000000000000))*(pp)))+(((x371)*(x378)))+(((cj0)*(x358)))+(((cj1)*(x370)))+(((IkReal(-0.0450000000000000))*(sj1))));
01363 evalcond[6]=((((IkReal(0.300000000000000))*(x375)))+(((x357)*(x363)))+(((IkReal(0.0750000000000000))*(x350)))+(((IkReal(-1.00000000000000))*(r02)*(x364)))+(((IkReal(-1.00000000000000))*(x353)))+(((IkReal(0.300000000000000))*(sj1)*(x350)))+(((IkReal(0.0750000000000000))*(x366)))+(((IkReal(-1.00000000000000))*(x362))));
01364 evalcond[7]=((((IkReal(-1.00000000000000))*(x350)*(x364)))+(x383)+(((x363)*(x367)))+(((IkReal(0.300000000000000))*(cj1)*(x350)))+(((r02)*(x376)))+(((IkReal(-0.300000000000000))*(x361)))+(((IkReal(-1.00000000000000))*(x364)*(x366)))+(((IkReal(-0.0750000000000000))*(r02))));
01365 evalcond[8]=((IkReal(-0.114425000000000))+(((IkReal(-2.00000000000000))*(x379)*(x381)))+(((IkReal(-2.00000000000000))*(x347)*(x360)))+(((IkReal(-1.00000000000000))*(sj0)*(x369)))+(((x351)*(x371)))+(((IkReal(-1.00000000000000))*(x386)))+(((IkReal(-1.00000000000000))*(cj1)*(x354)*(x355)))+(((IkReal(0.150000000000000))*(x351)))+(((IkReal(-1.00000000000000))*(pp)*(x382)))+(((py)*(x350)*(x372)))+(((IkReal(-0.0450000000000000))*(sj0)*(x365)))+(((py)*(x355)*(x367)))+(((cj1)*(x370)*(x382)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x371)))+(((IkReal(-1.00000000000000))*(cj0)*(x351)*(x372)))+(((IkReal(-1.00000000000000))*(cj1)*(x360)*(x370)))+(((IkReal(0.0956250000000000))*(x360)))+(((IkReal(0.0450000000000000))*(r01)*(x357)))+(((IkReal(-1.00000000000000))*(r01)*(x358)))+(((IkReal(2.00000000000000))*(x354)*(x379)))+(((IkReal(2.00000000000000))*(x348)*(x382)))+(((pp)*(x360))));
01366 evalcond[9]=((((IkReal(-1.00000000000000))*(x357)*(x385)))+(((x353)*(x357)*(x372)))+(((cj0)*(r02)*(x352)*(x372)))+(((x357)*(x387)))+(((r02)*(x356)*(x376)))+(((IkReal(-0.150000000000000))*(r02)*(x352)))+(((IkReal(-1.00000000000000))*(x358)*(x365)))+(((IkReal(0.0450000000000000))*(x350)))+(((x347)*(x350)*(x373)))+(((IkReal(-0.600000000000000))*(x362)))+(((IkReal(-1.00000000000000))*(pp)*(x375)))+(((x356)*(x383)))+(((pz)*(x353)*(x359)))+(((IkReal(0.0843750000000000))*(x375)))+(((IkReal(-1.00000000000000))*(pz)*(x350)*(x356)))+(((r02)*(x349)*(x359)))+(((IkReal(0.0956250000000000))*(sj1)*(x350)))+(((IkReal(2.00000000000000))*(x352)*(x383)))+(((IkReal(-1.00000000000000))*(pz)*(x356)*(x366)))+(((IkReal(-0.600000000000000))*(x353)))+(((IkReal(-1.00000000000000))*(x353)*(x374)))+(((x357)*(x369)))+(((x351)*(x354)*(x373)))+(((IkReal(-1.00000000000000))*(pz)*(x355)))+(((IkReal(-1.00000000000000))*(pp)*(x350)*(x368)))+(((IkReal(0.0450000000000000))*(x366)))+(((pz)*(x359)*(x362))));
01367 evalcond[10]=((((IkReal(-1.00000000000000))*(x356)*(x379)))+(((IkReal(-1.00000000000000))*(x350)*(x384)))+(((x347)*(x350)*(x359)))+(((IkReal(-1.00000000000000))*(x366)*(x384)))+(((IkReal(0.150000000000000))*(x352)*(x366)))+(((x366)*(x370)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x355)*(x378)))+(((x353)*(x359)*(x376)))+(((IkReal(-1.00000000000000))*(x356)*(x362)))+(((IkReal(-2.00000000000000))*(x349)*(x361)))+(((x359)*(x378)*(x379)))+(((x359)*(x376)*(x379)))+(((x351)*(x354)*(x359)))+(((x348)*(x359)*(x366)))+(((IkReal(-1.00000000000000))*(x350)*(x377)))+(((IkReal(-2.00000000000000))*(x352)*(x362)))+(((IkReal(-1.00000000000000))*(x353)*(x356)))+(((pp)*(x361)))+(((IkReal(-1.00000000000000))*(r02)*(x357)*(x358)))+(((IkReal(0.0956250000000000))*(x361)))+(((IkReal(-1.00000000000000))*(x366)*(x377)))+(((IkReal(-0.150000000000000))*(x361)*(x378)))+(((x350)*(x370)))+(((IkReal(-2.00000000000000))*(x352)*(x353)))+(((IkReal(-1.00000000000000))*(x355)*(x376)))+(((IkReal(0.150000000000000))*(x350)*(x352))));
01368 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  && IKabs(evalcond[9]) < 0.0000010000000000  && IKabs(evalcond[10]) < 0.0000010000000000  )
01369 {
01370 {
01371 IkReal dummyeval[1];
01372 IkReal gconst4;
01373 gconst4=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01374 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
01375 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01376 {
01377 {
01378 IkReal dummyeval[1];
01379 IkReal gconst5;
01380 gconst5=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01381 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
01382 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01383 {
01384 continue;
01385 
01386 } else
01387 {
01388 {
01389 IkReal j2array[1], cj2array[1], sj2array[1];
01390 bool j2valid[1]={false};
01391 _nj2 = 1;
01392 IkReal x389=((r02)*(sj0));
01393 IkReal x390=((IkReal(0.0800000000000000))*(sj1));
01394 IkReal x391=((cj3)*(px));
01395 IkReal x392=((cj0)*(r01));
01396 IkReal x393=((IkReal(0.0240000000000000))*(cj1));
01397 IkReal x394=((pz)*(sj3));
01398 IkReal x395=((IkReal(0.00600000000000000))*(cj1));
01399 IkReal x396=((IkReal(0.320000000000000))*(px));
01400 IkReal x397=((cj0)*(sj1));
01401 IkReal x398=((cj1)*(r01));
01402 IkReal x399=((IkReal(0.0750000000000000))*(px));
01403 IkReal x400=((IkReal(0.00562500000000000))*(cj1));
01404 IkReal x401=((py)*(r02));
01405 IkReal x402=((IkReal(0.0750000000000000))*(pz));
01406 IkReal x403=((r00)*(sj0));
01407 IkReal x404=((cj3)*(pz));
01408 IkReal x405=((IkReal(0.320000000000000))*(py));
01409 IkReal x406=((sj0)*(sj1));
01410 IkReal x407=((IkReal(0.0800000000000000))*(cj1));
01411 IkReal x408=((cj1)*(r00));
01412 IkReal x409=((IkReal(0.0750000000000000))*(py));
01413 IkReal x410=((cj3)*(py));
01414 IkReal x411=((IkReal(0.00600000000000000))*(sj1));
01415 IkReal x412=((py)*(sj3));
01416 IkReal x413=((IkReal(0.320000000000000))*(pz)*(sj1));
01417 IkReal x414=((px)*(sj3)*(x390));
01418 if( IKabs(((gconst5)*(((IkReal(-0.0960000000000000))+(((x390)*(x392)*(x394)))+(((sj1)*(x392)*(x402)))+(((x392)*(x400)))+(((r00)*(x407)*(x412)))+(((x405)*(x406)))+(((IkReal(-1.00000000000000))*(x400)*(x403)))+(((cj0)*(x390)*(x391)))+(((IkReal(-0.0750000000000000))*(x397)*(x401)))+(((IkReal(-1.00000000000000))*(sj1)*(x402)*(x403)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x404)*(x407)))+(((sj1)*(x389)*(x399)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x389)*(x414)))+(((x408)*(x409)))+(((IkReal(-1.00000000000000))*(x398)*(x399)))+(((IkReal(-0.0800000000000000))*(px)*(sj3)*(x398)))+(((sj0)*(x390)*(x410)))+(((IkReal(-1.00000000000000))*(sj3)*(x395)*(x403)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((IkReal(-1.00000000000000))*(x390)*(x394)*(x403)))+(((x396)*(x397)))+(((IkReal(-1.00000000000000))*(cj3)*(x411)))+(((sj3)*(x392)*(x395)))+(((IkReal(-1.00000000000000))*(cj0)*(sj3)*(x390)*(x401))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x390)*(x392)*(x404)))+(((IkReal(-1.00000000000000))*(x392)*(x393)))+(((cj0)*(x414)))+(((x390)*(x403)*(x404)))+(((cj1)*(x402)))+(((x406)*(x409)))+(((IkReal(0.320000000000000))*(x397)*(x401)))+(((IkReal(-1.00000000000000))*(sj1)*(x389)*(x396)))+(((x396)*(x398)))+(((x397)*(x399)))+(((x394)*(x407)))+(((IkReal(-1.00000000000000))*(x392)*(x413)))+(((IkReal(-1.00000000000000))*(x389)*(x390)*(x391)))+(((IkReal(-1.00000000000000))*(sj3)*(x411)))+(((cj3)*(x395)*(x403)))+(((cj0)*(cj3)*(x390)*(x401)))+(((sj0)*(x390)*(x412)))+(((IkReal(-1.00000000000000))*(x405)*(x408)))+(((x393)*(x403)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(0.0800000000000000))*(x391)*(x398)))+(((x403)*(x413)))+(((IkReal(-1.00000000000000))*(r00)*(x407)*(x410)))+(((IkReal(-1.00000000000000))*(cj3)*(x392)*(x395))))))) < IKFAST_ATAN2_MAGTHRESH )
01419     continue;
01420 j2array[0]=IKatan2(((gconst5)*(((IkReal(-0.0960000000000000))+(((x390)*(x392)*(x394)))+(((sj1)*(x392)*(x402)))+(((x392)*(x400)))+(((r00)*(x407)*(x412)))+(((x405)*(x406)))+(((IkReal(-1.00000000000000))*(x400)*(x403)))+(((cj0)*(x390)*(x391)))+(((IkReal(-0.0750000000000000))*(x397)*(x401)))+(((IkReal(-1.00000000000000))*(sj1)*(x402)*(x403)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x404)*(x407)))+(((sj1)*(x389)*(x399)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x389)*(x414)))+(((x408)*(x409)))+(((IkReal(-1.00000000000000))*(x398)*(x399)))+(((IkReal(-0.0800000000000000))*(px)*(sj3)*(x398)))+(((sj0)*(x390)*(x410)))+(((IkReal(-1.00000000000000))*(sj3)*(x395)*(x403)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((IkReal(-1.00000000000000))*(x390)*(x394)*(x403)))+(((x396)*(x397)))+(((IkReal(-1.00000000000000))*(cj3)*(x411)))+(((sj3)*(x392)*(x395)))+(((IkReal(-1.00000000000000))*(cj0)*(sj3)*(x390)*(x401)))))), ((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x390)*(x392)*(x404)))+(((IkReal(-1.00000000000000))*(x392)*(x393)))+(((cj0)*(x414)))+(((x390)*(x403)*(x404)))+(((cj1)*(x402)))+(((x406)*(x409)))+(((IkReal(0.320000000000000))*(x397)*(x401)))+(((IkReal(-1.00000000000000))*(sj1)*(x389)*(x396)))+(((x396)*(x398)))+(((x397)*(x399)))+(((x394)*(x407)))+(((IkReal(-1.00000000000000))*(x392)*(x413)))+(((IkReal(-1.00000000000000))*(x389)*(x390)*(x391)))+(((IkReal(-1.00000000000000))*(sj3)*(x411)))+(((cj3)*(x395)*(x403)))+(((cj0)*(cj3)*(x390)*(x401)))+(((sj0)*(x390)*(x412)))+(((IkReal(-1.00000000000000))*(x405)*(x408)))+(((x393)*(x403)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(0.0800000000000000))*(x391)*(x398)))+(((x403)*(x413)))+(((IkReal(-1.00000000000000))*(r00)*(x407)*(x410)))+(((IkReal(-1.00000000000000))*(cj3)*(x392)*(x395)))))));
01421 sj2array[0]=IKsin(j2array[0]);
01422 cj2array[0]=IKcos(j2array[0]);
01423 if( j2array[0] > IKPI )
01424 {
01425     j2array[0]-=IK2PI;
01426 }
01427 else if( j2array[0] < -IKPI )
01428 {    j2array[0]+=IK2PI;
01429 }
01430 j2valid[0] = true;
01431 for(int ij2 = 0; ij2 < 1; ++ij2)
01432 {
01433 if( !j2valid[ij2] )
01434 {
01435     continue;
01436 }
01437 _ij2[0] = ij2; _ij2[1] = -1;
01438 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01439 {
01440 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01441 {
01442     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01443 }
01444 }
01445 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01446 {
01447 IkReal evalcond[4];
01448 IkReal x415=IKcos(j2);
01449 IkReal x416=IKsin(j2);
01450 IkReal x417=((IkReal(0.0800000000000000))*(sj3));
01451 IkReal x418=((cj0)*(r01));
01452 IkReal x419=((IkReal(1.00000000000000))*(px));
01453 IkReal x420=((py)*(sj1));
01454 IkReal x421=((cj0)*(r02));
01455 IkReal x422=((IkReal(0.0750000000000000))*(cj1));
01456 IkReal x423=((r02)*(sj0));
01457 IkReal x424=((IkReal(0.0750000000000000))*(sj1));
01458 IkReal x425=((cj1)*(pz));
01459 IkReal x426=((r00)*(sj0));
01460 IkReal x427=((IkReal(0.0800000000000000))*(cj3));
01461 IkReal x428=((pz)*(sj1));
01462 IkReal x429=((IkReal(1.00000000000000))*(sj0));
01463 IkReal x430=((cj1)*(py));
01464 IkReal x431=((IkReal(0.0750000000000000))*(x416));
01465 IkReal x432=((IkReal(0.320000000000000))*(x415));
01466 IkReal x433=((IkReal(0.320000000000000))*(x416));
01467 IkReal x434=((IkReal(0.0750000000000000))*(x415));
01468 IkReal x435=((sj1)*(x426));
01469 IkReal x436=((x416)*(x417));
01470 IkReal x437=((x415)*(x427));
01471 IkReal x438=((x415)*(x417));
01472 IkReal x439=((x416)*(x427));
01473 IkReal x440=((x431)+(x436));
01474 IkReal x441=((x432)+(x437));
01475 IkReal x442=((x438)+(x439)+(x433)+(x434));
01476 evalcond[0]=((x428)+(x422)+(x441)+(((IkReal(-1.00000000000000))*(x429)*(x430)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x419)))+(((IkReal(-1.00000000000000))*(x440))));
01477 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x419)))+(((IkReal(-1.00000000000000))*(x420)*(x429)))+(x424)+(x442)+(((IkReal(-1.00000000000000))*(x425))));
01478 evalcond[2]=((((IkReal(-1.00000000000000))*(x418)*(x422)))+(x440)+(((IkReal(-1.00000000000000))*(x418)*(x428)))+(((x420)*(x421)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x441)))+(((IkReal(-1.00000000000000))*(r00)*(x430)))+(((x422)*(x426)))+(((IkReal(-1.00000000000000))*(sj1)*(x419)*(x423)))+(((x426)*(x428))));
01479 evalcond[3]=((((IkReal(-0.300000000000000))*(x426)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x419)))+(((x418)*(x424)))+(((x421)*(x430)))+(((x425)*(x426)))+(x442)+(((IkReal(-1.00000000000000))*(cj1)*(x419)*(x423)))+(((r00)*(x420)))+(((IkReal(0.300000000000000))*(x418)))+(((IkReal(-1.00000000000000))*(x424)*(x426)))+(((IkReal(-1.00000000000000))*(x418)*(x425))));
01480 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01481 {
01482 continue;
01483 }
01484 }
01485 
01486 {
01487 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01488 vinfos[0].jointtype = 1;
01489 vinfos[0].foffset = j0;
01490 vinfos[0].indices[0] = _ij0[0];
01491 vinfos[0].indices[1] = _ij0[1];
01492 vinfos[0].maxsolutions = _nj0;
01493 vinfos[1].jointtype = 1;
01494 vinfos[1].foffset = j1;
01495 vinfos[1].indices[0] = _ij1[0];
01496 vinfos[1].indices[1] = _ij1[1];
01497 vinfos[1].maxsolutions = _nj1;
01498 vinfos[2].jointtype = 1;
01499 vinfos[2].foffset = j2;
01500 vinfos[2].indices[0] = _ij2[0];
01501 vinfos[2].indices[1] = _ij2[1];
01502 vinfos[2].maxsolutions = _nj2;
01503 vinfos[3].jointtype = 1;
01504 vinfos[3].foffset = j3;
01505 vinfos[3].indices[0] = _ij3[0];
01506 vinfos[3].indices[1] = _ij3[1];
01507 vinfos[3].maxsolutions = _nj3;
01508 vinfos[4].jointtype = 1;
01509 vinfos[4].foffset = j4;
01510 vinfos[4].indices[0] = _ij4[0];
01511 vinfos[4].indices[1] = _ij4[1];
01512 vinfos[4].maxsolutions = _nj4;
01513 std::vector<int> vfree(0);
01514 solutions.AddSolution(vinfos,vfree);
01515 }
01516 }
01517 }
01518 
01519 }
01520 
01521 }
01522 
01523 } else
01524 {
01525 {
01526 IkReal j2array[1], cj2array[1], sj2array[1];
01527 bool j2valid[1]={false};
01528 _nj2 = 1;
01529 IkReal x443=((IkReal(0.0800000000000000))*(cj1));
01530 IkReal x444=((cj0)*(px));
01531 IkReal x445=((py)*(sj0));
01532 IkReal x446=((IkReal(0.320000000000000))*(sj1));
01533 IkReal x447=((IkReal(0.00600000000000000))*(cj3));
01534 IkReal x448=((pz)*(sj3));
01535 IkReal x449=((IkReal(0.0750000000000000))*(cj1));
01536 IkReal x450=((IkReal(0.0800000000000000))*(sj1));
01537 IkReal x451=((IkReal(0.0750000000000000))*(sj1));
01538 IkReal x452=((IkReal(0.00600000000000000))*(sj3));
01539 IkReal x453=((cj3)*(pz));
01540 IkReal x454=((IkReal(0.320000000000000))*(cj1));
01541 if( IKabs(((gconst4)*(((IkReal(-0.0960000000000000))+(((x445)*(x446)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x443)*(x445)))+(((x448)*(x450)))+(((x443)*(x453)))+(((pz)*(x451)))+(((IkReal(-1.00000000000000))*(sj3)*(x443)*(x444)))+(((cj3)*(x444)*(x450)))+(((cj1)*(x452)))+(((IkReal(-1.00000000000000))*(x445)*(x449)))+(((IkReal(-1.00000000000000))*(sj1)*(x447)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x444)*(x446)))+(((pz)*(x454)))+(((cj3)*(x445)*(x450)))+(((IkReal(-1.00000000000000))*(x444)*(x449))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(pz)*(x446)))+(((pz)*(x449)))+(((x445)*(x454)))+(((IkReal(-1.00000000000000))*(cj1)*(x447)))+(((x444)*(x451)))+(((cj3)*(x443)*(x444)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x452)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x443)*(x448)))+(((cj3)*(x443)*(x445)))+(((x445)*(x451)))+(((sj3)*(x445)*(x450)))+(((sj3)*(x444)*(x450)))+(((IkReal(-1.00000000000000))*(x450)*(x453)))+(((x444)*(x454))))))) < IKFAST_ATAN2_MAGTHRESH )
01542     continue;
01543 j2array[0]=IKatan2(((gconst4)*(((IkReal(-0.0960000000000000))+(((x445)*(x446)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x443)*(x445)))+(((x448)*(x450)))+(((x443)*(x453)))+(((pz)*(x451)))+(((IkReal(-1.00000000000000))*(sj3)*(x443)*(x444)))+(((cj3)*(x444)*(x450)))+(((cj1)*(x452)))+(((IkReal(-1.00000000000000))*(x445)*(x449)))+(((IkReal(-1.00000000000000))*(sj1)*(x447)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x444)*(x446)))+(((pz)*(x454)))+(((cj3)*(x445)*(x450)))+(((IkReal(-1.00000000000000))*(x444)*(x449)))))), ((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(pz)*(x446)))+(((pz)*(x449)))+(((x445)*(x454)))+(((IkReal(-1.00000000000000))*(cj1)*(x447)))+(((x444)*(x451)))+(((cj3)*(x443)*(x444)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x452)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x443)*(x448)))+(((cj3)*(x443)*(x445)))+(((x445)*(x451)))+(((sj3)*(x445)*(x450)))+(((sj3)*(x444)*(x450)))+(((IkReal(-1.00000000000000))*(x450)*(x453)))+(((x444)*(x454)))))));
01544 sj2array[0]=IKsin(j2array[0]);
01545 cj2array[0]=IKcos(j2array[0]);
01546 if( j2array[0] > IKPI )
01547 {
01548     j2array[0]-=IK2PI;
01549 }
01550 else if( j2array[0] < -IKPI )
01551 {    j2array[0]+=IK2PI;
01552 }
01553 j2valid[0] = true;
01554 for(int ij2 = 0; ij2 < 1; ++ij2)
01555 {
01556 if( !j2valid[ij2] )
01557 {
01558     continue;
01559 }
01560 _ij2[0] = ij2; _ij2[1] = -1;
01561 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01562 {
01563 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01564 {
01565     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01566 }
01567 }
01568 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01569 {
01570 IkReal evalcond[4];
01571 IkReal x455=IKcos(j2);
01572 IkReal x456=IKsin(j2);
01573 IkReal x457=((IkReal(0.0800000000000000))*(sj3));
01574 IkReal x458=((cj0)*(r01));
01575 IkReal x459=((IkReal(1.00000000000000))*(px));
01576 IkReal x460=((py)*(sj1));
01577 IkReal x461=((cj0)*(r02));
01578 IkReal x462=((IkReal(0.0750000000000000))*(cj1));
01579 IkReal x463=((r02)*(sj0));
01580 IkReal x464=((IkReal(0.0750000000000000))*(sj1));
01581 IkReal x465=((cj1)*(pz));
01582 IkReal x466=((r00)*(sj0));
01583 IkReal x467=((IkReal(0.0800000000000000))*(cj3));
01584 IkReal x468=((pz)*(sj1));
01585 IkReal x469=((IkReal(1.00000000000000))*(sj0));
01586 IkReal x470=((cj1)*(py));
01587 IkReal x471=((IkReal(0.0750000000000000))*(x456));
01588 IkReal x472=((IkReal(0.320000000000000))*(x455));
01589 IkReal x473=((IkReal(0.320000000000000))*(x456));
01590 IkReal x474=((IkReal(0.0750000000000000))*(x455));
01591 IkReal x475=((sj1)*(x466));
01592 IkReal x476=((x456)*(x457));
01593 IkReal x477=((x455)*(x467));
01594 IkReal x478=((x455)*(x457));
01595 IkReal x479=((x456)*(x467));
01596 IkReal x480=((x476)+(x471));
01597 IkReal x481=((x477)+(x472));
01598 IkReal x482=((x474)+(x473)+(x478)+(x479));
01599 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x459)))+(x468)+(x462)+(x481)+(((IkReal(-1.00000000000000))*(x480)))+(((IkReal(-1.00000000000000))*(x469)*(x470))));
01600 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x465)))+(x464)+(((IkReal(-1.00000000000000))*(x460)*(x469)))+(x482)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x459))));
01601 evalcond[2]=((((IkReal(-1.00000000000000))*(x458)*(x462)))+(((x460)*(x461)))+(((x466)*(x468)))+(((IkReal(-1.00000000000000))*(sj1)*(x459)*(x463)))+(((cj1)*(px)*(r01)))+(((x462)*(x466)))+(x480)+(((IkReal(-1.00000000000000))*(r00)*(x470)))+(((IkReal(-1.00000000000000))*(x481)))+(((IkReal(-1.00000000000000))*(x458)*(x468))));
01602 evalcond[3]=((((r00)*(x460)))+(((x465)*(x466)))+(((IkReal(-1.00000000000000))*(cj1)*(x459)*(x463)))+(((x458)*(x464)))+(((x461)*(x470)))+(((IkReal(-1.00000000000000))*(x458)*(x465)))+(((IkReal(-0.300000000000000))*(x466)))+(x482)+(((IkReal(0.300000000000000))*(x458)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x459)))+(((IkReal(-1.00000000000000))*(x464)*(x466))));
01603 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01604 {
01605 continue;
01606 }
01607 }
01608 
01609 {
01610 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01611 vinfos[0].jointtype = 1;
01612 vinfos[0].foffset = j0;
01613 vinfos[0].indices[0] = _ij0[0];
01614 vinfos[0].indices[1] = _ij0[1];
01615 vinfos[0].maxsolutions = _nj0;
01616 vinfos[1].jointtype = 1;
01617 vinfos[1].foffset = j1;
01618 vinfos[1].indices[0] = _ij1[0];
01619 vinfos[1].indices[1] = _ij1[1];
01620 vinfos[1].maxsolutions = _nj1;
01621 vinfos[2].jointtype = 1;
01622 vinfos[2].foffset = j2;
01623 vinfos[2].indices[0] = _ij2[0];
01624 vinfos[2].indices[1] = _ij2[1];
01625 vinfos[2].maxsolutions = _nj2;
01626 vinfos[3].jointtype = 1;
01627 vinfos[3].foffset = j3;
01628 vinfos[3].indices[0] = _ij3[0];
01629 vinfos[3].indices[1] = _ij3[1];
01630 vinfos[3].maxsolutions = _nj3;
01631 vinfos[4].jointtype = 1;
01632 vinfos[4].foffset = j4;
01633 vinfos[4].indices[0] = _ij4[0];
01634 vinfos[4].indices[1] = _ij4[1];
01635 vinfos[4].maxsolutions = _nj4;
01636 std::vector<int> vfree(0);
01637 solutions.AddSolution(vinfos,vfree);
01638 }
01639 }
01640 }
01641 
01642 }
01643 
01644 }
01645 
01646 } else
01647 {
01648 IkReal x483=((IkReal(0.0512000000000000))*(cj3));
01649 IkReal x484=((IkReal(0.0120000000000000))*(sj3));
01650 IkReal x485=(py)*(py);
01651 IkReal x486=(px)*(px);
01652 IkReal x487=(pz)*(pz);
01653 IkReal x488=((r01)*(sj0));
01654 IkReal x489=((py)*(r00));
01655 IkReal x490=((pz)*(sj1));
01656 IkReal x491=((py)*(r01));
01657 IkReal x492=((px)*(sj0));
01658 IkReal x493=((IkReal(0.600000000000000))*(r02));
01659 IkReal x494=((IkReal(0.150000000000000))*(cj1));
01660 IkReal x495=((cj0)*(sj1));
01661 IkReal x496=((IkReal(0.150000000000000))*(px));
01662 IkReal x497=((IkReal(2.00000000000000))*(cj1));
01663 IkReal x498=((cj0)*(r01));
01664 IkReal x499=((r02)*(sj1));
01665 IkReal x500=((px)*(r00));
01666 IkReal x501=((IkReal(0.300000000000000))*(r00));
01667 IkReal x502=((IkReal(1.00000000000000))*(pz));
01668 IkReal x503=((r00)*(sj1));
01669 IkReal x504=((cj0)*(r00));
01670 IkReal x505=((cj0)*(cj1));
01671 IkReal x506=((IkReal(1.00000000000000))*(sj1));
01672 IkReal x507=((IkReal(0.0956250000000000))*(r00));
01673 IkReal x508=((IkReal(0.600000000000000))*(pz));
01674 IkReal x509=((IkReal(0.600000000000000))*(sj1));
01675 IkReal x510=((IkReal(2.00000000000000))*(px));
01676 IkReal x511=((IkReal(2.00000000000000))*(sj1));
01677 IkReal x512=((IkReal(0.150000000000000))*(sj1));
01678 IkReal x513=((cj1)*(r02));
01679 IkReal x514=((cj0)*(px));
01680 IkReal x515=((IkReal(0.0843750000000000))*(cj1));
01681 IkReal x516=((py)*(sj0));
01682 IkReal x517=((pz)*(r02));
01683 IkReal x518=((IkReal(1.00000000000000))*(cj1));
01684 IkReal x519=((cj0)*(py));
01685 IkReal x520=((r00)*(sj0));
01686 IkReal x521=((r02)*(x516));
01687 IkReal x522=((pp)*(x518));
01688 IkReal x523=((IkReal(1.00000000000000))*(pp)*(r00));
01689 IkReal x524=((x483)+(x484));
01690 IkReal x525=((IkReal(2.00000000000000))*(r00)*(x486));
01691 IkReal x526=((cj0)*(x510)*(x517));
01692 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
01693 evalcond[1]=((((IkReal(-1.00000000000000))*(x492)))+(x519));
01694 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x520)))+(x498));
01695 evalcond[3]=((((IkReal(-1.00000000000000))*(x488)*(x518)))+(x499)+(((IkReal(-1.00000000000000))*(x504)*(x518))));
01696 evalcond[4]=((((IkReal(-1.00000000000000))*(x488)*(x506)))+(((IkReal(-1.00000000000000))*(r00)*(x495)))+(((IkReal(-1.00000000000000))*(x513))));
01697 evalcond[5]=((IkReal(0.0188000000000000))+(((cj0)*(x496)))+(((IkReal(0.150000000000000))*(x516)))+(((x509)*(x516)))+(((cj1)*(x508)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.600000000000000))*(px)*(x495)))+(((IkReal(-0.0450000000000000))*(sj1)))+(x524));
01698 evalcond[6]=((((IkReal(-1.00000000000000))*(x500)))+(((IkReal(0.0750000000000000))*(x504)))+(((IkReal(0.300000000000000))*(sj1)*(x488)))+(((x495)*(x501)))+(((IkReal(-1.00000000000000))*(r02)*(x502)))+(((IkReal(0.300000000000000))*(x513)))+(((IkReal(0.0750000000000000))*(x488)))+(((IkReal(-1.00000000000000))*(x491))));
01699 evalcond[7]=((((IkReal(-0.300000000000000))*(x499)))+(((IkReal(0.300000000000000))*(cj1)*(x488)))+(((IkReal(-1.00000000000000))*(x502)*(x504)))+(((r02)*(x514)))+(((IkReal(-1.00000000000000))*(x488)*(x502)))+(((IkReal(-0.0750000000000000))*(r02)))+(x521)+(((x501)*(x505))));
01700 evalcond[8]=((IkReal(0.114425000000000))+(((cj1)*(x508)*(x520)))+(((IkReal(0.0956250000000000))*(x498)))+(((pp)*(x498)))+(((IkReal(-1.00000000000000))*(cj0)*(x489)*(x510)))+(((IkReal(-1.00000000000000))*(cj1)*(x498)*(x508)))+(((IkReal(0.0450000000000000))*(r01)*(x495)))+(((IkReal(-2.00000000000000))*(x485)*(x498)))+(((IkReal(-1.00000000000000))*(pp)*(x520)))+(((py)*(x493)*(x505)))+(((IkReal(0.150000000000000))*(x489)))+(((IkReal(-1.00000000000000))*(cj1)*(x492)*(x493)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x509)))+(((IkReal(-1.00000000000000))*(r01)*(x496)))+(((py)*(x488)*(x510)))+(((IkReal(2.00000000000000))*(x486)*(x520)))+(((IkReal(-0.0450000000000000))*(sj0)*(x503)))+(((IkReal(2.00000000000000))*(x492)*(x517)))+(((IkReal(-2.00000000000000))*(x517)*(x519)))+(((IkReal(-1.00000000000000))*(sj0)*(x507)))+(x524)+(((x489)*(x509))));
01701 evalcond[9]=((((IkReal(0.0843750000000000))*(x513)))+(((IkReal(-1.00000000000000))*(x491)*(x512)))+(((pz)*(x491)*(x497)))+(((IkReal(0.0450000000000000))*(x504)))+(((IkReal(0.0450000000000000))*(x488)))+(((x491)*(x495)*(x510)))+(((x495)*(x525)))+(((IkReal(-0.150000000000000))*(r02)*(x490)))+(((IkReal(-1.00000000000000))*(pp)*(x513)))+(((r02)*(x494)*(x514)))+(((r02)*(x487)*(x497)))+(((x495)*(x507)))+(((IkReal(-1.00000000000000))*(x495)*(x523)))+(((IkReal(0.0956250000000000))*(sj1)*(x488)))+(((IkReal(-1.00000000000000))*(pz)*(x488)*(x494)))+(((IkReal(2.00000000000000))*(x490)*(x521)))+(((x489)*(x492)*(x511)))+(((pz)*(x497)*(x500)))+(((x485)*(x488)*(x511)))+(((cj0)*(r02)*(x490)*(x510)))+(((IkReal(-1.00000000000000))*(pz)*(x494)*(x504)))+(((IkReal(-0.600000000000000))*(x491)))+(((IkReal(-1.00000000000000))*(pp)*(x488)*(x506)))+(((IkReal(-0.600000000000000))*(x500)))+(((x494)*(x521)))+(((IkReal(-1.00000000000000))*(x496)*(x503)))+(((IkReal(-1.00000000000000))*(pz)*(x493))));
01702 evalcond[10]=((((IkReal(-2.00000000000000))*(x490)*(x491)))+(((IkReal(-1.00000000000000))*(x488)*(x522)))+(((IkReal(-1.00000000000000))*(r02)*(x495)*(x496)))+(((IkReal(-2.00000000000000))*(x490)*(x500)))+(((IkReal(-1.00000000000000))*(x494)*(x517)))+(((IkReal(-2.00000000000000))*(x487)*(x499)))+(((x497)*(x516)*(x517)))+(((IkReal(0.150000000000000))*(x488)*(x490)))+(((x489)*(x492)*(x497)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x494)*(x500)))+(((IkReal(-1.00000000000000))*(x488)*(x515)))+(((x486)*(x497)*(x504)))+(((IkReal(-1.00000000000000))*(x504)*(x515)))+(((x504)*(x508)))+(((pp)*(x499)))+(((x488)*(x508)))+(((x485)*(x488)*(x497)))+(((IkReal(-1.00000000000000))*(x493)*(x514)))+(((IkReal(-0.150000000000000))*(x499)*(x516)))+(((IkReal(0.150000000000000))*(x490)*(x504)))+(((IkReal(-1.00000000000000))*(x491)*(x494)))+(((IkReal(-1.00000000000000))*(x504)*(x522)))+(((IkReal(-1.00000000000000))*(x493)*(x516)))+(((IkReal(0.0956250000000000))*(x499)))+(((x491)*(x497)*(x514)))+(((x497)*(x514)*(x517))));
01703 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  && IKabs(evalcond[9]) < 0.0000010000000000  && IKabs(evalcond[10]) < 0.0000010000000000  )
01704 {
01705 {
01706 IkReal dummyeval[1];
01707 IkReal gconst6;
01708 gconst6=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01709 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
01710 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01711 {
01712 {
01713 IkReal dummyeval[1];
01714 IkReal gconst7;
01715 gconst7=IKsign(((IkReal(-0.108025000000000))+(((IkReal(-0.0512000000000000))*(cj3)))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))));
01716 dummyeval[0]=((IkReal(-16.8789062500000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
01717 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01718 {
01719 continue;
01720 
01721 } else
01722 {
01723 {
01724 IkReal j2array[1], cj2array[1], sj2array[1];
01725 bool j2valid[1]={false};
01726 _nj2 = 1;
01727 IkReal x527=((r02)*(sj0));
01728 IkReal x528=((IkReal(0.0800000000000000))*(sj1));
01729 IkReal x529=((cj3)*(px));
01730 IkReal x530=((cj0)*(r01));
01731 IkReal x531=((IkReal(0.0240000000000000))*(cj1));
01732 IkReal x532=((pz)*(sj3));
01733 IkReal x533=((IkReal(0.00600000000000000))*(cj1));
01734 IkReal x534=((IkReal(0.0750000000000000))*(sj1));
01735 IkReal x535=((py)*(sj0));
01736 IkReal x536=((IkReal(0.00562500000000000))*(cj1));
01737 IkReal x537=((r00)*(sj0));
01738 IkReal x538=((cj3)*(pz));
01739 IkReal x539=((IkReal(0.320000000000000))*(sj1));
01740 IkReal x540=((IkReal(0.0800000000000000))*(cj1));
01741 IkReal x541=((IkReal(0.0750000000000000))*(cj1));
01742 IkReal x542=((py)*(r00));
01743 IkReal x543=((IkReal(0.320000000000000))*(cj1));
01744 IkReal x544=((cj0)*(px));
01745 IkReal x545=((IkReal(0.00600000000000000))*(sj1));
01746 IkReal x546=((cj1)*(px)*(r01));
01747 IkReal x547=((cj0)*(py)*(r02));
01748 IkReal x548=((px)*(sj3)*(x528));
01749 if( IKabs(((gconst7)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(x535)*(x539)))+(((sj3)*(x540)*(x542)))+(((IkReal(-1.00000000000000))*(cj3)*(x528)*(x535)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x547)))+(((px)*(x527)*(x534)))+(((IkReal(-1.00000000000000))*(x534)*(x547)))+(((IkReal(-1.00000000000000))*(x536)*(x537)))+(((x528)*(x530)*(x532)))+(((IkReal(-1.00000000000000))*(pz)*(x534)*(x537)))+(((IkReal(-1.00000000000000))*(pz)*(x543)))+(((sj3)*(x530)*(x533)))+(((IkReal(0.0240000000000000))*(sj1)))+(((x530)*(x536)))+(((IkReal(-1.00000000000000))*(cj0)*(x528)*(x529)))+(((IkReal(-1.00000000000000))*(x539)*(x544)))+(((x541)*(x542)))+(((pz)*(x530)*(x534)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x541)))+(((x527)*(x548)))+(((cj3)*(x545)))+(((IkReal(-1.00000000000000))*(sj3)*(x533)*(x537)))+(((IkReal(0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x528)*(x532)*(x537)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x540)))+(((IkReal(-1.00000000000000))*(x538)*(x540))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((IkReal(0.0225000000000000))+(((cj3)*(x533)*(x537)))+(((IkReal(-1.00000000000000))*(pz)*(x530)*(x539)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x535)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x541)))+(((IkReal(-1.00000000000000))*(x527)*(x528)*(x529)))+(((x539)*(x547)))+(((IkReal(-1.00000000000000))*(cj3)*(x540)*(x542)))+(((IkReal(-1.00000000000000))*(x542)*(x543)))+(((IkReal(-1.00000000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(x534)*(x535)))+(((cj3)*(x528)*(x547)))+(((x528)*(x537)*(x538)))+(((IkReal(-1.00000000000000))*(x528)*(x530)*(x538)))+(((pz)*(x537)*(x539)))+(((r01)*(x529)*(x540)))+(((IkReal(-1.00000000000000))*(cj3)*(x530)*(x533)))+(((IkReal(-1.00000000000000))*(x534)*(x544)))+(((IkReal(-1.00000000000000))*(px)*(x527)*(x539)))+(((IkReal(-1.00000000000000))*(x532)*(x540)))+(((px)*(r01)*(x543)))+(((x531)*(x537)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x544)))+(((sj3)*(x545)))+(((IkReal(0.0240000000000000))*(sj3))))))) < IKFAST_ATAN2_MAGTHRESH )
01750     continue;
01751 j2array[0]=IKatan2(((gconst7)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(x535)*(x539)))+(((sj3)*(x540)*(x542)))+(((IkReal(-1.00000000000000))*(cj3)*(x528)*(x535)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x547)))+(((px)*(x527)*(x534)))+(((IkReal(-1.00000000000000))*(x534)*(x547)))+(((IkReal(-1.00000000000000))*(x536)*(x537)))+(((x528)*(x530)*(x532)))+(((IkReal(-1.00000000000000))*(pz)*(x534)*(x537)))+(((IkReal(-1.00000000000000))*(pz)*(x543)))+(((sj3)*(x530)*(x533)))+(((IkReal(0.0240000000000000))*(sj1)))+(((x530)*(x536)))+(((IkReal(-1.00000000000000))*(cj0)*(x528)*(x529)))+(((IkReal(-1.00000000000000))*(x539)*(x544)))+(((x541)*(x542)))+(((pz)*(x530)*(x534)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x541)))+(((x527)*(x548)))+(((cj3)*(x545)))+(((IkReal(-1.00000000000000))*(sj3)*(x533)*(x537)))+(((IkReal(0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x528)*(x532)*(x537)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x540)))+(((IkReal(-1.00000000000000))*(x538)*(x540)))))), ((gconst7)*(((IkReal(0.0225000000000000))+(((cj3)*(x533)*(x537)))+(((IkReal(-1.00000000000000))*(pz)*(x530)*(x539)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x535)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x541)))+(((IkReal(-1.00000000000000))*(x527)*(x528)*(x529)))+(((x539)*(x547)))+(((IkReal(-1.00000000000000))*(cj3)*(x540)*(x542)))+(((IkReal(-1.00000000000000))*(x542)*(x543)))+(((IkReal(-1.00000000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(x534)*(x535)))+(((cj3)*(x528)*(x547)))+(((x528)*(x537)*(x538)))+(((IkReal(-1.00000000000000))*(x528)*(x530)*(x538)))+(((pz)*(x537)*(x539)))+(((r01)*(x529)*(x540)))+(((IkReal(-1.00000000000000))*(cj3)*(x530)*(x533)))+(((IkReal(-1.00000000000000))*(x534)*(x544)))+(((IkReal(-1.00000000000000))*(px)*(x527)*(x539)))+(((IkReal(-1.00000000000000))*(x532)*(x540)))+(((px)*(r01)*(x543)))+(((x531)*(x537)))+(((IkReal(-1.00000000000000))*(sj3)*(x528)*(x544)))+(((sj3)*(x545)))+(((IkReal(0.0240000000000000))*(sj3)))))));
01752 sj2array[0]=IKsin(j2array[0]);
01753 cj2array[0]=IKcos(j2array[0]);
01754 if( j2array[0] > IKPI )
01755 {
01756     j2array[0]-=IK2PI;
01757 }
01758 else if( j2array[0] < -IKPI )
01759 {    j2array[0]+=IK2PI;
01760 }
01761 j2valid[0] = true;
01762 for(int ij2 = 0; ij2 < 1; ++ij2)
01763 {
01764 if( !j2valid[ij2] )
01765 {
01766     continue;
01767 }
01768 _ij2[0] = ij2; _ij2[1] = -1;
01769 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01770 {
01771 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01772 {
01773     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01774 }
01775 }
01776 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01777 {
01778 IkReal evalcond[4];
01779 IkReal x549=IKcos(j2);
01780 IkReal x550=IKsin(j2);
01781 IkReal x551=((IkReal(0.0800000000000000))*(sj3));
01782 IkReal x552=((cj0)*(r01));
01783 IkReal x553=((IkReal(1.00000000000000))*(px));
01784 IkReal x554=((py)*(sj1));
01785 IkReal x555=((cj0)*(r02));
01786 IkReal x556=((IkReal(0.0750000000000000))*(cj1));
01787 IkReal x557=((r02)*(sj0));
01788 IkReal x558=((IkReal(0.0750000000000000))*(sj1));
01789 IkReal x559=((cj1)*(pz));
01790 IkReal x560=((r00)*(sj0));
01791 IkReal x561=((IkReal(0.0800000000000000))*(cj3));
01792 IkReal x562=((pz)*(sj1));
01793 IkReal x563=((IkReal(1.00000000000000))*(sj0));
01794 IkReal x564=((cj1)*(py));
01795 IkReal x565=((IkReal(0.320000000000000))*(x549));
01796 IkReal x566=((IkReal(0.0750000000000000))*(x550));
01797 IkReal x567=((IkReal(0.320000000000000))*(x550));
01798 IkReal x568=((IkReal(0.0750000000000000))*(x549));
01799 IkReal x569=((sj1)*(x560));
01800 IkReal x570=((x549)*(x561));
01801 IkReal x571=((x550)*(x551));
01802 IkReal x572=((x549)*(x551));
01803 IkReal x573=((x550)*(x561));
01804 IkReal x574=((x571)+(x566));
01805 IkReal x575=((x570)+(x565));
01806 IkReal x576=((x573)+(x572)+(x568)+(x567));
01807 evalcond[0]=((x575)+(((IkReal(-1.00000000000000))*(x574)))+(x562)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x553)))+(((IkReal(-1.00000000000000))*(x563)*(x564)))+(x556));
01808 evalcond[1]=((IkReal(0.300000000000000))+(x576)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x553)))+(((IkReal(-1.00000000000000))*(x559)))+(((IkReal(-1.00000000000000))*(x554)*(x563)))+(x558));
01809 evalcond[2]=((x575)+(((IkReal(-1.00000000000000))*(x574)))+(((IkReal(-1.00000000000000))*(sj1)*(x553)*(x557)))+(((x554)*(x555)))+(((x556)*(x560)))+(((IkReal(-1.00000000000000))*(x552)*(x562)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x552)*(x556)))+(((x560)*(x562)))+(((IkReal(-1.00000000000000))*(r00)*(x564))));
01810 evalcond[3]=((((IkReal(-1.00000000000000))*(x552)*(x559)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x553)))+(((x552)*(x558)))+(((x559)*(x560)))+(((IkReal(-1.00000000000000))*(x576)))+(((IkReal(-1.00000000000000))*(x558)*(x560)))+(((IkReal(0.300000000000000))*(x552)))+(((r00)*(x554)))+(((x555)*(x564)))+(((IkReal(-1.00000000000000))*(cj1)*(x553)*(x557)))+(((IkReal(-0.300000000000000))*(x560))));
01811 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01812 {
01813 continue;
01814 }
01815 }
01816 
01817 {
01818 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01819 vinfos[0].jointtype = 1;
01820 vinfos[0].foffset = j0;
01821 vinfos[0].indices[0] = _ij0[0];
01822 vinfos[0].indices[1] = _ij0[1];
01823 vinfos[0].maxsolutions = _nj0;
01824 vinfos[1].jointtype = 1;
01825 vinfos[1].foffset = j1;
01826 vinfos[1].indices[0] = _ij1[0];
01827 vinfos[1].indices[1] = _ij1[1];
01828 vinfos[1].maxsolutions = _nj1;
01829 vinfos[2].jointtype = 1;
01830 vinfos[2].foffset = j2;
01831 vinfos[2].indices[0] = _ij2[0];
01832 vinfos[2].indices[1] = _ij2[1];
01833 vinfos[2].maxsolutions = _nj2;
01834 vinfos[3].jointtype = 1;
01835 vinfos[3].foffset = j3;
01836 vinfos[3].indices[0] = _ij3[0];
01837 vinfos[3].indices[1] = _ij3[1];
01838 vinfos[3].maxsolutions = _nj3;
01839 vinfos[4].jointtype = 1;
01840 vinfos[4].foffset = j4;
01841 vinfos[4].indices[0] = _ij4[0];
01842 vinfos[4].indices[1] = _ij4[1];
01843 vinfos[4].maxsolutions = _nj4;
01844 std::vector<int> vfree(0);
01845 solutions.AddSolution(vinfos,vfree);
01846 }
01847 }
01848 }
01849 
01850 }
01851 
01852 }
01853 
01854 } else
01855 {
01856 {
01857 IkReal j2array[1], cj2array[1], sj2array[1];
01858 bool j2valid[1]={false};
01859 _nj2 = 1;
01860 IkReal x577=((IkReal(0.0800000000000000))*(cj1));
01861 IkReal x578=((cj0)*(px));
01862 IkReal x579=((py)*(sj0));
01863 IkReal x580=((IkReal(0.320000000000000))*(sj1));
01864 IkReal x581=((IkReal(0.00600000000000000))*(cj3));
01865 IkReal x582=((pz)*(sj3));
01866 IkReal x583=((IkReal(0.0750000000000000))*(cj1));
01867 IkReal x584=((IkReal(0.0800000000000000))*(sj1));
01868 IkReal x585=((IkReal(0.0750000000000000))*(sj1));
01869 IkReal x586=((IkReal(0.00600000000000000))*(sj3));
01870 IkReal x587=((cj3)*(pz));
01871 IkReal x588=((IkReal(0.320000000000000))*(cj1));
01872 if( IKabs(((gconst6)*(((IkReal(-0.0960000000000000))+(((cj1)*(x586)))+(((pz)*(x588)))+(((IkReal(-1.00000000000000))*(sj3)*(x577)*(x579)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x577)*(x578)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x577)*(x587)))+(((x579)*(x580)))+(((pz)*(x585)))+(((cj3)*(x579)*(x584)))+(((x578)*(x580)))+(((IkReal(0.00562500000000000))*(cj1)))+(((cj3)*(x578)*(x584)))+(((x582)*(x584)))+(((IkReal(-1.00000000000000))*(x579)*(x583)))+(((IkReal(-1.00000000000000))*(sj1)*(x581)))+(((IkReal(-1.00000000000000))*(x578)*(x583))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(-0.0225000000000000))+(((sj3)*(x578)*(x584)))+(((IkReal(-1.00000000000000))*(sj1)*(x586)))+(((x579)*(x588)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x578)*(x585)))+(((cj3)*(x577)*(x579)))+(((pz)*(x583)))+(((x578)*(x588)))+(((IkReal(-1.00000000000000))*(cj1)*(x581)))+(((IkReal(-1.00000000000000))*(x584)*(x587)))+(((sj3)*(x579)*(x584)))+(((x577)*(x582)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x580)))+(((x579)*(x585)))+(((cj3)*(x577)*(x578))))))) < IKFAST_ATAN2_MAGTHRESH )
01873     continue;
01874 j2array[0]=IKatan2(((gconst6)*(((IkReal(-0.0960000000000000))+(((cj1)*(x586)))+(((pz)*(x588)))+(((IkReal(-1.00000000000000))*(sj3)*(x577)*(x579)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x577)*(x578)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x577)*(x587)))+(((x579)*(x580)))+(((pz)*(x585)))+(((cj3)*(x579)*(x584)))+(((x578)*(x580)))+(((IkReal(0.00562500000000000))*(cj1)))+(((cj3)*(x578)*(x584)))+(((x582)*(x584)))+(((IkReal(-1.00000000000000))*(x579)*(x583)))+(((IkReal(-1.00000000000000))*(sj1)*(x581)))+(((IkReal(-1.00000000000000))*(x578)*(x583)))))), ((gconst6)*(((IkReal(-0.0225000000000000))+(((sj3)*(x578)*(x584)))+(((IkReal(-1.00000000000000))*(sj1)*(x586)))+(((x579)*(x588)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x578)*(x585)))+(((cj3)*(x577)*(x579)))+(((pz)*(x583)))+(((x578)*(x588)))+(((IkReal(-1.00000000000000))*(cj1)*(x581)))+(((IkReal(-1.00000000000000))*(x584)*(x587)))+(((sj3)*(x579)*(x584)))+(((x577)*(x582)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x580)))+(((x579)*(x585)))+(((cj3)*(x577)*(x578)))))));
01875 sj2array[0]=IKsin(j2array[0]);
01876 cj2array[0]=IKcos(j2array[0]);
01877 if( j2array[0] > IKPI )
01878 {
01879     j2array[0]-=IK2PI;
01880 }
01881 else if( j2array[0] < -IKPI )
01882 {    j2array[0]+=IK2PI;
01883 }
01884 j2valid[0] = true;
01885 for(int ij2 = 0; ij2 < 1; ++ij2)
01886 {
01887 if( !j2valid[ij2] )
01888 {
01889     continue;
01890 }
01891 _ij2[0] = ij2; _ij2[1] = -1;
01892 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01893 {
01894 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01895 {
01896     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01897 }
01898 }
01899 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01900 {
01901 IkReal evalcond[4];
01902 IkReal x589=IKcos(j2);
01903 IkReal x590=IKsin(j2);
01904 IkReal x591=((IkReal(0.0800000000000000))*(sj3));
01905 IkReal x592=((cj0)*(r01));
01906 IkReal x593=((IkReal(1.00000000000000))*(px));
01907 IkReal x594=((py)*(sj1));
01908 IkReal x595=((cj0)*(r02));
01909 IkReal x596=((IkReal(0.0750000000000000))*(cj1));
01910 IkReal x597=((r02)*(sj0));
01911 IkReal x598=((IkReal(0.0750000000000000))*(sj1));
01912 IkReal x599=((cj1)*(pz));
01913 IkReal x600=((r00)*(sj0));
01914 IkReal x601=((IkReal(0.0800000000000000))*(cj3));
01915 IkReal x602=((pz)*(sj1));
01916 IkReal x603=((IkReal(1.00000000000000))*(sj0));
01917 IkReal x604=((cj1)*(py));
01918 IkReal x605=((IkReal(0.320000000000000))*(x589));
01919 IkReal x606=((IkReal(0.0750000000000000))*(x590));
01920 IkReal x607=((IkReal(0.320000000000000))*(x590));
01921 IkReal x608=((IkReal(0.0750000000000000))*(x589));
01922 IkReal x609=((sj1)*(x600));
01923 IkReal x610=((x589)*(x601));
01924 IkReal x611=((x590)*(x591));
01925 IkReal x612=((x589)*(x591));
01926 IkReal x613=((x590)*(x601));
01927 IkReal x614=((x611)+(x606));
01928 IkReal x615=((x610)+(x605));
01929 IkReal x616=((x612)+(x613)+(x607)+(x608));
01930 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x593)))+(((IkReal(-1.00000000000000))*(x603)*(x604)))+(((IkReal(-1.00000000000000))*(x614)))+(x615)+(x596)+(x602));
01931 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x593)))+(((IkReal(-1.00000000000000))*(x594)*(x603)))+(x616)+(x598)+(((IkReal(-1.00000000000000))*(x599))));
01932 evalcond[2]=((((x594)*(x595)))+(((IkReal(-1.00000000000000))*(x592)*(x596)))+(((x600)*(x602)))+(((IkReal(-1.00000000000000))*(sj1)*(x593)*(x597)))+(((x596)*(x600)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x614)))+(x615)+(((IkReal(-1.00000000000000))*(x592)*(x602)))+(((IkReal(-1.00000000000000))*(r00)*(x604))));
01933 evalcond[3]=((((IkReal(-1.00000000000000))*(x592)*(x599)))+(((x595)*(x604)))+(((x599)*(x600)))+(((x592)*(x598)))+(((IkReal(0.300000000000000))*(x592)))+(((IkReal(-0.300000000000000))*(x600)))+(((r00)*(x594)))+(((IkReal(-1.00000000000000))*(x616)))+(((IkReal(-1.00000000000000))*(cj1)*(x593)*(x597)))+(((IkReal(-1.00000000000000))*(x598)*(x600)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x593))));
01934 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01935 {
01936 continue;
01937 }
01938 }
01939 
01940 {
01941 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01942 vinfos[0].jointtype = 1;
01943 vinfos[0].foffset = j0;
01944 vinfos[0].indices[0] = _ij0[0];
01945 vinfos[0].indices[1] = _ij0[1];
01946 vinfos[0].maxsolutions = _nj0;
01947 vinfos[1].jointtype = 1;
01948 vinfos[1].foffset = j1;
01949 vinfos[1].indices[0] = _ij1[0];
01950 vinfos[1].indices[1] = _ij1[1];
01951 vinfos[1].maxsolutions = _nj1;
01952 vinfos[2].jointtype = 1;
01953 vinfos[2].foffset = j2;
01954 vinfos[2].indices[0] = _ij2[0];
01955 vinfos[2].indices[1] = _ij2[1];
01956 vinfos[2].maxsolutions = _nj2;
01957 vinfos[3].jointtype = 1;
01958 vinfos[3].foffset = j3;
01959 vinfos[3].indices[0] = _ij3[0];
01960 vinfos[3].indices[1] = _ij3[1];
01961 vinfos[3].maxsolutions = _nj3;
01962 vinfos[4].jointtype = 1;
01963 vinfos[4].foffset = j4;
01964 vinfos[4].indices[0] = _ij4[0];
01965 vinfos[4].indices[1] = _ij4[1];
01966 vinfos[4].maxsolutions = _nj4;
01967 std::vector<int> vfree(0);
01968 solutions.AddSolution(vinfos,vfree);
01969 }
01970 }
01971 }
01972 
01973 }
01974 
01975 }
01976 
01977 } else
01978 {
01979 if( 1 )
01980 {
01981 continue;
01982 
01983 } else
01984 {
01985 }
01986 }
01987 }
01988 }
01989 
01990 } else
01991 {
01992 {
01993 IkReal j2array[1], cj2array[1], sj2array[1];
01994 bool j2valid[1]={false};
01995 _nj2 = 1;
01996 IkReal x617=((IkReal(0.0800000000000000))*(cj3));
01997 IkReal x618=((IkReal(0.0750000000000000))*(cj1));
01998 IkReal x619=((r01)*(sj0));
01999 IkReal x620=((r02)*(sj1));
02000 IkReal x621=((IkReal(0.0800000000000000))*(sj3));
02001 IkReal x622=((cj3)*(cj4));
02002 IkReal x623=((cj4)*(sj3));
02003 IkReal x624=((pz)*(sj1));
02004 IkReal x625=((cj0)*(cj1)*(r00));
02005 IkReal x626=((cj0)*(cj1)*(px));
02006 IkReal x627=((cj1)*(py)*(sj0));
02007 if( IKabs(((gconst3)*(((((IkReal(-0.320000000000000))*(cj1)*(x619)))+(((IkReal(-0.320000000000000))*(x625)))+(((IkReal(-1.00000000000000))*(cj1)*(x617)*(x619)))+(((x617)*(x620)))+(((x623)*(x624)))+(((x618)*(x623)))+(((IkReal(-1.00000000000000))*(x623)*(x626)))+(((IkReal(-1.00000000000000))*(x617)*(x625)))+(((IkReal(-1.00000000000000))*(x623)*(x627)))+(((IkReal(0.320000000000000))*(x620))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(x618)*(x619)))+(((IkReal(-1.00000000000000))*(cj1)*(x619)*(x621)))+(((x622)*(x626)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x618)))+(((IkReal(-1.00000000000000))*(x621)*(x625)))+(((IkReal(-1.00000000000000))*(x622)*(x624)))+(((IkReal(-1.00000000000000))*(x618)*(x622)))+(((x622)*(x627)))+(((IkReal(0.0750000000000000))*(x620)))+(((x620)*(x621))))))) < IKFAST_ATAN2_MAGTHRESH )
02008     continue;
02009 j2array[0]=IKatan2(((gconst3)*(((((IkReal(-0.320000000000000))*(cj1)*(x619)))+(((IkReal(-0.320000000000000))*(x625)))+(((IkReal(-1.00000000000000))*(cj1)*(x617)*(x619)))+(((x617)*(x620)))+(((x623)*(x624)))+(((x618)*(x623)))+(((IkReal(-1.00000000000000))*(x623)*(x626)))+(((IkReal(-1.00000000000000))*(x617)*(x625)))+(((IkReal(-1.00000000000000))*(x623)*(x627)))+(((IkReal(0.320000000000000))*(x620)))))), ((gconst3)*(((((IkReal(-1.00000000000000))*(x618)*(x619)))+(((IkReal(-1.00000000000000))*(cj1)*(x619)*(x621)))+(((x622)*(x626)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x618)))+(((IkReal(-1.00000000000000))*(x621)*(x625)))+(((IkReal(-1.00000000000000))*(x622)*(x624)))+(((IkReal(-1.00000000000000))*(x618)*(x622)))+(((x622)*(x627)))+(((IkReal(0.0750000000000000))*(x620)))+(((x620)*(x621)))))));
02010 sj2array[0]=IKsin(j2array[0]);
02011 cj2array[0]=IKcos(j2array[0]);
02012 if( j2array[0] > IKPI )
02013 {
02014     j2array[0]-=IK2PI;
02015 }
02016 else if( j2array[0] < -IKPI )
02017 {    j2array[0]+=IK2PI;
02018 }
02019 j2valid[0] = true;
02020 for(int ij2 = 0; ij2 < 1; ++ij2)
02021 {
02022 if( !j2valid[ij2] )
02023 {
02024     continue;
02025 }
02026 _ij2[0] = ij2; _ij2[1] = -1;
02027 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02028 {
02029 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02030 {
02031     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02032 }
02033 }
02034 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02035 {
02036 IkReal evalcond[8];
02037 IkReal x628=IKcos(j2);
02038 IkReal x629=IKsin(j2);
02039 IkReal x630=(py)*(py);
02040 IkReal x631=(px)*(px);
02041 IkReal x632=(pz)*(pz);
02042 IkReal x633=((sj0)*(sj1));
02043 IkReal x634=((IkReal(1.00000000000000))*(r01));
02044 IkReal x635=((r00)*(sj1));
02045 IkReal x636=((IkReal(0.0480000000000000))*(sj3));
02046 IkReal x637=((IkReal(0.0750000000000000))*(r00));
02047 IkReal x638=((IkReal(0.0800000000000000))*(sj3));
02048 IkReal x639=((cj1)*(r01));
02049 IkReal x640=((IkReal(0.150000000000000))*(py));
02050 IkReal x641=((pz)*(r02));
02051 IkReal x642=((px)*(r02));
02052 IkReal x643=((IkReal(0.0750000000000000))*(sj4));
02053 IkReal x644=((cj1)*(sj0));
02054 IkReal x645=((pz)*(r00));
02055 IkReal x646=((IkReal(0.0750000000000000))*(cj0));
02056 IkReal x647=((IkReal(2.00000000000000))*(cj0));
02057 IkReal x648=((cj1)*(r02));
02058 IkReal x649=((IkReal(0.150000000000000))*(sj1));
02059 IkReal x650=((px)*(r00));
02060 IkReal x651=((IkReal(2.00000000000000))*(py));
02061 IkReal x652=((IkReal(0.0903750000000000))*(sj3));
02062 IkReal x653=((r02)*(sj1));
02063 IkReal x654=((IkReal(0.150000000000000))*(cj1));
02064 IkReal x655=((cj0)*(py));
02065 IkReal x656=((IkReal(0.0480000000000000))*(cj3));
02066 IkReal x657=((r01)*(sj1));
02067 IkReal x658=((IkReal(0.0800000000000000))*(cj3));
02068 IkReal x659=((IkReal(0.150000000000000))*(pz));
02069 IkReal x660=((IkReal(1.00000000000000))*(cj1));
02070 IkReal x661=((cj0)*(r00));
02071 IkReal x662=((IkReal(0.600000000000000))*(py));
02072 IkReal x663=((IkReal(1.00000000000000))*(py));
02073 IkReal x664=((px)*(sj1));
02074 IkReal x665=((IkReal(1.00000000000000))*(cj0));
02075 IkReal x666=((cj0)*(pz));
02076 IkReal x667=((IkReal(0.103175000000000))*(cj3));
02077 IkReal x668=((IkReal(0.600000000000000))*(cj0));
02078 IkReal x669=((IkReal(1.00000000000000))*(sj3));
02079 IkReal x670=((px)*(py));
02080 IkReal x671=((r01)*(sj0));
02081 IkReal x672=((IkReal(2.00000000000000))*(px));
02082 IkReal x673=((cj4)*(x629));
02083 IkReal x674=((cj4)*(x628));
02084 IkReal x675=((sj4)*(x629));
02085 IkReal x676=((IkReal(2.00000000000000))*(x632));
02086 IkReal x677=((sj4)*(x628));
02087 IkReal x678=((IkReal(2.00000000000000))*(x630));
02088 IkReal x679=((px)*(x641)*(x647));
02089 evalcond[0]=((x653)+(((IkReal(-1.00000000000000))*(x669)*(x674)))+(((IkReal(-1.00000000000000))*(x660)*(x661)))+(((IkReal(-1.00000000000000))*(x634)*(x644)))+(((IkReal(-1.00000000000000))*(cj3)*(x673))));
02090 evalcond[1]=((((IkReal(-1.00000000000000))*(x669)*(x673)))+(((IkReal(-1.00000000000000))*(x633)*(x634)))+(((cj3)*(x674)))+(((IkReal(-1.00000000000000))*(x635)*(x665)))+(((IkReal(-1.00000000000000))*(x648))));
02091 evalcond[2]=((((IkReal(-1.00000000000000))*(x629)*(x638)))+(((IkReal(-1.00000000000000))*(x644)*(x663)))+(((pz)*(sj1)))+(((x628)*(x658)))+(((IkReal(-0.0750000000000000))*(x629)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x660)))+(((IkReal(0.0750000000000000))*(cj1)))+(((IkReal(0.320000000000000))*(x628))));
02092 evalcond[3]=((IkReal(0.300000000000000))+(((IkReal(0.320000000000000))*(x629)))+(((IkReal(-1.00000000000000))*(x633)*(x663)))+(((x628)*(x638)))+(((IkReal(0.0750000000000000))*(x628)))+(((IkReal(-1.00000000000000))*(pz)*(x660)))+(((IkReal(-1.00000000000000))*(x664)*(x665)))+(((x629)*(x658)))+(((IkReal(0.0750000000000000))*(sj1))));
02093 evalcond[4]=((((x638)*(x675)))+(((IkReal(-0.320000000000000))*(x677)))+(((x629)*(x643)))+(((IkReal(-1.00000000000000))*(x658)*(x677)))+(((x633)*(x645)))+(((IkReal(-1.00000000000000))*(sj1)*(x634)*(x666)))+(((px)*(x639)))+(((x637)*(x644)))+(((IkReal(-1.00000000000000))*(x633)*(x642)))+(((x653)*(x655)))+(((IkReal(-1.00000000000000))*(x639)*(x646)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x660))));
02094 evalcond[5]=((((x628)*(x643)))+(((x646)*(x657)))+(((py)*(x635)))+(((x638)*(x677)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((x658)*(x675)))+(((x644)*(x645)))+(((IkReal(-1.00000000000000))*(x634)*(x664)))+(((IkReal(-1.00000000000000))*(x633)*(x637)))+(((x648)*(x655)))+(((IkReal(0.320000000000000))*(x675)))+(((IkReal(-1.00000000000000))*(cj1)*(x634)*(x666)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(x642)*(x644))));
02095 evalcond[6]=((((cj1)*(x645)*(x672)))+(((x647)*(x657)*(x670)))+(((x633)*(x650)*(x651)))+(((IkReal(-1.00000000000000))*(sj0)*(x639)*(x659)))+(((IkReal(0.0512000000000000))*(x674)))+(((cj0)*(x642)*(x654)))+(((IkReal(0.0956250000000000))*(cj0)*(x635)))+(((x633)*(x641)*(x651)))+(((IkReal(-0.600000000000000))*(x641)))+(((IkReal(-1.00000000000000))*(r01)*(x662)))+(((IkReal(-1.00000000000000))*(pp)*(x635)*(x665)))+(((x652)*(x673)))+(((IkReal(0.0450000000000000))*(x671)))+(((IkReal(-1.00000000000000))*(x640)*(x657)))+(((IkReal(-1.00000000000000))*(x641)*(x649)))+(((x636)*(x674)))+(((IkReal(-1.00000000000000))*(pp)*(x633)*(x634)))+(((IkReal(0.0450000000000000))*(x661)))+(((r01)*(x633)*(x678)))+(((IkReal(-1.00000000000000))*(cj0)*(x645)*(x654)))+(((x631)*(x635)*(x647)))+(((IkReal(-0.600000000000000))*(x650)))+(((x641)*(x647)*(x664)))+(((IkReal(-1.00000000000000))*(x656)*(x673)))+(((r02)*(x640)*(x644)))+(((IkReal(0.0956250000000000))*(r01)*(x633)))+(((IkReal(-0.0120000000000000))*(x673)))+(((IkReal(-1.00000000000000))*(pp)*(x648)))+(((x648)*(x676)))+(((IkReal(0.0843750000000000))*(x648)))+(((pz)*(x639)*(x651)))+(((x667)*(x674)))+(((IkReal(-0.150000000000000))*(px)*(x635))));
02096 evalcond[7]=((((IkReal(-1.00000000000000))*(x636)*(x673)))+(((IkReal(-1.00000000000000))*(cj0)*(x642)*(x649)))+(((IkReal(-1.00000000000000))*(x641)*(x654)))+(((IkReal(-1.00000000000000))*(x642)*(x668)))+(((IkReal(-1.00000000000000))*(r02)*(x633)*(x640)))+(((cj0)*(x635)*(x659)))+(((IkReal(0.0450000000000000))*(r02)))+(((cj1)*(x679)))+(((IkReal(-1.00000000000000))*(pp)*(x660)*(x661)))+(((IkReal(-1.00000000000000))*(x667)*(x673)))+(((IkReal(-1.00000000000000))*(pp)*(x634)*(x644)))+(((sj0)*(x639)*(x678)))+(((IkReal(-0.0843750000000000))*(sj0)*(x639)))+(((x639)*(x647)*(x670)))+(((IkReal(-1.00000000000000))*(x653)*(x676)))+(((cj1)*(r00)*(x631)*(x647)))+(((IkReal(0.0956250000000000))*(x653)))+(((x652)*(x674)))+(((x644)*(x650)*(x651)))+(((r01)*(x633)*(x659)))+(((IkReal(-1.00000000000000))*(pz)*(x635)*(x672)))+(((IkReal(-0.0512000000000000))*(x673)))+(((IkReal(-1.00000000000000))*(x639)*(x640)))+(((IkReal(-1.00000000000000))*(x650)*(x654)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x662)))+(((x641)*(x644)*(x651)))+(((pp)*(x653)))+(((IkReal(-1.00000000000000))*(x656)*(x674)))+(((IkReal(-0.0843750000000000))*(cj1)*(x661)))+(((x645)*(x668)))+(((IkReal(-0.0120000000000000))*(x674)))+(((IkReal(0.600000000000000))*(pz)*(x671)))+(((IkReal(-1.00000000000000))*(pz)*(x651)*(x657))));
02097 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  || IKabs(evalcond[6]) > 0.000001  || IKabs(evalcond[7]) > 0.000001  )
02098 {
02099 continue;
02100 }
02101 }
02102 
02103 {
02104 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02105 vinfos[0].jointtype = 1;
02106 vinfos[0].foffset = j0;
02107 vinfos[0].indices[0] = _ij0[0];
02108 vinfos[0].indices[1] = _ij0[1];
02109 vinfos[0].maxsolutions = _nj0;
02110 vinfos[1].jointtype = 1;
02111 vinfos[1].foffset = j1;
02112 vinfos[1].indices[0] = _ij1[0];
02113 vinfos[1].indices[1] = _ij1[1];
02114 vinfos[1].maxsolutions = _nj1;
02115 vinfos[2].jointtype = 1;
02116 vinfos[2].foffset = j2;
02117 vinfos[2].indices[0] = _ij2[0];
02118 vinfos[2].indices[1] = _ij2[1];
02119 vinfos[2].maxsolutions = _nj2;
02120 vinfos[3].jointtype = 1;
02121 vinfos[3].foffset = j3;
02122 vinfos[3].indices[0] = _ij3[0];
02123 vinfos[3].indices[1] = _ij3[1];
02124 vinfos[3].maxsolutions = _nj3;
02125 vinfos[4].jointtype = 1;
02126 vinfos[4].foffset = j4;
02127 vinfos[4].indices[0] = _ij4[0];
02128 vinfos[4].indices[1] = _ij4[1];
02129 vinfos[4].maxsolutions = _nj4;
02130 std::vector<int> vfree(0);
02131 solutions.AddSolution(vinfos,vfree);
02132 }
02133 }
02134 }
02135 
02136 }
02137 
02138 }
02139 
02140 } else
02141 {
02142 {
02143 IkReal j2array[1], cj2array[1], sj2array[1];
02144 bool j2valid[1]={false};
02145 _nj2 = 1;
02146 IkReal x680=((IkReal(1.00000000000000))*(cj1));
02147 IkReal x681=((cj0)*(r00));
02148 IkReal x682=((cj3)*(r02));
02149 IkReal x683=((sj1)*(sj3));
02150 IkReal x684=((r01)*(sj0));
02151 IkReal x685=((cj3)*(x684));
02152 if( IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x683)*(x684)))+(((IkReal(-1.00000000000000))*(cj3)*(x680)*(x681)))+(((IkReal(-1.00000000000000))*(x680)*(x685)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x680)))+(((IkReal(-1.00000000000000))*(x681)*(x683)))+(((sj1)*(x682))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(sj3)*(x680)*(x684)))+(((cj3)*(sj1)*(x681)))+(((cj1)*(x682)))+(((IkReal(-1.00000000000000))*(sj3)*(x680)*(x681)))+(((r02)*(x683)))+(((sj1)*(x685))))))) < IKFAST_ATAN2_MAGTHRESH )
02153     continue;
02154 j2array[0]=IKatan2(((gconst2)*(((((IkReal(-1.00000000000000))*(x683)*(x684)))+(((IkReal(-1.00000000000000))*(cj3)*(x680)*(x681)))+(((IkReal(-1.00000000000000))*(x680)*(x685)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x680)))+(((IkReal(-1.00000000000000))*(x681)*(x683)))+(((sj1)*(x682)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(sj3)*(x680)*(x684)))+(((cj3)*(sj1)*(x681)))+(((cj1)*(x682)))+(((IkReal(-1.00000000000000))*(sj3)*(x680)*(x681)))+(((r02)*(x683)))+(((sj1)*(x685)))))));
02155 sj2array[0]=IKsin(j2array[0]);
02156 cj2array[0]=IKcos(j2array[0]);
02157 if( j2array[0] > IKPI )
02158 {
02159     j2array[0]-=IK2PI;
02160 }
02161 else if( j2array[0] < -IKPI )
02162 {    j2array[0]+=IK2PI;
02163 }
02164 j2valid[0] = true;
02165 for(int ij2 = 0; ij2 < 1; ++ij2)
02166 {
02167 if( !j2valid[ij2] )
02168 {
02169     continue;
02170 }
02171 _ij2[0] = ij2; _ij2[1] = -1;
02172 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02173 {
02174 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02175 {
02176     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02177 }
02178 }
02179 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02180 {
02181 IkReal evalcond[8];
02182 IkReal x686=IKcos(j2);
02183 IkReal x687=IKsin(j2);
02184 IkReal x688=(py)*(py);
02185 IkReal x689=(px)*(px);
02186 IkReal x690=(pz)*(pz);
02187 IkReal x691=((sj0)*(sj1));
02188 IkReal x692=((IkReal(1.00000000000000))*(r01));
02189 IkReal x693=((r00)*(sj1));
02190 IkReal x694=((IkReal(0.0480000000000000))*(sj3));
02191 IkReal x695=((IkReal(0.0750000000000000))*(r00));
02192 IkReal x696=((IkReal(0.0800000000000000))*(sj3));
02193 IkReal x697=((cj1)*(r01));
02194 IkReal x698=((IkReal(0.150000000000000))*(py));
02195 IkReal x699=((pz)*(r02));
02196 IkReal x700=((px)*(r02));
02197 IkReal x701=((IkReal(0.0750000000000000))*(sj4));
02198 IkReal x702=((cj1)*(sj0));
02199 IkReal x703=((pz)*(r00));
02200 IkReal x704=((IkReal(0.0750000000000000))*(cj0));
02201 IkReal x705=((IkReal(2.00000000000000))*(cj0));
02202 IkReal x706=((cj1)*(r02));
02203 IkReal x707=((IkReal(0.150000000000000))*(sj1));
02204 IkReal x708=((px)*(r00));
02205 IkReal x709=((IkReal(2.00000000000000))*(py));
02206 IkReal x710=((IkReal(0.0903750000000000))*(sj3));
02207 IkReal x711=((r02)*(sj1));
02208 IkReal x712=((IkReal(0.150000000000000))*(cj1));
02209 IkReal x713=((cj0)*(py));
02210 IkReal x714=((IkReal(0.0480000000000000))*(cj3));
02211 IkReal x715=((r01)*(sj1));
02212 IkReal x716=((IkReal(0.0800000000000000))*(cj3));
02213 IkReal x717=((IkReal(0.150000000000000))*(pz));
02214 IkReal x718=((IkReal(1.00000000000000))*(cj1));
02215 IkReal x719=((cj0)*(r00));
02216 IkReal x720=((IkReal(0.600000000000000))*(py));
02217 IkReal x721=((IkReal(1.00000000000000))*(py));
02218 IkReal x722=((px)*(sj1));
02219 IkReal x723=((IkReal(1.00000000000000))*(cj0));
02220 IkReal x724=((cj0)*(pz));
02221 IkReal x725=((IkReal(0.103175000000000))*(cj3));
02222 IkReal x726=((IkReal(0.600000000000000))*(cj0));
02223 IkReal x727=((IkReal(1.00000000000000))*(sj3));
02224 IkReal x728=((px)*(py));
02225 IkReal x729=((r01)*(sj0));
02226 IkReal x730=((IkReal(2.00000000000000))*(px));
02227 IkReal x731=((cj4)*(x687));
02228 IkReal x732=((cj4)*(x686));
02229 IkReal x733=((sj4)*(x687));
02230 IkReal x734=((IkReal(2.00000000000000))*(x690));
02231 IkReal x735=((sj4)*(x686));
02232 IkReal x736=((IkReal(2.00000000000000))*(x688));
02233 IkReal x737=((px)*(x699)*(x705));
02234 evalcond[0]=((((IkReal(-1.00000000000000))*(x718)*(x719)))+(((IkReal(-1.00000000000000))*(x727)*(x732)))+(((IkReal(-1.00000000000000))*(cj3)*(x731)))+(x711)+(((IkReal(-1.00000000000000))*(x692)*(x702))));
02235 evalcond[1]=((((cj3)*(x732)))+(((IkReal(-1.00000000000000))*(x693)*(x723)))+(((IkReal(-1.00000000000000))*(x691)*(x692)))+(((IkReal(-1.00000000000000))*(x727)*(x731)))+(((IkReal(-1.00000000000000))*(x706))));
02236 evalcond[2]=((((IkReal(-0.0750000000000000))*(x687)))+(((IkReal(-1.00000000000000))*(x702)*(x721)))+(((x686)*(x716)))+(((pz)*(sj1)))+(((IkReal(0.320000000000000))*(x686)))+(((IkReal(-1.00000000000000))*(x687)*(x696)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x718)))+(((IkReal(0.0750000000000000))*(cj1))));
02237 evalcond[3]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x691)*(x721)))+(((IkReal(0.320000000000000))*(x687)))+(((IkReal(-1.00000000000000))*(x722)*(x723)))+(((IkReal(0.0750000000000000))*(x686)))+(((x686)*(x696)))+(((IkReal(-1.00000000000000))*(pz)*(x718)))+(((x687)*(x716)))+(((IkReal(0.0750000000000000))*(sj1))));
02238 evalcond[4]=((((px)*(x697)))+(((IkReal(-1.00000000000000))*(x691)*(x700)))+(((x695)*(x702)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x718)))+(((IkReal(-0.320000000000000))*(x735)))+(((IkReal(-1.00000000000000))*(sj1)*(x692)*(x724)))+(((x687)*(x701)))+(((IkReal(-1.00000000000000))*(x697)*(x704)))+(((x711)*(x713)))+(((x696)*(x733)))+(((IkReal(-1.00000000000000))*(x716)*(x735)))+(((x691)*(x703))));
02239 evalcond[5]=((((IkReal(0.320000000000000))*(x733)))+(((x702)*(x703)))+(((x706)*(x713)))+(((IkReal(-1.00000000000000))*(x692)*(x722)))+(((x696)*(x735)))+(((IkReal(-1.00000000000000))*(cj1)*(x692)*(x724)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((x704)*(x715)))+(((py)*(x693)))+(((IkReal(-1.00000000000000))*(x700)*(x702)))+(((x716)*(x733)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(x691)*(x695)))+(((x686)*(x701))));
02240 evalcond[6]=((((IkReal(-1.00000000000000))*(pp)*(x693)*(x723)))+(((IkReal(0.0956250000000000))*(cj0)*(x693)))+(((x706)*(x734)))+(((IkReal(-0.600000000000000))*(x699)))+(((IkReal(0.0512000000000000))*(x732)))+(((IkReal(-0.150000000000000))*(px)*(x693)))+(((x691)*(x699)*(x709)))+(((pz)*(x697)*(x709)))+(((r02)*(x698)*(x702)))+(((r01)*(x691)*(x736)))+(((IkReal(-1.00000000000000))*(x698)*(x715)))+(((IkReal(-1.00000000000000))*(sj0)*(x697)*(x717)))+(((x694)*(x732)))+(((x705)*(x715)*(x728)))+(((cj0)*(x700)*(x712)))+(((x689)*(x693)*(x705)))+(((IkReal(0.0450000000000000))*(x729)))+(((IkReal(-0.0120000000000000))*(x731)))+(((IkReal(0.0956250000000000))*(r01)*(x691)))+(((IkReal(-1.00000000000000))*(x714)*(x731)))+(((IkReal(-0.600000000000000))*(x708)))+(((x725)*(x732)))+(((IkReal(-1.00000000000000))*(pp)*(x691)*(x692)))+(((x691)*(x708)*(x709)))+(((IkReal(0.0843750000000000))*(x706)))+(((IkReal(-1.00000000000000))*(cj0)*(x703)*(x712)))+(((x699)*(x705)*(x722)))+(((x710)*(x731)))+(((cj1)*(x703)*(x730)))+(((IkReal(0.0450000000000000))*(x719)))+(((IkReal(-1.00000000000000))*(r01)*(x720)))+(((IkReal(-1.00000000000000))*(pp)*(x706)))+(((IkReal(-1.00000000000000))*(x699)*(x707))));
02241 evalcond[7]=((((IkReal(0.0956250000000000))*(x711)))+(((x702)*(x708)*(x709)))+(((IkReal(-0.0512000000000000))*(x731)))+(((IkReal(-1.00000000000000))*(x699)*(x712)))+(((IkReal(-1.00000000000000))*(pp)*(x692)*(x702)))+(((IkReal(0.0450000000000000))*(r02)))+(((x699)*(x702)*(x709)))+(((cj1)*(x737)))+(((IkReal(-1.00000000000000))*(cj0)*(x700)*(x707)))+(((IkReal(-1.00000000000000))*(pp)*(x718)*(x719)))+(((cj0)*(x693)*(x717)))+(((IkReal(-0.0843750000000000))*(sj0)*(x697)))+(((IkReal(-1.00000000000000))*(pz)*(x709)*(x715)))+(((pp)*(x711)))+(((r01)*(x691)*(x717)))+(((IkReal(-1.00000000000000))*(pz)*(x693)*(x730)))+(((x697)*(x705)*(x728)))+(((IkReal(-1.00000000000000))*(x714)*(x732)))+(((sj0)*(x697)*(x736)))+(((IkReal(-0.0120000000000000))*(x732)))+(((IkReal(-1.00000000000000))*(x697)*(x698)))+(((IkReal(-1.00000000000000))*(x711)*(x734)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x720)))+(((cj1)*(r00)*(x689)*(x705)))+(((IkReal(-1.00000000000000))*(x725)*(x731)))+(((IkReal(0.600000000000000))*(pz)*(x729)))+(((IkReal(-1.00000000000000))*(x694)*(x731)))+(((IkReal(-0.0843750000000000))*(cj1)*(x719)))+(((IkReal(-1.00000000000000))*(x708)*(x712)))+(((x710)*(x732)))+(((IkReal(-1.00000000000000))*(r02)*(x691)*(x698)))+(((IkReal(-1.00000000000000))*(x700)*(x726)))+(((x703)*(x726))));
02242 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  || IKabs(evalcond[6]) > 0.000001  || IKabs(evalcond[7]) > 0.000001  )
02243 {
02244 continue;
02245 }
02246 }
02247 
02248 {
02249 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02250 vinfos[0].jointtype = 1;
02251 vinfos[0].foffset = j0;
02252 vinfos[0].indices[0] = _ij0[0];
02253 vinfos[0].indices[1] = _ij0[1];
02254 vinfos[0].maxsolutions = _nj0;
02255 vinfos[1].jointtype = 1;
02256 vinfos[1].foffset = j1;
02257 vinfos[1].indices[0] = _ij1[0];
02258 vinfos[1].indices[1] = _ij1[1];
02259 vinfos[1].maxsolutions = _nj1;
02260 vinfos[2].jointtype = 1;
02261 vinfos[2].foffset = j2;
02262 vinfos[2].indices[0] = _ij2[0];
02263 vinfos[2].indices[1] = _ij2[1];
02264 vinfos[2].maxsolutions = _nj2;
02265 vinfos[3].jointtype = 1;
02266 vinfos[3].foffset = j3;
02267 vinfos[3].indices[0] = _ij3[0];
02268 vinfos[3].indices[1] = _ij3[1];
02269 vinfos[3].maxsolutions = _nj3;
02270 vinfos[4].jointtype = 1;
02271 vinfos[4].foffset = j4;
02272 vinfos[4].indices[0] = _ij4[0];
02273 vinfos[4].indices[1] = _ij4[1];
02274 vinfos[4].maxsolutions = _nj4;
02275 std::vector<int> vfree(0);
02276 solutions.AddSolution(vinfos,vfree);
02277 }
02278 }
02279 }
02280 
02281 }
02282 
02283 }
02284 }
02285 }
02286 
02287 }
02288 
02289 }
02290 
02291 } else
02292 {
02293 {
02294 IkReal j3array[1], cj3array[1], sj3array[1];
02295 bool j3valid[1]={false};
02296 _nj3 = 1;
02297 IkReal x738=((r01)*(sj0));
02298 IkReal x739=((cj0)*(sj1));
02299 IkReal x740=((cj4)*(px));
02300 IkReal x741=((cj0)*(r00));
02301 IkReal x742=((cj4)*(pp));
02302 IkReal x743=((cj1)*(r02));
02303 IkReal x744=((pz)*(r02));
02304 IkReal x745=((cj4)*(sj1));
02305 IkReal x746=((px)*(r00));
02306 IkReal x747=((py)*(r01));
02307 IkReal x748=((cj4)*(py)*(sj0));
02308 IkReal x749=((cj1)*(cj4)*(pz));
02309 if( IKabs(((gconst0)*(((((IkReal(3840.00000000000))*(r00)*(x739)))+(((IkReal(3840.00000000000))*(sj1)*(x738)))+(((IkReal(-12800.0000000000))*(x747)))+(((IkReal(-12800.0000000000))*(x744)))+(((IkReal(-2812.50000000000))*(x748)))+(((IkReal(-352.500000000000))*(cj4)))+(((IkReal(960.000000000000))*(x738)))+(((IkReal(843.750000000000))*(x745)))+(((IkReal(3840.00000000000))*(x743)))+(((IkReal(-12800.0000000000))*(x746)))+(((IkReal(-11250.0000000000))*(x749)))+(((IkReal(-2812.50000000000))*(cj0)*(x740)))+(((IkReal(-11250.0000000000))*(x739)*(x740)))+(((IkReal(960.000000000000))*(x741)))+(((IkReal(18750.0000000000))*(x742)))+(((IkReal(-11250.0000000000))*(py)*(sj0)*(x745))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-12000.0000000000))*(cj0)*(x740)))+(((IkReal(-900.000000000000))*(r00)*(x739)))+(((IkReal(-12000.0000000000))*(x748)))+(((IkReal(-48000.0000000000))*(x739)*(x740)))+(((IkReal(-48000.0000000000))*(py)*(sj0)*(x745)))+(((IkReal(3000.00000000000))*(x747)))+(((IkReal(-48000.0000000000))*(x749)))+(((IkReal(-900.000000000000))*(sj1)*(x738)))+(((IkReal(-225.000000000000))*(x741)))+(((IkReal(3000.00000000000))*(x746)))+(((IkReal(3000.00000000000))*(x744)))+(((IkReal(-900.000000000000))*(x743)))+(((IkReal(80000.0000000000))*(x742)))+(((IkReal(-225.000000000000))*(x738)))+(((IkReal(3600.00000000000))*(x745)))+(((IkReal(-1504.00000000000))*(cj4))))))) < IKFAST_ATAN2_MAGTHRESH )
02310     continue;
02311 j3array[0]=IKatan2(((gconst0)*(((((IkReal(3840.00000000000))*(r00)*(x739)))+(((IkReal(3840.00000000000))*(sj1)*(x738)))+(((IkReal(-12800.0000000000))*(x747)))+(((IkReal(-12800.0000000000))*(x744)))+(((IkReal(-2812.50000000000))*(x748)))+(((IkReal(-352.500000000000))*(cj4)))+(((IkReal(960.000000000000))*(x738)))+(((IkReal(843.750000000000))*(x745)))+(((IkReal(3840.00000000000))*(x743)))+(((IkReal(-12800.0000000000))*(x746)))+(((IkReal(-11250.0000000000))*(x749)))+(((IkReal(-2812.50000000000))*(cj0)*(x740)))+(((IkReal(-11250.0000000000))*(x739)*(x740)))+(((IkReal(960.000000000000))*(x741)))+(((IkReal(18750.0000000000))*(x742)))+(((IkReal(-11250.0000000000))*(py)*(sj0)*(x745)))))), ((gconst0)*(((((IkReal(-12000.0000000000))*(cj0)*(x740)))+(((IkReal(-900.000000000000))*(r00)*(x739)))+(((IkReal(-12000.0000000000))*(x748)))+(((IkReal(-48000.0000000000))*(x739)*(x740)))+(((IkReal(-48000.0000000000))*(py)*(sj0)*(x745)))+(((IkReal(3000.00000000000))*(x747)))+(((IkReal(-48000.0000000000))*(x749)))+(((IkReal(-900.000000000000))*(sj1)*(x738)))+(((IkReal(-225.000000000000))*(x741)))+(((IkReal(3000.00000000000))*(x746)))+(((IkReal(3000.00000000000))*(x744)))+(((IkReal(-900.000000000000))*(x743)))+(((IkReal(80000.0000000000))*(x742)))+(((IkReal(-225.000000000000))*(x738)))+(((IkReal(3600.00000000000))*(x745)))+(((IkReal(-1504.00000000000))*(cj4)))))));
02312 sj3array[0]=IKsin(j3array[0]);
02313 cj3array[0]=IKcos(j3array[0]);
02314 if( j3array[0] > IKPI )
02315 {
02316     j3array[0]-=IK2PI;
02317 }
02318 else if( j3array[0] < -IKPI )
02319 {    j3array[0]+=IK2PI;
02320 }
02321 j3valid[0] = true;
02322 for(int ij3 = 0; ij3 < 1; ++ij3)
02323 {
02324 if( !j3valid[ij3] )
02325 {
02326     continue;
02327 }
02328 _ij3[0] = ij3; _ij3[1] = -1;
02329 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02330 {
02331 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02332 {
02333     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02334 }
02335 }
02336 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02337 {
02338 IkReal evalcond[4];
02339 IkReal x750=IKcos(j3);
02340 IkReal x751=IKsin(j3);
02341 IkReal x752=((r01)*(sj0));
02342 IkReal x753=((IkReal(0.300000000000000))*(r02));
02343 IkReal x754=((r00)*(sj0));
02344 IkReal x755=((py)*(sj0));
02345 IkReal x756=((IkReal(0.600000000000000))*(cj1));
02346 IkReal x757=((IkReal(0.150000000000000))*(px));
02347 IkReal x758=((IkReal(0.320000000000000))*(cj4));
02348 IkReal x759=((IkReal(1.00000000000000))*(pz));
02349 IkReal x760=((py)*(r00));
02350 IkReal x761=((IkReal(0.300000000000000))*(cj1));
02351 IkReal x762=((IkReal(1.00000000000000))*(pp));
02352 IkReal x763=((cj0)*(r00));
02353 IkReal x764=((IkReal(0.0450000000000000))*(sj1));
02354 IkReal x765=((IkReal(0.600000000000000))*(sj1));
02355 IkReal x766=((IkReal(0.0750000000000000))*(cj4));
02356 IkReal x767=((cj0)*(r01));
02357 IkReal x768=((IkReal(2.00000000000000))*(pz));
02358 IkReal x769=((cj0)*(px));
02359 IkReal x770=((IkReal(0.300000000000000))*(sj1));
02360 IkReal x771=((IkReal(2.00000000000000))*(px)*(py));
02361 IkReal x772=((IkReal(0.0120000000000000))*(x751));
02362 IkReal x773=((IkReal(0.0512000000000000))*(x750));
02363 IkReal x774=((cj0)*(py)*(r02));
02364 IkReal x775=((px)*(r02)*(sj0));
02365 evalcond[0]=((IkReal(0.0188000000000000))+(((cj0)*(x757)))+(((pz)*(x756)))+(((IkReal(0.150000000000000))*(x755)))+(((x755)*(x765)))+(((IkReal(-1.00000000000000))*(x762)))+(x773)+(x772)+(((IkReal(-1.00000000000000))*(x764)))+(((x765)*(x769))));
02366 evalcond[1]=((((IkReal(-1.00000000000000))*(py)*(r01)))+(((x752)*(x770)))+(((IkReal(0.0750000000000000))*(x763)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((cj1)*(x753)))+(((x750)*(x766)))+(((IkReal(0.0750000000000000))*(x752)))+(((IkReal(-1.00000000000000))*(r02)*(x759)))+(((x763)*(x770)))+(((IkReal(-1.00000000000000))*(x751)*(x758))));
02367 evalcond[2]=((((IkReal(-0.0800000000000000))*(cj4)))+(((r02)*(x769)))+(((x752)*(x761)))+(((IkReal(-1.00000000000000))*(x759)*(x763)))+(((r02)*(x755)))+(((IkReal(-1.00000000000000))*(sj1)*(x753)))+(((IkReal(-1.00000000000000))*(x752)*(x759)))+(((x761)*(x763)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x751)*(x766)))+(((IkReal(-1.00000000000000))*(x750)*(x758))));
02368 evalcond[3]=((((pp)*(x767)))+(((x752)*(x771)))+(((IkReal(-1.00000000000000))*(x754)*(x764)))+(((IkReal(-1.00000000000000))*(r01)*(x757)))+(((pz)*(x754)*(x756)))+(((IkReal(0.150000000000000))*(x760)))+(((IkReal(-1.00000000000000))*(x754)*(x762)))+(((IkReal(-2.00000000000000))*(x760)*(x769)))+(((IkReal(-1.00000000000000))*(pz)*(x756)*(x767)))+(((IkReal(-1.00000000000000))*(x768)*(x774)))+(((x756)*(x774)))+(((IkReal(-1.00000000000000))*(sj4)*(x772)))+(((IkReal(0.0956250000000000))*(x767)))+(((IkReal(-2.00000000000000))*(x767)*((py)*(py))))+(((IkReal(-0.114425000000000))*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x773)))+(((x768)*(x775)))+(((IkReal(2.00000000000000))*(x754)*((px)*(px))))+(((IkReal(-0.0956250000000000))*(x754)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x765)))+(((x760)*(x765)))+(((IkReal(-1.00000000000000))*(x756)*(x775)))+(((x764)*(x767))));
02369 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02370 {
02371 continue;
02372 }
02373 }
02374 
02375 {
02376 IkReal dummyeval[1];
02377 IkReal gconst2;
02378 gconst2=IKsign(((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3))))));
02379 dummyeval[0]=((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3)))));
02380 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02381 {
02382 {
02383 IkReal dummyeval[1];
02384 IkReal gconst3;
02385 IkReal x776=((IkReal(0.0800000000000000))*(cj4));
02386 gconst3=IKsign(((((IkReal(0.320000000000000))*(cj3)*(cj4)))+(((IkReal(0.0750000000000000))*(cj4)*(sj3)))+(((x776)*((sj3)*(sj3))))+(((x776)*((cj3)*(cj3))))));
02387 IkReal x777=((IkReal(1.06666666666667))*(cj4));
02388 dummyeval[0]=((((IkReal(4.26666666666667))*(cj3)*(cj4)))+(((x777)*((cj3)*(cj3))))+(((x777)*((sj3)*(sj3))))+(((cj4)*(sj3))));
02389 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02390 {
02391 {
02392 IkReal evalcond[11];
02393 IkReal x778=((IkReal(0.0512000000000000))*(cj3));
02394 IkReal x779=((IkReal(0.0120000000000000))*(sj3));
02395 IkReal x780=(py)*(py);
02396 IkReal x781=(px)*(px);
02397 IkReal x782=(pz)*(pz);
02398 IkReal x783=((r01)*(sj0));
02399 IkReal x784=((py)*(r00));
02400 IkReal x785=((pz)*(sj1));
02401 IkReal x786=((py)*(r01));
02402 IkReal x787=((px)*(sj0));
02403 IkReal x788=((IkReal(0.600000000000000))*(r02));
02404 IkReal x789=((IkReal(0.150000000000000))*(cj1));
02405 IkReal x790=((cj0)*(sj1));
02406 IkReal x791=((IkReal(0.150000000000000))*(px));
02407 IkReal x792=((IkReal(2.00000000000000))*(cj1));
02408 IkReal x793=((cj0)*(r01));
02409 IkReal x794=((r02)*(sj1));
02410 IkReal x795=((px)*(r00));
02411 IkReal x796=((IkReal(0.300000000000000))*(r00));
02412 IkReal x797=((IkReal(1.00000000000000))*(pz));
02413 IkReal x798=((r00)*(sj1));
02414 IkReal x799=((cj0)*(r00));
02415 IkReal x800=((cj0)*(cj1));
02416 IkReal x801=((IkReal(1.00000000000000))*(sj1));
02417 IkReal x802=((IkReal(0.0956250000000000))*(r00));
02418 IkReal x803=((IkReal(0.600000000000000))*(pz));
02419 IkReal x804=((IkReal(0.600000000000000))*(sj1));
02420 IkReal x805=((IkReal(2.00000000000000))*(px));
02421 IkReal x806=((IkReal(2.00000000000000))*(sj1));
02422 IkReal x807=((IkReal(0.150000000000000))*(sj1));
02423 IkReal x808=((cj1)*(r02));
02424 IkReal x809=((cj0)*(px));
02425 IkReal x810=((IkReal(0.0843750000000000))*(cj1));
02426 IkReal x811=((py)*(sj0));
02427 IkReal x812=((pz)*(r02));
02428 IkReal x813=((IkReal(1.00000000000000))*(cj1));
02429 IkReal x814=((cj0)*(py));
02430 IkReal x815=((r00)*(sj0));
02431 IkReal x816=((r02)*(x811));
02432 IkReal x817=((pp)*(x813));
02433 IkReal x818=((IkReal(1.00000000000000))*(pp)*(r00));
02434 IkReal x819=((x779)+(x778));
02435 IkReal x820=((IkReal(2.00000000000000))*(r00)*(x781));
02436 IkReal x821=((cj0)*(x805)*(x812));
02437 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
02438 evalcond[1]=((((IkReal(-1.00000000000000))*(x787)))+(x814));
02439 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(x815)))+(x793));
02440 evalcond[3]=((((IkReal(-1.00000000000000))*(x799)*(x813)))+(x794)+(((IkReal(-1.00000000000000))*(x783)*(x813))));
02441 evalcond[4]=((((IkReal(-1.00000000000000))*(x808)))+(((IkReal(-1.00000000000000))*(r00)*(x790)))+(((IkReal(-1.00000000000000))*(x783)*(x801))));
02442 evalcond[5]=((IkReal(0.0188000000000000))+(((cj0)*(x791)))+(((x804)*(x811)))+(((IkReal(-1.00000000000000))*(pp)))+(((cj1)*(x803)))+(((IkReal(0.150000000000000))*(x811)))+(((IkReal(0.600000000000000))*(px)*(x790)))+(x819)+(((IkReal(-0.0450000000000000))*(sj1))));
02443 evalcond[6]=((((IkReal(-1.00000000000000))*(r02)*(x797)))+(((IkReal(0.0750000000000000))*(x783)))+(((IkReal(-1.00000000000000))*(x786)))+(((IkReal(0.300000000000000))*(x808)))+(((IkReal(0.300000000000000))*(sj1)*(x783)))+(((IkReal(0.0750000000000000))*(x799)))+(((x790)*(x796)))+(((IkReal(-1.00000000000000))*(x795))));
02444 evalcond[7]=((((r02)*(x809)))+(((IkReal(0.300000000000000))*(cj1)*(x783)))+(((IkReal(-1.00000000000000))*(x797)*(x799)))+(((IkReal(-1.00000000000000))*(x783)*(x797)))+(((IkReal(-0.300000000000000))*(x794)))+(((IkReal(-0.0750000000000000))*(r02)))+(x816)+(((x796)*(x800))));
02445 evalcond[8]=((IkReal(-0.114425000000000))+(((pp)*(x793)))+(((IkReal(2.00000000000000))*(x787)*(x812)))+(((IkReal(0.0450000000000000))*(r01)*(x790)))+(((IkReal(-0.0450000000000000))*(sj0)*(x798)))+(((IkReal(-1.00000000000000))*(cj1)*(x787)*(x788)))+(((cj1)*(x803)*(x815)))+(((IkReal(2.00000000000000))*(x781)*(x815)))+(((IkReal(-1.00000000000000))*(r01)*(x791)))+(((IkReal(-2.00000000000000))*(x780)*(x793)))+(((IkReal(0.0956250000000000))*(x793)))+(((IkReal(-2.00000000000000))*(x812)*(x814)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x804)))+(((IkReal(-1.00000000000000))*(x819)))+(((IkReal(0.150000000000000))*(x784)))+(((x784)*(x804)))+(((IkReal(-1.00000000000000))*(pp)*(x815)))+(((IkReal(-1.00000000000000))*(sj0)*(x802)))+(((py)*(x783)*(x805)))+(((py)*(x788)*(x800)))+(((IkReal(-1.00000000000000))*(cj0)*(x784)*(x805)))+(((IkReal(-1.00000000000000))*(cj1)*(x793)*(x803))));
02446 evalcond[9]=((((IkReal(0.0843750000000000))*(x808)))+(((r02)*(x789)*(x809)))+(((IkReal(-1.00000000000000))*(pz)*(x789)*(x799)))+(((IkReal(-1.00000000000000))*(pp)*(x783)*(x801)))+(((IkReal(-0.600000000000000))*(x786)))+(((x790)*(x802)))+(((x780)*(x783)*(x806)))+(((r02)*(x782)*(x792)))+(((IkReal(-1.00000000000000))*(pp)*(x808)))+(((pz)*(x786)*(x792)))+(((IkReal(-1.00000000000000))*(pz)*(x788)))+(((x789)*(x816)))+(((cj0)*(r02)*(x785)*(x805)))+(((IkReal(2.00000000000000))*(x785)*(x816)))+(((x784)*(x787)*(x806)))+(((IkReal(-1.00000000000000))*(pz)*(x783)*(x789)))+(((IkReal(-0.150000000000000))*(r02)*(x785)))+(((IkReal(0.0450000000000000))*(x799)))+(((pz)*(x792)*(x795)))+(((IkReal(-1.00000000000000))*(x791)*(x798)))+(((x790)*(x820)))+(((IkReal(-1.00000000000000))*(x786)*(x807)))+(((IkReal(-1.00000000000000))*(x790)*(x818)))+(((IkReal(-0.600000000000000))*(x795)))+(((x786)*(x790)*(x805)))+(((IkReal(0.0956250000000000))*(sj1)*(x783)))+(((IkReal(0.0450000000000000))*(x783))));
02447 evalcond[10]=((((x783)*(x803)))+(((IkReal(-1.00000000000000))*(x783)*(x810)))+(((x784)*(x787)*(x792)))+(((x799)*(x803)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x788)*(x811)))+(((IkReal(-1.00000000000000))*(r02)*(x790)*(x791)))+(((IkReal(-1.00000000000000))*(x799)*(x810)))+(((IkReal(-2.00000000000000))*(x785)*(x786)))+(((pp)*(x794)))+(((IkReal(0.0956250000000000))*(x794)))+(((IkReal(-1.00000000000000))*(x789)*(x795)))+(((IkReal(-1.00000000000000))*(x783)*(x817)))+(((IkReal(0.150000000000000))*(x785)*(x799)))+(((IkReal(-1.00000000000000))*(x799)*(x817)))+(((x781)*(x792)*(x799)))+(((IkReal(-1.00000000000000))*(x786)*(x789)))+(((IkReal(-2.00000000000000))*(x782)*(x794)))+(((IkReal(-0.150000000000000))*(x794)*(x811)))+(((IkReal(-2.00000000000000))*(x785)*(x795)))+(((x786)*(x792)*(x809)))+(((x792)*(x811)*(x812)))+(((IkReal(-1.00000000000000))*(x789)*(x812)))+(((x780)*(x783)*(x792)))+(((x792)*(x809)*(x812)))+(((IkReal(0.150000000000000))*(x783)*(x785)))+(((IkReal(-1.00000000000000))*(x788)*(x809))));
02448 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  && IKabs(evalcond[9]) < 0.0000010000000000  && IKabs(evalcond[10]) < 0.0000010000000000  )
02449 {
02450 {
02451 IkReal dummyeval[1];
02452 IkReal gconst4;
02453 gconst4=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02454 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
02455 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02456 {
02457 {
02458 IkReal dummyeval[1];
02459 IkReal gconst5;
02460 gconst5=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02461 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
02462 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02463 {
02464 continue;
02465 
02466 } else
02467 {
02468 {
02469 IkReal j2array[1], cj2array[1], sj2array[1];
02470 bool j2valid[1]={false};
02471 _nj2 = 1;
02472 IkReal x822=((r02)*(sj0));
02473 IkReal x823=((IkReal(0.0800000000000000))*(sj1));
02474 IkReal x824=((cj3)*(px));
02475 IkReal x825=((cj0)*(r01));
02476 IkReal x826=((IkReal(0.0240000000000000))*(cj1));
02477 IkReal x827=((pz)*(sj3));
02478 IkReal x828=((IkReal(0.00600000000000000))*(cj1));
02479 IkReal x829=((IkReal(0.320000000000000))*(px));
02480 IkReal x830=((cj0)*(sj1));
02481 IkReal x831=((cj1)*(r01));
02482 IkReal x832=((IkReal(0.0750000000000000))*(px));
02483 IkReal x833=((IkReal(0.00562500000000000))*(cj1));
02484 IkReal x834=((py)*(r02));
02485 IkReal x835=((IkReal(0.0750000000000000))*(pz));
02486 IkReal x836=((r00)*(sj0));
02487 IkReal x837=((cj3)*(pz));
02488 IkReal x838=((IkReal(0.320000000000000))*(py));
02489 IkReal x839=((sj0)*(sj1));
02490 IkReal x840=((IkReal(0.0800000000000000))*(cj1));
02491 IkReal x841=((cj1)*(r00));
02492 IkReal x842=((IkReal(0.0750000000000000))*(py));
02493 IkReal x843=((cj3)*(py));
02494 IkReal x844=((IkReal(0.00600000000000000))*(sj1));
02495 IkReal x845=((py)*(sj3));
02496 IkReal x846=((IkReal(0.320000000000000))*(pz)*(sj1));
02497 IkReal x847=((px)*(sj3)*(x823));
02498 if( IKabs(((gconst5)*(((IkReal(-0.0960000000000000))+(((IkReal(-0.0800000000000000))*(px)*(sj3)*(x831)))+(((sj0)*(x823)*(x843)))+(((IkReal(-1.00000000000000))*(sj1)*(x835)*(x836)))+(((x838)*(x839)))+(((x837)*(x840)))+(((IkReal(-1.00000000000000))*(cj0)*(sj3)*(x823)*(x834)))+(((IkReal(-1.00000000000000))*(x831)*(x832)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((sj1)*(x825)*(x835)))+(((sj3)*(x825)*(x828)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((sj1)*(x822)*(x832)))+(((x841)*(x842)))+(((x825)*(x833)))+(((IkReal(-1.00000000000000))*(x833)*(x836)))+(((IkReal(-1.00000000000000))*(cj3)*(x844)))+(((IkReal(-1.00000000000000))*(sj3)*(x828)*(x836)))+(((IkReal(-1.00000000000000))*(x823)*(x827)*(x836)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((x829)*(x830)))+(((x823)*(x825)*(x827)))+(((r00)*(x840)*(x845)))+(((x822)*(x847)))+(((IkReal(-0.0750000000000000))*(x830)*(x834)))+(((cj0)*(x823)*(x824))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x825)*(x828)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x822)*(x823)*(x824)))+(((x830)*(x832)))+(((IkReal(-1.00000000000000))*(x825)*(x826)))+(((IkReal(-1.00000000000000))*(sj3)*(x844)))+(((x827)*(x840)))+(((IkReal(-1.00000000000000))*(sj1)*(x822)*(x829)))+(((x829)*(x831)))+(((x826)*(x836)))+(((cj1)*(x835)))+(((IkReal(-1.00000000000000))*(x838)*(x841)))+(((x839)*(x842)))+(((IkReal(-1.00000000000000))*(x823)*(x825)*(x837)))+(((x823)*(x836)*(x837)))+(((sj0)*(x823)*(x845)))+(((x836)*(x846)))+(((cj0)*(cj3)*(x823)*(x834)))+(((IkReal(-1.00000000000000))*(x825)*(x846)))+(((IkReal(-1.00000000000000))*(r00)*(x840)*(x843)))+(((IkReal(0.0800000000000000))*(x824)*(x831)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x828)*(x836)))+(((cj0)*(x847)))+(((IkReal(0.320000000000000))*(x830)*(x834))))))) < IKFAST_ATAN2_MAGTHRESH )
02499     continue;
02500 j2array[0]=IKatan2(((gconst5)*(((IkReal(-0.0960000000000000))+(((IkReal(-0.0800000000000000))*(px)*(sj3)*(x831)))+(((sj0)*(x823)*(x843)))+(((IkReal(-1.00000000000000))*(sj1)*(x835)*(x836)))+(((x838)*(x839)))+(((x837)*(x840)))+(((IkReal(-1.00000000000000))*(cj0)*(sj3)*(x823)*(x834)))+(((IkReal(-1.00000000000000))*(x831)*(x832)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((sj1)*(x825)*(x835)))+(((sj3)*(x825)*(x828)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((sj1)*(x822)*(x832)))+(((x841)*(x842)))+(((x825)*(x833)))+(((IkReal(-1.00000000000000))*(x833)*(x836)))+(((IkReal(-1.00000000000000))*(cj3)*(x844)))+(((IkReal(-1.00000000000000))*(sj3)*(x828)*(x836)))+(((IkReal(-1.00000000000000))*(x823)*(x827)*(x836)))+(((IkReal(0.320000000000000))*(cj1)*(pz)))+(((x829)*(x830)))+(((x823)*(x825)*(x827)))+(((r00)*(x840)*(x845)))+(((x822)*(x847)))+(((IkReal(-0.0750000000000000))*(x830)*(x834)))+(((cj0)*(x823)*(x824)))))), ((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x825)*(x828)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x822)*(x823)*(x824)))+(((x830)*(x832)))+(((IkReal(-1.00000000000000))*(x825)*(x826)))+(((IkReal(-1.00000000000000))*(sj3)*(x844)))+(((x827)*(x840)))+(((IkReal(-1.00000000000000))*(sj1)*(x822)*(x829)))+(((x829)*(x831)))+(((x826)*(x836)))+(((cj1)*(x835)))+(((IkReal(-1.00000000000000))*(x838)*(x841)))+(((x839)*(x842)))+(((IkReal(-1.00000000000000))*(x823)*(x825)*(x837)))+(((x823)*(x836)*(x837)))+(((sj0)*(x823)*(x845)))+(((x836)*(x846)))+(((cj0)*(cj3)*(x823)*(x834)))+(((IkReal(-1.00000000000000))*(x825)*(x846)))+(((IkReal(-1.00000000000000))*(r00)*(x840)*(x843)))+(((IkReal(0.0800000000000000))*(x824)*(x831)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x828)*(x836)))+(((cj0)*(x847)))+(((IkReal(0.320000000000000))*(x830)*(x834)))))));
02501 sj2array[0]=IKsin(j2array[0]);
02502 cj2array[0]=IKcos(j2array[0]);
02503 if( j2array[0] > IKPI )
02504 {
02505     j2array[0]-=IK2PI;
02506 }
02507 else if( j2array[0] < -IKPI )
02508 {    j2array[0]+=IK2PI;
02509 }
02510 j2valid[0] = true;
02511 for(int ij2 = 0; ij2 < 1; ++ij2)
02512 {
02513 if( !j2valid[ij2] )
02514 {
02515     continue;
02516 }
02517 _ij2[0] = ij2; _ij2[1] = -1;
02518 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02519 {
02520 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02521 {
02522     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02523 }
02524 }
02525 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02526 {
02527 IkReal evalcond[4];
02528 IkReal x848=IKcos(j2);
02529 IkReal x849=IKsin(j2);
02530 IkReal x850=((IkReal(0.0800000000000000))*(sj3));
02531 IkReal x851=((cj0)*(r01));
02532 IkReal x852=((IkReal(1.00000000000000))*(px));
02533 IkReal x853=((py)*(sj1));
02534 IkReal x854=((cj0)*(r02));
02535 IkReal x855=((IkReal(0.0750000000000000))*(cj1));
02536 IkReal x856=((r02)*(sj0));
02537 IkReal x857=((IkReal(0.0750000000000000))*(sj1));
02538 IkReal x858=((cj1)*(pz));
02539 IkReal x859=((r00)*(sj0));
02540 IkReal x860=((IkReal(0.0800000000000000))*(cj3));
02541 IkReal x861=((pz)*(sj1));
02542 IkReal x862=((IkReal(1.00000000000000))*(sj0));
02543 IkReal x863=((cj1)*(py));
02544 IkReal x864=((IkReal(0.0750000000000000))*(x849));
02545 IkReal x865=((IkReal(0.320000000000000))*(x848));
02546 IkReal x866=((IkReal(0.320000000000000))*(x849));
02547 IkReal x867=((IkReal(0.0750000000000000))*(x848));
02548 IkReal x868=((sj1)*(x859));
02549 IkReal x869=((x849)*(x850));
02550 IkReal x870=((x848)*(x860));
02551 IkReal x871=((x848)*(x850));
02552 IkReal x872=((x849)*(x860));
02553 IkReal x873=((x869)+(x864));
02554 IkReal x874=((x865)+(x870));
02555 IkReal x875=((x867)+(x866)+(x871)+(x872));
02556 evalcond[0]=((((IkReal(-1.00000000000000))*(x862)*(x863)))+(x861)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x852)))+(x855)+(x874)+(((IkReal(-1.00000000000000))*(x873))));
02557 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x858)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x852)))+(((IkReal(-1.00000000000000))*(x853)*(x862)))+(x857)+(x875));
02558 evalcond[2]=((((IkReal(-1.00000000000000))*(r00)*(x863)))+(((x859)*(x861)))+(((x855)*(x859)))+(((IkReal(-1.00000000000000))*(x874)))+(((x853)*(x854)))+(((IkReal(-1.00000000000000))*(sj1)*(x852)*(x856)))+(((IkReal(-1.00000000000000))*(x851)*(x861)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x851)*(x855)))+(x873));
02559 evalcond[3]=((((IkReal(-1.00000000000000))*(x851)*(x858)))+(((IkReal(-1.00000000000000))*(cj1)*(x852)*(x856)))+(((r00)*(x853)))+(((x851)*(x857)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x852)))+(((IkReal(-1.00000000000000))*(x857)*(x859)))+(x875)+(((IkReal(0.300000000000000))*(x851)))+(((x854)*(x863)))+(((x858)*(x859)))+(((IkReal(-0.300000000000000))*(x859))));
02560 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02561 {
02562 continue;
02563 }
02564 }
02565 
02566 {
02567 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02568 vinfos[0].jointtype = 1;
02569 vinfos[0].foffset = j0;
02570 vinfos[0].indices[0] = _ij0[0];
02571 vinfos[0].indices[1] = _ij0[1];
02572 vinfos[0].maxsolutions = _nj0;
02573 vinfos[1].jointtype = 1;
02574 vinfos[1].foffset = j1;
02575 vinfos[1].indices[0] = _ij1[0];
02576 vinfos[1].indices[1] = _ij1[1];
02577 vinfos[1].maxsolutions = _nj1;
02578 vinfos[2].jointtype = 1;
02579 vinfos[2].foffset = j2;
02580 vinfos[2].indices[0] = _ij2[0];
02581 vinfos[2].indices[1] = _ij2[1];
02582 vinfos[2].maxsolutions = _nj2;
02583 vinfos[3].jointtype = 1;
02584 vinfos[3].foffset = j3;
02585 vinfos[3].indices[0] = _ij3[0];
02586 vinfos[3].indices[1] = _ij3[1];
02587 vinfos[3].maxsolutions = _nj3;
02588 vinfos[4].jointtype = 1;
02589 vinfos[4].foffset = j4;
02590 vinfos[4].indices[0] = _ij4[0];
02591 vinfos[4].indices[1] = _ij4[1];
02592 vinfos[4].maxsolutions = _nj4;
02593 std::vector<int> vfree(0);
02594 solutions.AddSolution(vinfos,vfree);
02595 }
02596 }
02597 }
02598 
02599 }
02600 
02601 }
02602 
02603 } else
02604 {
02605 {
02606 IkReal j2array[1], cj2array[1], sj2array[1];
02607 bool j2valid[1]={false};
02608 _nj2 = 1;
02609 IkReal x876=((IkReal(0.0800000000000000))*(cj1));
02610 IkReal x877=((cj0)*(px));
02611 IkReal x878=((py)*(sj0));
02612 IkReal x879=((IkReal(0.320000000000000))*(sj1));
02613 IkReal x880=((IkReal(0.00600000000000000))*(cj3));
02614 IkReal x881=((pz)*(sj3));
02615 IkReal x882=((IkReal(0.0750000000000000))*(cj1));
02616 IkReal x883=((IkReal(0.0800000000000000))*(sj1));
02617 IkReal x884=((IkReal(0.0750000000000000))*(sj1));
02618 IkReal x885=((IkReal(0.00600000000000000))*(sj3));
02619 IkReal x886=((cj3)*(pz));
02620 IkReal x887=((IkReal(0.320000000000000))*(cj1));
02621 if( IKabs(((gconst4)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x880)))+(((IkReal(-1.00000000000000))*(sj3)*(x876)*(x878)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x877)*(x879)))+(((x881)*(x883)))+(((pz)*(x884)))+(((pz)*(x887)))+(((cj1)*(x885)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x878)*(x879)))+(((cj3)*(x878)*(x883)))+(((x876)*(x886)))+(((IkReal(-1.00000000000000))*(sj3)*(x876)*(x877)))+(((IkReal(-1.00000000000000))*(x877)*(x882)))+(((cj3)*(x877)*(x883)))+(((IkReal(-1.00000000000000))*(x878)*(x882))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(-0.0225000000000000))+(((x876)*(x881)))+(((cj3)*(x876)*(x877)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x883)*(x886)))+(((sj3)*(x878)*(x883)))+(((x877)*(x887)))+(((sj3)*(x877)*(x883)))+(((x878)*(x884)))+(((cj3)*(x876)*(x878)))+(((IkReal(-1.00000000000000))*(cj1)*(x880)))+(((x877)*(x884)))+(((x878)*(x887)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((pz)*(x882)))+(((IkReal(-1.00000000000000))*(sj1)*(x885)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x879))))))) < IKFAST_ATAN2_MAGTHRESH )
02622     continue;
02623 j2array[0]=IKatan2(((gconst4)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x880)))+(((IkReal(-1.00000000000000))*(sj3)*(x876)*(x878)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((x877)*(x879)))+(((x881)*(x883)))+(((pz)*(x884)))+(((pz)*(x887)))+(((cj1)*(x885)))+(((IkReal(0.00562500000000000))*(cj1)))+(((x878)*(x879)))+(((cj3)*(x878)*(x883)))+(((x876)*(x886)))+(((IkReal(-1.00000000000000))*(sj3)*(x876)*(x877)))+(((IkReal(-1.00000000000000))*(x877)*(x882)))+(((cj3)*(x877)*(x883)))+(((IkReal(-1.00000000000000))*(x878)*(x882)))))), ((gconst4)*(((IkReal(-0.0225000000000000))+(((x876)*(x881)))+(((cj3)*(x876)*(x877)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x883)*(x886)))+(((sj3)*(x878)*(x883)))+(((x877)*(x887)))+(((sj3)*(x877)*(x883)))+(((x878)*(x884)))+(((cj3)*(x876)*(x878)))+(((IkReal(-1.00000000000000))*(cj1)*(x880)))+(((x877)*(x884)))+(((x878)*(x887)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((pz)*(x882)))+(((IkReal(-1.00000000000000))*(sj1)*(x885)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x879)))))));
02624 sj2array[0]=IKsin(j2array[0]);
02625 cj2array[0]=IKcos(j2array[0]);
02626 if( j2array[0] > IKPI )
02627 {
02628     j2array[0]-=IK2PI;
02629 }
02630 else if( j2array[0] < -IKPI )
02631 {    j2array[0]+=IK2PI;
02632 }
02633 j2valid[0] = true;
02634 for(int ij2 = 0; ij2 < 1; ++ij2)
02635 {
02636 if( !j2valid[ij2] )
02637 {
02638     continue;
02639 }
02640 _ij2[0] = ij2; _ij2[1] = -1;
02641 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02642 {
02643 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02644 {
02645     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02646 }
02647 }
02648 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02649 {
02650 IkReal evalcond[4];
02651 IkReal x888=IKcos(j2);
02652 IkReal x889=IKsin(j2);
02653 IkReal x890=((IkReal(0.0800000000000000))*(sj3));
02654 IkReal x891=((cj0)*(r01));
02655 IkReal x892=((IkReal(1.00000000000000))*(px));
02656 IkReal x893=((py)*(sj1));
02657 IkReal x894=((cj0)*(r02));
02658 IkReal x895=((IkReal(0.0750000000000000))*(cj1));
02659 IkReal x896=((r02)*(sj0));
02660 IkReal x897=((IkReal(0.0750000000000000))*(sj1));
02661 IkReal x898=((cj1)*(pz));
02662 IkReal x899=((r00)*(sj0));
02663 IkReal x900=((IkReal(0.0800000000000000))*(cj3));
02664 IkReal x901=((pz)*(sj1));
02665 IkReal x902=((IkReal(1.00000000000000))*(sj0));
02666 IkReal x903=((cj1)*(py));
02667 IkReal x904=((IkReal(0.0750000000000000))*(x889));
02668 IkReal x905=((IkReal(0.320000000000000))*(x888));
02669 IkReal x906=((IkReal(0.320000000000000))*(x889));
02670 IkReal x907=((IkReal(0.0750000000000000))*(x888));
02671 IkReal x908=((sj1)*(x899));
02672 IkReal x909=((x889)*(x890));
02673 IkReal x910=((x888)*(x900));
02674 IkReal x911=((x888)*(x890));
02675 IkReal x912=((x889)*(x900));
02676 IkReal x913=((x904)+(x909));
02677 IkReal x914=((x905)+(x910));
02678 IkReal x915=((x906)+(x907)+(x912)+(x911));
02679 evalcond[0]=((((IkReal(-1.00000000000000))*(x902)*(x903)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x892)))+(((IkReal(-1.00000000000000))*(x913)))+(x901)+(x914)+(x895));
02680 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x892)))+(((IkReal(-1.00000000000000))*(x893)*(x902)))+(((IkReal(-1.00000000000000))*(x898)))+(x915)+(x897));
02681 evalcond[2]=((((x895)*(x899)))+(((IkReal(-1.00000000000000))*(x891)*(x895)))+(((IkReal(-1.00000000000000))*(x891)*(x901)))+(((cj1)*(px)*(r01)))+(((x893)*(x894)))+(((IkReal(-1.00000000000000))*(sj1)*(x892)*(x896)))+(((IkReal(-1.00000000000000))*(x914)))+(x913)+(((IkReal(-1.00000000000000))*(r00)*(x903)))+(((x899)*(x901))));
02682 evalcond[3]=((((IkReal(-0.300000000000000))*(x899)))+(((IkReal(-1.00000000000000))*(x897)*(x899)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x892)))+(((IkReal(-1.00000000000000))*(x891)*(x898)))+(((x891)*(x897)))+(x915)+(((x894)*(x903)))+(((IkReal(-1.00000000000000))*(cj1)*(x892)*(x896)))+(((r00)*(x893)))+(((IkReal(0.300000000000000))*(x891)))+(((x898)*(x899))));
02683 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02684 {
02685 continue;
02686 }
02687 }
02688 
02689 {
02690 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02691 vinfos[0].jointtype = 1;
02692 vinfos[0].foffset = j0;
02693 vinfos[0].indices[0] = _ij0[0];
02694 vinfos[0].indices[1] = _ij0[1];
02695 vinfos[0].maxsolutions = _nj0;
02696 vinfos[1].jointtype = 1;
02697 vinfos[1].foffset = j1;
02698 vinfos[1].indices[0] = _ij1[0];
02699 vinfos[1].indices[1] = _ij1[1];
02700 vinfos[1].maxsolutions = _nj1;
02701 vinfos[2].jointtype = 1;
02702 vinfos[2].foffset = j2;
02703 vinfos[2].indices[0] = _ij2[0];
02704 vinfos[2].indices[1] = _ij2[1];
02705 vinfos[2].maxsolutions = _nj2;
02706 vinfos[3].jointtype = 1;
02707 vinfos[3].foffset = j3;
02708 vinfos[3].indices[0] = _ij3[0];
02709 vinfos[3].indices[1] = _ij3[1];
02710 vinfos[3].maxsolutions = _nj3;
02711 vinfos[4].jointtype = 1;
02712 vinfos[4].foffset = j4;
02713 vinfos[4].indices[0] = _ij4[0];
02714 vinfos[4].indices[1] = _ij4[1];
02715 vinfos[4].maxsolutions = _nj4;
02716 std::vector<int> vfree(0);
02717 solutions.AddSolution(vinfos,vfree);
02718 }
02719 }
02720 }
02721 
02722 }
02723 
02724 }
02725 
02726 } else
02727 {
02728 IkReal x916=((IkReal(0.0512000000000000))*(cj3));
02729 IkReal x917=((IkReal(0.0120000000000000))*(sj3));
02730 IkReal x918=(py)*(py);
02731 IkReal x919=(px)*(px);
02732 IkReal x920=(pz)*(pz);
02733 IkReal x921=((r01)*(sj0));
02734 IkReal x922=((py)*(r00));
02735 IkReal x923=((pz)*(sj1));
02736 IkReal x924=((py)*(r01));
02737 IkReal x925=((px)*(sj0));
02738 IkReal x926=((IkReal(0.600000000000000))*(r02));
02739 IkReal x927=((IkReal(0.150000000000000))*(cj1));
02740 IkReal x928=((cj0)*(sj1));
02741 IkReal x929=((IkReal(0.150000000000000))*(px));
02742 IkReal x930=((IkReal(2.00000000000000))*(cj1));
02743 IkReal x931=((cj0)*(r01));
02744 IkReal x932=((r02)*(sj1));
02745 IkReal x933=((px)*(r00));
02746 IkReal x934=((IkReal(0.300000000000000))*(r00));
02747 IkReal x935=((IkReal(1.00000000000000))*(pz));
02748 IkReal x936=((r00)*(sj1));
02749 IkReal x937=((cj0)*(r00));
02750 IkReal x938=((cj0)*(cj1));
02751 IkReal x939=((IkReal(1.00000000000000))*(sj1));
02752 IkReal x940=((IkReal(0.0956250000000000))*(r00));
02753 IkReal x941=((IkReal(0.600000000000000))*(pz));
02754 IkReal x942=((IkReal(0.600000000000000))*(sj1));
02755 IkReal x943=((IkReal(2.00000000000000))*(px));
02756 IkReal x944=((IkReal(2.00000000000000))*(sj1));
02757 IkReal x945=((IkReal(0.150000000000000))*(sj1));
02758 IkReal x946=((cj1)*(r02));
02759 IkReal x947=((cj0)*(px));
02760 IkReal x948=((IkReal(0.0843750000000000))*(cj1));
02761 IkReal x949=((py)*(sj0));
02762 IkReal x950=((pz)*(r02));
02763 IkReal x951=((IkReal(1.00000000000000))*(cj1));
02764 IkReal x952=((cj0)*(py));
02765 IkReal x953=((r00)*(sj0));
02766 IkReal x954=((r02)*(x949));
02767 IkReal x955=((pp)*(x951));
02768 IkReal x956=((IkReal(1.00000000000000))*(pp)*(r00));
02769 IkReal x957=((x917)+(x916));
02770 IkReal x958=((IkReal(2.00000000000000))*(r00)*(x919));
02771 IkReal x959=((cj0)*(x943)*(x950));
02772 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
02773 evalcond[1]=((((IkReal(-1.00000000000000))*(x925)))+(x952));
02774 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x953)))+(x931));
02775 evalcond[3]=((((IkReal(-1.00000000000000))*(x937)*(x951)))+(x932)+(((IkReal(-1.00000000000000))*(x921)*(x951))));
02776 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x928)))+(((IkReal(-1.00000000000000))*(x921)*(x939)))+(((IkReal(-1.00000000000000))*(x946))));
02777 evalcond[5]=((IkReal(0.0188000000000000))+(((IkReal(0.150000000000000))*(x949)))+(((x942)*(x949)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.600000000000000))*(px)*(x928)))+(x957)+(((cj1)*(x941)))+(((cj0)*(x929)))+(((IkReal(-0.0450000000000000))*(sj1))));
02778 evalcond[6]=((((IkReal(0.300000000000000))*(sj1)*(x921)))+(((IkReal(-1.00000000000000))*(r02)*(x935)))+(((IkReal(-1.00000000000000))*(x933)))+(((IkReal(0.300000000000000))*(x946)))+(((IkReal(-1.00000000000000))*(x924)))+(((IkReal(0.0750000000000000))*(x937)))+(((IkReal(0.0750000000000000))*(x921)))+(((x928)*(x934))));
02779 evalcond[7]=((((IkReal(0.300000000000000))*(cj1)*(x921)))+(((IkReal(-1.00000000000000))*(x935)*(x937)))+(((r02)*(x947)))+(x954)+(((IkReal(-0.300000000000000))*(x932)))+(((IkReal(-0.0750000000000000))*(r02)))+(((x934)*(x938)))+(((IkReal(-1.00000000000000))*(x921)*(x935))));
02780 evalcond[8]=((IkReal(0.114425000000000))+(((x922)*(x942)))+(((py)*(x921)*(x943)))+(((IkReal(-1.00000000000000))*(cj1)*(x931)*(x941)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x942)))+(((IkReal(-1.00000000000000))*(sj0)*(x940)))+(((IkReal(2.00000000000000))*(x925)*(x950)))+(((IkReal(0.150000000000000))*(x922)))+(((IkReal(-2.00000000000000))*(x918)*(x931)))+(((IkReal(-1.00000000000000))*(cj0)*(x922)*(x943)))+(((cj1)*(x941)*(x953)))+(((IkReal(2.00000000000000))*(x919)*(x953)))+(x957)+(((IkReal(-1.00000000000000))*(pp)*(x953)))+(((pp)*(x931)))+(((IkReal(0.0956250000000000))*(x931)))+(((IkReal(-0.0450000000000000))*(sj0)*(x936)))+(((IkReal(-2.00000000000000))*(x950)*(x952)))+(((py)*(x926)*(x938)))+(((IkReal(0.0450000000000000))*(r01)*(x928)))+(((IkReal(-1.00000000000000))*(r01)*(x929)))+(((IkReal(-1.00000000000000))*(cj1)*(x925)*(x926))));
02781 evalcond[9]=((((x924)*(x928)*(x943)))+(((x928)*(x958)))+(((r02)*(x927)*(x947)))+(((IkReal(-0.600000000000000))*(x933)))+(((r02)*(x920)*(x930)))+(((IkReal(-1.00000000000000))*(x928)*(x956)))+(((IkReal(-1.00000000000000))*(pp)*(x921)*(x939)))+(((IkReal(2.00000000000000))*(x923)*(x954)))+(((x928)*(x940)))+(((x918)*(x921)*(x944)))+(((cj0)*(r02)*(x923)*(x943)))+(((x922)*(x925)*(x944)))+(((IkReal(-1.00000000000000))*(pz)*(x926)))+(((x927)*(x954)))+(((IkReal(-1.00000000000000))*(pz)*(x921)*(x927)))+(((IkReal(-1.00000000000000))*(x929)*(x936)))+(((pz)*(x924)*(x930)))+(((pz)*(x930)*(x933)))+(((IkReal(-1.00000000000000))*(pp)*(x946)))+(((IkReal(0.0956250000000000))*(sj1)*(x921)))+(((IkReal(-1.00000000000000))*(x924)*(x945)))+(((IkReal(0.0843750000000000))*(x946)))+(((IkReal(-0.150000000000000))*(r02)*(x923)))+(((IkReal(0.0450000000000000))*(x921)))+(((IkReal(-1.00000000000000))*(pz)*(x927)*(x937)))+(((IkReal(0.0450000000000000))*(x937)))+(((IkReal(-0.600000000000000))*(x924))));
02782 evalcond[10]=((((IkReal(-1.00000000000000))*(x926)*(x947)))+(((IkReal(-1.00000000000000))*(x927)*(x933)))+(((x930)*(x949)*(x950)))+(((IkReal(-2.00000000000000))*(x923)*(x924)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x921)*(x955)))+(((pp)*(x932)))+(((IkReal(-1.00000000000000))*(x921)*(x948)))+(((IkReal(-2.00000000000000))*(x920)*(x932)))+(((IkReal(0.0956250000000000))*(x932)))+(((x921)*(x941)))+(((IkReal(0.150000000000000))*(x921)*(x923)))+(((IkReal(-1.00000000000000))*(x926)*(x949)))+(((x924)*(x930)*(x947)))+(((IkReal(0.150000000000000))*(x923)*(x937)))+(((IkReal(-1.00000000000000))*(x937)*(x948)))+(((x919)*(x930)*(x937)))+(((x930)*(x947)*(x950)))+(((IkReal(-1.00000000000000))*(x937)*(x955)))+(((x937)*(x941)))+(((x922)*(x925)*(x930)))+(((x918)*(x921)*(x930)))+(((IkReal(-0.150000000000000))*(x932)*(x949)))+(((IkReal(-1.00000000000000))*(x924)*(x927)))+(((IkReal(-1.00000000000000))*(x927)*(x950)))+(((IkReal(-1.00000000000000))*(r02)*(x928)*(x929)))+(((IkReal(-2.00000000000000))*(x923)*(x933))));
02783 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  && IKabs(evalcond[9]) < 0.0000010000000000  && IKabs(evalcond[10]) < 0.0000010000000000  )
02784 {
02785 {
02786 IkReal dummyeval[1];
02787 IkReal gconst6;
02788 gconst6=IKsign(((IkReal(0.108025000000000))+(((IkReal(0.0512000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02789 dummyeval[0]=((IkReal(16.8789062500000))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3))+(((IkReal(8.00000000000000))*(cj3))));
02790 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02791 {
02792 {
02793 IkReal dummyeval[1];
02794 IkReal gconst7;
02795 gconst7=IKsign(((IkReal(-0.108025000000000))+(((IkReal(-0.0512000000000000))*(cj3)))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))));
02796 dummyeval[0]=((IkReal(-16.8789062500000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.00000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
02797 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02798 {
02799 continue;
02800 
02801 } else
02802 {
02803 {
02804 IkReal j2array[1], cj2array[1], sj2array[1];
02805 bool j2valid[1]={false};
02806 _nj2 = 1;
02807 IkReal x960=((r02)*(sj0));
02808 IkReal x961=((IkReal(0.0800000000000000))*(sj1));
02809 IkReal x962=((cj3)*(px));
02810 IkReal x963=((cj0)*(r01));
02811 IkReal x964=((IkReal(0.0240000000000000))*(cj1));
02812 IkReal x965=((pz)*(sj3));
02813 IkReal x966=((IkReal(0.00600000000000000))*(cj1));
02814 IkReal x967=((IkReal(0.0750000000000000))*(sj1));
02815 IkReal x968=((py)*(sj0));
02816 IkReal x969=((IkReal(0.00562500000000000))*(cj1));
02817 IkReal x970=((r00)*(sj0));
02818 IkReal x971=((cj3)*(pz));
02819 IkReal x972=((IkReal(0.320000000000000))*(sj1));
02820 IkReal x973=((IkReal(0.0800000000000000))*(cj1));
02821 IkReal x974=((IkReal(0.0750000000000000))*(cj1));
02822 IkReal x975=((py)*(r00));
02823 IkReal x976=((IkReal(0.320000000000000))*(cj1));
02824 IkReal x977=((cj0)*(px));
02825 IkReal x978=((IkReal(0.00600000000000000))*(sj1));
02826 IkReal x979=((cj1)*(px)*(r01));
02827 IkReal x980=((cj0)*(py)*(r02));
02828 IkReal x981=((px)*(sj3)*(x961));
02829 if( IKabs(((gconst7)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(x971)*(x973)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x980)))+(((IkReal(-1.00000000000000))*(x961)*(x965)*(x970)))+(((cj3)*(x978)))+(((px)*(x960)*(x967)))+(((sj3)*(x973)*(x975)))+(((x960)*(x981)))+(((IkReal(-1.00000000000000))*(x969)*(x970)))+(((sj3)*(x963)*(x966)))+(((IkReal(-1.00000000000000))*(cj3)*(x961)*(x968)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x974)))+(((IkReal(-1.00000000000000))*(pz)*(x967)*(x970)))+(((IkReal(-1.00000000000000))*(x972)*(x977)))+(((IkReal(-1.00000000000000))*(cj0)*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(sj3)*(x966)*(x970)))+(((IkReal(-1.00000000000000))*(pz)*(x976)))+(((IkReal(-1.00000000000000))*(x968)*(x972)))+(((IkReal(0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x967)*(x980)))+(((pz)*(x963)*(x967)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x973)))+(((x961)*(x963)*(x965)))+(((x974)*(x975)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x963)*(x969))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((IkReal(0.0225000000000000))+(((x961)*(x970)*(x971)))+(((IkReal(-1.00000000000000))*(pz)*(x963)*(x972)))+(((cj3)*(x966)*(x970)))+(((IkReal(0.00562500000000000))*(sj1)))+(((pz)*(x970)*(x972)))+(((IkReal(-1.00000000000000))*(px)*(x960)*(x972)))+(((IkReal(-1.00000000000000))*(x967)*(x977)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x977)))+(((IkReal(-1.00000000000000))*(pz)*(x974)))+(((x972)*(x980)))+(((IkReal(-1.00000000000000))*(x967)*(x968)))+(((IkReal(-1.00000000000000))*(x960)*(x961)*(x962)))+(((sj3)*(x978)))+(((IkReal(-1.00000000000000))*(x975)*(x976)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x968)))+(((x964)*(x970)))+(((IkReal(-1.00000000000000))*(x963)*(x964)))+(((cj3)*(x961)*(x980)))+(((IkReal(-1.00000000000000))*(x965)*(x973)))+(((IkReal(-1.00000000000000))*(x961)*(x963)*(x971)))+(((px)*(r01)*(x976)))+(((IkReal(-1.00000000000000))*(cj3)*(x963)*(x966)))+(((IkReal(0.0240000000000000))*(sj3)))+(((r01)*(x962)*(x973)))+(((IkReal(-1.00000000000000))*(cj3)*(x973)*(x975))))))) < IKFAST_ATAN2_MAGTHRESH )
02830     continue;
02831 j2array[0]=IKatan2(((gconst7)*(((IkReal(0.0960000000000000))+(((IkReal(-1.00000000000000))*(x971)*(x973)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x980)))+(((IkReal(-1.00000000000000))*(x961)*(x965)*(x970)))+(((cj3)*(x978)))+(((px)*(x960)*(x967)))+(((sj3)*(x973)*(x975)))+(((x960)*(x981)))+(((IkReal(-1.00000000000000))*(x969)*(x970)))+(((sj3)*(x963)*(x966)))+(((IkReal(-1.00000000000000))*(cj3)*(x961)*(x968)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x974)))+(((IkReal(-1.00000000000000))*(pz)*(x967)*(x970)))+(((IkReal(-1.00000000000000))*(x972)*(x977)))+(((IkReal(-1.00000000000000))*(cj0)*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(sj3)*(x966)*(x970)))+(((IkReal(-1.00000000000000))*(pz)*(x976)))+(((IkReal(-1.00000000000000))*(x968)*(x972)))+(((IkReal(0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x967)*(x980)))+(((pz)*(x963)*(x967)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(sj3)*(x973)))+(((x961)*(x963)*(x965)))+(((x974)*(x975)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x963)*(x969)))))), ((gconst7)*(((IkReal(0.0225000000000000))+(((x961)*(x970)*(x971)))+(((IkReal(-1.00000000000000))*(pz)*(x963)*(x972)))+(((cj3)*(x966)*(x970)))+(((IkReal(0.00562500000000000))*(sj1)))+(((pz)*(x970)*(x972)))+(((IkReal(-1.00000000000000))*(px)*(x960)*(x972)))+(((IkReal(-1.00000000000000))*(x967)*(x977)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x977)))+(((IkReal(-1.00000000000000))*(pz)*(x974)))+(((x972)*(x980)))+(((IkReal(-1.00000000000000))*(x967)*(x968)))+(((IkReal(-1.00000000000000))*(x960)*(x961)*(x962)))+(((sj3)*(x978)))+(((IkReal(-1.00000000000000))*(x975)*(x976)))+(((IkReal(-1.00000000000000))*(sj3)*(x961)*(x968)))+(((x964)*(x970)))+(((IkReal(-1.00000000000000))*(x963)*(x964)))+(((cj3)*(x961)*(x980)))+(((IkReal(-1.00000000000000))*(x965)*(x973)))+(((IkReal(-1.00000000000000))*(x961)*(x963)*(x971)))+(((px)*(r01)*(x976)))+(((IkReal(-1.00000000000000))*(cj3)*(x963)*(x966)))+(((IkReal(0.0240000000000000))*(sj3)))+(((r01)*(x962)*(x973)))+(((IkReal(-1.00000000000000))*(cj3)*(x973)*(x975)))))));
02832 sj2array[0]=IKsin(j2array[0]);
02833 cj2array[0]=IKcos(j2array[0]);
02834 if( j2array[0] > IKPI )
02835 {
02836     j2array[0]-=IK2PI;
02837 }
02838 else if( j2array[0] < -IKPI )
02839 {    j2array[0]+=IK2PI;
02840 }
02841 j2valid[0] = true;
02842 for(int ij2 = 0; ij2 < 1; ++ij2)
02843 {
02844 if( !j2valid[ij2] )
02845 {
02846     continue;
02847 }
02848 _ij2[0] = ij2; _ij2[1] = -1;
02849 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02850 {
02851 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02852 {
02853     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02854 }
02855 }
02856 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02857 {
02858 IkReal evalcond[4];
02859 IkReal x982=IKcos(j2);
02860 IkReal x983=IKsin(j2);
02861 IkReal x984=((IkReal(0.0800000000000000))*(sj3));
02862 IkReal x985=((cj0)*(r01));
02863 IkReal x986=((IkReal(1.00000000000000))*(px));
02864 IkReal x987=((py)*(sj1));
02865 IkReal x988=((cj0)*(r02));
02866 IkReal x989=((IkReal(0.0750000000000000))*(cj1));
02867 IkReal x990=((r02)*(sj0));
02868 IkReal x991=((IkReal(0.0750000000000000))*(sj1));
02869 IkReal x992=((cj1)*(pz));
02870 IkReal x993=((r00)*(sj0));
02871 IkReal x994=((IkReal(0.0800000000000000))*(cj3));
02872 IkReal x995=((pz)*(sj1));
02873 IkReal x996=((IkReal(1.00000000000000))*(sj0));
02874 IkReal x997=((cj1)*(py));
02875 IkReal x998=((IkReal(0.320000000000000))*(x982));
02876 IkReal x999=((IkReal(0.0750000000000000))*(x983));
02877 IkReal x1000=((IkReal(0.320000000000000))*(x983));
02878 IkReal x1001=((IkReal(0.0750000000000000))*(x982));
02879 IkReal x1002=((sj1)*(x993));
02880 IkReal x1003=((x982)*(x994));
02881 IkReal x1004=((x983)*(x984));
02882 IkReal x1005=((x982)*(x984));
02883 IkReal x1006=((x983)*(x994));
02884 IkReal x1007=((x1004)+(x999));
02885 IkReal x1008=((x1003)+(x998));
02886 IkReal x1009=((x1006)+(x1005)+(x1001)+(x1000));
02887 evalcond[0]=((((IkReal(-1.00000000000000))*(x996)*(x997)))+(x989)+(((IkReal(-1.00000000000000))*(x1007)))+(x1008)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x986)))+(x995));
02888 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x992)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x986)))+(x1009)+(((IkReal(-1.00000000000000))*(x987)*(x996)))+(x991));
02889 evalcond[2]=((((x993)*(x995)))+(((IkReal(-1.00000000000000))*(sj1)*(x986)*(x990)))+(((x987)*(x988)))+(((IkReal(-1.00000000000000))*(x985)*(x989)))+(((IkReal(-1.00000000000000))*(x1007)))+(((cj1)*(px)*(r01)))+(x1008)+(((x989)*(x993)))+(((IkReal(-1.00000000000000))*(x985)*(x995)))+(((IkReal(-1.00000000000000))*(r00)*(x997))));
02890 evalcond[3]=((((IkReal(0.300000000000000))*(x985)))+(((IkReal(-1.00000000000000))*(x1009)))+(((x985)*(x991)))+(((IkReal(-0.300000000000000))*(x993)))+(((x988)*(x997)))+(((IkReal(-1.00000000000000))*(x991)*(x993)))+(((x992)*(x993)))+(((IkReal(-1.00000000000000))*(x985)*(x992)))+(((IkReal(-1.00000000000000))*(cj1)*(x986)*(x990)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x986)))+(((r00)*(x987))));
02891 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02892 {
02893 continue;
02894 }
02895 }
02896 
02897 {
02898 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02899 vinfos[0].jointtype = 1;
02900 vinfos[0].foffset = j0;
02901 vinfos[0].indices[0] = _ij0[0];
02902 vinfos[0].indices[1] = _ij0[1];
02903 vinfos[0].maxsolutions = _nj0;
02904 vinfos[1].jointtype = 1;
02905 vinfos[1].foffset = j1;
02906 vinfos[1].indices[0] = _ij1[0];
02907 vinfos[1].indices[1] = _ij1[1];
02908 vinfos[1].maxsolutions = _nj1;
02909 vinfos[2].jointtype = 1;
02910 vinfos[2].foffset = j2;
02911 vinfos[2].indices[0] = _ij2[0];
02912 vinfos[2].indices[1] = _ij2[1];
02913 vinfos[2].maxsolutions = _nj2;
02914 vinfos[3].jointtype = 1;
02915 vinfos[3].foffset = j3;
02916 vinfos[3].indices[0] = _ij3[0];
02917 vinfos[3].indices[1] = _ij3[1];
02918 vinfos[3].maxsolutions = _nj3;
02919 vinfos[4].jointtype = 1;
02920 vinfos[4].foffset = j4;
02921 vinfos[4].indices[0] = _ij4[0];
02922 vinfos[4].indices[1] = _ij4[1];
02923 vinfos[4].maxsolutions = _nj4;
02924 std::vector<int> vfree(0);
02925 solutions.AddSolution(vinfos,vfree);
02926 }
02927 }
02928 }
02929 
02930 }
02931 
02932 }
02933 
02934 } else
02935 {
02936 {
02937 IkReal j2array[1], cj2array[1], sj2array[1];
02938 bool j2valid[1]={false};
02939 _nj2 = 1;
02940 IkReal x1010=((IkReal(0.0800000000000000))*(cj1));
02941 IkReal x1011=((cj0)*(px));
02942 IkReal x1012=((py)*(sj0));
02943 IkReal x1013=((IkReal(0.320000000000000))*(sj1));
02944 IkReal x1014=((IkReal(0.00600000000000000))*(cj3));
02945 IkReal x1015=((pz)*(sj3));
02946 IkReal x1016=((IkReal(0.0750000000000000))*(cj1));
02947 IkReal x1017=((IkReal(0.0800000000000000))*(sj1));
02948 IkReal x1018=((IkReal(0.0750000000000000))*(sj1));
02949 IkReal x1019=((IkReal(0.00600000000000000))*(sj3));
02950 IkReal x1020=((cj3)*(pz));
02951 IkReal x1021=((IkReal(0.320000000000000))*(cj1));
02952 if( IKabs(((gconst6)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj3)*(x1010)*(x1012)))+(((x1010)*(x1020)))+(((IkReal(-1.00000000000000))*(x1012)*(x1016)))+(((x1012)*(x1013)))+(((IkReal(-1.00000000000000))*(x1011)*(x1016)))+(((pz)*(x1018)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x1010)*(x1011)))+(((cj3)*(x1012)*(x1017)))+(((cj3)*(x1011)*(x1017)))+(((pz)*(x1021)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x1014)))+(((x1011)*(x1013)))+(((cj1)*(x1019)))+(((x1015)*(x1017))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x1019)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x1011)*(x1018)))+(((x1012)*(x1021)))+(((sj3)*(x1012)*(x1017)))+(((IkReal(-1.00000000000000))*(cj1)*(x1014)))+(((sj3)*(x1011)*(x1017)))+(((IkReal(-1.00000000000000))*(x1017)*(x1020)))+(((x1011)*(x1021)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(pz)*(x1013)))+(((x1012)*(x1018)))+(((x1010)*(x1015)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x1010)*(x1012)))+(((cj3)*(x1010)*(x1011)))+(((pz)*(x1016))))))) < IKFAST_ATAN2_MAGTHRESH )
02953     continue;
02954 j2array[0]=IKatan2(((gconst6)*(((IkReal(-0.0960000000000000))+(((IkReal(-1.00000000000000))*(sj3)*(x1010)*(x1012)))+(((x1010)*(x1020)))+(((IkReal(-1.00000000000000))*(x1012)*(x1016)))+(((x1012)*(x1013)))+(((IkReal(-1.00000000000000))*(x1011)*(x1016)))+(((pz)*(x1018)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-0.0240000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(sj3)*(x1010)*(x1011)))+(((cj3)*(x1012)*(x1017)))+(((cj3)*(x1011)*(x1017)))+(((pz)*(x1021)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(sj1)*(x1014)))+(((x1011)*(x1013)))+(((cj1)*(x1019)))+(((x1015)*(x1017)))))), ((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(sj1)*(x1019)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x1011)*(x1018)))+(((x1012)*(x1021)))+(((sj3)*(x1012)*(x1017)))+(((IkReal(-1.00000000000000))*(cj1)*(x1014)))+(((sj3)*(x1011)*(x1017)))+(((IkReal(-1.00000000000000))*(x1017)*(x1020)))+(((x1011)*(x1021)))+(((IkReal(-0.0240000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(pz)*(x1013)))+(((x1012)*(x1018)))+(((x1010)*(x1015)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x1010)*(x1012)))+(((cj3)*(x1010)*(x1011)))+(((pz)*(x1016)))))));
02955 sj2array[0]=IKsin(j2array[0]);
02956 cj2array[0]=IKcos(j2array[0]);
02957 if( j2array[0] > IKPI )
02958 {
02959     j2array[0]-=IK2PI;
02960 }
02961 else if( j2array[0] < -IKPI )
02962 {    j2array[0]+=IK2PI;
02963 }
02964 j2valid[0] = true;
02965 for(int ij2 = 0; ij2 < 1; ++ij2)
02966 {
02967 if( !j2valid[ij2] )
02968 {
02969     continue;
02970 }
02971 _ij2[0] = ij2; _ij2[1] = -1;
02972 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02973 {
02974 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02975 {
02976     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02977 }
02978 }
02979 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02980 {
02981 IkReal evalcond[4];
02982 IkReal x1022=IKcos(j2);
02983 IkReal x1023=IKsin(j2);
02984 IkReal x1024=((IkReal(0.0800000000000000))*(sj3));
02985 IkReal x1025=((cj0)*(r01));
02986 IkReal x1026=((IkReal(1.00000000000000))*(px));
02987 IkReal x1027=((py)*(sj1));
02988 IkReal x1028=((cj0)*(r02));
02989 IkReal x1029=((IkReal(0.0750000000000000))*(cj1));
02990 IkReal x1030=((r02)*(sj0));
02991 IkReal x1031=((IkReal(0.0750000000000000))*(sj1));
02992 IkReal x1032=((cj1)*(pz));
02993 IkReal x1033=((r00)*(sj0));
02994 IkReal x1034=((IkReal(0.0800000000000000))*(cj3));
02995 IkReal x1035=((pz)*(sj1));
02996 IkReal x1036=((IkReal(1.00000000000000))*(sj0));
02997 IkReal x1037=((cj1)*(py));
02998 IkReal x1038=((IkReal(0.320000000000000))*(x1022));
02999 IkReal x1039=((IkReal(0.0750000000000000))*(x1023));
03000 IkReal x1040=((IkReal(0.320000000000000))*(x1023));
03001 IkReal x1041=((IkReal(0.0750000000000000))*(x1022));
03002 IkReal x1042=((sj1)*(x1033));
03003 IkReal x1043=((x1022)*(x1034));
03004 IkReal x1044=((x1023)*(x1024));
03005 IkReal x1045=((x1022)*(x1024));
03006 IkReal x1046=((x1023)*(x1034));
03007 IkReal x1047=((x1044)+(x1039));
03008 IkReal x1048=((x1043)+(x1038));
03009 IkReal x1049=((x1041)+(x1040)+(x1046)+(x1045));
03010 evalcond[0]=((((IkReal(-1.00000000000000))*(x1036)*(x1037)))+(x1048)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1026)))+(x1035)+(((IkReal(-1.00000000000000))*(x1047)))+(x1029));
03011 evalcond[1]=((IkReal(0.300000000000000))+(x1049)+(x1031)+(((IkReal(-1.00000000000000))*(x1032)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x1026)))+(((IkReal(-1.00000000000000))*(x1027)*(x1036))));
03012 evalcond[2]=((x1048)+(((x1033)*(x1035)))+(((x1029)*(x1033)))+(((IkReal(-1.00000000000000))*(x1047)))+(((IkReal(-1.00000000000000))*(sj1)*(x1026)*(x1030)))+(((x1027)*(x1028)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x1025)*(x1029)))+(((IkReal(-1.00000000000000))*(r00)*(x1037)))+(((IkReal(-1.00000000000000))*(x1025)*(x1035))));
03013 evalcond[3]=((((IkReal(-0.300000000000000))*(x1033)))+(((x1032)*(x1033)))+(((IkReal(-1.00000000000000))*(cj1)*(x1026)*(x1030)))+(((IkReal(-1.00000000000000))*(x1025)*(x1032)))+(((IkReal(0.300000000000000))*(x1025)))+(((x1025)*(x1031)))+(((r00)*(x1027)))+(((x1028)*(x1037)))+(((IkReal(-1.00000000000000))*(x1049)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x1026)))+(((IkReal(-1.00000000000000))*(x1031)*(x1033))));
03014 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03015 {
03016 continue;
03017 }
03018 }
03019 
03020 {
03021 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03022 vinfos[0].jointtype = 1;
03023 vinfos[0].foffset = j0;
03024 vinfos[0].indices[0] = _ij0[0];
03025 vinfos[0].indices[1] = _ij0[1];
03026 vinfos[0].maxsolutions = _nj0;
03027 vinfos[1].jointtype = 1;
03028 vinfos[1].foffset = j1;
03029 vinfos[1].indices[0] = _ij1[0];
03030 vinfos[1].indices[1] = _ij1[1];
03031 vinfos[1].maxsolutions = _nj1;
03032 vinfos[2].jointtype = 1;
03033 vinfos[2].foffset = j2;
03034 vinfos[2].indices[0] = _ij2[0];
03035 vinfos[2].indices[1] = _ij2[1];
03036 vinfos[2].maxsolutions = _nj2;
03037 vinfos[3].jointtype = 1;
03038 vinfos[3].foffset = j3;
03039 vinfos[3].indices[0] = _ij3[0];
03040 vinfos[3].indices[1] = _ij3[1];
03041 vinfos[3].maxsolutions = _nj3;
03042 vinfos[4].jointtype = 1;
03043 vinfos[4].foffset = j4;
03044 vinfos[4].indices[0] = _ij4[0];
03045 vinfos[4].indices[1] = _ij4[1];
03046 vinfos[4].maxsolutions = _nj4;
03047 std::vector<int> vfree(0);
03048 solutions.AddSolution(vinfos,vfree);
03049 }
03050 }
03051 }
03052 
03053 }
03054 
03055 }
03056 
03057 } else
03058 {
03059 if( 1 )
03060 {
03061 continue;
03062 
03063 } else
03064 {
03065 }
03066 }
03067 }
03068 }
03069 
03070 } else
03071 {
03072 {
03073 IkReal j2array[1], cj2array[1], sj2array[1];
03074 bool j2valid[1]={false};
03075 _nj2 = 1;
03076 IkReal x1050=((IkReal(0.0800000000000000))*(cj3));
03077 IkReal x1051=((IkReal(0.0750000000000000))*(cj1));
03078 IkReal x1052=((r01)*(sj0));
03079 IkReal x1053=((r02)*(sj1));
03080 IkReal x1054=((IkReal(0.0800000000000000))*(sj3));
03081 IkReal x1055=((cj3)*(cj4));
03082 IkReal x1056=((cj4)*(sj3));
03083 IkReal x1057=((pz)*(sj1));
03084 IkReal x1058=((cj0)*(cj1)*(r00));
03085 IkReal x1059=((cj0)*(cj1)*(px));
03086 IkReal x1060=((cj1)*(py)*(sj0));
03087 if( IKabs(((gconst3)*(((((IkReal(-0.320000000000000))*(x1058)))+(((IkReal(-1.00000000000000))*(cj1)*(x1050)*(x1052)))+(((IkReal(-0.320000000000000))*(cj1)*(x1052)))+(((IkReal(-1.00000000000000))*(x1056)*(x1059)))+(((x1056)*(x1057)))+(((x1050)*(x1053)))+(((IkReal(-1.00000000000000))*(x1050)*(x1058)))+(((IkReal(-1.00000000000000))*(x1056)*(x1060)))+(((IkReal(0.320000000000000))*(x1053)))+(((x1051)*(x1056))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(x1051)*(x1055)))+(((x1055)*(x1060)))+(((x1055)*(x1059)))+(((IkReal(-1.00000000000000))*(x1054)*(x1058)))+(((IkReal(-1.00000000000000))*(x1051)*(x1052)))+(((IkReal(0.0750000000000000))*(x1053)))+(((IkReal(-1.00000000000000))*(cj1)*(x1052)*(x1054)))+(((x1053)*(x1054)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1051)))+(((IkReal(-1.00000000000000))*(x1055)*(x1057))))))) < IKFAST_ATAN2_MAGTHRESH )
03088     continue;
03089 j2array[0]=IKatan2(((gconst3)*(((((IkReal(-0.320000000000000))*(x1058)))+(((IkReal(-1.00000000000000))*(cj1)*(x1050)*(x1052)))+(((IkReal(-0.320000000000000))*(cj1)*(x1052)))+(((IkReal(-1.00000000000000))*(x1056)*(x1059)))+(((x1056)*(x1057)))+(((x1050)*(x1053)))+(((IkReal(-1.00000000000000))*(x1050)*(x1058)))+(((IkReal(-1.00000000000000))*(x1056)*(x1060)))+(((IkReal(0.320000000000000))*(x1053)))+(((x1051)*(x1056)))))), ((gconst3)*(((((IkReal(-1.00000000000000))*(x1051)*(x1055)))+(((x1055)*(x1060)))+(((x1055)*(x1059)))+(((IkReal(-1.00000000000000))*(x1054)*(x1058)))+(((IkReal(-1.00000000000000))*(x1051)*(x1052)))+(((IkReal(0.0750000000000000))*(x1053)))+(((IkReal(-1.00000000000000))*(cj1)*(x1052)*(x1054)))+(((x1053)*(x1054)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x1051)))+(((IkReal(-1.00000000000000))*(x1055)*(x1057)))))));
03090 sj2array[0]=IKsin(j2array[0]);
03091 cj2array[0]=IKcos(j2array[0]);
03092 if( j2array[0] > IKPI )
03093 {
03094     j2array[0]-=IK2PI;
03095 }
03096 else if( j2array[0] < -IKPI )
03097 {    j2array[0]+=IK2PI;
03098 }
03099 j2valid[0] = true;
03100 for(int ij2 = 0; ij2 < 1; ++ij2)
03101 {
03102 if( !j2valid[ij2] )
03103 {
03104     continue;
03105 }
03106 _ij2[0] = ij2; _ij2[1] = -1;
03107 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03108 {
03109 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03110 {
03111     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03112 }
03113 }
03114 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03115 {
03116 IkReal evalcond[8];
03117 IkReal x1061=IKcos(j2);
03118 IkReal x1062=IKsin(j2);
03119 IkReal x1063=(py)*(py);
03120 IkReal x1064=(px)*(px);
03121 IkReal x1065=(pz)*(pz);
03122 IkReal x1066=((sj0)*(sj1));
03123 IkReal x1067=((IkReal(1.00000000000000))*(r01));
03124 IkReal x1068=((r00)*(sj1));
03125 IkReal x1069=((IkReal(0.0480000000000000))*(sj3));
03126 IkReal x1070=((IkReal(0.0750000000000000))*(r00));
03127 IkReal x1071=((IkReal(0.0800000000000000))*(sj3));
03128 IkReal x1072=((cj1)*(r01));
03129 IkReal x1073=((IkReal(0.150000000000000))*(py));
03130 IkReal x1074=((pz)*(r02));
03131 IkReal x1075=((px)*(r02));
03132 IkReal x1076=((IkReal(0.0750000000000000))*(sj4));
03133 IkReal x1077=((cj1)*(sj0));
03134 IkReal x1078=((pz)*(r00));
03135 IkReal x1079=((IkReal(0.0750000000000000))*(cj0));
03136 IkReal x1080=((IkReal(2.00000000000000))*(cj0));
03137 IkReal x1081=((cj1)*(r02));
03138 IkReal x1082=((IkReal(0.150000000000000))*(sj1));
03139 IkReal x1083=((px)*(r00));
03140 IkReal x1084=((IkReal(2.00000000000000))*(py));
03141 IkReal x1085=((IkReal(0.0903750000000000))*(sj3));
03142 IkReal x1086=((r02)*(sj1));
03143 IkReal x1087=((IkReal(0.150000000000000))*(cj1));
03144 IkReal x1088=((cj0)*(py));
03145 IkReal x1089=((IkReal(0.0480000000000000))*(cj3));
03146 IkReal x1090=((r01)*(sj1));
03147 IkReal x1091=((IkReal(0.0800000000000000))*(cj3));
03148 IkReal x1092=((IkReal(0.150000000000000))*(pz));
03149 IkReal x1093=((IkReal(1.00000000000000))*(cj1));
03150 IkReal x1094=((cj0)*(r00));
03151 IkReal x1095=((IkReal(0.600000000000000))*(py));
03152 IkReal x1096=((IkReal(1.00000000000000))*(py));
03153 IkReal x1097=((px)*(sj1));
03154 IkReal x1098=((IkReal(1.00000000000000))*(cj0));
03155 IkReal x1099=((cj0)*(pz));
03156 IkReal x1100=((IkReal(0.103175000000000))*(cj3));
03157 IkReal x1101=((IkReal(0.600000000000000))*(cj0));
03158 IkReal x1102=((IkReal(1.00000000000000))*(sj3));
03159 IkReal x1103=((px)*(py));
03160 IkReal x1104=((r01)*(sj0));
03161 IkReal x1105=((IkReal(2.00000000000000))*(px));
03162 IkReal x1106=((cj4)*(x1062));
03163 IkReal x1107=((cj4)*(x1061));
03164 IkReal x1108=((sj4)*(x1062));
03165 IkReal x1109=((IkReal(2.00000000000000))*(x1065));
03166 IkReal x1110=((sj4)*(x1061));
03167 IkReal x1111=((IkReal(2.00000000000000))*(x1063));
03168 IkReal x1112=((px)*(x1074)*(x1080));
03169 evalcond[0]=((((IkReal(-1.00000000000000))*(x1067)*(x1077)))+(x1086)+(((IkReal(-1.00000000000000))*(x1093)*(x1094)))+(((IkReal(-1.00000000000000))*(cj3)*(x1106)))+(((IkReal(-1.00000000000000))*(x1102)*(x1107))));
03170 evalcond[1]=((((IkReal(-1.00000000000000))*(x1102)*(x1106)))+(((IkReal(-1.00000000000000))*(x1081)))+(((cj3)*(x1107)))+(((IkReal(-1.00000000000000))*(x1068)*(x1098)))+(((IkReal(-1.00000000000000))*(x1066)*(x1067))));
03171 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(px)*(x1093)))+(((IkReal(0.320000000000000))*(x1061)))+(((IkReal(-1.00000000000000))*(x1062)*(x1071)))+(((pz)*(sj1)))+(((IkReal(-0.0750000000000000))*(x1062)))+(((x1061)*(x1091)))+(((IkReal(-1.00000000000000))*(x1077)*(x1096)))+(((IkReal(0.0750000000000000))*(cj1))));
03172 evalcond[3]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x1097)*(x1098)))+(((x1062)*(x1091)))+(((IkReal(0.320000000000000))*(x1062)))+(((IkReal(0.0750000000000000))*(x1061)))+(((x1061)*(x1071)))+(((IkReal(-1.00000000000000))*(x1066)*(x1096)))+(((IkReal(0.0750000000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x1093))));
03173 evalcond[4]=((((IkReal(-1.00000000000000))*(py)*(r00)*(x1093)))+(((IkReal(-1.00000000000000))*(x1066)*(x1075)))+(((IkReal(-1.00000000000000))*(sj1)*(x1067)*(x1099)))+(((IkReal(-0.320000000000000))*(x1110)))+(((x1066)*(x1078)))+(((px)*(x1072)))+(((x1086)*(x1088)))+(((x1071)*(x1108)))+(((x1062)*(x1076)))+(((IkReal(-1.00000000000000))*(x1091)*(x1110)))+(((IkReal(-1.00000000000000))*(x1072)*(x1079)))+(((x1070)*(x1077))));
03174 evalcond[5]=((((x1061)*(x1076)))+(((IkReal(0.320000000000000))*(x1108)))+(((py)*(x1068)))+(((IkReal(-1.00000000000000))*(x1067)*(x1097)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((x1077)*(x1078)))+(((x1081)*(x1088)))+(((IkReal(-1.00000000000000))*(x1066)*(x1070)))+(((x1071)*(x1110)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(x1075)*(x1077)))+(((IkReal(-1.00000000000000))*(cj1)*(x1067)*(x1099)))+(((x1091)*(x1108)))+(((x1079)*(x1090))));
03175 evalcond[6]=((((x1069)*(x1107)))+(((cj0)*(x1075)*(x1087)))+(((IkReal(-1.00000000000000))*(pp)*(x1081)))+(((IkReal(-0.150000000000000))*(px)*(x1068)))+(((x1085)*(x1106)))+(((IkReal(-0.600000000000000))*(x1083)))+(((IkReal(0.0450000000000000))*(x1104)))+(((IkReal(0.0956250000000000))*(r01)*(x1066)))+(((x1081)*(x1109)))+(((IkReal(-1.00000000000000))*(x1074)*(x1082)))+(((cj1)*(x1078)*(x1105)))+(((x1066)*(x1074)*(x1084)))+(((IkReal(-1.00000000000000))*(sj0)*(x1072)*(x1092)))+(((IkReal(-1.00000000000000))*(r01)*(x1095)))+(((r01)*(x1066)*(x1111)))+(((IkReal(-0.600000000000000))*(x1074)))+(((x1066)*(x1083)*(x1084)))+(((x1100)*(x1107)))+(((IkReal(0.0843750000000000))*(x1081)))+(((IkReal(-1.00000000000000))*(x1089)*(x1106)))+(((x1064)*(x1068)*(x1080)))+(((r02)*(x1073)*(x1077)))+(((IkReal(-1.00000000000000))*(x1073)*(x1090)))+(((IkReal(0.0956250000000000))*(cj0)*(x1068)))+(((IkReal(0.0512000000000000))*(x1107)))+(((IkReal(-1.00000000000000))*(cj0)*(x1078)*(x1087)))+(((IkReal(-0.0120000000000000))*(x1106)))+(((IkReal(-1.00000000000000))*(pp)*(x1066)*(x1067)))+(((IkReal(-1.00000000000000))*(pp)*(x1068)*(x1098)))+(((x1074)*(x1080)*(x1097)))+(((IkReal(0.0450000000000000))*(x1094)))+(((pz)*(x1072)*(x1084)))+(((x1080)*(x1090)*(x1103))));
03176 evalcond[7]=((((IkReal(-0.0512000000000000))*(x1106)))+(((IkReal(-1.00000000000000))*(x1089)*(x1107)))+(((IkReal(0.0450000000000000))*(r02)))+(((x1078)*(x1101)))+(((IkReal(-1.00000000000000))*(pz)*(x1068)*(x1105)))+(((IkReal(0.600000000000000))*(pz)*(x1104)))+(((cj0)*(x1068)*(x1092)))+(((IkReal(-1.00000000000000))*(r02)*(x1066)*(x1073)))+(((x1072)*(x1080)*(x1103)))+(((IkReal(-0.0843750000000000))*(sj0)*(x1072)))+(((IkReal(-1.00000000000000))*(pp)*(x1067)*(x1077)))+(((x1085)*(x1107)))+(((IkReal(-1.00000000000000))*(pp)*(x1093)*(x1094)))+(((IkReal(-1.00000000000000))*(x1075)*(x1101)))+(((cj1)*(r00)*(x1064)*(x1080)))+(((IkReal(-1.00000000000000))*(x1074)*(x1087)))+(((pp)*(x1086)))+(((IkReal(-0.0120000000000000))*(x1107)))+(((IkReal(-1.00000000000000))*(x1083)*(x1087)))+(((IkReal(-1.00000000000000))*(cj0)*(x1075)*(x1082)))+(((x1074)*(x1077)*(x1084)))+(((IkReal(-0.0843750000000000))*(cj1)*(x1094)))+(((IkReal(-1.00000000000000))*(x1069)*(x1106)))+(((IkReal(-1.00000000000000))*(pz)*(x1084)*(x1090)))+(((sj0)*(x1072)*(x1111)))+(((IkReal(-1.00000000000000))*(x1072)*(x1073)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1095)))+(((IkReal(0.0956250000000000))*(x1086)))+(((IkReal(-1.00000000000000))*(x1086)*(x1109)))+(((cj1)*(x1112)))+(((IkReal(-1.00000000000000))*(x1100)*(x1106)))+(((x1077)*(x1083)*(x1084)))+(((r01)*(x1066)*(x1092))));
03177 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  || IKabs(evalcond[6]) > 0.000001  || IKabs(evalcond[7]) > 0.000001  )
03178 {
03179 continue;
03180 }
03181 }
03182 
03183 {
03184 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03185 vinfos[0].jointtype = 1;
03186 vinfos[0].foffset = j0;
03187 vinfos[0].indices[0] = _ij0[0];
03188 vinfos[0].indices[1] = _ij0[1];
03189 vinfos[0].maxsolutions = _nj0;
03190 vinfos[1].jointtype = 1;
03191 vinfos[1].foffset = j1;
03192 vinfos[1].indices[0] = _ij1[0];
03193 vinfos[1].indices[1] = _ij1[1];
03194 vinfos[1].maxsolutions = _nj1;
03195 vinfos[2].jointtype = 1;
03196 vinfos[2].foffset = j2;
03197 vinfos[2].indices[0] = _ij2[0];
03198 vinfos[2].indices[1] = _ij2[1];
03199 vinfos[2].maxsolutions = _nj2;
03200 vinfos[3].jointtype = 1;
03201 vinfos[3].foffset = j3;
03202 vinfos[3].indices[0] = _ij3[0];
03203 vinfos[3].indices[1] = _ij3[1];
03204 vinfos[3].maxsolutions = _nj3;
03205 vinfos[4].jointtype = 1;
03206 vinfos[4].foffset = j4;
03207 vinfos[4].indices[0] = _ij4[0];
03208 vinfos[4].indices[1] = _ij4[1];
03209 vinfos[4].maxsolutions = _nj4;
03210 std::vector<int> vfree(0);
03211 solutions.AddSolution(vinfos,vfree);
03212 }
03213 }
03214 }
03215 
03216 }
03217 
03218 }
03219 
03220 } else
03221 {
03222 {
03223 IkReal j2array[1], cj2array[1], sj2array[1];
03224 bool j2valid[1]={false};
03225 _nj2 = 1;
03226 IkReal x1113=((IkReal(1.00000000000000))*(cj1));
03227 IkReal x1114=((cj0)*(r00));
03228 IkReal x1115=((cj3)*(r02));
03229 IkReal x1116=((sj1)*(sj3));
03230 IkReal x1117=((r01)*(sj0));
03231 IkReal x1118=((cj3)*(x1117));
03232 if( IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(cj3)*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(x1113)*(x1118)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1113)))+(((sj1)*(x1115)))+(((IkReal(-1.00000000000000))*(x1116)*(x1117)))+(((IkReal(-1.00000000000000))*(x1114)*(x1116))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((r02)*(x1116)))+(((sj1)*(x1118)))+(((IkReal(-1.00000000000000))*(sj3)*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(sj3)*(x1113)*(x1117)))+(((cj1)*(x1115)))+(((cj3)*(sj1)*(x1114))))))) < IKFAST_ATAN2_MAGTHRESH )
03233     continue;
03234 j2array[0]=IKatan2(((gconst2)*(((((IkReal(-1.00000000000000))*(cj3)*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(x1113)*(x1118)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1113)))+(((sj1)*(x1115)))+(((IkReal(-1.00000000000000))*(x1116)*(x1117)))+(((IkReal(-1.00000000000000))*(x1114)*(x1116)))))), ((gconst2)*(((((r02)*(x1116)))+(((sj1)*(x1118)))+(((IkReal(-1.00000000000000))*(sj3)*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(sj3)*(x1113)*(x1117)))+(((cj1)*(x1115)))+(((cj3)*(sj1)*(x1114)))))));
03235 sj2array[0]=IKsin(j2array[0]);
03236 cj2array[0]=IKcos(j2array[0]);
03237 if( j2array[0] > IKPI )
03238 {
03239     j2array[0]-=IK2PI;
03240 }
03241 else if( j2array[0] < -IKPI )
03242 {    j2array[0]+=IK2PI;
03243 }
03244 j2valid[0] = true;
03245 for(int ij2 = 0; ij2 < 1; ++ij2)
03246 {
03247 if( !j2valid[ij2] )
03248 {
03249     continue;
03250 }
03251 _ij2[0] = ij2; _ij2[1] = -1;
03252 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03253 {
03254 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03255 {
03256     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03257 }
03258 }
03259 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03260 {
03261 IkReal evalcond[8];
03262 IkReal x1119=IKcos(j2);
03263 IkReal x1120=IKsin(j2);
03264 IkReal x1121=(py)*(py);
03265 IkReal x1122=(px)*(px);
03266 IkReal x1123=(pz)*(pz);
03267 IkReal x1124=((sj0)*(sj1));
03268 IkReal x1125=((IkReal(1.00000000000000))*(r01));
03269 IkReal x1126=((r00)*(sj1));
03270 IkReal x1127=((IkReal(0.0480000000000000))*(sj3));
03271 IkReal x1128=((IkReal(0.0750000000000000))*(r00));
03272 IkReal x1129=((IkReal(0.0800000000000000))*(sj3));
03273 IkReal x1130=((cj1)*(r01));
03274 IkReal x1131=((IkReal(0.150000000000000))*(py));
03275 IkReal x1132=((pz)*(r02));
03276 IkReal x1133=((px)*(r02));
03277 IkReal x1134=((IkReal(0.0750000000000000))*(sj4));
03278 IkReal x1135=((cj1)*(sj0));
03279 IkReal x1136=((pz)*(r00));
03280 IkReal x1137=((IkReal(0.0750000000000000))*(cj0));
03281 IkReal x1138=((IkReal(2.00000000000000))*(cj0));
03282 IkReal x1139=((cj1)*(r02));
03283 IkReal x1140=((IkReal(0.150000000000000))*(sj1));
03284 IkReal x1141=((px)*(r00));
03285 IkReal x1142=((IkReal(2.00000000000000))*(py));
03286 IkReal x1143=((IkReal(0.0903750000000000))*(sj3));
03287 IkReal x1144=((r02)*(sj1));
03288 IkReal x1145=((IkReal(0.150000000000000))*(cj1));
03289 IkReal x1146=((cj0)*(py));
03290 IkReal x1147=((IkReal(0.0480000000000000))*(cj3));
03291 IkReal x1148=((r01)*(sj1));
03292 IkReal x1149=((IkReal(0.0800000000000000))*(cj3));
03293 IkReal x1150=((IkReal(0.150000000000000))*(pz));
03294 IkReal x1151=((IkReal(1.00000000000000))*(cj1));
03295 IkReal x1152=((cj0)*(r00));
03296 IkReal x1153=((IkReal(0.600000000000000))*(py));
03297 IkReal x1154=((IkReal(1.00000000000000))*(py));
03298 IkReal x1155=((px)*(sj1));
03299 IkReal x1156=((IkReal(1.00000000000000))*(cj0));
03300 IkReal x1157=((cj0)*(pz));
03301 IkReal x1158=((IkReal(0.103175000000000))*(cj3));
03302 IkReal x1159=((IkReal(0.600000000000000))*(cj0));
03303 IkReal x1160=((IkReal(1.00000000000000))*(sj3));
03304 IkReal x1161=((px)*(py));
03305 IkReal x1162=((r01)*(sj0));
03306 IkReal x1163=((IkReal(2.00000000000000))*(px));
03307 IkReal x1164=((cj4)*(x1120));
03308 IkReal x1165=((cj4)*(x1119));
03309 IkReal x1166=((sj4)*(x1120));
03310 IkReal x1167=((IkReal(2.00000000000000))*(x1123));
03311 IkReal x1168=((sj4)*(x1119));
03312 IkReal x1169=((IkReal(2.00000000000000))*(x1121));
03313 IkReal x1170=((px)*(x1132)*(x1138));
03314 evalcond[0]=((x1144)+(((IkReal(-1.00000000000000))*(x1160)*(x1165)))+(((IkReal(-1.00000000000000))*(x1151)*(x1152)))+(((IkReal(-1.00000000000000))*(x1125)*(x1135)))+(((IkReal(-1.00000000000000))*(cj3)*(x1164))));
03315 evalcond[1]=((((IkReal(-1.00000000000000))*(x1160)*(x1164)))+(((IkReal(-1.00000000000000))*(x1139)))+(((cj3)*(x1165)))+(((IkReal(-1.00000000000000))*(x1126)*(x1156)))+(((IkReal(-1.00000000000000))*(x1124)*(x1125))));
03316 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(px)*(x1151)))+(((IkReal(-0.0750000000000000))*(x1120)))+(((IkReal(0.320000000000000))*(x1119)))+(((pz)*(sj1)))+(((IkReal(-1.00000000000000))*(x1135)*(x1154)))+(((x1119)*(x1149)))+(((IkReal(0.0750000000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x1120)*(x1129))));
03317 evalcond[3]=((IkReal(0.300000000000000))+(((x1120)*(x1149)))+(((IkReal(-1.00000000000000))*(x1124)*(x1154)))+(((IkReal(-1.00000000000000))*(pz)*(x1151)))+(((IkReal(0.0750000000000000))*(x1119)))+(((IkReal(0.320000000000000))*(x1120)))+(((IkReal(-1.00000000000000))*(x1155)*(x1156)))+(((x1119)*(x1129)))+(((IkReal(0.0750000000000000))*(sj1))));
03318 evalcond[4]=((((IkReal(-0.320000000000000))*(x1168)))+(((x1124)*(x1136)))+(((px)*(x1130)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x1151)))+(((IkReal(-1.00000000000000))*(x1130)*(x1137)))+(((x1129)*(x1166)))+(((IkReal(-1.00000000000000))*(x1124)*(x1133)))+(((IkReal(-1.00000000000000))*(sj1)*(x1125)*(x1157)))+(((x1128)*(x1135)))+(((x1144)*(x1146)))+(((IkReal(-1.00000000000000))*(x1149)*(x1168)))+(((x1120)*(x1134))));
03319 evalcond[5]=((((IkReal(0.320000000000000))*(x1166)))+(((x1137)*(x1148)))+(((x1149)*(x1166)))+(((x1135)*(x1136)))+(((x1119)*(x1134)))+(((py)*(x1126)))+(((IkReal(-1.00000000000000))*(x1133)*(x1135)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((IkReal(-1.00000000000000))*(x1124)*(x1128)))+(((IkReal(-1.00000000000000))*(cj1)*(x1125)*(x1157)))+(((x1129)*(x1168)))+(((IkReal(-1.00000000000000))*(x1125)*(x1155)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((x1139)*(x1146))));
03320 evalcond[6]=((((x1124)*(x1132)*(x1142)))+(((IkReal(-1.00000000000000))*(x1131)*(x1148)))+(((IkReal(0.0512000000000000))*(x1165)))+(((cj0)*(x1133)*(x1145)))+(((pz)*(x1130)*(x1142)))+(((x1139)*(x1167)))+(((r02)*(x1131)*(x1135)))+(((x1143)*(x1164)))+(((IkReal(-1.00000000000000))*(pp)*(x1139)))+(((IkReal(0.0450000000000000))*(x1162)))+(((IkReal(-1.00000000000000))*(x1132)*(x1140)))+(((IkReal(-1.00000000000000))*(sj0)*(x1130)*(x1150)))+(((IkReal(0.0450000000000000))*(x1152)))+(((IkReal(-0.600000000000000))*(x1132)))+(((x1127)*(x1165)))+(((x1158)*(x1165)))+(((x1138)*(x1148)*(x1161)))+(((r01)*(x1124)*(x1169)))+(((cj1)*(x1136)*(x1163)))+(((IkReal(-0.0120000000000000))*(x1164)))+(((IkReal(0.0956250000000000))*(cj0)*(x1126)))+(((IkReal(-1.00000000000000))*(pp)*(x1124)*(x1125)))+(((IkReal(-0.600000000000000))*(x1141)))+(((x1122)*(x1126)*(x1138)))+(((IkReal(0.0956250000000000))*(r01)*(x1124)))+(((x1132)*(x1138)*(x1155)))+(((IkReal(-1.00000000000000))*(r01)*(x1153)))+(((IkReal(-1.00000000000000))*(x1147)*(x1164)))+(((IkReal(-1.00000000000000))*(cj0)*(x1136)*(x1145)))+(((IkReal(-0.150000000000000))*(px)*(x1126)))+(((IkReal(0.0843750000000000))*(x1139)))+(((x1124)*(x1141)*(x1142)))+(((IkReal(-1.00000000000000))*(pp)*(x1126)*(x1156))));
03321 evalcond[7]=((((IkReal(-1.00000000000000))*(x1130)*(x1131)))+(((IkReal(-1.00000000000000))*(pz)*(x1126)*(x1163)))+(((r01)*(x1124)*(x1150)))+(((IkReal(-0.0843750000000000))*(cj1)*(x1152)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1153)))+(((IkReal(-0.0843750000000000))*(sj0)*(x1130)))+(((x1130)*(x1138)*(x1161)))+(((cj0)*(x1126)*(x1150)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(pz)*(x1142)*(x1148)))+(((IkReal(-1.00000000000000))*(x1141)*(x1145)))+(((IkReal(0.0956250000000000))*(x1144)))+(((IkReal(-1.00000000000000))*(x1158)*(x1164)))+(((IkReal(-1.00000000000000))*(pp)*(x1125)*(x1135)))+(((IkReal(-1.00000000000000))*(x1133)*(x1159)))+(((cj1)*(x1170)))+(((pp)*(x1144)))+(((cj1)*(r00)*(x1122)*(x1138)))+(((IkReal(-1.00000000000000))*(x1132)*(x1145)))+(((IkReal(-0.0512000000000000))*(x1164)))+(((x1143)*(x1165)))+(((x1136)*(x1159)))+(((x1135)*(x1141)*(x1142)))+(((IkReal(-1.00000000000000))*(x1144)*(x1167)))+(((IkReal(-1.00000000000000))*(x1147)*(x1165)))+(((IkReal(0.600000000000000))*(pz)*(x1162)))+(((IkReal(-1.00000000000000))*(pp)*(x1151)*(x1152)))+(((IkReal(-1.00000000000000))*(x1127)*(x1164)))+(((IkReal(-0.0120000000000000))*(x1165)))+(((IkReal(-1.00000000000000))*(cj0)*(x1133)*(x1140)))+(((IkReal(-1.00000000000000))*(r02)*(x1124)*(x1131)))+(((x1132)*(x1135)*(x1142)))+(((sj0)*(x1130)*(x1169))));
03322 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  || IKabs(evalcond[6]) > 0.000001  || IKabs(evalcond[7]) > 0.000001  )
03323 {
03324 continue;
03325 }
03326 }
03327 
03328 {
03329 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03330 vinfos[0].jointtype = 1;
03331 vinfos[0].foffset = j0;
03332 vinfos[0].indices[0] = _ij0[0];
03333 vinfos[0].indices[1] = _ij0[1];
03334 vinfos[0].maxsolutions = _nj0;
03335 vinfos[1].jointtype = 1;
03336 vinfos[1].foffset = j1;
03337 vinfos[1].indices[0] = _ij1[0];
03338 vinfos[1].indices[1] = _ij1[1];
03339 vinfos[1].maxsolutions = _nj1;
03340 vinfos[2].jointtype = 1;
03341 vinfos[2].foffset = j2;
03342 vinfos[2].indices[0] = _ij2[0];
03343 vinfos[2].indices[1] = _ij2[1];
03344 vinfos[2].maxsolutions = _nj2;
03345 vinfos[3].jointtype = 1;
03346 vinfos[3].foffset = j3;
03347 vinfos[3].indices[0] = _ij3[0];
03348 vinfos[3].indices[1] = _ij3[1];
03349 vinfos[3].maxsolutions = _nj3;
03350 vinfos[4].jointtype = 1;
03351 vinfos[4].foffset = j4;
03352 vinfos[4].indices[0] = _ij4[0];
03353 vinfos[4].indices[1] = _ij4[1];
03354 vinfos[4].maxsolutions = _nj4;
03355 std::vector<int> vfree(0);
03356 solutions.AddSolution(vinfos,vfree);
03357 }
03358 }
03359 }
03360 
03361 }
03362 
03363 }
03364 }
03365 }
03366 
03367 }
03368 
03369 }
03370 }
03371 }
03372     }
03373 }
03374 }
03375 }
03376 return solutions.GetNumSolutions()>0;
03377 }
03378 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
03379 {
03380     using std::complex;
03381     IKFAST_ASSERT(rawcoeffs[0] != 0);
03382     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
03383     const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
03384     complex<IkReal> coeffs[4];
03385     const int maxsteps = 110;
03386     for(int i = 0; i < 4; ++i) {
03387         coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
03388     }
03389     complex<IkReal> roots[4];
03390     IkReal err[4];
03391     roots[0] = complex<IkReal>(1,0);
03392     roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
03393     err[0] = 1.0;
03394     err[1] = 1.0;
03395     for(int i = 2; i < 4; ++i) {
03396         roots[i] = roots[i-1]*roots[1];
03397         err[i] = 1.0;
03398     }
03399     for(int step = 0; step < maxsteps; ++step) {
03400         bool changed = false;
03401         for(int i = 0; i < 4; ++i) {
03402             if ( err[i] >= tol ) {
03403                 changed = true;
03404                 // evaluate
03405                 complex<IkReal> x = roots[i] + coeffs[0];
03406                 for(int j = 1; j < 4; ++j) {
03407                     x = roots[i] * x + coeffs[j];
03408                 }
03409                 for(int j = 0; j < 4; ++j) {
03410                     if( i != j ) {
03411                         if( roots[i] != roots[j] ) {
03412                             x /= (roots[i] - roots[j]);
03413                         }
03414                     }
03415                 }
03416                 roots[i] -= x;
03417                 err[i] = abs(x);
03418             }
03419         }
03420         if( !changed ) {
03421             break;
03422         }
03423     }
03424 
03425     numroots = 0;
03426     bool visited[4] = {false};
03427     for(int i = 0; i < 4; ++i) {
03428         if( !visited[i] ) {
03429             // might be a multiple root, in which case it will have more error than the other roots
03430             // find any neighboring roots, and take the average
03431             complex<IkReal> newroot=roots[i];
03432             int n = 1;
03433             for(int j = i+1; j < 4; ++j) {
03434                 if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
03435                     newroot += roots[j];
03436                     n += 1;
03437                     visited[j] = true;
03438                 }
03439             }
03440             if( n > 1 ) {
03441                 newroot /= n;
03442             }
03443             // there are still cases where even the mean is not accurate enough, until a better multi-root algorithm is used, need to use the sqrt
03444             if( IKabs(imag(newroot)) < tolsqrt ) {
03445                 rawroots[numroots++] = real(newroot);
03446             }
03447         }
03448     }
03449 }
03450 };
03451 
03452 
03455 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
03456 IKSolver solver;
03457 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
03458 }
03459 
03460 IKFAST_API const char* GetKinematicsHash() { return "e1ede99669e4a55117e29b2cffeb063c"; }
03461 
03462 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
03463 
03464 #ifdef IKFAST_NAMESPACE
03465 } // end namespace
03466 #endif
03467 
03468 #ifndef IKFAST_NO_MAIN
03469 #include <stdio.h>
03470 #include <stdlib.h>
03471 #ifdef IKFAST_NAMESPACE
03472 using namespace IKFAST_NAMESPACE;
03473 #endif
03474 int main(int argc, char** argv)
03475 {
03476     if( argc != 12+GetNumFreeParameters()+1 ) {
03477         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
03478                "Returns the ik solutions given the transformation of the end effector specified by\n"
03479                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
03480                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
03481         return 1;
03482     }
03483 
03484     IkSolutionList<IkReal> solutions;
03485     std::vector<IkReal> vfree(GetNumFreeParameters());
03486     IkReal eerot[9],eetrans[3];
03487     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
03488     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
03489     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
03490     for(std::size_t i = 0; i < vfree.size(); ++i)
03491         vfree[i] = atof(argv[13+i]);
03492     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
03493 
03494     if( !bSuccess ) {
03495         fprintf(stderr,"Failed to get ik solution\n");
03496         return -1;
03497     }
03498 
03499     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
03500     std::vector<IkReal> solvalues(GetNumJoints());
03501     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
03502         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
03503         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
03504         std::vector<IkReal> vsolfree(sol.GetFree().size());
03505         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
03506         for( std::size_t j = 0; j < solvalues.size(); ++j)
03507             printf("%.15f, ", solvalues[j]);
03508         printf("\n");
03509     }
03510     return 0;
03511 }
03512 
03513 #endif


fanuc_lrmate200ic_moveit_plugins
Author(s): G.A. vd. Hoorn (TU Delft Robotics Institute)
autogenerated on Sat Jun 8 2019 20:43:41