fanuc_lrmate200ic5f_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[3]);
00218 x6=IKsin(j[0]);
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))*(x6));
00224 x12=((IkReal(1.00000000000000))*(x0));
00225 x13=((IkReal(1.00000000000000))*(x6));
00226 x14=((IkReal(0.327500000000000))*(x0));
00227 x15=((IkReal(0.327500000000000))*(x6));
00228 x16=((IkReal(0.300000000000000))*(x1));
00229 x17=((IkReal(0.0800000000000000))*(x0));
00230 x18=((IkReal(0.0750000000000000))*(x6));
00231 x19=((x3)*(x4));
00232 x20=((x1)*(x2));
00233 x21=((x2)*(x3));
00234 x22=((x1)*(x4));
00235 x23=((IkReal(0.0750000000000000))*(x20));
00236 x24=((x1)*(x11));
00237 IkReal x25=((IkReal(1.00000000000000))*(x19));
00238 eetrans[0]=((((x0)*(x16)))+(((IkReal(-1.00000000000000))*(x10)*(x25)))+(x10)+(((x10)*(x20)))+(((x7)*(((((x17)*(x22)))+(((x17)*(x21)))))))+(((x14)*(x21)))+(((x14)*(x22)))+(((x5)*(((((IkReal(-1.00000000000000))*(x17)*(x25)))+(((x17)*(x20))))))));
00239 IkReal x26=((IkReal(1.00000000000000))*(x19));
00240 eetrans[1]=((((x7)*(((((x11)*(x21)))+(((x11)*(x22)))))))+(((x15)*(x21)))+(((x15)*(x22)))+(x18)+(((IkReal(-1.00000000000000))*(x18)*(x26)))+(((x16)*(x6)))+(((x5)*(((((x11)*(x20)))+(((IkReal(-1.00000000000000))*(x11)*(x26)))))))+(((x18)*(x20))));
00241 eetrans[2]=((IkReal(0.330000000000000))+(((x7)*(((((IkReal(0.0800000000000000))*(x19)))+(((IkReal(-0.0800000000000000))*(x20)))))))+(((IkReal(0.327500000000000))*(x19)))+(((IkReal(-0.327500000000000))*(x20)))+(((IkReal(0.0750000000000000))*(x21)))+(((IkReal(0.300000000000000))*(x3)))+(((IkReal(0.0750000000000000))*(x22)))+(((x5)*(((((IkReal(0.0800000000000000))*(x21)))+(((IkReal(0.0800000000000000))*(x22))))))));
00242 IkReal x27=((IkReal(1.00000000000000))*(x12));
00243 eerot[0]=((((IkReal(-1.00000000000000))*(x13)*(x9)))+(((x8)*(((((x5)*(((((IkReal(-1.00000000000000))*(x21)*(x27)))+(((IkReal(-1.00000000000000))*(x22)*(x27)))))))+(((x7)*(((((x0)*(x20)))+(((IkReal(-1.00000000000000))*(x19)*(x27))))))))))));
00244 IkReal x28=((IkReal(1.00000000000000))*(x13));
00245 eerot[1]=((((x8)*(((((x5)*(((((IkReal(-1.00000000000000))*(x21)*(x28)))+(((IkReal(-1.00000000000000))*(x22)*(x28)))))))+(((x7)*(((((x20)*(x6)))+(((IkReal(-1.00000000000000))*(x19)*(x28)))))))))))+(((x0)*(x9))));
00246 eerot[2]=((x8)*(((((x5)*(((((IkReal(1.00000000000000))*(x20)))+(((IkReal(-1.00000000000000))*(x19)))))))+(((x7)*(((x21)+(x22))))))));
00247 }
00248 
00249 IKFAST_API int GetNumFreeParameters() { return 0; }
00250 IKFAST_API int* GetFreeParameters() { return NULL; }
00251 IKFAST_API int GetNumJoints() { return 5; }
00252 
00253 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00254 
00255 IKFAST_API int GetIkType() { return 0x56000007; }
00256 
00257 class IKSolver {
00258 public:
00259 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;
00260 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4;
00261 
00262 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00263 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; 
00264 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00265     solutions.Clear();
00266 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00267 
00268 r00 = eerot[0];
00269 r01 = eerot[1];
00270 r02 = eerot[2];
00271 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00272 new_r00=r00;
00273 new_px=px;
00274 new_r01=r01;
00275 new_py=py;
00276 new_r02=r02;
00277 new_pz=((IkReal(-0.330000000000000))+(pz));
00278 r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz;
00279 
00280 pp=(((px)*(px))+((pz)*(pz))+((py)*(py)));
00281 {
00282 IkReal j0array[2], cj0array[2], sj0array[2];
00283 bool j0valid[2]={false};
00284 _nj0 = 2;
00285 if( IKabs(((IkReal(-1.00000000000000))*(py))) < IKFAST_ATAN2_MAGTHRESH && IKabs(px) < IKFAST_ATAN2_MAGTHRESH )
00286     continue;
00287 IkReal x29=IKatan2(((IkReal(-1.00000000000000))*(py)), px);
00288 j0array[0]=((IkReal(-1.00000000000000))*(x29));
00289 sj0array[0]=IKsin(j0array[0]);
00290 cj0array[0]=IKcos(j0array[0]);
00291 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x29))));
00292 sj0array[1]=IKsin(j0array[1]);
00293 cj0array[1]=IKcos(j0array[1]);
00294 if( j0array[0] > IKPI )
00295 {
00296     j0array[0]-=IK2PI;
00297 }
00298 else if( j0array[0] < -IKPI )
00299 {    j0array[0]+=IK2PI;
00300 }
00301 j0valid[0] = true;
00302 if( j0array[1] > IKPI )
00303 {
00304     j0array[1]-=IK2PI;
00305 }
00306 else if( j0array[1] < -IKPI )
00307 {    j0array[1]+=IK2PI;
00308 }
00309 j0valid[1] = true;
00310 for(int ij0 = 0; ij0 < 2; ++ij0)
00311 {
00312 if( !j0valid[ij0] )
00313 {
00314     continue;
00315 }
00316 _ij0[0] = ij0; _ij0[1] = -1;
00317 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
00318 {
00319 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00320 {
00321     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00322 }
00323 }
00324 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00325 
00326 IkReal op[4+1], zeror[4];
00327 int numroots;
00328 op[0]=((((IkReal(-0.00325687500000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-2.40000000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.676575000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.763425000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(1.20000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(-2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.763425000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((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.0567750000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.20000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-4.80000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-4.80000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.138050000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.0283875000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.0130275000000000))*(pz)*((r02)*(r02))))+(((IkReal(-0.381712500000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.180000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((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.00709687500000000))*(cj0)*(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.600000000000000))*(pp)*(pz)*(r01)*(r02)*(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(0.763425000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-4.00000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(2.61418359375000e-5))*((r02)*(r02))))+(((IkReal(0.600000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.600000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.625375000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-2.40000000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00325687500000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(0.0690250000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-1.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-0.0283875000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-0.765000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(-0.00709687500000000))*(py)*(sj0)*((r02)*(r02))))+(((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.0130275000000000))*(py)*(r01)*(r02)))+(((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(-0.763425000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(2.40000000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((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(-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(-0.00325687500000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-8.00000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.00325687500000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(0.0690250000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.180000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.00218614183593750))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.00437228367187500))*(cj0)*(r00)*(r01)*(sj0)))+(((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(1.20000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((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.00218614183593750))*((r01)*(r01))*((sj0)*(sj0))))+(((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.763425000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-4.80000000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(0.138050000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-8.00000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.381712500000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((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(0.0283875000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(0.763425000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.180000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.294075000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((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.625375000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.382500000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.0283875000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.763425000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(0.763425000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.0690250000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.300000000000000))*(pp)*(px)*(r00)*(r01)*(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.0442125000000000))*(pp)*((r02)*(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.180000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((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.0690250000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0283875000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.625375000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.625375000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.180000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.676575000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(0.763425000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(2.40000000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0130275000000000))*(px)*(r00)*(r02)))+(((IkReal(0.0283875000000000))*(pz)*((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(-4.80000000000000))*(px)*(r00)*(r02)*((pz)*(pz)))));
00329 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.000945000000000000))*(cj0)*(px)*((r00)*(r00))))+(((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.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.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(-1.44000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.00390825000000000))*(cj0)*(r00)*(r01)*(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.000945000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.000945000000000000))*(px)*(r00)*(r01)*(sj0)))+(((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(0.00195412500000000))*((r01)*(r01))*((sj0)*(sj0))))+(((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.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.360000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((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.0297750000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(1.44000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.00195412500000000))*((cj0)*(cj0))*((r00)*(r00))))+(((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(-0.0297750000000000))*(cj0)*(px)*((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.00425812500000000))*((r02)*(r02))))+(((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(0.000945000000000000))*(py)*(sj0)*((r01)*(r01))))+(((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.180000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(1.44000000000000))*(cj0)*(px)*(pz)*((r00)*(r00)))));
00330 op[2]=((((IkReal(-16.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0129437163281250))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.201806250000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.276100000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-1.62925000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.20000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(1.20000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.676575000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.52685000000000))*(py)*(pz)*(r01)*(r02)))+(((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(-1.35315000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((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(0.138050000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.209486250000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(0.600000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(8.00000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.209486250000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.676575000000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00768000000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(0.209486250000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-1.62925000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.20000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.35315000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(0.209486250000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(1.20000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(1.35315000000000))*(cj0)*(pp)*(r00)*(r01)*(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(-32.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-2.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-1.35315000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((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(0.276100000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(1.20000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.765000000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(1.20000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-1.62925000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.35315000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.00116828367187500))*((r02)*(r02))))+(((IkReal(-1.52842500000000))*(pp)*((r02)*(r02))))+(((IkReal(1.20000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.53000000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.35315000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.201806250000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(2.40000000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-0.765000000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(1.52685000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.138050000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((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(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(2.29185000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.600000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-1.35315000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-0.0129437163281250))*((r01)*(r01))*((sj0)*(sj0))))+(((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(-1.62925000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.138050000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(8.00000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-1.35315000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((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(-1.35315000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.20000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(0.138050000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((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(2.40000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0258874326562500))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.20000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02))));
00331 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(0.000945000000000000))*(cj0)*(px)*((r00)*(r00))))+(((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.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.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(-1.44000000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.108000000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00390825000000000))*(cj0)*(r00)*(r01)*(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.000945000000000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-0.360000000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.80000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.000945000000000000))*(px)*(r00)*(r01)*(sj0)))+(((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(0.00195412500000000))*((r01)*(r01))*((sj0)*(sj0))))+(((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.00921600000000000))*(cj0)*(r00)*(r02)))+(((IkReal(-1.44000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0307200000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.108000000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.360000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((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(-0.0297750000000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-1.44000000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.00195412500000000))*((cj0)*(cj0))*((r00)*(r00))))+(((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(-0.0297750000000000))*(cj0)*(px)*((r02)*(r02))))+(((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.00425812500000000))*((r02)*(r02))))+(((IkReal(-0.00921600000000000))*(r01)*(r02)*(sj0)))+(((IkReal(0.360000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-0.360000000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.000945000000000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.108000000000000))*(pz)*((r02)*(r02))))+(((IkReal(4.80000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.44000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-1.44000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(0.180000000000000))*(pp)*((cj0)*(cj0))*((r00)*(r00)))));
00332 op[4]=((((IkReal(-0.00325687500000000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.676575000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-1.20000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.763425000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(2.40000000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0130275000000000))*(pz)*((r02)*(r02))))+(((IkReal(-0.0567750000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.763425000000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((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.600000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(0.138050000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.381712500000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((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(-1.20000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.00709687500000000))*(cj0)*(px)*((r02)*(r02))))+(((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(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.763425000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.180000000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-4.00000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(2.61418359375000e-5))*((r02)*(r02))))+(((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.625375000000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.20000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-0.00325687500000000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(0.0690250000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((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.00709687500000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.600000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(2.40000000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((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(-0.763425000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(0.0283875000000000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.0283875000000000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.600000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(4.80000000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0130275000000000))*(px)*(r00)*(r02)))+(((IkReal(0.00384000000000000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.600000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-0.180000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((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.00325687500000000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-8.00000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.00325687500000000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-2.40000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.0690250000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.00218614183593750))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.180000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(0.00437228367187500))*(cj0)*(r00)*(r01)*(sj0)))+(((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.600000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.300000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-2.40000000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(2.40000000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.00218614183593750))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.600000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(4.80000000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.763425000000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.138050000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-8.00000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.381712500000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((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.763425000000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.180000000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(0.0283875000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-0.294075000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.20000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(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.0130275000000000))*(py)*(r01)*(r02)))+(((IkReal(0.625375000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.382500000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(2.40000000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.0283875000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.763425000000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.300000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(0.763425000000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((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.0690250000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.180000000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.300000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0442125000000000))*(pp)*((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.300000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.600000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.20000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.0283875000000000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(1.20000000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.0690250000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.180000000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.625375000000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.180000000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.625375000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.676575000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(0.0283875000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.763425000000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((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.600000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.180000000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(0.600000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-2.40000000000000))*(pz)*((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)))));
00333 polyroots4(op,zeror,numroots);
00334 IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1];
00335 int numsolutions = 0;
00336 for(int ij1 = 0; ij1 < numroots; ++ij1)
00337 {
00338 IkReal htj1 = zeror[ij1];
00339 tempj1array[0]=((IkReal(2.00000000000000))*(atan(htj1)));
00340 for(int kj1 = 0; kj1 < 1; ++kj1)
00341 {
00342 j1array[numsolutions] = tempj1array[kj1];
00343 if( j1array[numsolutions] > IKPI )
00344 {
00345     j1array[numsolutions]-=IK2PI;
00346 }
00347 else if( j1array[numsolutions] < -IKPI )
00348 {
00349     j1array[numsolutions]+=IK2PI;
00350 }
00351 sj1array[numsolutions] = IKsin(j1array[numsolutions]);
00352 cj1array[numsolutions] = IKcos(j1array[numsolutions]);
00353 numsolutions++;
00354 }
00355 }
00356 bool j1valid[4]={true,true,true,true};
00357 _nj1 = 4;
00358 for(int ij1 = 0; ij1 < numsolutions; ++ij1)
00359     {
00360 if( !j1valid[ij1] )
00361 {
00362     continue;
00363 }
00364     j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00365 htj1 = IKtan(j1/2);
00366 
00367 _ij1[0] = ij1; _ij1[1] = -1;
00368 for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1)
00369 {
00370 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00371 {
00372     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00373 }
00374 }
00375 {
00376 IkReal j4array[2], cj4array[2], sj4array[2];
00377 bool j4valid[2]={false};
00378 _nj4 = 2;
00379 sj4array[0]=((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00380 if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH )
00381 {
00382     j4valid[0] = j4valid[1] = true;
00383     j4array[0] = IKasin(sj4array[0]);
00384     cj4array[0] = IKcos(j4array[0]);
00385     sj4array[1] = sj4array[0];
00386     j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]);
00387     cj4array[1] = -cj4array[0];
00388 }
00389 else if( isnan(sj4array[0]) )
00390 {
00391     // probably any value will work
00392     j4valid[0] = true;
00393     cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0;
00394 }
00395 for(int ij4 = 0; ij4 < 2; ++ij4)
00396 {
00397 if( !j4valid[ij4] )
00398 {
00399     continue;
00400 }
00401 _ij4[0] = ij4; _ij4[1] = -1;
00402 for(int iij4 = ij4+1; iij4 < 2; ++iij4)
00403 {
00404 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
00405 {
00406     j4valid[iij4]=false; _ij4[1] = iij4; break; 
00407 }
00408 }
00409 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
00410 
00411 {
00412 IkReal dummyeval[1];
00413 IkReal gconst0;
00414 gconst0=IKsign(cj4);
00415 dummyeval[0]=cj4;
00416 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00417 {
00418 {
00419 IkReal dummyeval[1];
00420 IkReal gconst1;
00421 gconst1=IKsign(cj4);
00422 dummyeval[0]=cj4;
00423 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00424 {
00425 {
00426 IkReal evalcond[9];
00427 IkReal x30=(py)*(py);
00428 IkReal x31=(px)*(px);
00429 IkReal x32=(pz)*(pz);
00430 IkReal x33=((r02)*(sj1));
00431 IkReal x34=((cj1)*(pz));
00432 IkReal x35=((IkReal(0.150000000000000))*(r00));
00433 IkReal x36=((IkReal(0.600000000000000))*(r02));
00434 IkReal x37=((cj0)*(px));
00435 IkReal x38=((r01)*(sj0));
00436 IkReal x39=((IkReal(1.00000000000000))*(cj1));
00437 IkReal x40=((py)*(sj0));
00438 IkReal x41=((py)*(r01));
00439 IkReal x42=((IkReal(0.150000000000000))*(sj1));
00440 IkReal x43=((IkReal(1.00000000000000))*(pz));
00441 IkReal x44=((px)*(sj1));
00442 IkReal x45=((IkReal(0.600000000000000))*(r00));
00443 IkReal x46=((cj0)*(r00));
00444 IkReal x47=((IkReal(0.0843750000000000))*(cj1));
00445 IkReal x48=((IkReal(2.00000000000000))*(pz));
00446 IkReal x49=((cj1)*(px));
00447 IkReal x50=((IkReal(1.00000000000000))*(px));
00448 IkReal x51=((IkReal(0.300000000000000))*(cj1));
00449 IkReal x52=((IkReal(0.0956250000000000))*(sj1));
00450 IkReal x53=((IkReal(1.00000000000000))*(sj1));
00451 IkReal x54=((cj0)*(pz));
00452 IkReal x55=((IkReal(0.150000000000000))*(cj1));
00453 IkReal x56=((IkReal(2.00000000000000))*(sj1));
00454 IkReal x57=((IkReal(2.00000000000000))*(cj1));
00455 IkReal x58=((IkReal(2.00000000000000))*(r00));
00456 IkReal x59=((IkReal(0.300000000000000))*(sj1));
00457 IkReal x60=((r02)*(x40));
00458 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
00459 evalcond[1]=((((cj0)*(py)))+(((IkReal(-1.00000000000000))*(sj0)*(x50))));
00460 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00461 evalcond[3]=((((IkReal(-1.00000000000000))*(x38)*(x39)))+(x33)+(((IkReal(-1.00000000000000))*(x39)*(x46))));
00462 evalcond[4]=((((IkReal(-1.00000000000000))*(r02)*(x39)))+(((IkReal(-1.00000000000000))*(x38)*(x53)))+(((IkReal(-1.00000000000000))*(x46)*(x53))));
00463 evalcond[5]=((((IkReal(-1.00000000000000))*(r02)*(x43)))+(((r02)*(x51)))+(((IkReal(0.0750000000000000))*(x38)))+(((IkReal(-1.00000000000000))*(r00)*(x50)))+(((IkReal(-1.00000000000000))*(x41)))+(((x46)*(x59)))+(((x38)*(x59)))+(((IkReal(0.0750000000000000))*(x46))));
00464 evalcond[6]=((((x46)*(x51)))+(x60)+(((IkReal(-0.300000000000000))*(x33)))+(((IkReal(-1.00000000000000))*(x43)*(x46)))+(((x38)*(x51)))+(((IkReal(-1.00000000000000))*(x38)*(x43)))+(((r02)*(x37)))+(((IkReal(-0.0750000000000000))*(r02))));
00465 evalcond[7]=((((x40)*(x44)*(x58)))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(x39)))+(((IkReal(-0.150000000000000))*(pz)*(x33)))+(((x33)*(x37)*(x48)))+(((IkReal(-1.00000000000000))*(px)*(x45)))+(((IkReal(-1.00000000000000))*(pz)*(x36)))+(((IkReal(-1.00000000000000))*(x41)*(x42)))+(((x31)*(x46)*(x56)))+(((x37)*(x41)*(x56)))+(((px)*(x34)*(x58)))+(((x30)*(x38)*(x56)))+(((x38)*(x52)))+(((x55)*(x60)))+(((x46)*(x52)))+(((r02)*(x32)*(x57)))+(((r02)*(x37)*(x55)))+(((IkReal(-1.00000000000000))*(pp)*(x46)*(x53)))+(((IkReal(0.0450000000000000))*(x38)))+(((IkReal(2.00000000000000))*(x34)*(x41)))+(((IkReal(-1.00000000000000))*(pp)*(x38)*(x53)))+(((IkReal(-1.00000000000000))*(x35)*(x44)))+(((x33)*(x40)*(x48)))+(((IkReal(-0.600000000000000))*(x41)))+(((r02)*(x47)))+(((IkReal(-0.150000000000000))*(x34)*(x38)))+(((IkReal(-1.00000000000000))*(cj0)*(x34)*(x35)))+(((IkReal(0.0450000000000000))*(x46))));
00466 evalcond[8]=((((IkReal(-0.150000000000000))*(r02)*(x34)))+(((IkReal(-1.00000000000000))*(pp)*(x38)*(x39)))+(((IkReal(2.00000000000000))*(r02)*(x34)*(x37)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x35)*(x49)))+(((pp)*(x33)))+(((x31)*(x46)*(x57)))+(((x45)*(x54)))+(((IkReal(-0.150000000000000))*(x33)*(x37)))+(((IkReal(-0.150000000000000))*(x33)*(x40)))+(((IkReal(2.00000000000000))*(x34)*(x60)))+(((x30)*(x38)*(x57)))+(((IkReal(0.600000000000000))*(pz)*(x38)))+(((IkReal(-1.00000000000000))*(x36)*(x37)))+(((x40)*(x49)*(x58)))+(((IkReal(-1.00000000000000))*(sj1)*(x41)*(x48)))+(((IkReal(-2.00000000000000))*(x32)*(x33)))+(((IkReal(-1.00000000000000))*(x38)*(x47)))+(((IkReal(0.0956250000000000))*(x33)))+(((x37)*(x41)*(x57)))+(((sj1)*(x35)*(x54)))+(((IkReal(-1.00000000000000))*(x41)*(x55)))+(((IkReal(-1.00000000000000))*(r00)*(x44)*(x48)))+(((IkReal(-1.00000000000000))*(pp)*(x39)*(x46)))+(((IkReal(-1.00000000000000))*(x36)*(x40)))+(((pz)*(x38)*(x42)))+(((IkReal(-1.00000000000000))*(x46)*(x47))));
00467 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  )
00468 {
00469 {
00470 IkReal j3array[2], cj3array[2], sj3array[2];
00471 bool j3valid[2]={false};
00472 _nj3 = 2;
00473 IkReal x61=((IkReal(11.1614434376257))*(sj1));
00474 IkReal x62=((py)*(sj0));
00475 IkReal x63=((cj0)*(px));
00476 if( (((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x61)*(x62)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x62)))+(((IkReal(2.79036085940642))*(x63)))+(((x61)*(x63))))) < -1-IKFAST_SINCOS_THRESH || (((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x61)*(x62)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x62)))+(((IkReal(2.79036085940642))*(x63)))+(((x61)*(x63))))) > 1+IKFAST_SINCOS_THRESH )
00477     continue;
00478 IkReal x64=IKasin(((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x61)*(x62)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x62)))+(((IkReal(2.79036085940642))*(x63)))+(((x61)*(x63)))));
00479 j3array[0]=((IkReal(-1.34567065063197))+(((IkReal(-1.00000000000000))*(x64))));
00480 sj3array[0]=IKsin(j3array[0]);
00481 cj3array[0]=IKcos(j3array[0]);
00482 j3array[1]=((IkReal(1.79592200295782))+(x64));
00483 sj3array[1]=IKsin(j3array[1]);
00484 cj3array[1]=IKcos(j3array[1]);
00485 if( j3array[0] > IKPI )
00486 {
00487     j3array[0]-=IK2PI;
00488 }
00489 else if( j3array[0] < -IKPI )
00490 {    j3array[0]+=IK2PI;
00491 }
00492 j3valid[0] = true;
00493 if( j3array[1] > IKPI )
00494 {
00495     j3array[1]-=IK2PI;
00496 }
00497 else if( j3array[1] < -IKPI )
00498 {    j3array[1]+=IK2PI;
00499 }
00500 j3valid[1] = true;
00501 for(int ij3 = 0; ij3 < 2; ++ij3)
00502 {
00503 if( !j3valid[ij3] )
00504 {
00505     continue;
00506 }
00507 _ij3[0] = ij3; _ij3[1] = -1;
00508 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00509 {
00510 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00511 {
00512     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00513 }
00514 }
00515 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00516 {
00517 IkReal evalcond[1];
00518 IkReal x65=((IkReal(2.00000000000000))*(sj0));
00519 IkReal x66=((px)*(py));
00520 IkReal x67=((r00)*(sj0));
00521 IkReal x68=((cj0)*(r01));
00522 IkReal x69=((py)*(r00));
00523 IkReal x70=((IkReal(2.00000000000000))*(cj0));
00524 IkReal x71=((px)*(r01));
00525 IkReal x72=((IkReal(0.600000000000000))*(cj1));
00526 IkReal x73=((py)*(r02));
00527 IkReal x74=((IkReal(0.600000000000000))*(sj1));
00528 IkReal x75=((IkReal(0.0450000000000000))*(sj1));
00529 IkReal x76=((px)*(r02));
00530 evalcond[0]=((IkReal(-0.119281250000000))+(((IkReal(-1.00000000000000))*(x67)*(x75)))+(((r01)*(x65)*(x66)))+(((IkReal(-0.0956250000000000))*(x67)))+(((x69)*(x74)))+(((cj0)*(x72)*(x73)))+(((IkReal(-1.00000000000000))*(pz)*(x68)*(x72)))+(((pp)*(x68)))+(((IkReal(-1.00000000000000))*(pp)*(x67)))+(((IkReal(0.0956250000000000))*(x68)))+(((IkReal(-2.00000000000000))*(x68)*((py)*(py))))+(((IkReal(-0.150000000000000))*(x71)))+(((IkReal(-1.00000000000000))*(r00)*(x66)*(x70)))+(((IkReal(-0.0120000000000000))*(IKsin(j3))))+(((IkReal(-1.00000000000000))*(x71)*(x74)))+(((IkReal(-1.00000000000000))*(sj0)*(x72)*(x76)))+(((pz)*(x67)*(x72)))+(((pz)*(x65)*(x76)))+(((IkReal(-0.0524000000000000))*(IKcos(j3))))+(((IkReal(-1.00000000000000))*(pz)*(x70)*(x73)))+(((IkReal(0.150000000000000))*(x69)))+(((r00)*(x65)*((px)*(px))))+(((x68)*(x75))));
00531 if( IKabs(evalcond[0]) > 0.000001  )
00532 {
00533 continue;
00534 }
00535 }
00536 
00537 {
00538 IkReal dummyeval[1];
00539 IkReal gconst8;
00540 gconst8=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00541 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
00542 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00543 {
00544 {
00545 IkReal dummyeval[1];
00546 IkReal gconst9;
00547 gconst9=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00548 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
00549 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00550 {
00551 continue;
00552 
00553 } else
00554 {
00555 {
00556 IkReal j2array[1], cj2array[1], sj2array[1];
00557 bool j2valid[1]={false};
00558 _nj2 = 1;
00559 IkReal x77=((pz)*(sj1));
00560 IkReal x78=((cj0)*(r01));
00561 IkReal x79=((IkReal(0.0800000000000000))*(sj3));
00562 IkReal x80=((r00)*(sj0));
00563 IkReal x81=((IkReal(0.00600000000000000))*(cj1));
00564 IkReal x82=((IkReal(0.0750000000000000))*(cj1));
00565 IkReal x83=((IkReal(0.0245625000000000))*(cj1));
00566 IkReal x84=((px)*(r01));
00567 IkReal x85=((IkReal(0.00562500000000000))*(cj1));
00568 IkReal x86=((IkReal(0.0800000000000000))*(cj3));
00569 IkReal x87=((px)*(sj1));
00570 IkReal x88=((cj1)*(pz));
00571 IkReal x89=((IkReal(0.0750000000000000))*(sj0));
00572 IkReal x90=((IkReal(0.327500000000000))*(cj0));
00573 IkReal x91=((py)*(sj1));
00574 IkReal x92=((cj0)*(r02));
00575 IkReal x93=((IkReal(0.00600000000000000))*(sj1));
00576 IkReal x94=((IkReal(0.327500000000000))*(sj0));
00577 IkReal x95=((cj1)*(py)*(r00));
00578 IkReal x96=((IkReal(0.0800000000000000))*(r02)*(sj0)*(x87));
00579 if( IKabs(((gconst9)*(((IkReal(-0.0982500000000000))+(((x79)*(x95)))+(((py)*(r00)*(x82)))+(((r02)*(x87)*(x89)))+(((IkReal(-1.00000000000000))*(x80)*(x85)))+(((IkReal(0.0750000000000000))*(x77)*(x78)))+(((cj0)*(x86)*(x87)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(x79)*(x84)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x79)*(x91)*(x92)))+(((IkReal(-1.00000000000000))*(x77)*(x79)*(x80)))+(((IkReal(-1.00000000000000))*(x82)*(x84)))+(((IkReal(0.327500000000000))*(x88)))+(((IkReal(-0.0750000000000000))*(x91)*(x92)))+(((IkReal(-1.00000000000000))*(sj3)*(x80)*(x81)))+(((r02)*(sj0)*(x79)*(x87)))+(((IkReal(-1.00000000000000))*(cj3)*(x93)))+(((x78)*(x85)))+(((sj3)*(x78)*(x81)))+(((x77)*(x78)*(x79)))+(((x86)*(x88)))+(((x87)*(x90)))+(((x91)*(x94)))+(((sj0)*(x86)*(x91)))+(((IkReal(-0.0750000000000000))*(x77)*(x80))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(0.327500000000000))*(cj1)*(x84)))+(((IkReal(0.0750000000000000))*(cj0)*(x87)))+(((IkReal(-1.00000000000000))*(sj3)*(x93)))+(((x89)*(x91)))+(((IkReal(-0.327500000000000))*(x95)))+(((IkReal(-1.00000000000000))*(x77)*(x78)*(x86)))+(((x77)*(x80)*(x86)))+(((cj1)*(x84)*(x86)))+(((IkReal(-1.00000000000000))*(r02)*(x87)*(x94)))+(((cj0)*(x79)*(x87)))+(((x80)*(x83)))+(((pz)*(x82)))+(((r02)*(x90)*(x91)))+(((x86)*(x91)*(x92)))+(((x79)*(x88)))+(((cj3)*(x80)*(x81)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x86)*(x87)))+(((IkReal(0.327500000000000))*(x77)*(x80)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((sj0)*(x79)*(x91)))+(((IkReal(-1.00000000000000))*(x78)*(x83)))+(((IkReal(-1.00000000000000))*(x86)*(x95)))+(((IkReal(-0.327500000000000))*(x77)*(x78)))+(((IkReal(-1.00000000000000))*(cj3)*(x78)*(x81))))))) < IKFAST_ATAN2_MAGTHRESH )
00580     continue;
00581 j2array[0]=IKatan2(((gconst9)*(((IkReal(-0.0982500000000000))+(((x79)*(x95)))+(((py)*(r00)*(x82)))+(((r02)*(x87)*(x89)))+(((IkReal(-1.00000000000000))*(x80)*(x85)))+(((IkReal(0.0750000000000000))*(x77)*(x78)))+(((cj0)*(x86)*(x87)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(x79)*(x84)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x79)*(x91)*(x92)))+(((IkReal(-1.00000000000000))*(x77)*(x79)*(x80)))+(((IkReal(-1.00000000000000))*(x82)*(x84)))+(((IkReal(0.327500000000000))*(x88)))+(((IkReal(-0.0750000000000000))*(x91)*(x92)))+(((IkReal(-1.00000000000000))*(sj3)*(x80)*(x81)))+(((r02)*(sj0)*(x79)*(x87)))+(((IkReal(-1.00000000000000))*(cj3)*(x93)))+(((x78)*(x85)))+(((sj3)*(x78)*(x81)))+(((x77)*(x78)*(x79)))+(((x86)*(x88)))+(((x87)*(x90)))+(((x91)*(x94)))+(((sj0)*(x86)*(x91)))+(((IkReal(-0.0750000000000000))*(x77)*(x80)))))), ((gconst9)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(0.327500000000000))*(cj1)*(x84)))+(((IkReal(0.0750000000000000))*(cj0)*(x87)))+(((IkReal(-1.00000000000000))*(sj3)*(x93)))+(((x89)*(x91)))+(((IkReal(-0.327500000000000))*(x95)))+(((IkReal(-1.00000000000000))*(x77)*(x78)*(x86)))+(((x77)*(x80)*(x86)))+(((cj1)*(x84)*(x86)))+(((IkReal(-1.00000000000000))*(r02)*(x87)*(x94)))+(((cj0)*(x79)*(x87)))+(((x80)*(x83)))+(((pz)*(x82)))+(((r02)*(x90)*(x91)))+(((x86)*(x91)*(x92)))+(((x79)*(x88)))+(((cj3)*(x80)*(x81)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x86)*(x87)))+(((IkReal(0.327500000000000))*(x77)*(x80)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((sj0)*(x79)*(x91)))+(((IkReal(-1.00000000000000))*(x78)*(x83)))+(((IkReal(-1.00000000000000))*(x86)*(x95)))+(((IkReal(-0.327500000000000))*(x77)*(x78)))+(((IkReal(-1.00000000000000))*(cj3)*(x78)*(x81)))))));
00582 sj2array[0]=IKsin(j2array[0]);
00583 cj2array[0]=IKcos(j2array[0]);
00584 if( j2array[0] > IKPI )
00585 {
00586     j2array[0]-=IK2PI;
00587 }
00588 else if( j2array[0] < -IKPI )
00589 {    j2array[0]+=IK2PI;
00590 }
00591 j2valid[0] = true;
00592 for(int ij2 = 0; ij2 < 1; ++ij2)
00593 {
00594 if( !j2valid[ij2] )
00595 {
00596     continue;
00597 }
00598 _ij2[0] = ij2; _ij2[1] = -1;
00599 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00600 {
00601 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00602 {
00603     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00604 }
00605 }
00606 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00607 {
00608 IkReal evalcond[4];
00609 IkReal x97=IKcos(j2);
00610 IkReal x98=IKsin(j2);
00611 IkReal x99=((IkReal(0.0800000000000000))*(sj3));
00612 IkReal x100=((cj0)*(r01));
00613 IkReal x101=((IkReal(1.00000000000000))*(px));
00614 IkReal x102=((py)*(sj1));
00615 IkReal x103=((cj0)*(r02));
00616 IkReal x104=((IkReal(0.0750000000000000))*(cj1));
00617 IkReal x105=((r02)*(sj0));
00618 IkReal x106=((IkReal(0.0750000000000000))*(sj1));
00619 IkReal x107=((cj1)*(pz));
00620 IkReal x108=((r00)*(sj0));
00621 IkReal x109=((IkReal(0.0800000000000000))*(cj3));
00622 IkReal x110=((pz)*(sj1));
00623 IkReal x111=((IkReal(1.00000000000000))*(sj0));
00624 IkReal x112=((cj1)*(py));
00625 IkReal x113=((IkReal(0.0750000000000000))*(x98));
00626 IkReal x114=((IkReal(0.327500000000000))*(x97));
00627 IkReal x115=((IkReal(0.0750000000000000))*(x97));
00628 IkReal x116=((IkReal(0.327500000000000))*(x98));
00629 IkReal x117=((sj1)*(x108));
00630 IkReal x118=((x98)*(x99));
00631 IkReal x119=((x109)*(x97));
00632 IkReal x120=((x97)*(x99));
00633 IkReal x121=((x109)*(x98));
00634 IkReal x122=((x113)+(x118));
00635 IkReal x123=((x114)+(x119));
00636 IkReal x124=((x120)+(x121)+(x116)+(x115));
00637 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x101)))+(((IkReal(-1.00000000000000))*(x111)*(x112)))+(x123)+(((IkReal(-1.00000000000000))*(x122)))+(x104)+(x110));
00638 evalcond[1]=((IkReal(0.300000000000000))+(x124)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x101)))+(x106)+(((IkReal(-1.00000000000000))*(x102)*(x111)))+(((IkReal(-1.00000000000000))*(x107))));
00639 evalcond[2]=((((x108)*(x110)))+(((x102)*(x103)))+(((cj1)*(px)*(r01)))+(x122)+(((IkReal(-1.00000000000000))*(x100)*(x104)))+(((IkReal(-1.00000000000000))*(x100)*(x110)))+(((IkReal(-1.00000000000000))*(sj1)*(x101)*(x105)))+(((x104)*(x108)))+(((IkReal(-1.00000000000000))*(x123)))+(((IkReal(-1.00000000000000))*(r00)*(x112))));
00640 evalcond[3]=((((IkReal(-0.300000000000000))*(x108)))+(((IkReal(-1.00000000000000))*(x106)*(x108)))+(((IkReal(-1.00000000000000))*(cj1)*(x101)*(x105)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x101)))+(((x100)*(x106)))+(((r00)*(x102)))+(((IkReal(0.300000000000000))*(x100)))+(((IkReal(-1.00000000000000))*(x100)*(x107)))+(x124)+(((x107)*(x108)))+(((x103)*(x112))));
00641 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00642 {
00643 continue;
00644 }
00645 }
00646 
00647 {
00648 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00649 vinfos[0].jointtype = 1;
00650 vinfos[0].foffset = j0;
00651 vinfos[0].indices[0] = _ij0[0];
00652 vinfos[0].indices[1] = _ij0[1];
00653 vinfos[0].maxsolutions = _nj0;
00654 vinfos[1].jointtype = 1;
00655 vinfos[1].foffset = j1;
00656 vinfos[1].indices[0] = _ij1[0];
00657 vinfos[1].indices[1] = _ij1[1];
00658 vinfos[1].maxsolutions = _nj1;
00659 vinfos[2].jointtype = 1;
00660 vinfos[2].foffset = j2;
00661 vinfos[2].indices[0] = _ij2[0];
00662 vinfos[2].indices[1] = _ij2[1];
00663 vinfos[2].maxsolutions = _nj2;
00664 vinfos[3].jointtype = 1;
00665 vinfos[3].foffset = j3;
00666 vinfos[3].indices[0] = _ij3[0];
00667 vinfos[3].indices[1] = _ij3[1];
00668 vinfos[3].maxsolutions = _nj3;
00669 vinfos[4].jointtype = 1;
00670 vinfos[4].foffset = j4;
00671 vinfos[4].indices[0] = _ij4[0];
00672 vinfos[4].indices[1] = _ij4[1];
00673 vinfos[4].maxsolutions = _nj4;
00674 std::vector<int> vfree(0);
00675 solutions.AddSolution(vinfos,vfree);
00676 }
00677 }
00678 }
00679 
00680 }
00681 
00682 }
00683 
00684 } else
00685 {
00686 {
00687 IkReal j2array[1], cj2array[1], sj2array[1];
00688 bool j2valid[1]={false};
00689 _nj2 = 1;
00690 IkReal x125=((IkReal(0.0800000000000000))*(cj1));
00691 IkReal x126=((cj0)*(px));
00692 IkReal x127=((py)*(sj0));
00693 IkReal x128=((IkReal(0.0750000000000000))*(cj1));
00694 IkReal x129=((IkReal(0.327500000000000))*(cj1));
00695 IkReal x130=((IkReal(0.327500000000000))*(sj1));
00696 IkReal x131=((IkReal(0.0750000000000000))*(sj1));
00697 IkReal x132=((IkReal(0.00600000000000000))*(sj1));
00698 IkReal x133=((IkReal(0.00600000000000000))*(cj1));
00699 IkReal x134=((IkReal(0.0800000000000000))*(sj1)*(sj3));
00700 IkReal x135=((IkReal(0.0800000000000000))*(cj3)*(sj1));
00701 if( IKabs(((gconst8)*(((IkReal(-0.0982500000000000))+(((x126)*(x130)))+(((IkReal(-1.00000000000000))*(cj3)*(x132)))+(((pz)*(x134)))+(((pz)*(x131)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((sj3)*(x133)))+(((pz)*(x129)))+(((x127)*(x130)))+(((IkReal(-1.00000000000000))*(sj3)*(x125)*(x126)))+(((x126)*(x135)))+(((IkReal(-1.00000000000000))*(x126)*(x128)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x127)*(x128)))+(((x127)*(x135)))+(((IkReal(-1.00000000000000))*(sj3)*(x125)*(x127)))+(((cj3)*(pz)*(x125))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x132)))+(((IkReal(-1.00000000000000))*(pz)*(x135)))+(((IkReal(-1.00000000000000))*(cj3)*(x133)))+(((x127)*(x134)))+(((x126)*(x129)))+(((x126)*(x134)))+(((pz)*(x128)))+(((x127)*(x131)))+(((x126)*(x131)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x125)*(x126)))+(((x127)*(x129)))+(((pz)*(sj3)*(x125)))+(((IkReal(-1.00000000000000))*(pz)*(x130)))+(((cj3)*(x125)*(x127))))))) < IKFAST_ATAN2_MAGTHRESH )
00702     continue;
00703 j2array[0]=IKatan2(((gconst8)*(((IkReal(-0.0982500000000000))+(((x126)*(x130)))+(((IkReal(-1.00000000000000))*(cj3)*(x132)))+(((pz)*(x134)))+(((pz)*(x131)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((sj3)*(x133)))+(((pz)*(x129)))+(((x127)*(x130)))+(((IkReal(-1.00000000000000))*(sj3)*(x125)*(x126)))+(((x126)*(x135)))+(((IkReal(-1.00000000000000))*(x126)*(x128)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x127)*(x128)))+(((x127)*(x135)))+(((IkReal(-1.00000000000000))*(sj3)*(x125)*(x127)))+(((cj3)*(pz)*(x125)))))), ((gconst8)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x132)))+(((IkReal(-1.00000000000000))*(pz)*(x135)))+(((IkReal(-1.00000000000000))*(cj3)*(x133)))+(((x127)*(x134)))+(((x126)*(x129)))+(((x126)*(x134)))+(((pz)*(x128)))+(((x127)*(x131)))+(((x126)*(x131)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((cj3)*(x125)*(x126)))+(((x127)*(x129)))+(((pz)*(sj3)*(x125)))+(((IkReal(-1.00000000000000))*(pz)*(x130)))+(((cj3)*(x125)*(x127)))))));
00704 sj2array[0]=IKsin(j2array[0]);
00705 cj2array[0]=IKcos(j2array[0]);
00706 if( j2array[0] > IKPI )
00707 {
00708     j2array[0]-=IK2PI;
00709 }
00710 else if( j2array[0] < -IKPI )
00711 {    j2array[0]+=IK2PI;
00712 }
00713 j2valid[0] = true;
00714 for(int ij2 = 0; ij2 < 1; ++ij2)
00715 {
00716 if( !j2valid[ij2] )
00717 {
00718     continue;
00719 }
00720 _ij2[0] = ij2; _ij2[1] = -1;
00721 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00722 {
00723 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00724 {
00725     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00726 }
00727 }
00728 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00729 {
00730 IkReal evalcond[4];
00731 IkReal x136=IKcos(j2);
00732 IkReal x137=IKsin(j2);
00733 IkReal x138=((IkReal(0.0800000000000000))*(sj3));
00734 IkReal x139=((cj0)*(r01));
00735 IkReal x140=((IkReal(1.00000000000000))*(px));
00736 IkReal x141=((py)*(sj1));
00737 IkReal x142=((cj0)*(r02));
00738 IkReal x143=((IkReal(0.0750000000000000))*(cj1));
00739 IkReal x144=((r02)*(sj0));
00740 IkReal x145=((IkReal(0.0750000000000000))*(sj1));
00741 IkReal x146=((cj1)*(pz));
00742 IkReal x147=((r00)*(sj0));
00743 IkReal x148=((IkReal(0.0800000000000000))*(cj3));
00744 IkReal x149=((pz)*(sj1));
00745 IkReal x150=((IkReal(1.00000000000000))*(sj0));
00746 IkReal x151=((cj1)*(py));
00747 IkReal x152=((IkReal(0.0750000000000000))*(x137));
00748 IkReal x153=((IkReal(0.327500000000000))*(x136));
00749 IkReal x154=((IkReal(0.0750000000000000))*(x136));
00750 IkReal x155=((IkReal(0.327500000000000))*(x137));
00751 IkReal x156=((sj1)*(x147));
00752 IkReal x157=((x137)*(x138));
00753 IkReal x158=((x136)*(x148));
00754 IkReal x159=((x136)*(x138));
00755 IkReal x160=((x137)*(x148));
00756 IkReal x161=((x157)+(x152));
00757 IkReal x162=((x153)+(x158));
00758 IkReal x163=((x155)+(x154)+(x159)+(x160));
00759 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x140)))+(((IkReal(-1.00000000000000))*(x150)*(x151)))+(x162)+(((IkReal(-1.00000000000000))*(x161)))+(x143)+(x149));
00760 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x141)*(x150)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x140)))+(((IkReal(-1.00000000000000))*(x146)))+(x163)+(x145));
00761 evalcond[2]=((((cj1)*(px)*(r01)))+(x161)+(((IkReal(-1.00000000000000))*(x139)*(x149)))+(((IkReal(-1.00000000000000))*(sj1)*(x140)*(x144)))+(((x143)*(x147)))+(((IkReal(-1.00000000000000))*(r00)*(x151)))+(((IkReal(-1.00000000000000))*(x139)*(x143)))+(((x147)*(x149)))+(((x141)*(x142)))+(((IkReal(-1.00000000000000))*(x162))));
00762 evalcond[3]=((((IkReal(-1.00000000000000))*(x139)*(x146)))+(((x139)*(x145)))+(((IkReal(-0.300000000000000))*(x147)))+(((r00)*(x141)))+(((IkReal(-1.00000000000000))*(cj1)*(x140)*(x144)))+(x163)+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x140)))+(((x142)*(x151)))+(((IkReal(-1.00000000000000))*(x145)*(x147)))+(((IkReal(0.300000000000000))*(x139)))+(((x146)*(x147))));
00763 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00764 {
00765 continue;
00766 }
00767 }
00768 
00769 {
00770 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00771 vinfos[0].jointtype = 1;
00772 vinfos[0].foffset = j0;
00773 vinfos[0].indices[0] = _ij0[0];
00774 vinfos[0].indices[1] = _ij0[1];
00775 vinfos[0].maxsolutions = _nj0;
00776 vinfos[1].jointtype = 1;
00777 vinfos[1].foffset = j1;
00778 vinfos[1].indices[0] = _ij1[0];
00779 vinfos[1].indices[1] = _ij1[1];
00780 vinfos[1].maxsolutions = _nj1;
00781 vinfos[2].jointtype = 1;
00782 vinfos[2].foffset = j2;
00783 vinfos[2].indices[0] = _ij2[0];
00784 vinfos[2].indices[1] = _ij2[1];
00785 vinfos[2].maxsolutions = _nj2;
00786 vinfos[3].jointtype = 1;
00787 vinfos[3].foffset = j3;
00788 vinfos[3].indices[0] = _ij3[0];
00789 vinfos[3].indices[1] = _ij3[1];
00790 vinfos[3].maxsolutions = _nj3;
00791 vinfos[4].jointtype = 1;
00792 vinfos[4].foffset = j4;
00793 vinfos[4].indices[0] = _ij4[0];
00794 vinfos[4].indices[1] = _ij4[1];
00795 vinfos[4].maxsolutions = _nj4;
00796 std::vector<int> vfree(0);
00797 solutions.AddSolution(vinfos,vfree);
00798 }
00799 }
00800 }
00801 
00802 }
00803 
00804 }
00805 }
00806 }
00807 
00808 } else
00809 {
00810 IkReal x164=(py)*(py);
00811 IkReal x165=(px)*(px);
00812 IkReal x166=(pz)*(pz);
00813 IkReal x167=((r02)*(sj1));
00814 IkReal x168=((cj1)*(pz));
00815 IkReal x169=((IkReal(0.150000000000000))*(r00));
00816 IkReal x170=((IkReal(0.600000000000000))*(r02));
00817 IkReal x171=((cj0)*(px));
00818 IkReal x172=((r01)*(sj0));
00819 IkReal x173=((IkReal(1.00000000000000))*(cj1));
00820 IkReal x174=((py)*(sj0));
00821 IkReal x175=((py)*(r01));
00822 IkReal x176=((IkReal(0.150000000000000))*(sj1));
00823 IkReal x177=((IkReal(1.00000000000000))*(pz));
00824 IkReal x178=((px)*(sj1));
00825 IkReal x179=((IkReal(0.600000000000000))*(r00));
00826 IkReal x180=((cj0)*(r00));
00827 IkReal x181=((IkReal(0.0843750000000000))*(cj1));
00828 IkReal x182=((IkReal(2.00000000000000))*(pz));
00829 IkReal x183=((cj1)*(px));
00830 IkReal x184=((IkReal(1.00000000000000))*(px));
00831 IkReal x185=((IkReal(0.300000000000000))*(cj1));
00832 IkReal x186=((IkReal(0.0956250000000000))*(sj1));
00833 IkReal x187=((IkReal(1.00000000000000))*(sj1));
00834 IkReal x188=((cj0)*(pz));
00835 IkReal x189=((IkReal(0.150000000000000))*(cj1));
00836 IkReal x190=((IkReal(2.00000000000000))*(sj1));
00837 IkReal x191=((IkReal(2.00000000000000))*(cj1));
00838 IkReal x192=((IkReal(2.00000000000000))*(r00));
00839 IkReal x193=((IkReal(0.300000000000000))*(sj1));
00840 IkReal x194=((r02)*(x174));
00841 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
00842 evalcond[1]=((((IkReal(-1.00000000000000))*(sj0)*(x184)))+(((cj0)*(py))));
00843 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00844 evalcond[3]=((((IkReal(-1.00000000000000))*(x173)*(x180)))+(x167)+(((IkReal(-1.00000000000000))*(x172)*(x173))));
00845 evalcond[4]=((((IkReal(-1.00000000000000))*(x180)*(x187)))+(((IkReal(-1.00000000000000))*(x172)*(x187)))+(((IkReal(-1.00000000000000))*(r02)*(x173))));
00846 evalcond[5]=((((x172)*(x193)))+(((IkReal(-1.00000000000000))*(x175)))+(((r02)*(x185)))+(((IkReal(-1.00000000000000))*(r02)*(x177)))+(((IkReal(0.0750000000000000))*(x172)))+(((x180)*(x193)))+(((IkReal(-1.00000000000000))*(r00)*(x184)))+(((IkReal(0.0750000000000000))*(x180))));
00847 evalcond[6]=((((IkReal(-1.00000000000000))*(x172)*(x177)))+(((IkReal(-1.00000000000000))*(x177)*(x180)))+(x194)+(((IkReal(-0.300000000000000))*(x167)))+(((x180)*(x185)))+(((x172)*(x185)))+(((r02)*(x171)))+(((IkReal(-0.0750000000000000))*(r02))));
00848 evalcond[7]=((((x167)*(x174)*(x182)))+(((IkReal(2.00000000000000))*(x168)*(x175)))+(((IkReal(0.0450000000000000))*(x172)))+(((IkReal(-1.00000000000000))*(x169)*(x178)))+(((IkReal(0.0450000000000000))*(x180)))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(x173)))+(((x174)*(x178)*(x192)))+(((r02)*(x166)*(x191)))+(((px)*(x168)*(x192)))+(((IkReal(-0.150000000000000))*(x168)*(x172)))+(((x165)*(x180)*(x190)))+(((IkReal(-1.00000000000000))*(pz)*(x170)))+(((IkReal(-1.00000000000000))*(pp)*(x180)*(x187)))+(((IkReal(-1.00000000000000))*(x175)*(x176)))+(((IkReal(-1.00000000000000))*(cj0)*(x168)*(x169)))+(((IkReal(-1.00000000000000))*(px)*(x179)))+(((IkReal(-0.150000000000000))*(pz)*(x167)))+(((x172)*(x186)))+(((r02)*(x171)*(x189)))+(((x167)*(x171)*(x182)))+(((IkReal(-1.00000000000000))*(pp)*(x172)*(x187)))+(((r02)*(x181)))+(((x164)*(x172)*(x190)))+(((x171)*(x175)*(x190)))+(((x189)*(x194)))+(((IkReal(-0.600000000000000))*(x175)))+(((x180)*(x186))));
00849 evalcond[8]=((((IkReal(-1.00000000000000))*(x172)*(x181)))+(((IkReal(-0.150000000000000))*(x167)*(x174)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(0.600000000000000))*(pz)*(x172)))+(((IkReal(-1.00000000000000))*(x180)*(x181)))+(((pp)*(x167)))+(((pz)*(x172)*(x176)))+(((IkReal(-0.150000000000000))*(x167)*(x171)))+(((x179)*(x188)))+(((IkReal(-2.00000000000000))*(x166)*(x167)))+(((IkReal(-1.00000000000000))*(r00)*(x178)*(x182)))+(((IkReal(-1.00000000000000))*(x169)*(x183)))+(((IkReal(2.00000000000000))*(r02)*(x168)*(x171)))+(((IkReal(-0.150000000000000))*(r02)*(x168)))+(((IkReal(0.0956250000000000))*(x167)))+(((IkReal(-1.00000000000000))*(pp)*(x173)*(x180)))+(((x164)*(x172)*(x191)))+(((IkReal(-1.00000000000000))*(x170)*(x171)))+(((IkReal(-1.00000000000000))*(x175)*(x189)))+(((IkReal(-1.00000000000000))*(sj1)*(x175)*(x182)))+(((IkReal(2.00000000000000))*(x168)*(x194)))+(((IkReal(-1.00000000000000))*(x170)*(x174)))+(((sj1)*(x169)*(x188)))+(((x165)*(x180)*(x191)))+(((x171)*(x175)*(x191)))+(((IkReal(-1.00000000000000))*(pp)*(x172)*(x173)))+(((x174)*(x183)*(x192))));
00850 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  )
00851 {
00852 {
00853 IkReal j3array[2], cj3array[2], sj3array[2];
00854 bool j3valid[2]={false};
00855 _nj3 = 2;
00856 IkReal x195=((IkReal(11.1614434376257))*(sj1));
00857 IkReal x196=((py)*(sj0));
00858 IkReal x197=((cj0)*(px));
00859 if( (((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x195)*(x196)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x196)))+(((IkReal(2.79036085940642))*(x197)))+(((x195)*(x197))))) < -1-IKFAST_SINCOS_THRESH || (((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x195)*(x196)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x196)))+(((IkReal(2.79036085940642))*(x197)))+(((x195)*(x197))))) > 1+IKFAST_SINCOS_THRESH )
00860     continue;
00861 IkReal x198=IKasin(((IkReal(0.440063160535554))+(((IkReal(-0.837108257821925))*(sj1)))+(((x195)*(x196)))+(((IkReal(11.1614434376257))*(cj1)*(pz)))+(((IkReal(-18.6024057293761))*(pp)))+(((IkReal(2.79036085940642))*(x196)))+(((IkReal(2.79036085940642))*(x197)))+(((x195)*(x197)))));
00862 j3array[0]=((IkReal(-1.34567065063197))+(((IkReal(-1.00000000000000))*(x198))));
00863 sj3array[0]=IKsin(j3array[0]);
00864 cj3array[0]=IKcos(j3array[0]);
00865 j3array[1]=((IkReal(1.79592200295782))+(x198));
00866 sj3array[1]=IKsin(j3array[1]);
00867 cj3array[1]=IKcos(j3array[1]);
00868 if( j3array[0] > IKPI )
00869 {
00870     j3array[0]-=IK2PI;
00871 }
00872 else if( j3array[0] < -IKPI )
00873 {    j3array[0]+=IK2PI;
00874 }
00875 j3valid[0] = true;
00876 if( j3array[1] > IKPI )
00877 {
00878     j3array[1]-=IK2PI;
00879 }
00880 else if( j3array[1] < -IKPI )
00881 {    j3array[1]+=IK2PI;
00882 }
00883 j3valid[1] = true;
00884 for(int ij3 = 0; ij3 < 2; ++ij3)
00885 {
00886 if( !j3valid[ij3] )
00887 {
00888     continue;
00889 }
00890 _ij3[0] = ij3; _ij3[1] = -1;
00891 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00892 {
00893 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00894 {
00895     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00896 }
00897 }
00898 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00899 {
00900 IkReal evalcond[1];
00901 IkReal x199=((IkReal(2.00000000000000))*(sj0));
00902 IkReal x200=((px)*(py));
00903 IkReal x201=((r00)*(sj0));
00904 IkReal x202=((cj0)*(r01));
00905 IkReal x203=((py)*(r00));
00906 IkReal x204=((IkReal(2.00000000000000))*(cj0));
00907 IkReal x205=((px)*(r01));
00908 IkReal x206=((IkReal(0.600000000000000))*(cj1));
00909 IkReal x207=((py)*(r02));
00910 IkReal x208=((IkReal(0.600000000000000))*(sj1));
00911 IkReal x209=((IkReal(0.0450000000000000))*(sj1));
00912 IkReal x210=((px)*(r02));
00913 evalcond[0]=((IkReal(0.119281250000000))+(((x203)*(x208)))+(((pp)*(x202)))+(((r01)*(x199)*(x200)))+(((IkReal(-1.00000000000000))*(pp)*(x201)))+(((r00)*(x199)*((px)*(px))))+(((IkReal(0.0956250000000000))*(x202)))+(((IkReal(-1.00000000000000))*(r00)*(x200)*(x204)))+(((IkReal(-2.00000000000000))*(x202)*((py)*(py))))+(((IkReal(-1.00000000000000))*(pz)*(x204)*(x207)))+(((IkReal(-1.00000000000000))*(pz)*(x202)*(x206)))+(((IkReal(-0.0956250000000000))*(x201)))+(((IkReal(-1.00000000000000))*(sj0)*(x206)*(x210)))+(((pz)*(x201)*(x206)))+(((x202)*(x209)))+(((IkReal(0.150000000000000))*(x203)))+(((pz)*(x199)*(x210)))+(((IkReal(-1.00000000000000))*(x201)*(x209)))+(((IkReal(0.0120000000000000))*(IKsin(j3))))+(((IkReal(0.0524000000000000))*(IKcos(j3))))+(((IkReal(-0.150000000000000))*(x205)))+(((IkReal(-1.00000000000000))*(x205)*(x208)))+(((cj0)*(x206)*(x207))));
00914 if( IKabs(evalcond[0]) > 0.000001  )
00915 {
00916 continue;
00917 }
00918 }
00919 
00920 {
00921 IkReal dummyeval[1];
00922 IkReal gconst10;
00923 gconst10=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
00924 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
00925 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00926 {
00927 {
00928 IkReal dummyeval[1];
00929 IkReal gconst11;
00930 gconst11=IKsign(((IkReal(-0.112881250000000))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(-0.0524000000000000))*(cj3)))));
00931 dummyeval[0]=((IkReal(-17.6376953125000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.18750000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
00932 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00933 {
00934 continue;
00935 
00936 } else
00937 {
00938 {
00939 IkReal j2array[1], cj2array[1], sj2array[1];
00940 bool j2valid[1]={false};
00941 _nj2 = 1;
00942 IkReal x211=((pz)*(r01));
00943 IkReal x212=((py)*(r02));
00944 IkReal x213=((cj1)*(r01));
00945 IkReal x214=((IkReal(0.00600000000000000))*(cj0));
00946 IkReal x215=((IkReal(0.0750000000000000))*(sj1));
00947 IkReal x216=((py)*(sj0));
00948 IkReal x217=((cj1)*(pz));
00949 IkReal x218=((r00)*(sj0));
00950 IkReal x219=((px)*(sj3));
00951 IkReal x220=((IkReal(0.0800000000000000))*(sj3));
00952 IkReal x221=((IkReal(0.0800000000000000))*(cj3));
00953 IkReal x222=((IkReal(0.00600000000000000))*(sj3));
00954 IkReal x223=((IkReal(0.00600000000000000))*(cj3));
00955 IkReal x224=((IkReal(0.327500000000000))*(sj1));
00956 IkReal x225=((IkReal(0.0800000000000000))*(cj0)*(sj1));
00957 IkReal x226=((cj0)*(x224));
00958 IkReal x227=((sj1)*(x221));
00959 IkReal x228=((px)*(r02)*(sj0));
00960 IkReal x229=((cj1)*(py)*(r00));
00961 IkReal x230=((IkReal(0.0800000000000000))*(sj1)*(x228));
00962 if( IKabs(((gconst11)*(((IkReal(0.0982500000000000))+(((IkReal(0.00562500000000000))*(cj0)*(x213)))+(((x220)*(x229)))+(((IkReal(-1.00000000000000))*(cj1)*(x218)*(x222)))+(((IkReal(-1.00000000000000))*(cj0)*(x212)*(x215)))+(((cj0)*(sj1)*(x211)*(x220)))+(((sj3)*(x213)*(x214)))+(((IkReal(0.0750000000000000))*(x229)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x227)))+(((IkReal(0.0245625000000000))*(sj1)))+(((IkReal(-0.327500000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x217)*(x221)))+(((IkReal(0.0800000000000000))*(r02)*(sj0)*(sj1)*(x219)))+(((IkReal(-0.00562500000000000))*(cj1)*(x218)))+(((IkReal(-0.0750000000000000))*(px)*(x213)))+(((IkReal(-1.00000000000000))*(pz)*(sj1)*(x218)*(x220)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x212)*(x220)))+(((x215)*(x228)))+(((IkReal(-1.00000000000000))*(x216)*(x224)))+(((IkReal(-1.00000000000000))*(x216)*(x227)))+(((IkReal(-1.00000000000000))*(pz)*(x215)*(x218)))+(((IkReal(-1.00000000000000))*(px)*(x226)))+(((cj0)*(x211)*(x215)))+(((sj1)*(x223)))+(((IkReal(0.0240000000000000))*(cj3)))+(((IkReal(-0.0800000000000000))*(x213)*(x219))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst11)*(((IkReal(0.0225000000000000))+(((cj1)*(x218)*(x223)))+(((IkReal(-1.00000000000000))*(x221)*(x229)))+(((IkReal(-0.0245625000000000))*(cj0)*(x213)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x211)*(x226)))+(((IkReal(-0.0750000000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x217)*(x220)))+(((IkReal(-1.00000000000000))*(x224)*(x228)))+(((pz)*(x218)*(x227)))+(((IkReal(-1.00000000000000))*(cj0)*(x211)*(x227)))+(((IkReal(-1.00000000000000))*(x219)*(x225)))+(((IkReal(-0.327500000000000))*(x229)))+(((IkReal(0.327500000000000))*(px)*(x213)))+(((IkReal(-1.00000000000000))*(x215)*(x216)))+(((IkReal(-1.00000000000000))*(sj1)*(x216)*(x220)))+(((IkReal(-1.00000000000000))*(x227)*(x228)))+(((px)*(x213)*(x221)))+(((IkReal(0.0245625000000000))*(cj1)*(x218)))+(((x212)*(x226)))+(((sj1)*(x222)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x215)))+(((IkReal(-1.00000000000000))*(cj3)*(x213)*(x214)))+(((pz)*(x218)*(x224)))+(((IkReal(0.0240000000000000))*(sj3)))+(((cj0)*(x212)*(x227))))))) < IKFAST_ATAN2_MAGTHRESH )
00963     continue;
00964 j2array[0]=IKatan2(((gconst11)*(((IkReal(0.0982500000000000))+(((IkReal(0.00562500000000000))*(cj0)*(x213)))+(((x220)*(x229)))+(((IkReal(-1.00000000000000))*(cj1)*(x218)*(x222)))+(((IkReal(-1.00000000000000))*(cj0)*(x212)*(x215)))+(((cj0)*(sj1)*(x211)*(x220)))+(((sj3)*(x213)*(x214)))+(((IkReal(0.0750000000000000))*(x229)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x227)))+(((IkReal(0.0245625000000000))*(sj1)))+(((IkReal(-0.327500000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x217)*(x221)))+(((IkReal(0.0800000000000000))*(r02)*(sj0)*(sj1)*(x219)))+(((IkReal(-0.00562500000000000))*(cj1)*(x218)))+(((IkReal(-0.0750000000000000))*(px)*(x213)))+(((IkReal(-1.00000000000000))*(pz)*(sj1)*(x218)*(x220)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x212)*(x220)))+(((x215)*(x228)))+(((IkReal(-1.00000000000000))*(x216)*(x224)))+(((IkReal(-1.00000000000000))*(x216)*(x227)))+(((IkReal(-1.00000000000000))*(pz)*(x215)*(x218)))+(((IkReal(-1.00000000000000))*(px)*(x226)))+(((cj0)*(x211)*(x215)))+(((sj1)*(x223)))+(((IkReal(0.0240000000000000))*(cj3)))+(((IkReal(-0.0800000000000000))*(x213)*(x219)))))), ((gconst11)*(((IkReal(0.0225000000000000))+(((cj1)*(x218)*(x223)))+(((IkReal(-1.00000000000000))*(x221)*(x229)))+(((IkReal(-0.0245625000000000))*(cj0)*(x213)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x211)*(x226)))+(((IkReal(-0.0750000000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x217)*(x220)))+(((IkReal(-1.00000000000000))*(x224)*(x228)))+(((pz)*(x218)*(x227)))+(((IkReal(-1.00000000000000))*(cj0)*(x211)*(x227)))+(((IkReal(-1.00000000000000))*(x219)*(x225)))+(((IkReal(-0.327500000000000))*(x229)))+(((IkReal(0.327500000000000))*(px)*(x213)))+(((IkReal(-1.00000000000000))*(x215)*(x216)))+(((IkReal(-1.00000000000000))*(sj1)*(x216)*(x220)))+(((IkReal(-1.00000000000000))*(x227)*(x228)))+(((px)*(x213)*(x221)))+(((IkReal(0.0245625000000000))*(cj1)*(x218)))+(((x212)*(x226)))+(((sj1)*(x222)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x215)))+(((IkReal(-1.00000000000000))*(cj3)*(x213)*(x214)))+(((pz)*(x218)*(x224)))+(((IkReal(0.0240000000000000))*(sj3)))+(((cj0)*(x212)*(x227)))))));
00965 sj2array[0]=IKsin(j2array[0]);
00966 cj2array[0]=IKcos(j2array[0]);
00967 if( j2array[0] > IKPI )
00968 {
00969     j2array[0]-=IK2PI;
00970 }
00971 else if( j2array[0] < -IKPI )
00972 {    j2array[0]+=IK2PI;
00973 }
00974 j2valid[0] = true;
00975 for(int ij2 = 0; ij2 < 1; ++ij2)
00976 {
00977 if( !j2valid[ij2] )
00978 {
00979     continue;
00980 }
00981 _ij2[0] = ij2; _ij2[1] = -1;
00982 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00983 {
00984 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00985 {
00986     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00987 }
00988 }
00989 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00990 {
00991 IkReal evalcond[4];
00992 IkReal x231=IKcos(j2);
00993 IkReal x232=IKsin(j2);
00994 IkReal x233=((IkReal(0.0800000000000000))*(sj3));
00995 IkReal x234=((cj0)*(r01));
00996 IkReal x235=((IkReal(1.00000000000000))*(px));
00997 IkReal x236=((py)*(sj1));
00998 IkReal x237=((cj0)*(r02));
00999 IkReal x238=((IkReal(0.0750000000000000))*(cj1));
01000 IkReal x239=((r02)*(sj0));
01001 IkReal x240=((IkReal(0.0750000000000000))*(sj1));
01002 IkReal x241=((cj1)*(pz));
01003 IkReal x242=((r00)*(sj0));
01004 IkReal x243=((IkReal(0.0800000000000000))*(cj3));
01005 IkReal x244=((pz)*(sj1));
01006 IkReal x245=((IkReal(1.00000000000000))*(sj0));
01007 IkReal x246=((cj1)*(py));
01008 IkReal x247=((IkReal(0.327500000000000))*(x231));
01009 IkReal x248=((IkReal(0.0750000000000000))*(x232));
01010 IkReal x249=((IkReal(0.0750000000000000))*(x231));
01011 IkReal x250=((IkReal(0.327500000000000))*(x232));
01012 IkReal x251=((sj1)*(x242));
01013 IkReal x252=((x231)*(x243));
01014 IkReal x253=((x232)*(x233));
01015 IkReal x254=((x231)*(x233));
01016 IkReal x255=((x232)*(x243));
01017 IkReal x256=((x253)+(x248));
01018 IkReal x257=((x252)+(x247));
01019 IkReal x258=((x254)+(x255)+(x250)+(x249));
01020 evalcond[0]=((((IkReal(-1.00000000000000))*(x256)))+(((IkReal(-1.00000000000000))*(x245)*(x246)))+(x238)+(x257)+(x244)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x235))));
01021 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x236)*(x245)))+(x258)+(x240)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x235)))+(((IkReal(-1.00000000000000))*(x241))));
01022 evalcond[2]=((((x242)*(x244)))+(((IkReal(-1.00000000000000))*(x256)))+(x257)+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(sj1)*(x235)*(x239)))+(((x238)*(x242)))+(((IkReal(-1.00000000000000))*(x234)*(x238)))+(((x236)*(x237)))+(((IkReal(-1.00000000000000))*(r00)*(x246)))+(((IkReal(-1.00000000000000))*(x234)*(x244))));
01023 evalcond[3]=((((x237)*(x246)))+(((IkReal(-1.00000000000000))*(cj1)*(x235)*(x239)))+(((IkReal(-1.00000000000000))*(x258)))+(((IkReal(-0.300000000000000))*(x242)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x235)))+(((x241)*(x242)))+(((x234)*(x240)))+(((IkReal(-1.00000000000000))*(x234)*(x241)))+(((IkReal(0.300000000000000))*(x234)))+(((IkReal(-1.00000000000000))*(x240)*(x242)))+(((r00)*(x236))));
01024 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01025 {
01026 continue;
01027 }
01028 }
01029 
01030 {
01031 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01032 vinfos[0].jointtype = 1;
01033 vinfos[0].foffset = j0;
01034 vinfos[0].indices[0] = _ij0[0];
01035 vinfos[0].indices[1] = _ij0[1];
01036 vinfos[0].maxsolutions = _nj0;
01037 vinfos[1].jointtype = 1;
01038 vinfos[1].foffset = j1;
01039 vinfos[1].indices[0] = _ij1[0];
01040 vinfos[1].indices[1] = _ij1[1];
01041 vinfos[1].maxsolutions = _nj1;
01042 vinfos[2].jointtype = 1;
01043 vinfos[2].foffset = j2;
01044 vinfos[2].indices[0] = _ij2[0];
01045 vinfos[2].indices[1] = _ij2[1];
01046 vinfos[2].maxsolutions = _nj2;
01047 vinfos[3].jointtype = 1;
01048 vinfos[3].foffset = j3;
01049 vinfos[3].indices[0] = _ij3[0];
01050 vinfos[3].indices[1] = _ij3[1];
01051 vinfos[3].maxsolutions = _nj3;
01052 vinfos[4].jointtype = 1;
01053 vinfos[4].foffset = j4;
01054 vinfos[4].indices[0] = _ij4[0];
01055 vinfos[4].indices[1] = _ij4[1];
01056 vinfos[4].maxsolutions = _nj4;
01057 std::vector<int> vfree(0);
01058 solutions.AddSolution(vinfos,vfree);
01059 }
01060 }
01061 }
01062 
01063 }
01064 
01065 }
01066 
01067 } else
01068 {
01069 {
01070 IkReal j2array[1], cj2array[1], sj2array[1];
01071 bool j2valid[1]={false};
01072 _nj2 = 1;
01073 IkReal x259=((IkReal(0.0800000000000000))*(cj1));
01074 IkReal x260=((cj0)*(px));
01075 IkReal x261=((py)*(sj0));
01076 IkReal x262=((IkReal(0.0750000000000000))*(cj1));
01077 IkReal x263=((IkReal(0.327500000000000))*(cj1));
01078 IkReal x264=((IkReal(0.327500000000000))*(sj1));
01079 IkReal x265=((IkReal(0.0750000000000000))*(sj1));
01080 IkReal x266=((IkReal(0.00600000000000000))*(sj1));
01081 IkReal x267=((IkReal(0.00600000000000000))*(cj1));
01082 IkReal x268=((IkReal(0.0800000000000000))*(sj1)*(sj3));
01083 IkReal x269=((IkReal(0.0800000000000000))*(cj3)*(sj1));
01084 if( IKabs(((gconst10)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(x261)*(x262)))+(((pz)*(x263)))+(((pz)*(x268)))+(((cj3)*(pz)*(x259)))+(((IkReal(-1.00000000000000))*(sj3)*(x259)*(x261)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x260)*(x262)))+(((x261)*(x269)))+(((IkReal(-1.00000000000000))*(cj3)*(x266)))+(((sj3)*(x267)))+(((x261)*(x264)))+(((IkReal(-1.00000000000000))*(sj3)*(x259)*(x260)))+(((x260)*(x264)))+(((x260)*(x269)))+(((IkReal(0.00562500000000000))*(cj1)))+(((pz)*(x265))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x259)))+(((cj3)*(x259)*(x260)))+(((x261)*(x265)))+(((x261)*(x263)))+(((x260)*(x265)))+(((IkReal(-1.00000000000000))*(pz)*(x269)))+(((IkReal(-1.00000000000000))*(sj3)*(x266)))+(((x261)*(x268)))+(((x260)*(x263)))+(((IkReal(-1.00000000000000))*(pz)*(x264)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((cj3)*(x259)*(x261)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(cj3)*(x267)))+(((x260)*(x268)))+(((pz)*(x262))))))) < IKFAST_ATAN2_MAGTHRESH )
01085     continue;
01086 j2array[0]=IKatan2(((gconst10)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(x261)*(x262)))+(((pz)*(x263)))+(((pz)*(x268)))+(((cj3)*(pz)*(x259)))+(((IkReal(-1.00000000000000))*(sj3)*(x259)*(x261)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x260)*(x262)))+(((x261)*(x269)))+(((IkReal(-1.00000000000000))*(cj3)*(x266)))+(((sj3)*(x267)))+(((x261)*(x264)))+(((IkReal(-1.00000000000000))*(sj3)*(x259)*(x260)))+(((x260)*(x264)))+(((x260)*(x269)))+(((IkReal(0.00562500000000000))*(cj1)))+(((pz)*(x265)))))), ((gconst10)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x259)))+(((cj3)*(x259)*(x260)))+(((x261)*(x265)))+(((x261)*(x263)))+(((x260)*(x265)))+(((IkReal(-1.00000000000000))*(pz)*(x269)))+(((IkReal(-1.00000000000000))*(sj3)*(x266)))+(((x261)*(x268)))+(((x260)*(x263)))+(((IkReal(-1.00000000000000))*(pz)*(x264)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((cj3)*(x259)*(x261)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(cj3)*(x267)))+(((x260)*(x268)))+(((pz)*(x262)))))));
01087 sj2array[0]=IKsin(j2array[0]);
01088 cj2array[0]=IKcos(j2array[0]);
01089 if( j2array[0] > IKPI )
01090 {
01091     j2array[0]-=IK2PI;
01092 }
01093 else if( j2array[0] < -IKPI )
01094 {    j2array[0]+=IK2PI;
01095 }
01096 j2valid[0] = true;
01097 for(int ij2 = 0; ij2 < 1; ++ij2)
01098 {
01099 if( !j2valid[ij2] )
01100 {
01101     continue;
01102 }
01103 _ij2[0] = ij2; _ij2[1] = -1;
01104 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01105 {
01106 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01107 {
01108     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01109 }
01110 }
01111 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01112 {
01113 IkReal evalcond[4];
01114 IkReal x270=IKcos(j2);
01115 IkReal x271=IKsin(j2);
01116 IkReal x272=((IkReal(0.0800000000000000))*(sj3));
01117 IkReal x273=((cj0)*(r01));
01118 IkReal x274=((IkReal(1.00000000000000))*(px));
01119 IkReal x275=((py)*(sj1));
01120 IkReal x276=((cj0)*(r02));
01121 IkReal x277=((IkReal(0.0750000000000000))*(cj1));
01122 IkReal x278=((r02)*(sj0));
01123 IkReal x279=((IkReal(0.0750000000000000))*(sj1));
01124 IkReal x280=((cj1)*(pz));
01125 IkReal x281=((r00)*(sj0));
01126 IkReal x282=((IkReal(0.0800000000000000))*(cj3));
01127 IkReal x283=((pz)*(sj1));
01128 IkReal x284=((IkReal(1.00000000000000))*(sj0));
01129 IkReal x285=((cj1)*(py));
01130 IkReal x286=((IkReal(0.327500000000000))*(x270));
01131 IkReal x287=((IkReal(0.0750000000000000))*(x271));
01132 IkReal x288=((IkReal(0.0750000000000000))*(x270));
01133 IkReal x289=((IkReal(0.327500000000000))*(x271));
01134 IkReal x290=((sj1)*(x281));
01135 IkReal x291=((x270)*(x282));
01136 IkReal x292=((x271)*(x272));
01137 IkReal x293=((x270)*(x272));
01138 IkReal x294=((x271)*(x282));
01139 IkReal x295=((x287)+(x292));
01140 IkReal x296=((x286)+(x291));
01141 IkReal x297=((x289)+(x288)+(x293)+(x294));
01142 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x274)))+(x283)+(x296)+(((IkReal(-1.00000000000000))*(x295)))+(x277)+(((IkReal(-1.00000000000000))*(x284)*(x285))));
01143 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x280)))+(((IkReal(-1.00000000000000))*(x275)*(x284)))+(x297)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x274)))+(x279));
01144 evalcond[2]=((((x281)*(x283)))+(((IkReal(-1.00000000000000))*(sj1)*(x274)*(x278)))+(((IkReal(-1.00000000000000))*(x273)*(x277)))+(x296)+(((cj1)*(px)*(r01)))+(((x275)*(x276)))+(((IkReal(-1.00000000000000))*(x295)))+(((IkReal(-1.00000000000000))*(x273)*(x283)))+(((x277)*(x281)))+(((IkReal(-1.00000000000000))*(r00)*(x285))));
01145 evalcond[3]=((((x280)*(x281)))+(((IkReal(-1.00000000000000))*(x279)*(x281)))+(((r00)*(x275)))+(((x273)*(x279)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x274)))+(((IkReal(0.300000000000000))*(x273)))+(((IkReal(-1.00000000000000))*(x297)))+(((IkReal(-0.300000000000000))*(x281)))+(((x276)*(x285)))+(((IkReal(-1.00000000000000))*(x273)*(x280)))+(((IkReal(-1.00000000000000))*(cj1)*(x274)*(x278))));
01146 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01147 {
01148 continue;
01149 }
01150 }
01151 
01152 {
01153 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01154 vinfos[0].jointtype = 1;
01155 vinfos[0].foffset = j0;
01156 vinfos[0].indices[0] = _ij0[0];
01157 vinfos[0].indices[1] = _ij0[1];
01158 vinfos[0].maxsolutions = _nj0;
01159 vinfos[1].jointtype = 1;
01160 vinfos[1].foffset = j1;
01161 vinfos[1].indices[0] = _ij1[0];
01162 vinfos[1].indices[1] = _ij1[1];
01163 vinfos[1].maxsolutions = _nj1;
01164 vinfos[2].jointtype = 1;
01165 vinfos[2].foffset = j2;
01166 vinfos[2].indices[0] = _ij2[0];
01167 vinfos[2].indices[1] = _ij2[1];
01168 vinfos[2].maxsolutions = _nj2;
01169 vinfos[3].jointtype = 1;
01170 vinfos[3].foffset = j3;
01171 vinfos[3].indices[0] = _ij3[0];
01172 vinfos[3].indices[1] = _ij3[1];
01173 vinfos[3].maxsolutions = _nj3;
01174 vinfos[4].jointtype = 1;
01175 vinfos[4].foffset = j4;
01176 vinfos[4].indices[0] = _ij4[0];
01177 vinfos[4].indices[1] = _ij4[1];
01178 vinfos[4].maxsolutions = _nj4;
01179 std::vector<int> vfree(0);
01180 solutions.AddSolution(vinfos,vfree);
01181 }
01182 }
01183 }
01184 
01185 }
01186 
01187 }
01188 }
01189 }
01190 
01191 } else
01192 {
01193 if( 1 )
01194 {
01195 continue;
01196 
01197 } else
01198 {
01199 }
01200 }
01201 }
01202 }
01203 
01204 } else
01205 {
01206 {
01207 IkReal j3array[1], cj3array[1], sj3array[1];
01208 bool j3valid[1]={false};
01209 _nj3 = 1;
01210 IkReal x298=((px)*(r00));
01211 IkReal x299=((cj0)*(r00));
01212 IkReal x300=((IkReal(15720.0000000000))*(cj1));
01213 IkReal x301=((IkReal(3600.00000000000))*(sj1));
01214 IkReal x302=((r01)*(sj0));
01215 IkReal x303=((IkReal(3600.00000000000))*(cj1));
01216 IkReal x304=((py)*(r01));
01217 IkReal x305=((pz)*(r02));
01218 IkReal x306=((IkReal(12000.0000000000))*(pz));
01219 IkReal x307=((IkReal(52400.0000000000))*(r02));
01220 IkReal x308=((cj0)*(px));
01221 IkReal x309=((py)*(sj0));
01222 IkReal x310=((IkReal(52400.0000000000))*(pz));
01223 IkReal x311=((IkReal(15720.0000000000))*(sj1));
01224 IkReal x312=((IkReal(12000.0000000000))*(r02));
01225 IkReal x313=((sj1)*(x302));
01226 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(x302)*(x306)))+(((IkReal(-900.000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x299)*(x306)))+(((x299)*(x303)))+(((IkReal(-52400.0000000000))*(x305)))+(((IkReal(-1.00000000000000))*(r02)*(x301)))+(((x308)*(x312)))+(((x299)*(x311)))+(((x302)*(x303)))+(((x309)*(x312)))+(((IkReal(3930.00000000000))*(x302)))+(((x302)*(x311)))+(((IkReal(-52400.0000000000))*(x304)))+(((r02)*(x300)))+(((IkReal(-960.000000000000))*(cj4)))+(((IkReal(3930.00000000000))*(x299)))+(((IkReal(-52400.0000000000))*(x298))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(x299)*(x301)))+(((IkReal(-900.000000000000))*(x302)))+(((IkReal(-1.00000000000000))*(r02)*(x311)))+(((IkReal(12000.0000000000))*(x304)))+(((IkReal(-1.00000000000000))*(r02)*(x303)))+(((IkReal(-3930.00000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x302)*(x310)))+(((IkReal(12000.0000000000))*(x305)))+(((IkReal(-1.00000000000000))*(x299)*(x310)))+(((x307)*(x309)))+(((IkReal(12000.0000000000))*(x298)))+(((x300)*(x302)))+(((x299)*(x300)))+(((x307)*(x308)))+(((IkReal(-900.000000000000))*(x299)))+(((IkReal(-4192.00000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x301)*(x302))))))) < IKFAST_ATAN2_MAGTHRESH )
01227     continue;
01228 j3array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(x302)*(x306)))+(((IkReal(-900.000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x299)*(x306)))+(((x299)*(x303)))+(((IkReal(-52400.0000000000))*(x305)))+(((IkReal(-1.00000000000000))*(r02)*(x301)))+(((x308)*(x312)))+(((x299)*(x311)))+(((x302)*(x303)))+(((x309)*(x312)))+(((IkReal(3930.00000000000))*(x302)))+(((x302)*(x311)))+(((IkReal(-52400.0000000000))*(x304)))+(((r02)*(x300)))+(((IkReal(-960.000000000000))*(cj4)))+(((IkReal(3930.00000000000))*(x299)))+(((IkReal(-52400.0000000000))*(x298)))))), ((gconst1)*(((((IkReal(-1.00000000000000))*(x299)*(x301)))+(((IkReal(-900.000000000000))*(x302)))+(((IkReal(-1.00000000000000))*(r02)*(x311)))+(((IkReal(12000.0000000000))*(x304)))+(((IkReal(-1.00000000000000))*(r02)*(x303)))+(((IkReal(-3930.00000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x302)*(x310)))+(((IkReal(12000.0000000000))*(x305)))+(((IkReal(-1.00000000000000))*(x299)*(x310)))+(((x307)*(x309)))+(((IkReal(12000.0000000000))*(x298)))+(((x300)*(x302)))+(((x299)*(x300)))+(((x307)*(x308)))+(((IkReal(-900.000000000000))*(x299)))+(((IkReal(-4192.00000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x301)*(x302)))))));
01229 sj3array[0]=IKsin(j3array[0]);
01230 cj3array[0]=IKcos(j3array[0]);
01231 if( j3array[0] > IKPI )
01232 {
01233     j3array[0]-=IK2PI;
01234 }
01235 else if( j3array[0] < -IKPI )
01236 {    j3array[0]+=IK2PI;
01237 }
01238 j3valid[0] = true;
01239 for(int ij3 = 0; ij3 < 1; ++ij3)
01240 {
01241 if( !j3valid[ij3] )
01242 {
01243     continue;
01244 }
01245 _ij3[0] = ij3; _ij3[1] = -1;
01246 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01247 {
01248 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01249 {
01250     j3valid[iij3]=false; _ij3[1] = iij3; break; 
01251 }
01252 }
01253 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01254 {
01255 IkReal evalcond[4];
01256 IkReal x314=IKcos(j3);
01257 IkReal x315=IKsin(j3);
01258 IkReal x316=((r01)*(sj0));
01259 IkReal x317=((IkReal(0.300000000000000))*(r02));
01260 IkReal x318=((r00)*(sj0));
01261 IkReal x319=((py)*(sj0));
01262 IkReal x320=((IkReal(0.600000000000000))*(cj1));
01263 IkReal x321=((IkReal(0.150000000000000))*(px));
01264 IkReal x322=((IkReal(1.00000000000000))*(pz));
01265 IkReal x323=((py)*(r00));
01266 IkReal x324=((IkReal(0.300000000000000))*(cj1));
01267 IkReal x325=((IkReal(1.00000000000000))*(pp));
01268 IkReal x326=((cj0)*(r00));
01269 IkReal x327=((IkReal(0.0450000000000000))*(sj1));
01270 IkReal x328=((IkReal(0.600000000000000))*(sj1));
01271 IkReal x329=((cj0)*(r01));
01272 IkReal x330=((IkReal(2.00000000000000))*(pz));
01273 IkReal x331=((cj0)*(px));
01274 IkReal x332=((IkReal(0.300000000000000))*(sj1));
01275 IkReal x333=((IkReal(2.00000000000000))*(px)*(py));
01276 IkReal x334=((IkReal(0.0120000000000000))*(x315));
01277 IkReal x335=((cj4)*(x315));
01278 IkReal x336=((IkReal(0.0524000000000000))*(x314));
01279 IkReal x337=((cj4)*(x314));
01280 IkReal x338=((cj0)*(py)*(r02));
01281 IkReal x339=((px)*(r02)*(sj0));
01282 evalcond[0]=((IkReal(0.0236562500000000))+(((x319)*(x328)))+(((IkReal(-1.00000000000000))*(x325)))+(((IkReal(-1.00000000000000))*(x327)))+(((x328)*(x331)))+(((cj0)*(x321)))+(x336)+(x334)+(((pz)*(x320)))+(((IkReal(0.150000000000000))*(x319))));
01283 evalcond[1]=((((IkReal(-1.00000000000000))*(py)*(r01)))+(((x326)*(x332)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((IkReal(0.0750000000000000))*(x316)))+(((IkReal(0.0750000000000000))*(x326)))+(((cj1)*(x317)))+(((IkReal(0.0750000000000000))*(x337)))+(((IkReal(-0.327500000000000))*(x335)))+(((x316)*(x332)))+(((IkReal(-1.00000000000000))*(r02)*(x322))));
01284 evalcond[2]=((((IkReal(-0.0800000000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x316)*(x322)))+(((r02)*(x319)))+(((x324)*(x326)))+(((x316)*(x324)))+(((IkReal(-0.0750000000000000))*(x335)))+(((IkReal(-1.00000000000000))*(x322)*(x326)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x317)))+(((r02)*(x331)))+(((IkReal(-0.327500000000000))*(x337))));
01285 evalcond[3]=((((x330)*(x339)))+(((IkReal(-0.119281250000000))*(sj4)))+(((IkReal(-1.00000000000000))*(sj4)*(x334)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x328)))+(((IkReal(-2.00000000000000))*(x329)*((py)*(py))))+(((IkReal(-1.00000000000000))*(sj4)*(x336)))+(((x316)*(x333)))+(((IkReal(-1.00000000000000))*(pz)*(x320)*(x329)))+(((IkReal(-1.00000000000000))*(r01)*(x321)))+(((x327)*(x329)))+(((x320)*(x338)))+(((IkReal(-1.00000000000000))*(x318)*(x327)))+(((pp)*(x329)))+(((IkReal(0.150000000000000))*(x323)))+(((IkReal(-0.0956250000000000))*(x318)))+(((IkReal(-2.00000000000000))*(x323)*(x331)))+(((IkReal(-1.00000000000000))*(x330)*(x338)))+(((IkReal(-1.00000000000000))*(x320)*(x339)))+(((pz)*(x318)*(x320)))+(((IkReal(0.0956250000000000))*(x329)))+(((IkReal(-1.00000000000000))*(x318)*(x325)))+(((IkReal(2.00000000000000))*(x318)*((px)*(px))))+(((x323)*(x328))));
01286 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01287 {
01288 continue;
01289 }
01290 }
01291 
01292 {
01293 IkReal dummyeval[1];
01294 IkReal gconst2;
01295 gconst2=IKsign(((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3))))));
01296 dummyeval[0]=((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3)))));
01297 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01298 {
01299 {
01300 IkReal dummyeval[1];
01301 IkReal gconst3;
01302 IkReal x340=((IkReal(0.0800000000000000))*(cj4));
01303 gconst3=IKsign(((((x340)*((sj3)*(sj3))))+(((x340)*((cj3)*(cj3))))+(((IkReal(0.0750000000000000))*(cj4)*(sj3)))+(((IkReal(0.327500000000000))*(cj3)*(cj4)))));
01304 IkReal x341=((IkReal(1.06666666666667))*(cj4));
01305 dummyeval[0]=((((IkReal(4.36666666666667))*(cj3)*(cj4)))+(((x341)*((sj3)*(sj3))))+(((cj4)*(sj3)))+(((x341)*((cj3)*(cj3)))));
01306 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01307 {
01308 {
01309 IkReal evalcond[11];
01310 IkReal x342=((IkReal(0.0524000000000000))*(cj3));
01311 IkReal x343=((IkReal(0.0120000000000000))*(sj3));
01312 IkReal x344=(py)*(py);
01313 IkReal x345=(px)*(px);
01314 IkReal x346=(pz)*(pz);
01315 IkReal x347=((r01)*(sj0));
01316 IkReal x348=((py)*(r00));
01317 IkReal x349=((pz)*(sj1));
01318 IkReal x350=((py)*(r01));
01319 IkReal x351=((px)*(sj0));
01320 IkReal x352=((IkReal(0.600000000000000))*(r02));
01321 IkReal x353=((IkReal(0.150000000000000))*(cj1));
01322 IkReal x354=((cj0)*(sj1));
01323 IkReal x355=((IkReal(0.150000000000000))*(px));
01324 IkReal x356=((IkReal(2.00000000000000))*(cj1));
01325 IkReal x357=((cj0)*(r01));
01326 IkReal x358=((r02)*(sj1));
01327 IkReal x359=((px)*(r00));
01328 IkReal x360=((IkReal(0.300000000000000))*(r00));
01329 IkReal x361=((IkReal(1.00000000000000))*(pz));
01330 IkReal x362=((r00)*(sj1));
01331 IkReal x363=((cj0)*(r00));
01332 IkReal x364=((cj0)*(cj1));
01333 IkReal x365=((IkReal(1.00000000000000))*(sj1));
01334 IkReal x366=((IkReal(0.0956250000000000))*(r00));
01335 IkReal x367=((IkReal(0.600000000000000))*(pz));
01336 IkReal x368=((IkReal(0.600000000000000))*(sj1));
01337 IkReal x369=((IkReal(2.00000000000000))*(px));
01338 IkReal x370=((IkReal(2.00000000000000))*(sj1));
01339 IkReal x371=((IkReal(0.150000000000000))*(sj1));
01340 IkReal x372=((cj1)*(r02));
01341 IkReal x373=((cj0)*(px));
01342 IkReal x374=((IkReal(0.0843750000000000))*(cj1));
01343 IkReal x375=((py)*(sj0));
01344 IkReal x376=((pz)*(r02));
01345 IkReal x377=((IkReal(1.00000000000000))*(cj1));
01346 IkReal x378=((cj0)*(py));
01347 IkReal x379=((r00)*(sj0));
01348 IkReal x380=((r02)*(x375));
01349 IkReal x381=((pp)*(x377));
01350 IkReal x382=((IkReal(1.00000000000000))*(pp)*(r00));
01351 IkReal x383=((x342)+(x343));
01352 IkReal x384=((IkReal(2.00000000000000))*(r00)*(x345));
01353 IkReal x385=((cj0)*(x369)*(x376));
01354 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
01355 evalcond[1]=((x378)+(((IkReal(-1.00000000000000))*(x351))));
01356 evalcond[2]=((IkReal(-1.00000000000000))+(x357)+(((IkReal(-1.00000000000000))*(x379))));
01357 evalcond[3]=((((IkReal(-1.00000000000000))*(x363)*(x377)))+(x358)+(((IkReal(-1.00000000000000))*(x347)*(x377))));
01358 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x354)))+(((IkReal(-1.00000000000000))*(x372)))+(((IkReal(-1.00000000000000))*(x347)*(x365))));
01359 evalcond[5]=((IkReal(0.0236562500000000))+(x383)+(((IkReal(0.150000000000000))*(x375)))+(((cj0)*(x355)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.600000000000000))*(px)*(x354)))+(((x368)*(x375)))+(((cj1)*(x367)))+(((IkReal(-0.0450000000000000))*(sj1))));
01360 evalcond[6]=((((IkReal(0.300000000000000))*(x372)))+(((IkReal(-1.00000000000000))*(r02)*(x361)))+(((x354)*(x360)))+(((IkReal(-1.00000000000000))*(x350)))+(((IkReal(-1.00000000000000))*(x359)))+(((IkReal(0.0750000000000000))*(x363)))+(((IkReal(0.0750000000000000))*(x347)))+(((IkReal(0.300000000000000))*(sj1)*(x347))));
01361 evalcond[7]=((((r02)*(x373)))+(((IkReal(-1.00000000000000))*(x361)*(x363)))+(x380)+(((IkReal(-1.00000000000000))*(x347)*(x361)))+(((IkReal(0.300000000000000))*(cj1)*(x347)))+(((x360)*(x364)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(-0.300000000000000))*(x358))));
01362 evalcond[8]=((IkReal(-0.119281250000000))+(((IkReal(2.00000000000000))*(x351)*(x376)))+(((IkReal(-2.00000000000000))*(x376)*(x378)))+(((IkReal(-1.00000000000000))*(x383)))+(((IkReal(-0.0450000000000000))*(sj0)*(x362)))+(((IkReal(-1.00000000000000))*(cj0)*(x348)*(x369)))+(((IkReal(-2.00000000000000))*(x344)*(x357)))+(((py)*(x352)*(x364)))+(((IkReal(-1.00000000000000))*(sj0)*(x366)))+(((IkReal(0.0450000000000000))*(r01)*(x354)))+(((x348)*(x368)))+(((IkReal(-1.00000000000000))*(cj1)*(x351)*(x352)))+(((IkReal(-1.00000000000000))*(cj1)*(x357)*(x367)))+(((IkReal(-1.00000000000000))*(r01)*(x355)))+(((IkReal(0.150000000000000))*(x348)))+(((IkReal(2.00000000000000))*(x345)*(x379)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x368)))+(((cj1)*(x367)*(x379)))+(((py)*(x347)*(x369)))+(((IkReal(-1.00000000000000))*(pp)*(x379)))+(((pp)*(x357)))+(((IkReal(0.0956250000000000))*(x357))));
01363 evalcond[9]=((((IkReal(2.00000000000000))*(x349)*(x380)))+(((IkReal(-1.00000000000000))*(x354)*(x382)))+(((IkReal(0.0956250000000000))*(sj1)*(x347)))+(((IkReal(-1.00000000000000))*(pp)*(x347)*(x365)))+(((IkReal(0.0843750000000000))*(x372)))+(((IkReal(-0.600000000000000))*(x359)))+(((IkReal(0.0450000000000000))*(x347)))+(((IkReal(-1.00000000000000))*(pz)*(x347)*(x353)))+(((r02)*(x353)*(x373)))+(((IkReal(-1.00000000000000))*(pz)*(x352)))+(((r02)*(x346)*(x356)))+(((IkReal(0.0450000000000000))*(x363)))+(((IkReal(-1.00000000000000))*(x350)*(x371)))+(((x348)*(x351)*(x370)))+(((IkReal(-0.150000000000000))*(r02)*(x349)))+(((IkReal(-0.600000000000000))*(x350)))+(((x344)*(x347)*(x370)))+(((x354)*(x366)))+(((IkReal(-1.00000000000000))*(pp)*(x372)))+(((IkReal(-1.00000000000000))*(x355)*(x362)))+(((x354)*(x384)))+(((pz)*(x356)*(x359)))+(((x353)*(x380)))+(((pz)*(x350)*(x356)))+(((x350)*(x354)*(x369)))+(((IkReal(-1.00000000000000))*(pz)*(x353)*(x363)))+(((cj0)*(r02)*(x349)*(x369))));
01364 evalcond[10]=((((IkReal(-1.00000000000000))*(x353)*(x359)))+(((x356)*(x375)*(x376)))+(((IkReal(-1.00000000000000))*(x363)*(x381)))+(((IkReal(-2.00000000000000))*(x349)*(x350)))+(((IkReal(-0.150000000000000))*(x358)*(x375)))+(((x363)*(x367)))+(((IkReal(-1.00000000000000))*(x353)*(x376)))+(((x345)*(x356)*(x363)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-2.00000000000000))*(x346)*(x358)))+(((IkReal(-1.00000000000000))*(x352)*(x375)))+(((IkReal(0.150000000000000))*(x347)*(x349)))+(((pp)*(x358)))+(((IkReal(0.0956250000000000))*(x358)))+(((x344)*(x347)*(x356)))+(((x356)*(x373)*(x376)))+(((x348)*(x351)*(x356)))+(((IkReal(-1.00000000000000))*(x363)*(x374)))+(((IkReal(0.150000000000000))*(x349)*(x363)))+(((IkReal(-1.00000000000000))*(x352)*(x373)))+(((IkReal(-1.00000000000000))*(x347)*(x374)))+(((x347)*(x367)))+(((IkReal(-1.00000000000000))*(r02)*(x354)*(x355)))+(((IkReal(-1.00000000000000))*(x347)*(x381)))+(((x350)*(x356)*(x373)))+(((IkReal(-1.00000000000000))*(x350)*(x353)))+(((IkReal(-2.00000000000000))*(x349)*(x359))));
01365 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  )
01366 {
01367 {
01368 IkReal dummyeval[1];
01369 IkReal gconst4;
01370 gconst4=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01371 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
01372 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01373 {
01374 {
01375 IkReal dummyeval[1];
01376 IkReal gconst5;
01377 gconst5=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01378 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
01379 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01380 {
01381 continue;
01382 
01383 } else
01384 {
01385 {
01386 IkReal j2array[1], cj2array[1], sj2array[1];
01387 bool j2valid[1]={false};
01388 _nj2 = 1;
01389 IkReal x386=((pz)*(r01));
01390 IkReal x387=((py)*(r02));
01391 IkReal x388=((cj1)*(r01));
01392 IkReal x389=((IkReal(0.00600000000000000))*(cj0));
01393 IkReal x390=((cj1)*(pz));
01394 IkReal x391=((r00)*(sj0));
01395 IkReal x392=((IkReal(0.0750000000000000))*(px));
01396 IkReal x393=((cj0)*(sj1));
01397 IkReal x394=((px)*(sj3));
01398 IkReal x395=((IkReal(0.0800000000000000))*(sj3));
01399 IkReal x396=((sj0)*(sj1));
01400 IkReal x397=((IkReal(0.327500000000000))*(px));
01401 IkReal x398=((IkReal(0.00600000000000000))*(cj1));
01402 IkReal x399=((IkReal(0.0750000000000000))*(py));
01403 IkReal x400=((IkReal(0.0800000000000000))*(cj3));
01404 IkReal x401=((pz)*(sj1));
01405 IkReal x402=((IkReal(0.00600000000000000))*(sj1));
01406 IkReal x403=((IkReal(0.0800000000000000))*(x393));
01407 IkReal x404=((sj1)*(x400));
01408 IkReal x405=((cj1)*(py)*(r00));
01409 IkReal x406=((IkReal(0.0800000000000000))*(px)*(r02)*(x396));
01410 if( IKabs(((gconst5)*(((IkReal(-0.0982500000000000))+(((IkReal(0.0800000000000000))*(r02)*(x394)*(x396)))+(((px)*(x393)*(x400)))+(((IkReal(-0.0800000000000000))*(x388)*(x394)))+(((IkReal(-0.0750000000000000))*(x391)*(x401)))+(((sj3)*(x388)*(x389)))+(((IkReal(-1.00000000000000))*(x388)*(x392)))+(((x393)*(x397)))+(((IkReal(-0.00562500000000000))*(cj1)*(x391)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x391)*(x398)))+(((IkReal(0.327500000000000))*(py)*(x396)))+(((x395)*(x405)))+(((cj1)*(r00)*(x399)))+(((IkReal(-0.0750000000000000))*(x387)*(x393)))+(((IkReal(0.327500000000000))*(x390)))+(((x390)*(x400)))+(((IkReal(-1.00000000000000))*(x387)*(x393)*(x395)))+(((IkReal(0.00562500000000000))*(cj0)*(x388)))+(((py)*(x396)*(x400)))+(((r02)*(x392)*(x396)))+(((IkReal(0.0750000000000000))*(x386)*(x393)))+(((x386)*(x393)*(x395)))+(((IkReal(-1.00000000000000))*(cj3)*(x402)))+(((IkReal(-1.00000000000000))*(x391)*(x395)*(x401))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x387)*(x393)*(x400)))+(((px)*(x388)*(x400)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x396)*(x400)))+(((IkReal(-0.327500000000000))*(x386)*(x393)))+(((IkReal(0.327500000000000))*(x391)*(x401)))+(((x391)*(x400)*(x401)))+(((IkReal(-1.00000000000000))*(r02)*(x396)*(x397)))+(((IkReal(0.0750000000000000))*(x390)))+(((IkReal(-1.00000000000000))*(x400)*(x405)))+(((IkReal(-0.327500000000000))*(x405)))+(((IkReal(-1.00000000000000))*(x386)*(x393)*(x400)))+(((x392)*(x393)))+(((cj3)*(x391)*(x398)))+(((x396)*(x399)))+(((IkReal(-1.00000000000000))*(sj3)*(x402)))+(((IkReal(0.0245625000000000))*(cj1)*(x391)))+(((x390)*(x395)))+(((py)*(x395)*(x396)))+(((IkReal(0.327500000000000))*(x387)*(x393)))+(((x394)*(x403)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x388)*(x397)))+(((IkReal(-0.0245625000000000))*(cj0)*(x388)))+(((IkReal(-1.00000000000000))*(cj3)*(x388)*(x389))))))) < IKFAST_ATAN2_MAGTHRESH )
01411     continue;
01412 j2array[0]=IKatan2(((gconst5)*(((IkReal(-0.0982500000000000))+(((IkReal(0.0800000000000000))*(r02)*(x394)*(x396)))+(((px)*(x393)*(x400)))+(((IkReal(-0.0800000000000000))*(x388)*(x394)))+(((IkReal(-0.0750000000000000))*(x391)*(x401)))+(((sj3)*(x388)*(x389)))+(((IkReal(-1.00000000000000))*(x388)*(x392)))+(((x393)*(x397)))+(((IkReal(-0.00562500000000000))*(cj1)*(x391)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x391)*(x398)))+(((IkReal(0.327500000000000))*(py)*(x396)))+(((x395)*(x405)))+(((cj1)*(r00)*(x399)))+(((IkReal(-0.0750000000000000))*(x387)*(x393)))+(((IkReal(0.327500000000000))*(x390)))+(((x390)*(x400)))+(((IkReal(-1.00000000000000))*(x387)*(x393)*(x395)))+(((IkReal(0.00562500000000000))*(cj0)*(x388)))+(((py)*(x396)*(x400)))+(((r02)*(x392)*(x396)))+(((IkReal(0.0750000000000000))*(x386)*(x393)))+(((x386)*(x393)*(x395)))+(((IkReal(-1.00000000000000))*(cj3)*(x402)))+(((IkReal(-1.00000000000000))*(x391)*(x395)*(x401)))))), ((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x387)*(x393)*(x400)))+(((px)*(x388)*(x400)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x396)*(x400)))+(((IkReal(-0.327500000000000))*(x386)*(x393)))+(((IkReal(0.327500000000000))*(x391)*(x401)))+(((x391)*(x400)*(x401)))+(((IkReal(-1.00000000000000))*(r02)*(x396)*(x397)))+(((IkReal(0.0750000000000000))*(x390)))+(((IkReal(-1.00000000000000))*(x400)*(x405)))+(((IkReal(-0.327500000000000))*(x405)))+(((IkReal(-1.00000000000000))*(x386)*(x393)*(x400)))+(((x392)*(x393)))+(((cj3)*(x391)*(x398)))+(((x396)*(x399)))+(((IkReal(-1.00000000000000))*(sj3)*(x402)))+(((IkReal(0.0245625000000000))*(cj1)*(x391)))+(((x390)*(x395)))+(((py)*(x395)*(x396)))+(((IkReal(0.327500000000000))*(x387)*(x393)))+(((x394)*(x403)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x388)*(x397)))+(((IkReal(-0.0245625000000000))*(cj0)*(x388)))+(((IkReal(-1.00000000000000))*(cj3)*(x388)*(x389)))))));
01413 sj2array[0]=IKsin(j2array[0]);
01414 cj2array[0]=IKcos(j2array[0]);
01415 if( j2array[0] > IKPI )
01416 {
01417     j2array[0]-=IK2PI;
01418 }
01419 else if( j2array[0] < -IKPI )
01420 {    j2array[0]+=IK2PI;
01421 }
01422 j2valid[0] = true;
01423 for(int ij2 = 0; ij2 < 1; ++ij2)
01424 {
01425 if( !j2valid[ij2] )
01426 {
01427     continue;
01428 }
01429 _ij2[0] = ij2; _ij2[1] = -1;
01430 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01431 {
01432 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01433 {
01434     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01435 }
01436 }
01437 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01438 {
01439 IkReal evalcond[4];
01440 IkReal x407=IKcos(j2);
01441 IkReal x408=IKsin(j2);
01442 IkReal x409=((IkReal(0.0800000000000000))*(sj3));
01443 IkReal x410=((cj0)*(r01));
01444 IkReal x411=((IkReal(1.00000000000000))*(px));
01445 IkReal x412=((py)*(sj1));
01446 IkReal x413=((cj0)*(r02));
01447 IkReal x414=((IkReal(0.0750000000000000))*(cj1));
01448 IkReal x415=((r02)*(sj0));
01449 IkReal x416=((IkReal(0.0750000000000000))*(sj1));
01450 IkReal x417=((cj1)*(pz));
01451 IkReal x418=((r00)*(sj0));
01452 IkReal x419=((IkReal(0.0800000000000000))*(cj3));
01453 IkReal x420=((pz)*(sj1));
01454 IkReal x421=((IkReal(1.00000000000000))*(sj0));
01455 IkReal x422=((cj1)*(py));
01456 IkReal x423=((IkReal(0.0750000000000000))*(x408));
01457 IkReal x424=((IkReal(0.327500000000000))*(x407));
01458 IkReal x425=((IkReal(0.0750000000000000))*(x407));
01459 IkReal x426=((IkReal(0.327500000000000))*(x408));
01460 IkReal x427=((sj1)*(x418));
01461 IkReal x428=((x408)*(x409));
01462 IkReal x429=((x407)*(x419));
01463 IkReal x430=((x407)*(x409));
01464 IkReal x431=((x408)*(x419));
01465 IkReal x432=((x428)+(x423));
01466 IkReal x433=((x429)+(x424));
01467 IkReal x434=((x430)+(x431)+(x426)+(x425));
01468 evalcond[0]=((x433)+(x420)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x411)))+(((IkReal(-1.00000000000000))*(x421)*(x422)))+(((IkReal(-1.00000000000000))*(x432)))+(x414));
01469 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x412)*(x421)))+(x434)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x411)))+(((IkReal(-1.00000000000000))*(x417)))+(x416));
01470 evalcond[2]=((((IkReal(-1.00000000000000))*(x410)*(x414)))+(((x412)*(x413)))+(x432)+(((x418)*(x420)))+(((IkReal(-1.00000000000000))*(r00)*(x422)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x410)*(x420)))+(((x414)*(x418)))+(((IkReal(-1.00000000000000))*(x433)))+(((IkReal(-1.00000000000000))*(sj1)*(x411)*(x415))));
01471 evalcond[3]=((x434)+(((IkReal(-0.300000000000000))*(x418)))+(((IkReal(-1.00000000000000))*(x416)*(x418)))+(((x413)*(x422)))+(((IkReal(-1.00000000000000))*(x410)*(x417)))+(((IkReal(0.300000000000000))*(x410)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x411)))+(((x417)*(x418)))+(((IkReal(-1.00000000000000))*(cj1)*(x411)*(x415)))+(((r00)*(x412)))+(((x410)*(x416))));
01472 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01473 {
01474 continue;
01475 }
01476 }
01477 
01478 {
01479 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01480 vinfos[0].jointtype = 1;
01481 vinfos[0].foffset = j0;
01482 vinfos[0].indices[0] = _ij0[0];
01483 vinfos[0].indices[1] = _ij0[1];
01484 vinfos[0].maxsolutions = _nj0;
01485 vinfos[1].jointtype = 1;
01486 vinfos[1].foffset = j1;
01487 vinfos[1].indices[0] = _ij1[0];
01488 vinfos[1].indices[1] = _ij1[1];
01489 vinfos[1].maxsolutions = _nj1;
01490 vinfos[2].jointtype = 1;
01491 vinfos[2].foffset = j2;
01492 vinfos[2].indices[0] = _ij2[0];
01493 vinfos[2].indices[1] = _ij2[1];
01494 vinfos[2].maxsolutions = _nj2;
01495 vinfos[3].jointtype = 1;
01496 vinfos[3].foffset = j3;
01497 vinfos[3].indices[0] = _ij3[0];
01498 vinfos[3].indices[1] = _ij3[1];
01499 vinfos[3].maxsolutions = _nj3;
01500 vinfos[4].jointtype = 1;
01501 vinfos[4].foffset = j4;
01502 vinfos[4].indices[0] = _ij4[0];
01503 vinfos[4].indices[1] = _ij4[1];
01504 vinfos[4].maxsolutions = _nj4;
01505 std::vector<int> vfree(0);
01506 solutions.AddSolution(vinfos,vfree);
01507 }
01508 }
01509 }
01510 
01511 }
01512 
01513 }
01514 
01515 } else
01516 {
01517 {
01518 IkReal j2array[1], cj2array[1], sj2array[1];
01519 bool j2valid[1]={false};
01520 _nj2 = 1;
01521 IkReal x435=((IkReal(0.0800000000000000))*(cj1));
01522 IkReal x436=((cj0)*(px));
01523 IkReal x437=((py)*(sj0));
01524 IkReal x438=((IkReal(0.0750000000000000))*(cj1));
01525 IkReal x439=((IkReal(0.327500000000000))*(cj1));
01526 IkReal x440=((IkReal(0.327500000000000))*(sj1));
01527 IkReal x441=((IkReal(0.0750000000000000))*(sj1));
01528 IkReal x442=((IkReal(0.00600000000000000))*(sj1));
01529 IkReal x443=((IkReal(0.00600000000000000))*(cj1));
01530 IkReal x444=((IkReal(0.0800000000000000))*(sj1)*(sj3));
01531 IkReal x445=((IkReal(0.0800000000000000))*(cj3)*(sj1));
01532 if( IKabs(((gconst4)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x442)))+(((pz)*(x439)))+(((x437)*(x440)))+(((x437)*(x445)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((pz)*(x441)))+(((x436)*(x440)))+(((IkReal(-1.00000000000000))*(x436)*(x438)))+(((IkReal(-1.00000000000000))*(x437)*(x438)))+(((cj3)*(pz)*(x435)))+(((IkReal(-1.00000000000000))*(sj3)*(x435)*(x436)))+(((IkReal(-1.00000000000000))*(sj3)*(x435)*(x437)))+(((IkReal(0.00562500000000000))*(cj1)))+(((pz)*(x444)))+(((x436)*(x445)))+(((sj3)*(x443))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x435)))+(((x436)*(x441)))+(((x436)*(x439)))+(((cj3)*(x435)*(x437)))+(((x436)*(x444)))+(((IkReal(-1.00000000000000))*(pz)*(x440)))+(((IkReal(-1.00000000000000))*(pz)*(x445)))+(((IkReal(-1.00000000000000))*(cj3)*(x443)))+(((cj3)*(x435)*(x436)))+(((x437)*(x444)))+(((IkReal(-1.00000000000000))*(sj3)*(x442)))+(((x437)*(x439)))+(((pz)*(x438)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x437)*(x441))))))) < IKFAST_ATAN2_MAGTHRESH )
01533     continue;
01534 j2array[0]=IKatan2(((gconst4)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x442)))+(((pz)*(x439)))+(((x437)*(x440)))+(((x437)*(x445)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((pz)*(x441)))+(((x436)*(x440)))+(((IkReal(-1.00000000000000))*(x436)*(x438)))+(((IkReal(-1.00000000000000))*(x437)*(x438)))+(((cj3)*(pz)*(x435)))+(((IkReal(-1.00000000000000))*(sj3)*(x435)*(x436)))+(((IkReal(-1.00000000000000))*(sj3)*(x435)*(x437)))+(((IkReal(0.00562500000000000))*(cj1)))+(((pz)*(x444)))+(((x436)*(x445)))+(((sj3)*(x443)))))), ((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x435)))+(((x436)*(x441)))+(((x436)*(x439)))+(((cj3)*(x435)*(x437)))+(((x436)*(x444)))+(((IkReal(-1.00000000000000))*(pz)*(x440)))+(((IkReal(-1.00000000000000))*(pz)*(x445)))+(((IkReal(-1.00000000000000))*(cj3)*(x443)))+(((cj3)*(x435)*(x436)))+(((x437)*(x444)))+(((IkReal(-1.00000000000000))*(sj3)*(x442)))+(((x437)*(x439)))+(((pz)*(x438)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x437)*(x441)))))));
01535 sj2array[0]=IKsin(j2array[0]);
01536 cj2array[0]=IKcos(j2array[0]);
01537 if( j2array[0] > IKPI )
01538 {
01539     j2array[0]-=IK2PI;
01540 }
01541 else if( j2array[0] < -IKPI )
01542 {    j2array[0]+=IK2PI;
01543 }
01544 j2valid[0] = true;
01545 for(int ij2 = 0; ij2 < 1; ++ij2)
01546 {
01547 if( !j2valid[ij2] )
01548 {
01549     continue;
01550 }
01551 _ij2[0] = ij2; _ij2[1] = -1;
01552 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01553 {
01554 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01555 {
01556     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01557 }
01558 }
01559 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01560 {
01561 IkReal evalcond[4];
01562 IkReal x446=IKcos(j2);
01563 IkReal x447=IKsin(j2);
01564 IkReal x448=((IkReal(0.0800000000000000))*(sj3));
01565 IkReal x449=((cj0)*(r01));
01566 IkReal x450=((IkReal(1.00000000000000))*(px));
01567 IkReal x451=((py)*(sj1));
01568 IkReal x452=((cj0)*(r02));
01569 IkReal x453=((IkReal(0.0750000000000000))*(cj1));
01570 IkReal x454=((r02)*(sj0));
01571 IkReal x455=((IkReal(0.0750000000000000))*(sj1));
01572 IkReal x456=((cj1)*(pz));
01573 IkReal x457=((r00)*(sj0));
01574 IkReal x458=((IkReal(0.0800000000000000))*(cj3));
01575 IkReal x459=((pz)*(sj1));
01576 IkReal x460=((IkReal(1.00000000000000))*(sj0));
01577 IkReal x461=((cj1)*(py));
01578 IkReal x462=((IkReal(0.0750000000000000))*(x447));
01579 IkReal x463=((IkReal(0.327500000000000))*(x446));
01580 IkReal x464=((IkReal(0.0750000000000000))*(x446));
01581 IkReal x465=((IkReal(0.327500000000000))*(x447));
01582 IkReal x466=((sj1)*(x457));
01583 IkReal x467=((x447)*(x448));
01584 IkReal x468=((x446)*(x458));
01585 IkReal x469=((x446)*(x448));
01586 IkReal x470=((x447)*(x458));
01587 IkReal x471=((x462)+(x467));
01588 IkReal x472=((x468)+(x463));
01589 IkReal x473=((x470)+(x469)+(x465)+(x464));
01590 evalcond[0]=((((IkReal(-1.00000000000000))*(x460)*(x461)))+(x472)+(x459)+(x453)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x450)))+(((IkReal(-1.00000000000000))*(x471))));
01591 evalcond[1]=((IkReal(0.300000000000000))+(x473)+(((IkReal(-1.00000000000000))*(x456)))+(x455)+(((IkReal(-1.00000000000000))*(x451)*(x460)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x450))));
01592 evalcond[2]=((x471)+(((IkReal(-1.00000000000000))*(x449)*(x453)))+(((IkReal(-1.00000000000000))*(sj1)*(x450)*(x454)))+(((IkReal(-1.00000000000000))*(x449)*(x459)))+(((cj1)*(px)*(r01)))+(((x457)*(x459)))+(((x453)*(x457)))+(((x451)*(x452)))+(((IkReal(-1.00000000000000))*(r00)*(x461)))+(((IkReal(-1.00000000000000))*(x472))));
01593 evalcond[3]=((((x452)*(x461)))+(x473)+(((x456)*(x457)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x450)))+(((IkReal(-0.300000000000000))*(x457)))+(((IkReal(-1.00000000000000))*(cj1)*(x450)*(x454)))+(((r00)*(x451)))+(((x449)*(x455)))+(((IkReal(-1.00000000000000))*(x455)*(x457)))+(((IkReal(-1.00000000000000))*(x449)*(x456)))+(((IkReal(0.300000000000000))*(x449))));
01594 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01595 {
01596 continue;
01597 }
01598 }
01599 
01600 {
01601 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01602 vinfos[0].jointtype = 1;
01603 vinfos[0].foffset = j0;
01604 vinfos[0].indices[0] = _ij0[0];
01605 vinfos[0].indices[1] = _ij0[1];
01606 vinfos[0].maxsolutions = _nj0;
01607 vinfos[1].jointtype = 1;
01608 vinfos[1].foffset = j1;
01609 vinfos[1].indices[0] = _ij1[0];
01610 vinfos[1].indices[1] = _ij1[1];
01611 vinfos[1].maxsolutions = _nj1;
01612 vinfos[2].jointtype = 1;
01613 vinfos[2].foffset = j2;
01614 vinfos[2].indices[0] = _ij2[0];
01615 vinfos[2].indices[1] = _ij2[1];
01616 vinfos[2].maxsolutions = _nj2;
01617 vinfos[3].jointtype = 1;
01618 vinfos[3].foffset = j3;
01619 vinfos[3].indices[0] = _ij3[0];
01620 vinfos[3].indices[1] = _ij3[1];
01621 vinfos[3].maxsolutions = _nj3;
01622 vinfos[4].jointtype = 1;
01623 vinfos[4].foffset = j4;
01624 vinfos[4].indices[0] = _ij4[0];
01625 vinfos[4].indices[1] = _ij4[1];
01626 vinfos[4].maxsolutions = _nj4;
01627 std::vector<int> vfree(0);
01628 solutions.AddSolution(vinfos,vfree);
01629 }
01630 }
01631 }
01632 
01633 }
01634 
01635 }
01636 
01637 } else
01638 {
01639 IkReal x474=((IkReal(0.0524000000000000))*(cj3));
01640 IkReal x475=((IkReal(0.0120000000000000))*(sj3));
01641 IkReal x476=(py)*(py);
01642 IkReal x477=(px)*(px);
01643 IkReal x478=(pz)*(pz);
01644 IkReal x479=((r01)*(sj0));
01645 IkReal x480=((py)*(r00));
01646 IkReal x481=((pz)*(sj1));
01647 IkReal x482=((py)*(r01));
01648 IkReal x483=((px)*(sj0));
01649 IkReal x484=((IkReal(0.600000000000000))*(r02));
01650 IkReal x485=((IkReal(0.150000000000000))*(cj1));
01651 IkReal x486=((cj0)*(sj1));
01652 IkReal x487=((IkReal(0.150000000000000))*(px));
01653 IkReal x488=((IkReal(2.00000000000000))*(cj1));
01654 IkReal x489=((cj0)*(r01));
01655 IkReal x490=((r02)*(sj1));
01656 IkReal x491=((px)*(r00));
01657 IkReal x492=((IkReal(0.300000000000000))*(r00));
01658 IkReal x493=((IkReal(1.00000000000000))*(pz));
01659 IkReal x494=((r00)*(sj1));
01660 IkReal x495=((cj0)*(r00));
01661 IkReal x496=((cj0)*(cj1));
01662 IkReal x497=((IkReal(1.00000000000000))*(sj1));
01663 IkReal x498=((IkReal(0.0956250000000000))*(r00));
01664 IkReal x499=((IkReal(0.600000000000000))*(pz));
01665 IkReal x500=((IkReal(0.600000000000000))*(sj1));
01666 IkReal x501=((IkReal(2.00000000000000))*(px));
01667 IkReal x502=((IkReal(2.00000000000000))*(sj1));
01668 IkReal x503=((IkReal(0.150000000000000))*(sj1));
01669 IkReal x504=((cj1)*(r02));
01670 IkReal x505=((cj0)*(px));
01671 IkReal x506=((IkReal(0.0843750000000000))*(cj1));
01672 IkReal x507=((py)*(sj0));
01673 IkReal x508=((pz)*(r02));
01674 IkReal x509=((IkReal(1.00000000000000))*(cj1));
01675 IkReal x510=((cj0)*(py));
01676 IkReal x511=((r00)*(sj0));
01677 IkReal x512=((r02)*(x507));
01678 IkReal x513=((pp)*(x509));
01679 IkReal x514=((IkReal(1.00000000000000))*(pp)*(r00));
01680 IkReal x515=((x474)+(x475));
01681 IkReal x516=((IkReal(2.00000000000000))*(r00)*(x477));
01682 IkReal x517=((cj0)*(x501)*(x508));
01683 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
01684 evalcond[1]=((x510)+(((IkReal(-1.00000000000000))*(x483))));
01685 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-1.00000000000000))*(x511)))+(x489));
01686 evalcond[3]=((((IkReal(-1.00000000000000))*(x495)*(x509)))+(((IkReal(-1.00000000000000))*(x479)*(x509)))+(x490));
01687 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x486)))+(((IkReal(-1.00000000000000))*(x504)))+(((IkReal(-1.00000000000000))*(x479)*(x497))));
01688 evalcond[5]=((IkReal(0.0236562500000000))+(((x500)*(x507)))+(((IkReal(0.600000000000000))*(px)*(x486)))+(x515)+(((cj1)*(x499)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(0.150000000000000))*(x507)))+(((cj0)*(x487)))+(((IkReal(-0.0450000000000000))*(sj1))));
01689 evalcond[6]=((((IkReal(0.300000000000000))*(sj1)*(x479)))+(((IkReal(0.0750000000000000))*(x495)))+(((IkReal(-1.00000000000000))*(r02)*(x493)))+(((x486)*(x492)))+(((IkReal(-1.00000000000000))*(x482)))+(((IkReal(0.300000000000000))*(x504)))+(((IkReal(0.0750000000000000))*(x479)))+(((IkReal(-1.00000000000000))*(x491))));
01690 evalcond[7]=((x512)+(((IkReal(-1.00000000000000))*(x479)*(x493)))+(((x492)*(x496)))+(((r02)*(x505)))+(((IkReal(-0.300000000000000))*(x490)))+(((IkReal(-1.00000000000000))*(x493)*(x495)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(0.300000000000000))*(cj1)*(x479))));
01691 evalcond[8]=((IkReal(0.119281250000000))+(((x480)*(x500)))+(((pp)*(x489)))+(((IkReal(-1.00000000000000))*(pp)*(x511)))+(((IkReal(2.00000000000000))*(x477)*(x511)))+(x515)+(((IkReal(-1.00000000000000))*(cj1)*(x489)*(x499)))+(((py)*(x484)*(x496)))+(((py)*(x479)*(x501)))+(((IkReal(2.00000000000000))*(x483)*(x508)))+(((IkReal(-1.00000000000000))*(cj0)*(x480)*(x501)))+(((IkReal(0.0956250000000000))*(x489)))+(((IkReal(0.0450000000000000))*(r01)*(x486)))+(((IkReal(-1.00000000000000))*(r01)*(x487)))+(((IkReal(-1.00000000000000))*(cj1)*(x483)*(x484)))+(((IkReal(-0.0450000000000000))*(sj0)*(x494)))+(((IkReal(-2.00000000000000))*(x476)*(x489)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x500)))+(((IkReal(0.150000000000000))*(x480)))+(((IkReal(-1.00000000000000))*(sj0)*(x498)))+(((cj1)*(x499)*(x511)))+(((IkReal(-2.00000000000000))*(x508)*(x510))));
01692 evalcond[9]=((((IkReal(-0.150000000000000))*(r02)*(x481)))+(((x486)*(x516)))+(((r02)*(x485)*(x505)))+(((IkReal(-1.00000000000000))*(pz)*(x485)*(x495)))+(((x485)*(x512)))+(((pz)*(x488)*(x491)))+(((x480)*(x483)*(x502)))+(((IkReal(2.00000000000000))*(x481)*(x512)))+(((x486)*(x498)))+(((IkReal(-0.600000000000000))*(x482)))+(((IkReal(-1.00000000000000))*(pz)*(x484)))+(((r02)*(x478)*(x488)))+(((x482)*(x486)*(x501)))+(((IkReal(-1.00000000000000))*(pz)*(x479)*(x485)))+(((IkReal(-1.00000000000000))*(pp)*(x504)))+(((IkReal(0.0450000000000000))*(x479)))+(((IkReal(-1.00000000000000))*(x486)*(x514)))+(((x476)*(x479)*(x502)))+(((IkReal(0.0956250000000000))*(sj1)*(x479)))+(((cj0)*(r02)*(x481)*(x501)))+(((IkReal(-0.600000000000000))*(x491)))+(((IkReal(0.0450000000000000))*(x495)))+(((pz)*(x482)*(x488)))+(((IkReal(-1.00000000000000))*(x482)*(x503)))+(((IkReal(0.0843750000000000))*(x504)))+(((IkReal(-1.00000000000000))*(pp)*(x479)*(x497)))+(((IkReal(-1.00000000000000))*(x487)*(x494))));
01693 evalcond[10]=((((x477)*(x488)*(x495)))+(((IkReal(-1.00000000000000))*(x485)*(x508)))+(((x476)*(x479)*(x488)))+(((x495)*(x499)))+(((x480)*(x483)*(x488)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(0.150000000000000))*(x481)*(x495)))+(((IkReal(-1.00000000000000))*(x479)*(x513)))+(((IkReal(-2.00000000000000))*(x478)*(x490)))+(((IkReal(-1.00000000000000))*(x479)*(x506)))+(((IkReal(-1.00000000000000))*(x484)*(x507)))+(((IkReal(-1.00000000000000))*(x484)*(x505)))+(((IkReal(0.0956250000000000))*(x490)))+(((IkReal(0.150000000000000))*(x479)*(x481)))+(((IkReal(-1.00000000000000))*(x485)*(x491)))+(((IkReal(-0.150000000000000))*(x490)*(x507)))+(((pp)*(x490)))+(((IkReal(-1.00000000000000))*(r02)*(x486)*(x487)))+(((IkReal(-2.00000000000000))*(x481)*(x482)))+(((x479)*(x499)))+(((x482)*(x488)*(x505)))+(((IkReal(-2.00000000000000))*(x481)*(x491)))+(((IkReal(-1.00000000000000))*(x495)*(x506)))+(((x488)*(x507)*(x508)))+(((IkReal(-1.00000000000000))*(x482)*(x485)))+(((IkReal(-1.00000000000000))*(x495)*(x513)))+(((x488)*(x505)*(x508))));
01694 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  )
01695 {
01696 {
01697 IkReal dummyeval[1];
01698 IkReal gconst6;
01699 gconst6=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
01700 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
01701 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01702 {
01703 {
01704 IkReal dummyeval[1];
01705 IkReal gconst7;
01706 gconst7=IKsign(((IkReal(-0.112881250000000))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(-0.0524000000000000))*(cj3)))));
01707 dummyeval[0]=((IkReal(-17.6376953125000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.18750000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
01708 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01709 {
01710 continue;
01711 
01712 } else
01713 {
01714 {
01715 IkReal j2array[1], cj2array[1], sj2array[1];
01716 bool j2valid[1]={false};
01717 _nj2 = 1;
01718 IkReal x518=((cj0)*(r01));
01719 IkReal x519=((pz)*(sj1));
01720 IkReal x520=((IkReal(0.0800000000000000))*(sj3));
01721 IkReal x521=((IkReal(0.00600000000000000))*(cj1));
01722 IkReal x522=((IkReal(0.0750000000000000))*(cj1));
01723 IkReal x523=((r00)*(sj0));
01724 IkReal x524=((IkReal(0.0245625000000000))*(cj1));
01725 IkReal x525=((px)*(r01));
01726 IkReal x526=((IkReal(0.00562500000000000))*(cj1));
01727 IkReal x527=((IkReal(0.0800000000000000))*(cj3));
01728 IkReal x528=((cj1)*(pz));
01729 IkReal x529=((px)*(r02));
01730 IkReal x530=((py)*(sj1));
01731 IkReal x531=((cj0)*(r02));
01732 IkReal x532=((IkReal(0.00600000000000000))*(sj1));
01733 IkReal x533=((IkReal(0.327500000000000))*(sj0));
01734 IkReal x534=((IkReal(0.0750000000000000))*(sj0)*(sj1));
01735 IkReal x535=((cj0)*(px)*(sj1));
01736 IkReal x536=((cj1)*(py)*(r00));
01737 IkReal x537=((IkReal(0.0800000000000000))*(sj0)*(sj1)*(x529));
01738 if( IKabs(((gconst7)*(((IkReal(0.0982500000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x527)*(x530)))+(((sj0)*(sj1)*(x520)*(x529)))+(((IkReal(-0.327500000000000))*(x528)))+(((IkReal(-1.00000000000000))*(x522)*(x525)))+(((IkReal(-1.00000000000000))*(x527)*(x528)))+(((IkReal(-1.00000000000000))*(x520)*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(x523)*(x526)))+(((IkReal(-1.00000000000000))*(x527)*(x535)))+(((IkReal(-0.327500000000000))*(x535)))+(((IkReal(-0.0750000000000000))*(x519)*(x523)))+(((IkReal(-0.0750000000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(cj1)*(x520)*(x525)))+(((IkReal(-1.00000000000000))*(x519)*(x520)*(x523)))+(((IkReal(0.0245625000000000))*(sj1)))+(((py)*(r00)*(x522)))+(((sj3)*(x518)*(x521)))+(((IkReal(-1.00000000000000))*(x530)*(x533)))+(((x529)*(x534)))+(((IkReal(-1.00000000000000))*(sj3)*(x521)*(x523)))+(((cj3)*(x532)))+(((x518)*(x519)*(x520)))+(((x518)*(x526)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x520)*(x536)))+(((IkReal(0.0750000000000000))*(x518)*(x519))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((IkReal(0.0225000000000000))+(((IkReal(-0.0750000000000000))*(sj0)*(x530)))+(((x527)*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(sj1)*(x529)*(x533)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(0.327500000000000))*(x519)*(x523)))+(((IkReal(-1.00000000000000))*(sj0)*(x520)*(x530)))+(((IkReal(-1.00000000000000))*(x520)*(x528)))+(((IkReal(-0.327500000000000))*(x536)))+(((cj1)*(x525)*(x527)))+(((IkReal(-1.00000000000000))*(pz)*(x522)))+(((IkReal(0.327500000000000))*(cj1)*(x525)))+(((x523)*(x524)))+(((IkReal(0.327500000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(sj0)*(sj1)*(x527)*(x529)))+(((cj3)*(x521)*(x523)))+(((IkReal(-0.0750000000000000))*(x535)))+(((IkReal(-1.00000000000000))*(x527)*(x536)))+(((IkReal(-1.00000000000000))*(cj3)*(x518)*(x521)))+(((IkReal(-1.00000000000000))*(x518)*(x519)*(x527)))+(((sj3)*(x532)))+(((IkReal(-1.00000000000000))*(x518)*(x524)))+(((IkReal(-0.327500000000000))*(x518)*(x519)))+(((IkReal(-1.00000000000000))*(x520)*(x535)))+(((IkReal(0.0240000000000000))*(sj3)))+(((x519)*(x523)*(x527))))))) < IKFAST_ATAN2_MAGTHRESH )
01739     continue;
01740 j2array[0]=IKatan2(((gconst7)*(((IkReal(0.0982500000000000))+(((IkReal(-1.00000000000000))*(sj0)*(x527)*(x530)))+(((sj0)*(sj1)*(x520)*(x529)))+(((IkReal(-0.327500000000000))*(x528)))+(((IkReal(-1.00000000000000))*(x522)*(x525)))+(((IkReal(-1.00000000000000))*(x527)*(x528)))+(((IkReal(-1.00000000000000))*(x520)*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(x523)*(x526)))+(((IkReal(-1.00000000000000))*(x527)*(x535)))+(((IkReal(-0.327500000000000))*(x535)))+(((IkReal(-0.0750000000000000))*(x519)*(x523)))+(((IkReal(-0.0750000000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(cj1)*(x520)*(x525)))+(((IkReal(-1.00000000000000))*(x519)*(x520)*(x523)))+(((IkReal(0.0245625000000000))*(sj1)))+(((py)*(r00)*(x522)))+(((sj3)*(x518)*(x521)))+(((IkReal(-1.00000000000000))*(x530)*(x533)))+(((x529)*(x534)))+(((IkReal(-1.00000000000000))*(sj3)*(x521)*(x523)))+(((cj3)*(x532)))+(((x518)*(x519)*(x520)))+(((x518)*(x526)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x520)*(x536)))+(((IkReal(0.0750000000000000))*(x518)*(x519)))))), ((gconst7)*(((IkReal(0.0225000000000000))+(((IkReal(-0.0750000000000000))*(sj0)*(x530)))+(((x527)*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(sj1)*(x529)*(x533)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(0.327500000000000))*(x519)*(x523)))+(((IkReal(-1.00000000000000))*(sj0)*(x520)*(x530)))+(((IkReal(-1.00000000000000))*(x520)*(x528)))+(((IkReal(-0.327500000000000))*(x536)))+(((cj1)*(x525)*(x527)))+(((IkReal(-1.00000000000000))*(pz)*(x522)))+(((IkReal(0.327500000000000))*(cj1)*(x525)))+(((x523)*(x524)))+(((IkReal(0.327500000000000))*(x530)*(x531)))+(((IkReal(-1.00000000000000))*(sj0)*(sj1)*(x527)*(x529)))+(((cj3)*(x521)*(x523)))+(((IkReal(-0.0750000000000000))*(x535)))+(((IkReal(-1.00000000000000))*(x527)*(x536)))+(((IkReal(-1.00000000000000))*(cj3)*(x518)*(x521)))+(((IkReal(-1.00000000000000))*(x518)*(x519)*(x527)))+(((sj3)*(x532)))+(((IkReal(-1.00000000000000))*(x518)*(x524)))+(((IkReal(-0.327500000000000))*(x518)*(x519)))+(((IkReal(-1.00000000000000))*(x520)*(x535)))+(((IkReal(0.0240000000000000))*(sj3)))+(((x519)*(x523)*(x527)))))));
01741 sj2array[0]=IKsin(j2array[0]);
01742 cj2array[0]=IKcos(j2array[0]);
01743 if( j2array[0] > IKPI )
01744 {
01745     j2array[0]-=IK2PI;
01746 }
01747 else if( j2array[0] < -IKPI )
01748 {    j2array[0]+=IK2PI;
01749 }
01750 j2valid[0] = true;
01751 for(int ij2 = 0; ij2 < 1; ++ij2)
01752 {
01753 if( !j2valid[ij2] )
01754 {
01755     continue;
01756 }
01757 _ij2[0] = ij2; _ij2[1] = -1;
01758 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01759 {
01760 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01761 {
01762     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01763 }
01764 }
01765 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01766 {
01767 IkReal evalcond[4];
01768 IkReal x538=IKcos(j2);
01769 IkReal x539=IKsin(j2);
01770 IkReal x540=((IkReal(0.0800000000000000))*(sj3));
01771 IkReal x541=((cj0)*(r01));
01772 IkReal x542=((IkReal(1.00000000000000))*(px));
01773 IkReal x543=((py)*(sj1));
01774 IkReal x544=((cj0)*(r02));
01775 IkReal x545=((IkReal(0.0750000000000000))*(cj1));
01776 IkReal x546=((r02)*(sj0));
01777 IkReal x547=((IkReal(0.0750000000000000))*(sj1));
01778 IkReal x548=((cj1)*(pz));
01779 IkReal x549=((r00)*(sj0));
01780 IkReal x550=((IkReal(0.0800000000000000))*(cj3));
01781 IkReal x551=((pz)*(sj1));
01782 IkReal x552=((IkReal(1.00000000000000))*(sj0));
01783 IkReal x553=((cj1)*(py));
01784 IkReal x554=((IkReal(0.327500000000000))*(x538));
01785 IkReal x555=((IkReal(0.0750000000000000))*(x539));
01786 IkReal x556=((IkReal(0.0750000000000000))*(x538));
01787 IkReal x557=((IkReal(0.327500000000000))*(x539));
01788 IkReal x558=((sj1)*(x549));
01789 IkReal x559=((x538)*(x550));
01790 IkReal x560=((x539)*(x540));
01791 IkReal x561=((x538)*(x540));
01792 IkReal x562=((x539)*(x550));
01793 IkReal x563=((x560)+(x555));
01794 IkReal x564=((x559)+(x554));
01795 IkReal x565=((x562)+(x561)+(x557)+(x556));
01796 evalcond[0]=((((IkReal(-1.00000000000000))*(x552)*(x553)))+(x545)+(x564)+(((IkReal(-1.00000000000000))*(x563)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x542)))+(x551));
01797 evalcond[1]=((IkReal(0.300000000000000))+(x547)+(((IkReal(-1.00000000000000))*(x543)*(x552)))+(x565)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x542)))+(((IkReal(-1.00000000000000))*(x548))));
01798 evalcond[2]=((((x549)*(x551)))+(((x545)*(x549)))+(x564)+(((IkReal(-1.00000000000000))*(x541)*(x545)))+(((IkReal(-1.00000000000000))*(x563)))+(((cj1)*(px)*(r01)))+(((x543)*(x544)))+(((IkReal(-1.00000000000000))*(sj1)*(x542)*(x546)))+(((IkReal(-1.00000000000000))*(r00)*(x553)))+(((IkReal(-1.00000000000000))*(x541)*(x551))));
01799 evalcond[3]=((((IkReal(0.300000000000000))*(x541)))+(((IkReal(-1.00000000000000))*(x547)*(x549)))+(((IkReal(-0.300000000000000))*(x549)))+(((x548)*(x549)))+(((IkReal(-1.00000000000000))*(x541)*(x548)))+(((IkReal(-1.00000000000000))*(x565)))+(((IkReal(-1.00000000000000))*(cj1)*(x542)*(x546)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x542)))+(((r00)*(x543)))+(((x541)*(x547)))+(((x544)*(x553))));
01800 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01801 {
01802 continue;
01803 }
01804 }
01805 
01806 {
01807 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01808 vinfos[0].jointtype = 1;
01809 vinfos[0].foffset = j0;
01810 vinfos[0].indices[0] = _ij0[0];
01811 vinfos[0].indices[1] = _ij0[1];
01812 vinfos[0].maxsolutions = _nj0;
01813 vinfos[1].jointtype = 1;
01814 vinfos[1].foffset = j1;
01815 vinfos[1].indices[0] = _ij1[0];
01816 vinfos[1].indices[1] = _ij1[1];
01817 vinfos[1].maxsolutions = _nj1;
01818 vinfos[2].jointtype = 1;
01819 vinfos[2].foffset = j2;
01820 vinfos[2].indices[0] = _ij2[0];
01821 vinfos[2].indices[1] = _ij2[1];
01822 vinfos[2].maxsolutions = _nj2;
01823 vinfos[3].jointtype = 1;
01824 vinfos[3].foffset = j3;
01825 vinfos[3].indices[0] = _ij3[0];
01826 vinfos[3].indices[1] = _ij3[1];
01827 vinfos[3].maxsolutions = _nj3;
01828 vinfos[4].jointtype = 1;
01829 vinfos[4].foffset = j4;
01830 vinfos[4].indices[0] = _ij4[0];
01831 vinfos[4].indices[1] = _ij4[1];
01832 vinfos[4].maxsolutions = _nj4;
01833 std::vector<int> vfree(0);
01834 solutions.AddSolution(vinfos,vfree);
01835 }
01836 }
01837 }
01838 
01839 }
01840 
01841 }
01842 
01843 } else
01844 {
01845 {
01846 IkReal j2array[1], cj2array[1], sj2array[1];
01847 bool j2valid[1]={false};
01848 _nj2 = 1;
01849 IkReal x566=((IkReal(0.0800000000000000))*(cj1));
01850 IkReal x567=((cj0)*(px));
01851 IkReal x568=((py)*(sj0));
01852 IkReal x569=((IkReal(0.0750000000000000))*(cj1));
01853 IkReal x570=((IkReal(0.327500000000000))*(cj1));
01854 IkReal x571=((IkReal(0.327500000000000))*(sj1));
01855 IkReal x572=((IkReal(0.0750000000000000))*(sj1));
01856 IkReal x573=((IkReal(0.00600000000000000))*(sj1));
01857 IkReal x574=((IkReal(0.00600000000000000))*(cj1));
01858 IkReal x575=((IkReal(0.0800000000000000))*(sj1)*(sj3));
01859 IkReal x576=((IkReal(0.0800000000000000))*(cj3)*(sj1));
01860 if( IKabs(((gconst6)*(((IkReal(-0.0982500000000000))+(((x568)*(x576)))+(((IkReal(-1.00000000000000))*(x568)*(x569)))+(((IkReal(-1.00000000000000))*(cj3)*(x573)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x567)*(x576)))+(((pz)*(x575)))+(((pz)*(x570)))+(((sj3)*(x574)))+(((x567)*(x571)))+(((IkReal(-1.00000000000000))*(sj3)*(x566)*(x568)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x567)*(x569)))+(((x568)*(x571)))+(((cj3)*(pz)*(x566)))+(((pz)*(x572)))+(((IkReal(-1.00000000000000))*(sj3)*(x566)*(x567))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x568)*(x572)))+(((IkReal(-1.00000000000000))*(pz)*(x571)))+(((x567)*(x572)))+(((IkReal(-1.00000000000000))*(sj3)*(x573)))+(((pz)*(x569)))+(((pz)*(sj3)*(x566)))+(((IkReal(-1.00000000000000))*(pz)*(x576)))+(((x568)*(x570)))+(((x568)*(x575)))+(((x567)*(x570)))+(((cj3)*(x566)*(x567)))+(((IkReal(-1.00000000000000))*(cj3)*(x574)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x567)*(x575)))+(((cj3)*(x566)*(x568))))))) < IKFAST_ATAN2_MAGTHRESH )
01861     continue;
01862 j2array[0]=IKatan2(((gconst6)*(((IkReal(-0.0982500000000000))+(((x568)*(x576)))+(((IkReal(-1.00000000000000))*(x568)*(x569)))+(((IkReal(-1.00000000000000))*(cj3)*(x573)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x567)*(x576)))+(((pz)*(x575)))+(((pz)*(x570)))+(((sj3)*(x574)))+(((x567)*(x571)))+(((IkReal(-1.00000000000000))*(sj3)*(x566)*(x568)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x567)*(x569)))+(((x568)*(x571)))+(((cj3)*(pz)*(x566)))+(((pz)*(x572)))+(((IkReal(-1.00000000000000))*(sj3)*(x566)*(x567)))))), ((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((x568)*(x572)))+(((IkReal(-1.00000000000000))*(pz)*(x571)))+(((x567)*(x572)))+(((IkReal(-1.00000000000000))*(sj3)*(x573)))+(((pz)*(x569)))+(((pz)*(sj3)*(x566)))+(((IkReal(-1.00000000000000))*(pz)*(x576)))+(((x568)*(x570)))+(((x568)*(x575)))+(((x567)*(x570)))+(((cj3)*(x566)*(x567)))+(((IkReal(-1.00000000000000))*(cj3)*(x574)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x567)*(x575)))+(((cj3)*(x566)*(x568)))))));
01863 sj2array[0]=IKsin(j2array[0]);
01864 cj2array[0]=IKcos(j2array[0]);
01865 if( j2array[0] > IKPI )
01866 {
01867     j2array[0]-=IK2PI;
01868 }
01869 else if( j2array[0] < -IKPI )
01870 {    j2array[0]+=IK2PI;
01871 }
01872 j2valid[0] = true;
01873 for(int ij2 = 0; ij2 < 1; ++ij2)
01874 {
01875 if( !j2valid[ij2] )
01876 {
01877     continue;
01878 }
01879 _ij2[0] = ij2; _ij2[1] = -1;
01880 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01881 {
01882 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01883 {
01884     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01885 }
01886 }
01887 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01888 {
01889 IkReal evalcond[4];
01890 IkReal x577=IKcos(j2);
01891 IkReal x578=IKsin(j2);
01892 IkReal x579=((IkReal(0.0800000000000000))*(sj3));
01893 IkReal x580=((cj0)*(r01));
01894 IkReal x581=((IkReal(1.00000000000000))*(px));
01895 IkReal x582=((py)*(sj1));
01896 IkReal x583=((cj0)*(r02));
01897 IkReal x584=((IkReal(0.0750000000000000))*(cj1));
01898 IkReal x585=((r02)*(sj0));
01899 IkReal x586=((IkReal(0.0750000000000000))*(sj1));
01900 IkReal x587=((cj1)*(pz));
01901 IkReal x588=((r00)*(sj0));
01902 IkReal x589=((IkReal(0.0800000000000000))*(cj3));
01903 IkReal x590=((pz)*(sj1));
01904 IkReal x591=((IkReal(1.00000000000000))*(sj0));
01905 IkReal x592=((cj1)*(py));
01906 IkReal x593=((IkReal(0.327500000000000))*(x577));
01907 IkReal x594=((IkReal(0.0750000000000000))*(x578));
01908 IkReal x595=((IkReal(0.0750000000000000))*(x577));
01909 IkReal x596=((IkReal(0.327500000000000))*(x578));
01910 IkReal x597=((sj1)*(x588));
01911 IkReal x598=((x577)*(x589));
01912 IkReal x599=((x578)*(x579));
01913 IkReal x600=((x577)*(x579));
01914 IkReal x601=((x578)*(x589));
01915 IkReal x602=((x594)+(x599));
01916 IkReal x603=((x593)+(x598));
01917 IkReal x604=((x596)+(x595)+(x601)+(x600));
01918 evalcond[0]=((((IkReal(-1.00000000000000))*(x591)*(x592)))+(((IkReal(-1.00000000000000))*(x602)))+(x590)+(x584)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x581)))+(x603));
01919 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x582)*(x591)))+(((IkReal(-1.00000000000000))*(x587)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x581)))+(x586)+(x604));
01920 evalcond[2]=((((IkReal(-1.00000000000000))*(sj1)*(x581)*(x585)))+(((IkReal(-1.00000000000000))*(r00)*(x592)))+(((x584)*(x588)))+(((x588)*(x590)))+(((IkReal(-1.00000000000000))*(x580)*(x584)))+(((cj1)*(px)*(r01)))+(((x582)*(x583)))+(((IkReal(-1.00000000000000))*(x602)))+(((IkReal(-1.00000000000000))*(x580)*(x590)))+(x603));
01921 evalcond[3]=((((IkReal(-1.00000000000000))*(x580)*(x587)))+(((IkReal(-0.300000000000000))*(x588)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x581)))+(((x583)*(x592)))+(((x587)*(x588)))+(((x580)*(x586)))+(((IkReal(-1.00000000000000))*(cj1)*(x581)*(x585)))+(((IkReal(-1.00000000000000))*(x604)))+(((r00)*(x582)))+(((IkReal(0.300000000000000))*(x580)))+(((IkReal(-1.00000000000000))*(x586)*(x588))));
01922 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01923 {
01924 continue;
01925 }
01926 }
01927 
01928 {
01929 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01930 vinfos[0].jointtype = 1;
01931 vinfos[0].foffset = j0;
01932 vinfos[0].indices[0] = _ij0[0];
01933 vinfos[0].indices[1] = _ij0[1];
01934 vinfos[0].maxsolutions = _nj0;
01935 vinfos[1].jointtype = 1;
01936 vinfos[1].foffset = j1;
01937 vinfos[1].indices[0] = _ij1[0];
01938 vinfos[1].indices[1] = _ij1[1];
01939 vinfos[1].maxsolutions = _nj1;
01940 vinfos[2].jointtype = 1;
01941 vinfos[2].foffset = j2;
01942 vinfos[2].indices[0] = _ij2[0];
01943 vinfos[2].indices[1] = _ij2[1];
01944 vinfos[2].maxsolutions = _nj2;
01945 vinfos[3].jointtype = 1;
01946 vinfos[3].foffset = j3;
01947 vinfos[3].indices[0] = _ij3[0];
01948 vinfos[3].indices[1] = _ij3[1];
01949 vinfos[3].maxsolutions = _nj3;
01950 vinfos[4].jointtype = 1;
01951 vinfos[4].foffset = j4;
01952 vinfos[4].indices[0] = _ij4[0];
01953 vinfos[4].indices[1] = _ij4[1];
01954 vinfos[4].maxsolutions = _nj4;
01955 std::vector<int> vfree(0);
01956 solutions.AddSolution(vinfos,vfree);
01957 }
01958 }
01959 }
01960 
01961 }
01962 
01963 }
01964 
01965 } else
01966 {
01967 if( 1 )
01968 {
01969 continue;
01970 
01971 } else
01972 {
01973 }
01974 }
01975 }
01976 }
01977 
01978 } else
01979 {
01980 {
01981 IkReal j2array[1], cj2array[1], sj2array[1];
01982 bool j2valid[1]={false};
01983 _nj2 = 1;
01984 IkReal x605=((r02)*(sj1));
01985 IkReal x606=((cj0)*(px));
01986 IkReal x607=((IkReal(0.0800000000000000))*(sj3));
01987 IkReal x608=((cj4)*(sj3));
01988 IkReal x609=((pz)*(sj1));
01989 IkReal x610=((IkReal(0.0800000000000000))*(cj3));
01990 IkReal x611=((IkReal(1.00000000000000))*(cj1));
01991 IkReal x612=((py)*(sj0));
01992 IkReal x613=((cj1)*(r01)*(sj0));
01993 IkReal x614=((cj1)*(cj3)*(cj4));
01994 IkReal x615=((cj0)*(cj1)*(r00));
01995 IkReal x616=((IkReal(0.0800000000000000))*(x615));
01996 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(x610)*(x615)))+(((IkReal(-0.327500000000000))*(x615)))+(((x605)*(x610)))+(((x608)*(x609)))+(((IkReal(-0.327500000000000))*(x613)))+(((IkReal(-1.00000000000000))*(x610)*(x613)))+(((IkReal(-1.00000000000000))*(x606)*(x608)*(x611)))+(((IkReal(-1.00000000000000))*(x608)*(x611)*(x612)))+(((IkReal(0.327500000000000))*(x605)))+(((IkReal(0.0750000000000000))*(cj1)*(x608))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((IkReal(-0.0750000000000000))*(x615)))+(((IkReal(-1.00000000000000))*(x607)*(x613)))+(((x606)*(x614)))+(((x612)*(x614)))+(((x605)*(x607)))+(((IkReal(-0.0750000000000000))*(x614)))+(((IkReal(-1.00000000000000))*(x607)*(x615)))+(((IkReal(0.0750000000000000))*(x605)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x609)))+(((IkReal(-0.0750000000000000))*(x613))))))) < IKFAST_ATAN2_MAGTHRESH )
01997     continue;
01998 j2array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(x610)*(x615)))+(((IkReal(-0.327500000000000))*(x615)))+(((x605)*(x610)))+(((x608)*(x609)))+(((IkReal(-0.327500000000000))*(x613)))+(((IkReal(-1.00000000000000))*(x610)*(x613)))+(((IkReal(-1.00000000000000))*(x606)*(x608)*(x611)))+(((IkReal(-1.00000000000000))*(x608)*(x611)*(x612)))+(((IkReal(0.327500000000000))*(x605)))+(((IkReal(0.0750000000000000))*(cj1)*(x608)))))), ((gconst3)*(((((IkReal(-0.0750000000000000))*(x615)))+(((IkReal(-1.00000000000000))*(x607)*(x613)))+(((x606)*(x614)))+(((x612)*(x614)))+(((x605)*(x607)))+(((IkReal(-0.0750000000000000))*(x614)))+(((IkReal(-1.00000000000000))*(x607)*(x615)))+(((IkReal(0.0750000000000000))*(x605)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x609)))+(((IkReal(-0.0750000000000000))*(x613)))))));
01999 sj2array[0]=IKsin(j2array[0]);
02000 cj2array[0]=IKcos(j2array[0]);
02001 if( j2array[0] > IKPI )
02002 {
02003     j2array[0]-=IK2PI;
02004 }
02005 else if( j2array[0] < -IKPI )
02006 {    j2array[0]+=IK2PI;
02007 }
02008 j2valid[0] = true;
02009 for(int ij2 = 0; ij2 < 1; ++ij2)
02010 {
02011 if( !j2valid[ij2] )
02012 {
02013     continue;
02014 }
02015 _ij2[0] = ij2; _ij2[1] = -1;
02016 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02017 {
02018 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02019 {
02020     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02021 }
02022 }
02023 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02024 {
02025 IkReal evalcond[8];
02026 IkReal x617=IKcos(j2);
02027 IkReal x618=IKsin(j2);
02028 IkReal x619=(py)*(py);
02029 IkReal x620=(px)*(px);
02030 IkReal x621=(pz)*(pz);
02031 IkReal x622=((sj0)*(sj1));
02032 IkReal x623=((IkReal(1.00000000000000))*(r01));
02033 IkReal x624=((r00)*(sj1));
02034 IkReal x625=((IkReal(0.0750000000000000))*(r00));
02035 IkReal x626=((IkReal(0.0491250000000000))*(sj3));
02036 IkReal x627=((cj1)*(r01));
02037 IkReal x628=((IkReal(0.150000000000000))*(py));
02038 IkReal x629=((pz)*(r02));
02039 IkReal x630=((px)*(r02));
02040 IkReal x631=((IkReal(0.0750000000000000))*(sj4));
02041 IkReal x632=((cj1)*(sj0));
02042 IkReal x633=((pz)*(r00));
02043 IkReal x634=((IkReal(0.0750000000000000))*(cj0));
02044 IkReal x635=((IkReal(2.00000000000000))*(cj0));
02045 IkReal x636=((cj1)*(r02));
02046 IkReal x637=((IkReal(0.150000000000000))*(sj1));
02047 IkReal x638=((px)*(r00));
02048 IkReal x639=((IkReal(2.00000000000000))*(py));
02049 IkReal x640=((r02)*(sj1));
02050 IkReal x641=((IkReal(0.150000000000000))*(cj1));
02051 IkReal x642=((IkReal(0.108031250000000))*(cj3));
02052 IkReal x643=((cj0)*(py));
02053 IkReal x644=((r01)*(sj1));
02054 IkReal x645=((IkReal(0.0800000000000000))*(cj3));
02055 IkReal x646=((IkReal(0.150000000000000))*(pz));
02056 IkReal x647=((IkReal(0.0491250000000000))*(cj3));
02057 IkReal x648=((cj1)*(pz));
02058 IkReal x649=((IkReal(0.0952312500000000))*(sj3));
02059 IkReal x650=((IkReal(0.600000000000000))*(py));
02060 IkReal x651=((IkReal(1.00000000000000))*(py));
02061 IkReal x652=((px)*(sj1));
02062 IkReal x653=((IkReal(1.00000000000000))*(cj0));
02063 IkReal x654=((cj0)*(r00));
02064 IkReal x655=((IkReal(0.600000000000000))*(cj0));
02065 IkReal x656=((IkReal(1.00000000000000))*(sj3));
02066 IkReal x657=((pz)*(sj1));
02067 IkReal x658=((IkReal(0.0800000000000000))*(sj3));
02068 IkReal x659=((px)*(py));
02069 IkReal x660=((cj1)*(r00));
02070 IkReal x661=((r01)*(sj0));
02071 IkReal x662=((cj1)*(px));
02072 IkReal x663=((cj4)*(x618));
02073 IkReal x664=((cj4)*(x617));
02074 IkReal x665=((sj4)*(x618));
02075 IkReal x666=((IkReal(2.00000000000000))*(x621));
02076 IkReal x667=((sj4)*(x617));
02077 IkReal x668=((IkReal(2.00000000000000))*(x619));
02078 IkReal x669=((x617)*(x658));
02079 IkReal x670=((px)*(x629)*(x635));
02080 evalcond[0]=((((IkReal(-1.00000000000000))*(cj3)*(x663)))+(x640)+(((IkReal(-1.00000000000000))*(x623)*(x632)))+(((IkReal(-1.00000000000000))*(x653)*(x660)))+(((IkReal(-1.00000000000000))*(x656)*(x664))));
02081 evalcond[1]=((((IkReal(-1.00000000000000))*(x656)*(x663)))+(((IkReal(-1.00000000000000))*(x622)*(x623)))+(((IkReal(-1.00000000000000))*(x624)*(x653)))+(((IkReal(-1.00000000000000))*(x636)))+(((cj3)*(x664))));
02082 evalcond[2]=((x657)+(((IkReal(0.327500000000000))*(x617)))+(((IkReal(-0.0750000000000000))*(x618)))+(((x617)*(x645)))+(((IkReal(-1.00000000000000))*(x632)*(x651)))+(((IkReal(-1.00000000000000))*(x653)*(x662)))+(((IkReal(-1.00000000000000))*(x618)*(x658)))+(((IkReal(0.0750000000000000))*(cj1))));
02083 evalcond[3]=((IkReal(0.300000000000000))+(x669)+(((x618)*(x645)))+(((IkReal(0.0750000000000000))*(x617)))+(((IkReal(-1.00000000000000))*(x652)*(x653)))+(((IkReal(0.327500000000000))*(x618)))+(((IkReal(-1.00000000000000))*(x622)*(x651)))+(((IkReal(-1.00000000000000))*(x648)))+(((IkReal(0.0750000000000000))*(sj1))));
02084 evalcond[4]=((((x625)*(x632)))+(((IkReal(-1.00000000000000))*(x651)*(x660)))+(((x658)*(x665)))+(((px)*(x627)))+(((IkReal(-1.00000000000000))*(x627)*(x634)))+(((IkReal(-1.00000000000000))*(x622)*(x630)))+(((IkReal(-1.00000000000000))*(cj0)*(x623)*(x657)))+(((IkReal(-0.327500000000000))*(x667)))+(((x640)*(x643)))+(((x622)*(x633)))+(((IkReal(-1.00000000000000))*(x645)*(x667)))+(((x618)*(x631))));
02085 evalcond[5]=((((IkReal(-1.00000000000000))*(x630)*(x632)))+(((x658)*(x667)))+(((IkReal(-1.00000000000000))*(cj0)*(x623)*(x648)))+(((x632)*(x633)))+(((x645)*(x665)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((IkReal(-1.00000000000000))*(x622)*(x625)))+(((IkReal(-1.00000000000000))*(x623)*(x652)))+(((x636)*(x643)))+(((x617)*(x631)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((py)*(x624)))+(((x634)*(x644)))+(((IkReal(0.327500000000000))*(x665))));
02086 evalcond[6]=((((IkReal(0.0843750000000000))*(x636)))+(((IkReal(-1.00000000000000))*(x647)*(x663)))+(((IkReal(0.0450000000000000))*(x654)))+(((IkReal(-0.600000000000000))*(x629)))+(((IkReal(-0.150000000000000))*(px)*(x624)))+(((IkReal(-1.00000000000000))*(x628)*(x644)))+(((IkReal(-1.00000000000000))*(sj0)*(x627)*(x646)))+(((x642)*(x664)))+(((IkReal(2.00000000000000))*(x633)*(x662)))+(((IkReal(-1.00000000000000))*(x629)*(x637)))+(((x636)*(x666)))+(((IkReal(-1.00000000000000))*(pp)*(x636)))+(((x649)*(x663)))+(((x620)*(x624)*(x635)))+(((IkReal(0.0956250000000000))*(cj0)*(x624)))+(((pz)*(x627)*(x639)))+(((r01)*(x622)*(x668)))+(((IkReal(0.0450000000000000))*(x661)))+(((r02)*(x628)*(x632)))+(((x626)*(x664)))+(((IkReal(-0.0120000000000000))*(x663)))+(((IkReal(0.0524000000000000))*(x664)))+(((IkReal(-0.600000000000000))*(x638)))+(((x635)*(x644)*(x659)))+(((cj0)*(x630)*(x641)))+(((IkReal(0.0956250000000000))*(r01)*(x622)))+(((IkReal(-1.00000000000000))*(pp)*(x624)*(x653)))+(((IkReal(-1.00000000000000))*(pp)*(x622)*(x623)))+(((IkReal(-1.00000000000000))*(r01)*(x650)))+(((IkReal(-1.00000000000000))*(cj0)*(x633)*(x641)))+(((x622)*(x629)*(x639)))+(((x622)*(x638)*(x639)))+(((x629)*(x635)*(x652))));
02087 evalcond[7]=((((IkReal(-1.00000000000000))*(x627)*(x628)))+(((r01)*(x622)*(x646)))+(((x632)*(x638)*(x639)))+(((IkReal(-1.00000000000000))*(x638)*(x641)))+(((x620)*(x635)*(x660)))+(((IkReal(-0.0843750000000000))*(sj0)*(x627)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(x630)*(x637)))+(((IkReal(-0.0120000000000000))*(x664)))+(((IkReal(0.0956250000000000))*(x640)))+(((IkReal(-1.00000000000000))*(pp)*(x623)*(x632)))+(((IkReal(-2.00000000000000))*(px)*(pz)*(x624)))+(((IkReal(-0.0843750000000000))*(cj1)*(x654)))+(((IkReal(0.600000000000000))*(pz)*(x661)))+(((IkReal(-1.00000000000000))*(pz)*(x639)*(x644)))+(((x629)*(x635)*(x662)))+(((x633)*(x655)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x650)))+(((IkReal(-1.00000000000000))*(x629)*(x641)))+(((IkReal(-1.00000000000000))*(x640)*(x666)))+(((IkReal(-0.0524000000000000))*(x663)))+(((x627)*(x635)*(x659)))+(((cj0)*(x624)*(x646)))+(((IkReal(-1.00000000000000))*(pp)*(x653)*(x660)))+(((x649)*(x664)))+(((IkReal(-1.00000000000000))*(x647)*(x664)))+(((IkReal(-1.00000000000000))*(x630)*(x655)))+(((pp)*(x640)))+(((IkReal(-1.00000000000000))*(x626)*(x663)))+(((sj0)*(x627)*(x668)))+(((IkReal(-1.00000000000000))*(r02)*(x622)*(x628)))+(((x629)*(x632)*(x639)))+(((IkReal(-1.00000000000000))*(x642)*(x663))));
02088 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  )
02089 {
02090 continue;
02091 }
02092 }
02093 
02094 {
02095 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02096 vinfos[0].jointtype = 1;
02097 vinfos[0].foffset = j0;
02098 vinfos[0].indices[0] = _ij0[0];
02099 vinfos[0].indices[1] = _ij0[1];
02100 vinfos[0].maxsolutions = _nj0;
02101 vinfos[1].jointtype = 1;
02102 vinfos[1].foffset = j1;
02103 vinfos[1].indices[0] = _ij1[0];
02104 vinfos[1].indices[1] = _ij1[1];
02105 vinfos[1].maxsolutions = _nj1;
02106 vinfos[2].jointtype = 1;
02107 vinfos[2].foffset = j2;
02108 vinfos[2].indices[0] = _ij2[0];
02109 vinfos[2].indices[1] = _ij2[1];
02110 vinfos[2].maxsolutions = _nj2;
02111 vinfos[3].jointtype = 1;
02112 vinfos[3].foffset = j3;
02113 vinfos[3].indices[0] = _ij3[0];
02114 vinfos[3].indices[1] = _ij3[1];
02115 vinfos[3].maxsolutions = _nj3;
02116 vinfos[4].jointtype = 1;
02117 vinfos[4].foffset = j4;
02118 vinfos[4].indices[0] = _ij4[0];
02119 vinfos[4].indices[1] = _ij4[1];
02120 vinfos[4].maxsolutions = _nj4;
02121 std::vector<int> vfree(0);
02122 solutions.AddSolution(vinfos,vfree);
02123 }
02124 }
02125 }
02126 
02127 }
02128 
02129 }
02130 
02131 } else
02132 {
02133 {
02134 IkReal j2array[1], cj2array[1], sj2array[1];
02135 bool j2valid[1]={false};
02136 _nj2 = 1;
02137 IkReal x671=((IkReal(1.00000000000000))*(cj1));
02138 IkReal x672=((cj0)*(r00));
02139 IkReal x673=((cj3)*(r02));
02140 IkReal x674=((sj1)*(sj3));
02141 IkReal x675=((r01)*(sj0));
02142 IkReal x676=((cj3)*(x675));
02143 if( IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x671)*(x676)))+(((IkReal(-1.00000000000000))*(x672)*(x674)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x671)))+(((sj1)*(x673)))+(((IkReal(-1.00000000000000))*(cj3)*(x671)*(x672)))+(((IkReal(-1.00000000000000))*(x674)*(x675))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(sj3)*(x671)*(x672)))+(((cj3)*(sj1)*(x672)))+(((cj1)*(x673)))+(((sj1)*(x676)))+(((IkReal(-1.00000000000000))*(sj3)*(x671)*(x675)))+(((r02)*(x674))))))) < IKFAST_ATAN2_MAGTHRESH )
02144     continue;
02145 j2array[0]=IKatan2(((gconst2)*(((((IkReal(-1.00000000000000))*(x671)*(x676)))+(((IkReal(-1.00000000000000))*(x672)*(x674)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x671)))+(((sj1)*(x673)))+(((IkReal(-1.00000000000000))*(cj3)*(x671)*(x672)))+(((IkReal(-1.00000000000000))*(x674)*(x675)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(sj3)*(x671)*(x672)))+(((cj3)*(sj1)*(x672)))+(((cj1)*(x673)))+(((sj1)*(x676)))+(((IkReal(-1.00000000000000))*(sj3)*(x671)*(x675)))+(((r02)*(x674)))))));
02146 sj2array[0]=IKsin(j2array[0]);
02147 cj2array[0]=IKcos(j2array[0]);
02148 if( j2array[0] > IKPI )
02149 {
02150     j2array[0]-=IK2PI;
02151 }
02152 else if( j2array[0] < -IKPI )
02153 {    j2array[0]+=IK2PI;
02154 }
02155 j2valid[0] = true;
02156 for(int ij2 = 0; ij2 < 1; ++ij2)
02157 {
02158 if( !j2valid[ij2] )
02159 {
02160     continue;
02161 }
02162 _ij2[0] = ij2; _ij2[1] = -1;
02163 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02164 {
02165 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02166 {
02167     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02168 }
02169 }
02170 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02171 {
02172 IkReal evalcond[8];
02173 IkReal x677=IKcos(j2);
02174 IkReal x678=IKsin(j2);
02175 IkReal x679=(py)*(py);
02176 IkReal x680=(px)*(px);
02177 IkReal x681=(pz)*(pz);
02178 IkReal x682=((sj0)*(sj1));
02179 IkReal x683=((IkReal(1.00000000000000))*(r01));
02180 IkReal x684=((r00)*(sj1));
02181 IkReal x685=((IkReal(0.0750000000000000))*(r00));
02182 IkReal x686=((IkReal(0.0491250000000000))*(sj3));
02183 IkReal x687=((cj1)*(r01));
02184 IkReal x688=((IkReal(0.150000000000000))*(py));
02185 IkReal x689=((pz)*(r02));
02186 IkReal x690=((px)*(r02));
02187 IkReal x691=((IkReal(0.0750000000000000))*(sj4));
02188 IkReal x692=((cj1)*(sj0));
02189 IkReal x693=((pz)*(r00));
02190 IkReal x694=((IkReal(0.0750000000000000))*(cj0));
02191 IkReal x695=((IkReal(2.00000000000000))*(cj0));
02192 IkReal x696=((cj1)*(r02));
02193 IkReal x697=((IkReal(0.150000000000000))*(sj1));
02194 IkReal x698=((px)*(r00));
02195 IkReal x699=((IkReal(2.00000000000000))*(py));
02196 IkReal x700=((r02)*(sj1));
02197 IkReal x701=((IkReal(0.150000000000000))*(cj1));
02198 IkReal x702=((IkReal(0.108031250000000))*(cj3));
02199 IkReal x703=((cj0)*(py));
02200 IkReal x704=((r01)*(sj1));
02201 IkReal x705=((IkReal(0.0800000000000000))*(cj3));
02202 IkReal x706=((IkReal(0.150000000000000))*(pz));
02203 IkReal x707=((IkReal(0.0491250000000000))*(cj3));
02204 IkReal x708=((cj1)*(pz));
02205 IkReal x709=((IkReal(0.0952312500000000))*(sj3));
02206 IkReal x710=((IkReal(0.600000000000000))*(py));
02207 IkReal x711=((IkReal(1.00000000000000))*(py));
02208 IkReal x712=((px)*(sj1));
02209 IkReal x713=((IkReal(1.00000000000000))*(cj0));
02210 IkReal x714=((cj0)*(r00));
02211 IkReal x715=((IkReal(0.600000000000000))*(cj0));
02212 IkReal x716=((IkReal(1.00000000000000))*(sj3));
02213 IkReal x717=((pz)*(sj1));
02214 IkReal x718=((IkReal(0.0800000000000000))*(sj3));
02215 IkReal x719=((px)*(py));
02216 IkReal x720=((cj1)*(r00));
02217 IkReal x721=((r01)*(sj0));
02218 IkReal x722=((cj1)*(px));
02219 IkReal x723=((cj4)*(x678));
02220 IkReal x724=((cj4)*(x677));
02221 IkReal x725=((sj4)*(x678));
02222 IkReal x726=((IkReal(2.00000000000000))*(x681));
02223 IkReal x727=((sj4)*(x677));
02224 IkReal x728=((IkReal(2.00000000000000))*(x679));
02225 IkReal x729=((x677)*(x718));
02226 IkReal x730=((px)*(x689)*(x695));
02227 evalcond[0]=((((IkReal(-1.00000000000000))*(cj3)*(x723)))+(((IkReal(-1.00000000000000))*(x716)*(x724)))+(x700)+(((IkReal(-1.00000000000000))*(x683)*(x692)))+(((IkReal(-1.00000000000000))*(x713)*(x720))));
02228 evalcond[1]=((((IkReal(-1.00000000000000))*(x716)*(x723)))+(((IkReal(-1.00000000000000))*(x682)*(x683)))+(((IkReal(-1.00000000000000))*(x696)))+(((IkReal(-1.00000000000000))*(x684)*(x713)))+(((cj3)*(x724))));
02229 evalcond[2]=((((IkReal(-1.00000000000000))*(x713)*(x722)))+(((IkReal(-1.00000000000000))*(x678)*(x718)))+(((IkReal(-0.0750000000000000))*(x678)))+(((IkReal(-1.00000000000000))*(x692)*(x711)))+(((IkReal(0.327500000000000))*(x677)))+(x717)+(((IkReal(0.0750000000000000))*(cj1)))+(((x677)*(x705))));
02230 evalcond[3]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x682)*(x711)))+(((IkReal(-1.00000000000000))*(x708)))+(x729)+(((x678)*(x705)))+(((IkReal(0.0750000000000000))*(x677)))+(((IkReal(0.327500000000000))*(x678)))+(((IkReal(-1.00000000000000))*(x712)*(x713)))+(((IkReal(0.0750000000000000))*(sj1))));
02231 evalcond[4]=((((x685)*(x692)))+(((IkReal(-1.00000000000000))*(cj0)*(x683)*(x717)))+(((IkReal(-1.00000000000000))*(x682)*(x690)))+(((x700)*(x703)))+(((IkReal(-0.327500000000000))*(x727)))+(((px)*(x687)))+(((IkReal(-1.00000000000000))*(x705)*(x727)))+(((x678)*(x691)))+(((IkReal(-1.00000000000000))*(x687)*(x694)))+(((IkReal(-1.00000000000000))*(x711)*(x720)))+(((x682)*(x693)))+(((x718)*(x725))));
02232 evalcond[5]=((((IkReal(-1.00000000000000))*(x683)*(x712)))+(((x692)*(x693)))+(((x696)*(x703)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((py)*(x684)))+(((IkReal(-1.00000000000000))*(x682)*(x685)))+(((IkReal(-1.00000000000000))*(x690)*(x692)))+(((x694)*(x704)))+(((x718)*(x727)))+(((x705)*(x725)))+(((IkReal(-1.00000000000000))*(cj0)*(x683)*(x708)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(0.327500000000000))*(x725)))+(((x677)*(x691))));
02233 evalcond[6]=((((r02)*(x688)*(x692)))+(((IkReal(-0.150000000000000))*(px)*(x684)))+(((IkReal(-0.600000000000000))*(x698)))+(((IkReal(0.0450000000000000))*(x721)))+(((x709)*(x723)))+(((x682)*(x689)*(x699)))+(((x695)*(x704)*(x719)))+(((IkReal(-0.600000000000000))*(x689)))+(((IkReal(2.00000000000000))*(x693)*(x722)))+(((IkReal(-1.00000000000000))*(pp)*(x682)*(x683)))+(((IkReal(0.0956250000000000))*(cj0)*(x684)))+(((IkReal(-1.00000000000000))*(pp)*(x696)))+(((IkReal(0.0524000000000000))*(x724)))+(((IkReal(-0.0120000000000000))*(x723)))+(((IkReal(-1.00000000000000))*(x689)*(x697)))+(((x680)*(x684)*(x695)))+(((IkReal(-1.00000000000000))*(pp)*(x684)*(x713)))+(((x702)*(x724)))+(((cj0)*(x690)*(x701)))+(((IkReal(0.0843750000000000))*(x696)))+(((IkReal(-1.00000000000000))*(sj0)*(x687)*(x706)))+(((IkReal(-1.00000000000000))*(x707)*(x723)))+(((IkReal(-1.00000000000000))*(r01)*(x710)))+(((x686)*(x724)))+(((r01)*(x682)*(x728)))+(((x682)*(x698)*(x699)))+(((x689)*(x695)*(x712)))+(((pz)*(x687)*(x699)))+(((IkReal(-1.00000000000000))*(cj0)*(x693)*(x701)))+(((x696)*(x726)))+(((IkReal(0.0956250000000000))*(r01)*(x682)))+(((IkReal(-1.00000000000000))*(x688)*(x704)))+(((IkReal(0.0450000000000000))*(x714))));
02234 evalcond[7]=((((IkReal(-1.00000000000000))*(pp)*(x713)*(x720)))+(((IkReal(-1.00000000000000))*(pp)*(x683)*(x692)))+(((IkReal(0.600000000000000))*(pz)*(x721)))+(((sj0)*(x687)*(x728)))+(((x689)*(x695)*(x722)))+(((IkReal(-1.00000000000000))*(x702)*(x723)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(r02)*(x682)*(x688)))+(((IkReal(-0.0843750000000000))*(cj1)*(x714)))+(((x709)*(x724)))+(((IkReal(-1.00000000000000))*(x698)*(x701)))+(((IkReal(-0.0524000000000000))*(x723)))+(((cj0)*(x684)*(x706)))+(((x692)*(x698)*(x699)))+(((IkReal(-1.00000000000000))*(x707)*(x724)))+(((x687)*(x695)*(x719)))+(((IkReal(-0.0120000000000000))*(x724)))+(((IkReal(0.0956250000000000))*(x700)))+(((r01)*(x682)*(x706)))+(((IkReal(-0.0843750000000000))*(sj0)*(x687)))+(((x689)*(x692)*(x699)))+(((IkReal(-2.00000000000000))*(px)*(pz)*(x684)))+(((IkReal(-1.00000000000000))*(x687)*(x688)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x710)))+(((IkReal(-1.00000000000000))*(x686)*(x723)))+(((IkReal(-1.00000000000000))*(x689)*(x701)))+(((x680)*(x695)*(x720)))+(((x693)*(x715)))+(((IkReal(-1.00000000000000))*(pz)*(x699)*(x704)))+(((IkReal(-1.00000000000000))*(cj0)*(x690)*(x697)))+(((pp)*(x700)))+(((IkReal(-1.00000000000000))*(x690)*(x715)))+(((IkReal(-1.00000000000000))*(x700)*(x726))));
02235 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  )
02236 {
02237 continue;
02238 }
02239 }
02240 
02241 {
02242 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02243 vinfos[0].jointtype = 1;
02244 vinfos[0].foffset = j0;
02245 vinfos[0].indices[0] = _ij0[0];
02246 vinfos[0].indices[1] = _ij0[1];
02247 vinfos[0].maxsolutions = _nj0;
02248 vinfos[1].jointtype = 1;
02249 vinfos[1].foffset = j1;
02250 vinfos[1].indices[0] = _ij1[0];
02251 vinfos[1].indices[1] = _ij1[1];
02252 vinfos[1].maxsolutions = _nj1;
02253 vinfos[2].jointtype = 1;
02254 vinfos[2].foffset = j2;
02255 vinfos[2].indices[0] = _ij2[0];
02256 vinfos[2].indices[1] = _ij2[1];
02257 vinfos[2].maxsolutions = _nj2;
02258 vinfos[3].jointtype = 1;
02259 vinfos[3].foffset = j3;
02260 vinfos[3].indices[0] = _ij3[0];
02261 vinfos[3].indices[1] = _ij3[1];
02262 vinfos[3].maxsolutions = _nj3;
02263 vinfos[4].jointtype = 1;
02264 vinfos[4].foffset = j4;
02265 vinfos[4].indices[0] = _ij4[0];
02266 vinfos[4].indices[1] = _ij4[1];
02267 vinfos[4].maxsolutions = _nj4;
02268 std::vector<int> vfree(0);
02269 solutions.AddSolution(vinfos,vfree);
02270 }
02271 }
02272 }
02273 
02274 }
02275 
02276 }
02277 }
02278 }
02279 
02280 }
02281 
02282 }
02283 
02284 } else
02285 {
02286 {
02287 IkReal j3array[1], cj3array[1], sj3array[1];
02288 bool j3valid[1]={false};
02289 _nj3 = 1;
02290 IkReal x731=((r01)*(sj0));
02291 IkReal x732=((IkReal(15720.0000000000))*(sj1));
02292 IkReal x733=((px)*(r00));
02293 IkReal x734=((IkReal(3600.00000000000))*(sj1));
02294 IkReal x735=((cj0)*(r00));
02295 IkReal x736=((cj1)*(r02));
02296 IkReal x737=((py)*(r01));
02297 IkReal x738=((cj4)*(sj1));
02298 IkReal x739=((pz)*(r02));
02299 IkReal x740=((cj4)*(pp));
02300 IkReal x741=((cj0)*(cj4)*(px));
02301 IkReal x742=((cj1)*(cj4)*(pz));
02302 IkReal x743=((cj4)*(py)*(sj0));
02303 IkReal x744=((py)*(sj0)*(x738));
02304 if( IKabs(((gconst0)*(((((IkReal(-11250.0000000000))*(x741)))+(((IkReal(-11250.0000000000))*(x743)))+(((x732)*(x735)))+(((IkReal(3930.00000000000))*(x731)))+(((x731)*(x732)))+(((IkReal(-45000.0000000000))*(x744)))+(((IkReal(-45000.0000000000))*(cj0)*(px)*(x738)))+(((IkReal(-45000.0000000000))*(x742)))+(((IkReal(3930.00000000000))*(x735)))+(((IkReal(-52400.0000000000))*(x739)))+(((IkReal(3375.00000000000))*(x738)))+(((IkReal(-52400.0000000000))*(x733)))+(((IkReal(15720.0000000000))*(x736)))+(((IkReal(-1774.21875000000))*(cj4)))+(((IkReal(-52400.0000000000))*(x737)))+(((IkReal(75000.0000000000))*(x740))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(-49125.0000000000))*(x743)))+(((IkReal(-1.00000000000000))*(x734)*(x735)))+(((IkReal(-196500.000000000))*(x742)))+(((IkReal(-3600.00000000000))*(x736)))+(((IkReal(-900.000000000000))*(x731)))+(((IkReal(12000.0000000000))*(x737)))+(((IkReal(-196500.000000000))*(x744)))+(((IkReal(-196500.000000000))*(cj0)*(px)*(x738)))+(((IkReal(-1.00000000000000))*(x731)*(x734)))+(((IkReal(12000.0000000000))*(x739)))+(((IkReal(12000.0000000000))*(x733)))+(((IkReal(327500.000000000))*(x740)))+(((IkReal(-7747.42187500000))*(cj4)))+(((IkReal(-900.000000000000))*(x735)))+(((IkReal(14737.5000000000))*(x738)))+(((IkReal(-49125.0000000000))*(x741))))))) < IKFAST_ATAN2_MAGTHRESH )
02305     continue;
02306 j3array[0]=IKatan2(((gconst0)*(((((IkReal(-11250.0000000000))*(x741)))+(((IkReal(-11250.0000000000))*(x743)))+(((x732)*(x735)))+(((IkReal(3930.00000000000))*(x731)))+(((x731)*(x732)))+(((IkReal(-45000.0000000000))*(x744)))+(((IkReal(-45000.0000000000))*(cj0)*(px)*(x738)))+(((IkReal(-45000.0000000000))*(x742)))+(((IkReal(3930.00000000000))*(x735)))+(((IkReal(-52400.0000000000))*(x739)))+(((IkReal(3375.00000000000))*(x738)))+(((IkReal(-52400.0000000000))*(x733)))+(((IkReal(15720.0000000000))*(x736)))+(((IkReal(-1774.21875000000))*(cj4)))+(((IkReal(-52400.0000000000))*(x737)))+(((IkReal(75000.0000000000))*(x740)))))), ((gconst0)*(((((IkReal(-49125.0000000000))*(x743)))+(((IkReal(-1.00000000000000))*(x734)*(x735)))+(((IkReal(-196500.000000000))*(x742)))+(((IkReal(-3600.00000000000))*(x736)))+(((IkReal(-900.000000000000))*(x731)))+(((IkReal(12000.0000000000))*(x737)))+(((IkReal(-196500.000000000))*(x744)))+(((IkReal(-196500.000000000))*(cj0)*(px)*(x738)))+(((IkReal(-1.00000000000000))*(x731)*(x734)))+(((IkReal(12000.0000000000))*(x739)))+(((IkReal(12000.0000000000))*(x733)))+(((IkReal(327500.000000000))*(x740)))+(((IkReal(-7747.42187500000))*(cj4)))+(((IkReal(-900.000000000000))*(x735)))+(((IkReal(14737.5000000000))*(x738)))+(((IkReal(-49125.0000000000))*(x741)))))));
02307 sj3array[0]=IKsin(j3array[0]);
02308 cj3array[0]=IKcos(j3array[0]);
02309 if( j3array[0] > IKPI )
02310 {
02311     j3array[0]-=IK2PI;
02312 }
02313 else if( j3array[0] < -IKPI )
02314 {    j3array[0]+=IK2PI;
02315 }
02316 j3valid[0] = true;
02317 for(int ij3 = 0; ij3 < 1; ++ij3)
02318 {
02319 if( !j3valid[ij3] )
02320 {
02321     continue;
02322 }
02323 _ij3[0] = ij3; _ij3[1] = -1;
02324 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02325 {
02326 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02327 {
02328     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02329 }
02330 }
02331 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02332 {
02333 IkReal evalcond[4];
02334 IkReal x745=IKcos(j3);
02335 IkReal x746=IKsin(j3);
02336 IkReal x747=((r01)*(sj0));
02337 IkReal x748=((IkReal(0.300000000000000))*(r02));
02338 IkReal x749=((r00)*(sj0));
02339 IkReal x750=((py)*(sj0));
02340 IkReal x751=((IkReal(0.600000000000000))*(cj1));
02341 IkReal x752=((IkReal(0.150000000000000))*(px));
02342 IkReal x753=((IkReal(1.00000000000000))*(pz));
02343 IkReal x754=((py)*(r00));
02344 IkReal x755=((IkReal(0.300000000000000))*(cj1));
02345 IkReal x756=((IkReal(1.00000000000000))*(pp));
02346 IkReal x757=((cj0)*(r00));
02347 IkReal x758=((IkReal(0.0450000000000000))*(sj1));
02348 IkReal x759=((IkReal(0.600000000000000))*(sj1));
02349 IkReal x760=((cj0)*(r01));
02350 IkReal x761=((IkReal(2.00000000000000))*(pz));
02351 IkReal x762=((cj0)*(px));
02352 IkReal x763=((IkReal(0.300000000000000))*(sj1));
02353 IkReal x764=((IkReal(2.00000000000000))*(px)*(py));
02354 IkReal x765=((IkReal(0.0120000000000000))*(x746));
02355 IkReal x766=((cj4)*(x746));
02356 IkReal x767=((IkReal(0.0524000000000000))*(x745));
02357 IkReal x768=((cj4)*(x745));
02358 IkReal x769=((cj0)*(py)*(r02));
02359 IkReal x770=((px)*(r02)*(sj0));
02360 evalcond[0]=((IkReal(0.0236562500000000))+(((x750)*(x759)))+(((cj0)*(x752)))+(((IkReal(-1.00000000000000))*(x756)))+(((IkReal(-1.00000000000000))*(x758)))+(x765)+(x767)+(((pz)*(x751)))+(((x759)*(x762)))+(((IkReal(0.150000000000000))*(x750))));
02361 evalcond[1]=((((IkReal(-1.00000000000000))*(py)*(r01)))+(((IkReal(-0.327500000000000))*(x766)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((cj1)*(x748)))+(((IkReal(-1.00000000000000))*(r02)*(x753)))+(((IkReal(0.0750000000000000))*(x757)))+(((IkReal(0.0750000000000000))*(x768)))+(((x757)*(x763)))+(((x747)*(x763)))+(((IkReal(0.0750000000000000))*(x747))));
02362 evalcond[2]=((((x747)*(x755)))+(((IkReal(-0.0800000000000000))*(cj4)))+(((IkReal(-1.00000000000000))*(x753)*(x757)))+(((IkReal(-0.0750000000000000))*(x766)))+(((r02)*(x750)))+(((r02)*(x762)))+(((IkReal(-0.0750000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x748)))+(((x755)*(x757)))+(((IkReal(-0.327500000000000))*(x768)))+(((IkReal(-1.00000000000000))*(x747)*(x753))));
02363 evalcond[3]=((((IkReal(-1.00000000000000))*(x761)*(x769)))+(((IkReal(-1.00000000000000))*(sj4)*(x767)))+(((IkReal(-1.00000000000000))*(pz)*(x751)*(x760)))+(((IkReal(-0.119281250000000))*(sj4)))+(((IkReal(-0.0956250000000000))*(x749)))+(((IkReal(-2.00000000000000))*(x760)*((py)*(py))))+(((IkReal(-1.00000000000000))*(r01)*(x752)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x759)))+(((IkReal(-1.00000000000000))*(x749)*(x758)))+(((x761)*(x770)))+(((x754)*(x759)))+(((pz)*(x749)*(x751)))+(((IkReal(0.150000000000000))*(x754)))+(((IkReal(-2.00000000000000))*(x754)*(x762)))+(((x747)*(x764)))+(((IkReal(-1.00000000000000))*(x751)*(x770)))+(((x758)*(x760)))+(((IkReal(2.00000000000000))*(x749)*((px)*(px))))+(((x751)*(x769)))+(((IkReal(0.0956250000000000))*(x760)))+(((IkReal(-1.00000000000000))*(sj4)*(x765)))+(((pp)*(x760)))+(((IkReal(-1.00000000000000))*(x749)*(x756))));
02364 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02365 {
02366 continue;
02367 }
02368 }
02369 
02370 {
02371 IkReal dummyeval[1];
02372 IkReal gconst2;
02373 gconst2=IKsign(((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3))))));
02374 dummyeval[0]=((((cj4)*((cj3)*(cj3))))+(((cj4)*((sj3)*(sj3)))));
02375 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02376 {
02377 {
02378 IkReal dummyeval[1];
02379 IkReal gconst3;
02380 IkReal x771=((IkReal(0.0800000000000000))*(cj4));
02381 gconst3=IKsign(((((IkReal(0.0750000000000000))*(cj4)*(sj3)))+(((x771)*((sj3)*(sj3))))+(((x771)*((cj3)*(cj3))))+(((IkReal(0.327500000000000))*(cj3)*(cj4)))));
02382 IkReal x772=((IkReal(1.06666666666667))*(cj4));
02383 dummyeval[0]=((((x772)*((cj3)*(cj3))))+(((x772)*((sj3)*(sj3))))+(((IkReal(4.36666666666667))*(cj3)*(cj4)))+(((cj4)*(sj3))));
02384 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02385 {
02386 {
02387 IkReal evalcond[11];
02388 IkReal x773=((IkReal(0.0524000000000000))*(cj3));
02389 IkReal x774=((IkReal(0.0120000000000000))*(sj3));
02390 IkReal x775=(py)*(py);
02391 IkReal x776=(px)*(px);
02392 IkReal x777=(pz)*(pz);
02393 IkReal x778=((r01)*(sj0));
02394 IkReal x779=((py)*(r00));
02395 IkReal x780=((pz)*(sj1));
02396 IkReal x781=((py)*(r01));
02397 IkReal x782=((px)*(sj0));
02398 IkReal x783=((IkReal(0.600000000000000))*(r02));
02399 IkReal x784=((IkReal(0.150000000000000))*(cj1));
02400 IkReal x785=((cj0)*(sj1));
02401 IkReal x786=((IkReal(0.150000000000000))*(px));
02402 IkReal x787=((IkReal(2.00000000000000))*(cj1));
02403 IkReal x788=((cj0)*(r01));
02404 IkReal x789=((r02)*(sj1));
02405 IkReal x790=((px)*(r00));
02406 IkReal x791=((IkReal(0.300000000000000))*(r00));
02407 IkReal x792=((IkReal(1.00000000000000))*(pz));
02408 IkReal x793=((r00)*(sj1));
02409 IkReal x794=((cj0)*(r00));
02410 IkReal x795=((cj0)*(cj1));
02411 IkReal x796=((IkReal(1.00000000000000))*(sj1));
02412 IkReal x797=((IkReal(0.0956250000000000))*(r00));
02413 IkReal x798=((IkReal(0.600000000000000))*(pz));
02414 IkReal x799=((IkReal(0.600000000000000))*(sj1));
02415 IkReal x800=((IkReal(2.00000000000000))*(px));
02416 IkReal x801=((IkReal(2.00000000000000))*(sj1));
02417 IkReal x802=((IkReal(0.150000000000000))*(sj1));
02418 IkReal x803=((cj1)*(r02));
02419 IkReal x804=((cj0)*(px));
02420 IkReal x805=((IkReal(0.0843750000000000))*(cj1));
02421 IkReal x806=((py)*(sj0));
02422 IkReal x807=((pz)*(r02));
02423 IkReal x808=((IkReal(1.00000000000000))*(cj1));
02424 IkReal x809=((cj0)*(py));
02425 IkReal x810=((r00)*(sj0));
02426 IkReal x811=((r02)*(x806));
02427 IkReal x812=((pp)*(x808));
02428 IkReal x813=((IkReal(1.00000000000000))*(pp)*(r00));
02429 IkReal x814=((x773)+(x774));
02430 IkReal x815=((IkReal(2.00000000000000))*(r00)*(x776));
02431 IkReal x816=((cj0)*(x800)*(x807));
02432 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
02433 evalcond[1]=((x809)+(((IkReal(-1.00000000000000))*(x782))));
02434 evalcond[2]=((IkReal(-1.00000000000000))+(x788)+(((IkReal(-1.00000000000000))*(x810))));
02435 evalcond[3]=((x789)+(((IkReal(-1.00000000000000))*(x778)*(x808)))+(((IkReal(-1.00000000000000))*(x794)*(x808))));
02436 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(x785)))+(((IkReal(-1.00000000000000))*(x778)*(x796)))+(((IkReal(-1.00000000000000))*(x803))));
02437 evalcond[5]=((IkReal(0.0236562500000000))+(((x799)*(x806)))+(((IkReal(-1.00000000000000))*(pp)))+(((cj1)*(x798)))+(((IkReal(0.150000000000000))*(x806)))+(((IkReal(0.600000000000000))*(px)*(x785)))+(x814)+(((IkReal(-0.0450000000000000))*(sj1)))+(((cj0)*(x786))));
02438 evalcond[6]=((((IkReal(0.0750000000000000))*(x794)))+(((IkReal(0.300000000000000))*(x803)))+(((IkReal(-1.00000000000000))*(r02)*(x792)))+(((IkReal(0.0750000000000000))*(x778)))+(((IkReal(-1.00000000000000))*(x790)))+(((IkReal(0.300000000000000))*(sj1)*(x778)))+(((IkReal(-1.00000000000000))*(x781)))+(((x785)*(x791))));
02439 evalcond[7]=((((IkReal(-1.00000000000000))*(x792)*(x794)))+(((IkReal(0.300000000000000))*(cj1)*(x778)))+(((r02)*(x804)))+(((IkReal(-0.300000000000000))*(x789)))+(((IkReal(-1.00000000000000))*(x778)*(x792)))+(((IkReal(-0.0750000000000000))*(r02)))+(x811)+(((x791)*(x795))));
02440 evalcond[8]=((IkReal(-0.119281250000000))+(((IkReal(-1.00000000000000))*(sj0)*(x797)))+(((py)*(x778)*(x800)))+(((IkReal(2.00000000000000))*(x776)*(x810)))+(((pp)*(x788)))+(((IkReal(-2.00000000000000))*(x807)*(x809)))+(((IkReal(-1.00000000000000))*(px)*(r01)*(x799)))+(((IkReal(-1.00000000000000))*(r01)*(x786)))+(((cj1)*(x798)*(x810)))+(((IkReal(0.0956250000000000))*(x788)))+(((IkReal(2.00000000000000))*(x782)*(x807)))+(((IkReal(-1.00000000000000))*(x814)))+(((IkReal(-2.00000000000000))*(x775)*(x788)))+(((IkReal(-1.00000000000000))*(cj1)*(x782)*(x783)))+(((IkReal(-1.00000000000000))*(pp)*(x810)))+(((IkReal(-0.0450000000000000))*(sj0)*(x793)))+(((x779)*(x799)))+(((py)*(x783)*(x795)))+(((IkReal(0.0450000000000000))*(r01)*(x785)))+(((IkReal(-1.00000000000000))*(cj0)*(x779)*(x800)))+(((IkReal(-1.00000000000000))*(cj1)*(x788)*(x798)))+(((IkReal(0.150000000000000))*(x779))));
02441 evalcond[9]=((((r02)*(x777)*(x787)))+(((pz)*(x781)*(x787)))+(((x785)*(x797)))+(((IkReal(0.0450000000000000))*(x778)))+(((IkReal(-1.00000000000000))*(pp)*(x778)*(x796)))+(((IkReal(-1.00000000000000))*(x781)*(x802)))+(((r02)*(x784)*(x804)))+(((IkReal(0.0956250000000000))*(sj1)*(x778)))+(((IkReal(-1.00000000000000))*(pz)*(x778)*(x784)))+(((IkReal(-1.00000000000000))*(pz)*(x784)*(x794)))+(((IkReal(-1.00000000000000))*(pp)*(x803)))+(((x785)*(x815)))+(((IkReal(-0.600000000000000))*(x790)))+(((IkReal(0.0843750000000000))*(x803)))+(((IkReal(-1.00000000000000))*(pz)*(x783)))+(((IkReal(0.0450000000000000))*(x794)))+(((x775)*(x778)*(x801)))+(((cj0)*(r02)*(x780)*(x800)))+(((x784)*(x811)))+(((IkReal(-1.00000000000000))*(x786)*(x793)))+(((x781)*(x785)*(x800)))+(((x779)*(x782)*(x801)))+(((IkReal(-0.600000000000000))*(x781)))+(((IkReal(-0.150000000000000))*(r02)*(x780)))+(((IkReal(2.00000000000000))*(x780)*(x811)))+(((IkReal(-1.00000000000000))*(x785)*(x813)))+(((pz)*(x787)*(x790))));
02442 evalcond[10]=((((IkReal(-1.00000000000000))*(r02)*(x785)*(x786)))+(((IkReal(-1.00000000000000))*(x781)*(x784)))+(((IkReal(-1.00000000000000))*(x783)*(x804)))+(((IkReal(-1.00000000000000))*(x778)*(x805)))+(((IkReal(-2.00000000000000))*(x777)*(x789)))+(((IkReal(0.0956250000000000))*(x789)))+(((IkReal(0.150000000000000))*(x780)*(x794)))+(((x776)*(x787)*(x794)))+(((IkReal(-1.00000000000000))*(x778)*(x812)))+(((IkReal(-1.00000000000000))*(x794)*(x812)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(x783)*(x806)))+(((x775)*(x778)*(x787)))+(((IkReal(-2.00000000000000))*(x780)*(x790)))+(((IkReal(-1.00000000000000))*(x794)*(x805)))+(((IkReal(-2.00000000000000))*(x780)*(x781)))+(((x778)*(x798)))+(((IkReal(-1.00000000000000))*(x784)*(x807)))+(((IkReal(-0.150000000000000))*(x789)*(x806)))+(((x794)*(x798)))+(((IkReal(-1.00000000000000))*(x784)*(x790)))+(((x779)*(x782)*(x787)))+(((x787)*(x804)*(x807)))+(((pp)*(x789)))+(((x787)*(x806)*(x807)))+(((x781)*(x787)*(x804)))+(((IkReal(0.150000000000000))*(x778)*(x780))));
02443 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  )
02444 {
02445 {
02446 IkReal dummyeval[1];
02447 IkReal gconst4;
02448 gconst4=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02449 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
02450 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02451 {
02452 {
02453 IkReal dummyeval[1];
02454 IkReal gconst5;
02455 gconst5=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02456 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
02457 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02458 {
02459 continue;
02460 
02461 } else
02462 {
02463 {
02464 IkReal j2array[1], cj2array[1], sj2array[1];
02465 bool j2valid[1]={false};
02466 _nj2 = 1;
02467 IkReal x817=((pz)*(r01));
02468 IkReal x818=((py)*(r02));
02469 IkReal x819=((cj1)*(r01));
02470 IkReal x820=((IkReal(0.00600000000000000))*(cj0));
02471 IkReal x821=((cj1)*(pz));
02472 IkReal x822=((r00)*(sj0));
02473 IkReal x823=((IkReal(0.0750000000000000))*(px));
02474 IkReal x824=((cj0)*(sj1));
02475 IkReal x825=((px)*(sj3));
02476 IkReal x826=((IkReal(0.0800000000000000))*(sj3));
02477 IkReal x827=((sj0)*(sj1));
02478 IkReal x828=((IkReal(0.327500000000000))*(px));
02479 IkReal x829=((IkReal(0.00600000000000000))*(cj1));
02480 IkReal x830=((IkReal(0.0750000000000000))*(py));
02481 IkReal x831=((IkReal(0.0800000000000000))*(cj3));
02482 IkReal x832=((pz)*(sj1));
02483 IkReal x833=((IkReal(0.00600000000000000))*(sj1));
02484 IkReal x834=((IkReal(0.0800000000000000))*(x824));
02485 IkReal x835=((sj1)*(x831));
02486 IkReal x836=((cj1)*(py)*(r00));
02487 IkReal x837=((IkReal(0.0800000000000000))*(px)*(r02)*(x827));
02488 if( IKabs(((gconst5)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x833)))+(((IkReal(0.327500000000000))*(x821)))+(((x821)*(x831)))+(((IkReal(-1.00000000000000))*(x822)*(x826)*(x832)))+(((IkReal(0.0800000000000000))*(r02)*(x825)*(x827)))+(((IkReal(-0.0750000000000000))*(x818)*(x824)))+(((py)*(x827)*(x831)))+(((sj3)*(x819)*(x820)))+(((IkReal(-1.00000000000000))*(x818)*(x824)*(x826)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x822)*(x829)))+(((IkReal(0.00562500000000000))*(cj0)*(x819)))+(((x817)*(x824)*(x826)))+(((x826)*(x836)))+(((IkReal(-0.00562500000000000))*(cj1)*(x822)))+(((px)*(x824)*(x831)))+(((IkReal(-0.0800000000000000))*(x819)*(x825)))+(((r02)*(x823)*(x827)))+(((IkReal(-1.00000000000000))*(x819)*(x823)))+(((cj1)*(r00)*(x830)))+(((x824)*(x828)))+(((IkReal(0.327500000000000))*(py)*(x827)))+(((IkReal(-0.0750000000000000))*(x822)*(x832)))+(((IkReal(0.0750000000000000))*(x817)*(x824))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(0.0750000000000000))*(x821)))+(((IkReal(-1.00000000000000))*(sj3)*(x833)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-0.327500000000000))*(x836)))+(((x822)*(x831)*(x832)))+(((IkReal(-1.00000000000000))*(x831)*(x836)))+(((x818)*(x824)*(x831)))+(((x827)*(x830)))+(((IkReal(-1.00000000000000))*(cj3)*(x819)*(x820)))+(((x819)*(x828)))+(((IkReal(-0.327500000000000))*(x817)*(x824)))+(((x821)*(x826)))+(((x823)*(x824)))+(((IkReal(0.327500000000000))*(x822)*(x832)))+(((IkReal(0.0245625000000000))*(cj1)*(x822)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x827)*(x831)))+(((IkReal(-1.00000000000000))*(r02)*(x827)*(x828)))+(((IkReal(0.327500000000000))*(x818)*(x824)))+(((cj3)*(x822)*(x829)))+(((py)*(x826)*(x827)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x825)*(x834)))+(((IkReal(-0.0245625000000000))*(cj0)*(x819)))+(((px)*(x819)*(x831)))+(((IkReal(-1.00000000000000))*(x817)*(x824)*(x831))))))) < IKFAST_ATAN2_MAGTHRESH )
02489     continue;
02490 j2array[0]=IKatan2(((gconst5)*(((IkReal(-0.0982500000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x833)))+(((IkReal(0.327500000000000))*(x821)))+(((x821)*(x831)))+(((IkReal(-1.00000000000000))*(x822)*(x826)*(x832)))+(((IkReal(0.0800000000000000))*(r02)*(x825)*(x827)))+(((IkReal(-0.0750000000000000))*(x818)*(x824)))+(((py)*(x827)*(x831)))+(((sj3)*(x819)*(x820)))+(((IkReal(-1.00000000000000))*(x818)*(x824)*(x826)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x822)*(x829)))+(((IkReal(0.00562500000000000))*(cj0)*(x819)))+(((x817)*(x824)*(x826)))+(((x826)*(x836)))+(((IkReal(-0.00562500000000000))*(cj1)*(x822)))+(((px)*(x824)*(x831)))+(((IkReal(-0.0800000000000000))*(x819)*(x825)))+(((r02)*(x823)*(x827)))+(((IkReal(-1.00000000000000))*(x819)*(x823)))+(((cj1)*(r00)*(x830)))+(((x824)*(x828)))+(((IkReal(0.327500000000000))*(py)*(x827)))+(((IkReal(-0.0750000000000000))*(x822)*(x832)))+(((IkReal(0.0750000000000000))*(x817)*(x824)))))), ((gconst5)*(((IkReal(-0.0225000000000000))+(((IkReal(0.0750000000000000))*(x821)))+(((IkReal(-1.00000000000000))*(sj3)*(x833)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((IkReal(-0.327500000000000))*(x836)))+(((x822)*(x831)*(x832)))+(((IkReal(-1.00000000000000))*(x831)*(x836)))+(((x818)*(x824)*(x831)))+(((x827)*(x830)))+(((IkReal(-1.00000000000000))*(cj3)*(x819)*(x820)))+(((x819)*(x828)))+(((IkReal(-0.327500000000000))*(x817)*(x824)))+(((x821)*(x826)))+(((x823)*(x824)))+(((IkReal(0.327500000000000))*(x822)*(x832)))+(((IkReal(0.0245625000000000))*(cj1)*(x822)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x827)*(x831)))+(((IkReal(-1.00000000000000))*(r02)*(x827)*(x828)))+(((IkReal(0.327500000000000))*(x818)*(x824)))+(((cj3)*(x822)*(x829)))+(((py)*(x826)*(x827)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x825)*(x834)))+(((IkReal(-0.0245625000000000))*(cj0)*(x819)))+(((px)*(x819)*(x831)))+(((IkReal(-1.00000000000000))*(x817)*(x824)*(x831)))))));
02491 sj2array[0]=IKsin(j2array[0]);
02492 cj2array[0]=IKcos(j2array[0]);
02493 if( j2array[0] > IKPI )
02494 {
02495     j2array[0]-=IK2PI;
02496 }
02497 else if( j2array[0] < -IKPI )
02498 {    j2array[0]+=IK2PI;
02499 }
02500 j2valid[0] = true;
02501 for(int ij2 = 0; ij2 < 1; ++ij2)
02502 {
02503 if( !j2valid[ij2] )
02504 {
02505     continue;
02506 }
02507 _ij2[0] = ij2; _ij2[1] = -1;
02508 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02509 {
02510 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02511 {
02512     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02513 }
02514 }
02515 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02516 {
02517 IkReal evalcond[4];
02518 IkReal x838=IKcos(j2);
02519 IkReal x839=IKsin(j2);
02520 IkReal x840=((IkReal(0.0800000000000000))*(sj3));
02521 IkReal x841=((cj0)*(r01));
02522 IkReal x842=((IkReal(1.00000000000000))*(px));
02523 IkReal x843=((py)*(sj1));
02524 IkReal x844=((cj0)*(r02));
02525 IkReal x845=((IkReal(0.0750000000000000))*(cj1));
02526 IkReal x846=((r02)*(sj0));
02527 IkReal x847=((IkReal(0.0750000000000000))*(sj1));
02528 IkReal x848=((cj1)*(pz));
02529 IkReal x849=((r00)*(sj0));
02530 IkReal x850=((IkReal(0.0800000000000000))*(cj3));
02531 IkReal x851=((pz)*(sj1));
02532 IkReal x852=((IkReal(1.00000000000000))*(sj0));
02533 IkReal x853=((cj1)*(py));
02534 IkReal x854=((IkReal(0.0750000000000000))*(x839));
02535 IkReal x855=((IkReal(0.327500000000000))*(x838));
02536 IkReal x856=((IkReal(0.0750000000000000))*(x838));
02537 IkReal x857=((IkReal(0.327500000000000))*(x839));
02538 IkReal x858=((sj1)*(x849));
02539 IkReal x859=((x839)*(x840));
02540 IkReal x860=((x838)*(x850));
02541 IkReal x861=((x838)*(x840));
02542 IkReal x862=((x839)*(x850));
02543 IkReal x863=((x854)+(x859));
02544 IkReal x864=((x860)+(x855));
02545 IkReal x865=((x862)+(x861)+(x856)+(x857));
02546 evalcond[0]=((((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x842)))+(x864)+(x845)+(((IkReal(-1.00000000000000))*(x863)))+(x851)+(((IkReal(-1.00000000000000))*(x852)*(x853))));
02547 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x842)))+(((IkReal(-1.00000000000000))*(x843)*(x852)))+(x865)+(x847)+(((IkReal(-1.00000000000000))*(x848))));
02548 evalcond[2]=((((x843)*(x844)))+(((IkReal(-1.00000000000000))*(x864)))+(((IkReal(-1.00000000000000))*(x841)*(x851)))+(x863)+(((x849)*(x851)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x841)*(x845)))+(((IkReal(-1.00000000000000))*(r00)*(x853)))+(((x845)*(x849)))+(((IkReal(-1.00000000000000))*(sj1)*(x842)*(x846))));
02549 evalcond[3]=((((IkReal(-1.00000000000000))*(x847)*(x849)))+(((IkReal(-0.300000000000000))*(x849)))+(((x848)*(x849)))+(((r00)*(x843)))+(((x844)*(x853)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x842)))+(x865)+(((IkReal(-1.00000000000000))*(x841)*(x848)))+(((x841)*(x847)))+(((IkReal(0.300000000000000))*(x841)))+(((IkReal(-1.00000000000000))*(cj1)*(x842)*(x846))));
02550 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02551 {
02552 continue;
02553 }
02554 }
02555 
02556 {
02557 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02558 vinfos[0].jointtype = 1;
02559 vinfos[0].foffset = j0;
02560 vinfos[0].indices[0] = _ij0[0];
02561 vinfos[0].indices[1] = _ij0[1];
02562 vinfos[0].maxsolutions = _nj0;
02563 vinfos[1].jointtype = 1;
02564 vinfos[1].foffset = j1;
02565 vinfos[1].indices[0] = _ij1[0];
02566 vinfos[1].indices[1] = _ij1[1];
02567 vinfos[1].maxsolutions = _nj1;
02568 vinfos[2].jointtype = 1;
02569 vinfos[2].foffset = j2;
02570 vinfos[2].indices[0] = _ij2[0];
02571 vinfos[2].indices[1] = _ij2[1];
02572 vinfos[2].maxsolutions = _nj2;
02573 vinfos[3].jointtype = 1;
02574 vinfos[3].foffset = j3;
02575 vinfos[3].indices[0] = _ij3[0];
02576 vinfos[3].indices[1] = _ij3[1];
02577 vinfos[3].maxsolutions = _nj3;
02578 vinfos[4].jointtype = 1;
02579 vinfos[4].foffset = j4;
02580 vinfos[4].indices[0] = _ij4[0];
02581 vinfos[4].indices[1] = _ij4[1];
02582 vinfos[4].maxsolutions = _nj4;
02583 std::vector<int> vfree(0);
02584 solutions.AddSolution(vinfos,vfree);
02585 }
02586 }
02587 }
02588 
02589 }
02590 
02591 }
02592 
02593 } else
02594 {
02595 {
02596 IkReal j2array[1], cj2array[1], sj2array[1];
02597 bool j2valid[1]={false};
02598 _nj2 = 1;
02599 IkReal x866=((IkReal(0.0800000000000000))*(cj1));
02600 IkReal x867=((cj0)*(px));
02601 IkReal x868=((py)*(sj0));
02602 IkReal x869=((IkReal(0.0750000000000000))*(cj1));
02603 IkReal x870=((IkReal(0.327500000000000))*(cj1));
02604 IkReal x871=((IkReal(0.327500000000000))*(sj1));
02605 IkReal x872=((IkReal(0.0750000000000000))*(sj1));
02606 IkReal x873=((IkReal(0.00600000000000000))*(sj1));
02607 IkReal x874=((IkReal(0.00600000000000000))*(cj1));
02608 IkReal x875=((IkReal(0.0800000000000000))*(sj1)*(sj3));
02609 IkReal x876=((IkReal(0.0800000000000000))*(cj3)*(sj1));
02610 if( IKabs(((gconst4)*(((IkReal(-0.0982500000000000))+(((sj3)*(x874)))+(((x868)*(x871)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x867)*(x871)))+(((IkReal(-1.00000000000000))*(x867)*(x869)))+(((pz)*(x870)))+(((IkReal(-1.00000000000000))*(sj3)*(x866)*(x868)))+(((x868)*(x876)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(cj3)*(x873)))+(((IkReal(-1.00000000000000))*(x868)*(x869)))+(((pz)*(x872)))+(((x867)*(x876)))+(((IkReal(-1.00000000000000))*(sj3)*(x866)*(x867)))+(((pz)*(x875)))+(((cj3)*(pz)*(x866))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((cj3)*(x866)*(x868)))+(((x868)*(x870)))+(((IkReal(-1.00000000000000))*(sj3)*(x873)))+(((x868)*(x875)))+(((x867)*(x875)))+(((x867)*(x870)))+(((x868)*(x872)))+(((pz)*(x869)))+(((cj3)*(x866)*(x867)))+(((pz)*(sj3)*(x866)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x871)))+(((IkReal(-1.00000000000000))*(pz)*(x876)))+(((IkReal(-1.00000000000000))*(cj3)*(x874)))+(((x867)*(x872))))))) < IKFAST_ATAN2_MAGTHRESH )
02611     continue;
02612 j2array[0]=IKatan2(((gconst4)*(((IkReal(-0.0982500000000000))+(((sj3)*(x874)))+(((x868)*(x871)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((x867)*(x871)))+(((IkReal(-1.00000000000000))*(x867)*(x869)))+(((pz)*(x870)))+(((IkReal(-1.00000000000000))*(sj3)*(x866)*(x868)))+(((x868)*(x876)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(cj3)*(x873)))+(((IkReal(-1.00000000000000))*(x868)*(x869)))+(((pz)*(x872)))+(((x867)*(x876)))+(((IkReal(-1.00000000000000))*(sj3)*(x866)*(x867)))+(((pz)*(x875)))+(((cj3)*(pz)*(x866)))))), ((gconst4)*(((IkReal(-0.0225000000000000))+(((IkReal(-0.0240000000000000))*(sj3)))+(((cj3)*(x866)*(x868)))+(((x868)*(x870)))+(((IkReal(-1.00000000000000))*(sj3)*(x873)))+(((x868)*(x875)))+(((x867)*(x875)))+(((x867)*(x870)))+(((x868)*(x872)))+(((pz)*(x869)))+(((cj3)*(x866)*(x867)))+(((pz)*(sj3)*(x866)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(pz)*(x871)))+(((IkReal(-1.00000000000000))*(pz)*(x876)))+(((IkReal(-1.00000000000000))*(cj3)*(x874)))+(((x867)*(x872)))))));
02613 sj2array[0]=IKsin(j2array[0]);
02614 cj2array[0]=IKcos(j2array[0]);
02615 if( j2array[0] > IKPI )
02616 {
02617     j2array[0]-=IK2PI;
02618 }
02619 else if( j2array[0] < -IKPI )
02620 {    j2array[0]+=IK2PI;
02621 }
02622 j2valid[0] = true;
02623 for(int ij2 = 0; ij2 < 1; ++ij2)
02624 {
02625 if( !j2valid[ij2] )
02626 {
02627     continue;
02628 }
02629 _ij2[0] = ij2; _ij2[1] = -1;
02630 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02631 {
02632 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02633 {
02634     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02635 }
02636 }
02637 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02638 {
02639 IkReal evalcond[4];
02640 IkReal x877=IKcos(j2);
02641 IkReal x878=IKsin(j2);
02642 IkReal x879=((IkReal(0.0800000000000000))*(sj3));
02643 IkReal x880=((cj0)*(r01));
02644 IkReal x881=((IkReal(1.00000000000000))*(px));
02645 IkReal x882=((py)*(sj1));
02646 IkReal x883=((cj0)*(r02));
02647 IkReal x884=((IkReal(0.0750000000000000))*(cj1));
02648 IkReal x885=((r02)*(sj0));
02649 IkReal x886=((IkReal(0.0750000000000000))*(sj1));
02650 IkReal x887=((cj1)*(pz));
02651 IkReal x888=((r00)*(sj0));
02652 IkReal x889=((IkReal(0.0800000000000000))*(cj3));
02653 IkReal x890=((pz)*(sj1));
02654 IkReal x891=((IkReal(1.00000000000000))*(sj0));
02655 IkReal x892=((cj1)*(py));
02656 IkReal x893=((IkReal(0.0750000000000000))*(x878));
02657 IkReal x894=((IkReal(0.327500000000000))*(x877));
02658 IkReal x895=((IkReal(0.0750000000000000))*(x877));
02659 IkReal x896=((IkReal(0.327500000000000))*(x878));
02660 IkReal x897=((sj1)*(x888));
02661 IkReal x898=((x878)*(x879));
02662 IkReal x899=((x877)*(x889));
02663 IkReal x900=((x877)*(x879));
02664 IkReal x901=((x878)*(x889));
02665 IkReal x902=((x893)+(x898));
02666 IkReal x903=((x894)+(x899));
02667 IkReal x904=((x900)+(x901)+(x896)+(x895));
02668 evalcond[0]=((((IkReal(-1.00000000000000))*(x891)*(x892)))+(x884)+(((IkReal(-1.00000000000000))*(x902)))+(x903)+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x881)))+(x890));
02669 evalcond[1]=((IkReal(0.300000000000000))+(x886)+(((IkReal(-1.00000000000000))*(x887)))+(x904)+(((IkReal(-1.00000000000000))*(x882)*(x891)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x881))));
02670 evalcond[2]=((((cj1)*(px)*(r01)))+(x902)+(((IkReal(-1.00000000000000))*(x903)))+(((IkReal(-1.00000000000000))*(r00)*(x892)))+(((IkReal(-1.00000000000000))*(x880)*(x890)))+(((IkReal(-1.00000000000000))*(x880)*(x884)))+(((IkReal(-1.00000000000000))*(sj1)*(x881)*(x885)))+(((x884)*(x888)))+(((x882)*(x883)))+(((x888)*(x890))));
02671 evalcond[3]=((((IkReal(0.300000000000000))*(x880)))+(((x887)*(x888)))+(((IkReal(-1.00000000000000))*(x880)*(x887)))+(((r00)*(x882)))+(((x883)*(x892)))+(((x880)*(x886)))+(((IkReal(-1.00000000000000))*(x886)*(x888)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x881)))+(((IkReal(-0.300000000000000))*(x888)))+(x904)+(((IkReal(-1.00000000000000))*(cj1)*(x881)*(x885))));
02672 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02673 {
02674 continue;
02675 }
02676 }
02677 
02678 {
02679 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02680 vinfos[0].jointtype = 1;
02681 vinfos[0].foffset = j0;
02682 vinfos[0].indices[0] = _ij0[0];
02683 vinfos[0].indices[1] = _ij0[1];
02684 vinfos[0].maxsolutions = _nj0;
02685 vinfos[1].jointtype = 1;
02686 vinfos[1].foffset = j1;
02687 vinfos[1].indices[0] = _ij1[0];
02688 vinfos[1].indices[1] = _ij1[1];
02689 vinfos[1].maxsolutions = _nj1;
02690 vinfos[2].jointtype = 1;
02691 vinfos[2].foffset = j2;
02692 vinfos[2].indices[0] = _ij2[0];
02693 vinfos[2].indices[1] = _ij2[1];
02694 vinfos[2].maxsolutions = _nj2;
02695 vinfos[3].jointtype = 1;
02696 vinfos[3].foffset = j3;
02697 vinfos[3].indices[0] = _ij3[0];
02698 vinfos[3].indices[1] = _ij3[1];
02699 vinfos[3].maxsolutions = _nj3;
02700 vinfos[4].jointtype = 1;
02701 vinfos[4].foffset = j4;
02702 vinfos[4].indices[0] = _ij4[0];
02703 vinfos[4].indices[1] = _ij4[1];
02704 vinfos[4].maxsolutions = _nj4;
02705 std::vector<int> vfree(0);
02706 solutions.AddSolution(vinfos,vfree);
02707 }
02708 }
02709 }
02710 
02711 }
02712 
02713 }
02714 
02715 } else
02716 {
02717 IkReal x905=((IkReal(0.0524000000000000))*(cj3));
02718 IkReal x906=((IkReal(0.0120000000000000))*(sj3));
02719 IkReal x907=(py)*(py);
02720 IkReal x908=(px)*(px);
02721 IkReal x909=(pz)*(pz);
02722 IkReal x910=((r01)*(sj0));
02723 IkReal x911=((py)*(r00));
02724 IkReal x912=((pz)*(sj1));
02725 IkReal x913=((py)*(r01));
02726 IkReal x914=((px)*(sj0));
02727 IkReal x915=((IkReal(0.600000000000000))*(r02));
02728 IkReal x916=((IkReal(0.150000000000000))*(cj1));
02729 IkReal x917=((cj0)*(sj1));
02730 IkReal x918=((IkReal(0.150000000000000))*(px));
02731 IkReal x919=((IkReal(2.00000000000000))*(cj1));
02732 IkReal x920=((cj0)*(r01));
02733 IkReal x921=((r02)*(sj1));
02734 IkReal x922=((px)*(r00));
02735 IkReal x923=((IkReal(0.300000000000000))*(r00));
02736 IkReal x924=((IkReal(1.00000000000000))*(pz));
02737 IkReal x925=((r00)*(sj1));
02738 IkReal x926=((cj0)*(r00));
02739 IkReal x927=((cj0)*(cj1));
02740 IkReal x928=((IkReal(1.00000000000000))*(sj1));
02741 IkReal x929=((IkReal(0.0956250000000000))*(r00));
02742 IkReal x930=((IkReal(0.600000000000000))*(pz));
02743 IkReal x931=((IkReal(0.600000000000000))*(sj1));
02744 IkReal x932=((IkReal(2.00000000000000))*(px));
02745 IkReal x933=((IkReal(2.00000000000000))*(sj1));
02746 IkReal x934=((IkReal(0.150000000000000))*(sj1));
02747 IkReal x935=((cj1)*(r02));
02748 IkReal x936=((cj0)*(px));
02749 IkReal x937=((IkReal(0.0843750000000000))*(cj1));
02750 IkReal x938=((py)*(sj0));
02751 IkReal x939=((pz)*(r02));
02752 IkReal x940=((IkReal(1.00000000000000))*(cj1));
02753 IkReal x941=((cj0)*(py));
02754 IkReal x942=((r00)*(sj0));
02755 IkReal x943=((r02)*(x938));
02756 IkReal x944=((pp)*(x940));
02757 IkReal x945=((IkReal(1.00000000000000))*(pp)*(r00));
02758 IkReal x946=((x905)+(x906));
02759 IkReal x947=((IkReal(2.00000000000000))*(r00)*(x908));
02760 IkReal x948=((cj0)*(x932)*(x939));
02761 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
02762 evalcond[1]=((((IkReal(-1.00000000000000))*(x914)))+(x941));
02763 evalcond[2]=((IkReal(1.00000000000000))+(x920)+(((IkReal(-1.00000000000000))*(x942))));
02764 evalcond[3]=((x921)+(((IkReal(-1.00000000000000))*(x910)*(x940)))+(((IkReal(-1.00000000000000))*(x926)*(x940))));
02765 evalcond[4]=((((IkReal(-1.00000000000000))*(x910)*(x928)))+(((IkReal(-1.00000000000000))*(x935)))+(((IkReal(-1.00000000000000))*(r00)*(x917))));
02766 evalcond[5]=((IkReal(0.0236562500000000))+(((IkReal(-1.00000000000000))*(pp)))+(x946)+(((IkReal(0.150000000000000))*(x938)))+(((IkReal(0.600000000000000))*(px)*(x917)))+(((cj0)*(x918)))+(((x931)*(x938)))+(((IkReal(-0.0450000000000000))*(sj1)))+(((cj1)*(x930))));
02767 evalcond[6]=((((x917)*(x923)))+(((IkReal(-1.00000000000000))*(x913)))+(((IkReal(0.300000000000000))*(x935)))+(((IkReal(0.300000000000000))*(sj1)*(x910)))+(((IkReal(-1.00000000000000))*(r02)*(x924)))+(((IkReal(0.0750000000000000))*(x926)))+(((IkReal(-1.00000000000000))*(x922)))+(((IkReal(0.0750000000000000))*(x910))));
02768 evalcond[7]=((((IkReal(0.300000000000000))*(cj1)*(x910)))+(x943)+(((IkReal(-0.300000000000000))*(x921)))+(((IkReal(-1.00000000000000))*(x924)*(x926)))+(((x923)*(x927)))+(((IkReal(-1.00000000000000))*(x910)*(x924)))+(((IkReal(-0.0750000000000000))*(r02)))+(((r02)*(x936))));
02769 evalcond[8]=((IkReal(0.119281250000000))+(((cj1)*(x930)*(x942)))+(((IkReal(-2.00000000000000))*(x939)*(x941)))+(((pp)*(x920)))+(((IkReal(0.0956250000000000))*(x920)))+(((IkReal(0.0450000000000000))*(r01)*(x917)))+(((IkReal(-1.00000000000000))*(r01)*(x918)))+(x946)+(((IkReal(-1.00000000000000))*(px)*(r01)*(x931)))+(((IkReal(2.00000000000000))*(x908)*(x942)))+(((IkReal(0.150000000000000))*(x911)))+(((IkReal(-2.00000000000000))*(x907)*(x920)))+(((py)*(x915)*(x927)))+(((IkReal(-1.00000000000000))*(cj0)*(x911)*(x932)))+(((IkReal(-1.00000000000000))*(cj1)*(x914)*(x915)))+(((IkReal(2.00000000000000))*(x914)*(x939)))+(((x911)*(x931)))+(((IkReal(-1.00000000000000))*(cj1)*(x920)*(x930)))+(((py)*(x910)*(x932)))+(((IkReal(-1.00000000000000))*(sj0)*(x929)))+(((IkReal(-1.00000000000000))*(pp)*(x942)))+(((IkReal(-0.0450000000000000))*(sj0)*(x925))));
02770 evalcond[9]=((((x917)*(x947)))+(((IkReal(0.0450000000000000))*(x926)))+(((r02)*(x916)*(x936)))+(((IkReal(-0.150000000000000))*(r02)*(x912)))+(((IkReal(-1.00000000000000))*(pz)*(x910)*(x916)))+(((IkReal(-1.00000000000000))*(pp)*(x910)*(x928)))+(((x911)*(x914)*(x933)))+(((IkReal(-1.00000000000000))*(pp)*(x935)))+(((pz)*(x913)*(x919)))+(((x916)*(x943)))+(((IkReal(-0.600000000000000))*(x922)))+(((IkReal(-0.600000000000000))*(x913)))+(((IkReal(0.0843750000000000))*(x935)))+(((IkReal(2.00000000000000))*(x912)*(x943)))+(((IkReal(-1.00000000000000))*(x917)*(x945)))+(((x917)*(x929)))+(((pz)*(x919)*(x922)))+(((IkReal(-1.00000000000000))*(x913)*(x934)))+(((IkReal(-1.00000000000000))*(pz)*(x916)*(x926)))+(((r02)*(x909)*(x919)))+(((IkReal(0.0956250000000000))*(sj1)*(x910)))+(((x907)*(x910)*(x933)))+(((IkReal(-1.00000000000000))*(x918)*(x925)))+(((IkReal(-1.00000000000000))*(pz)*(x915)))+(((x913)*(x917)*(x932)))+(((cj0)*(r02)*(x912)*(x932)))+(((IkReal(0.0450000000000000))*(x910))));
02771 evalcond[10]=((((IkReal(0.0956250000000000))*(x921)))+(((x910)*(x930)))+(((x911)*(x914)*(x919)))+(((IkReal(0.0450000000000000))*(r02)))+(((x919)*(x938)*(x939)))+(((IkReal(-1.00000000000000))*(x910)*(x944)))+(((IkReal(-1.00000000000000))*(x910)*(x937)))+(((x919)*(x936)*(x939)))+(((IkReal(-1.00000000000000))*(x915)*(x938)))+(((IkReal(-1.00000000000000))*(x916)*(x922)))+(((x908)*(x919)*(x926)))+(((IkReal(-1.00000000000000))*(x913)*(x916)))+(((IkReal(-1.00000000000000))*(x915)*(x936)))+(((IkReal(-1.00000000000000))*(x916)*(x939)))+(((x913)*(x919)*(x936)))+(((IkReal(-1.00000000000000))*(x926)*(x944)))+(((IkReal(-2.00000000000000))*(x912)*(x913)))+(((IkReal(-0.150000000000000))*(x921)*(x938)))+(((IkReal(0.150000000000000))*(x910)*(x912)))+(((pp)*(x921)))+(((IkReal(-2.00000000000000))*(x909)*(x921)))+(((IkReal(0.150000000000000))*(x912)*(x926)))+(((IkReal(-2.00000000000000))*(x912)*(x922)))+(((IkReal(-1.00000000000000))*(x926)*(x937)))+(((x926)*(x930)))+(((x907)*(x910)*(x919)))+(((IkReal(-1.00000000000000))*(r02)*(x917)*(x918))));
02772 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  )
02773 {
02774 {
02775 IkReal dummyeval[1];
02776 IkReal gconst6;
02777 gconst6=IKsign(((IkReal(0.112881250000000))+(((IkReal(0.0524000000000000))*(cj3)))+(((IkReal(0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(0.0120000000000000))*(sj3)))));
02778 dummyeval[0]=((IkReal(17.6376953125000))+(((IkReal(8.18750000000000))*(cj3)))+((cj3)*(cj3))+(((IkReal(1.87500000000000))*(sj3)))+((sj3)*(sj3)));
02779 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02780 {
02781 {
02782 IkReal dummyeval[1];
02783 IkReal gconst7;
02784 gconst7=IKsign(((IkReal(-0.112881250000000))+(((IkReal(-0.00640000000000000))*((sj3)*(sj3))))+(((IkReal(-0.0120000000000000))*(sj3)))+(((IkReal(-0.00640000000000000))*((cj3)*(cj3))))+(((IkReal(-0.0524000000000000))*(cj3)))));
02785 dummyeval[0]=((IkReal(-17.6376953125000))+(((IkReal(-1.87500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*((cj3)*(cj3))))+(((IkReal(-8.18750000000000))*(cj3)))+(((IkReal(-1.00000000000000))*((sj3)*(sj3)))));
02786 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02787 {
02788 continue;
02789 
02790 } else
02791 {
02792 {
02793 IkReal j2array[1], cj2array[1], sj2array[1];
02794 bool j2valid[1]={false};
02795 _nj2 = 1;
02796 IkReal x949=((cj0)*(r01));
02797 IkReal x950=((pz)*(sj1));
02798 IkReal x951=((IkReal(0.0800000000000000))*(sj3));
02799 IkReal x952=((IkReal(0.00600000000000000))*(cj1));
02800 IkReal x953=((IkReal(0.0750000000000000))*(cj1));
02801 IkReal x954=((r00)*(sj0));
02802 IkReal x955=((IkReal(0.0245625000000000))*(cj1));
02803 IkReal x956=((px)*(r01));
02804 IkReal x957=((IkReal(0.00562500000000000))*(cj1));
02805 IkReal x958=((IkReal(0.0800000000000000))*(cj3));
02806 IkReal x959=((cj1)*(pz));
02807 IkReal x960=((px)*(r02));
02808 IkReal x961=((py)*(sj1));
02809 IkReal x962=((cj0)*(r02));
02810 IkReal x963=((IkReal(0.00600000000000000))*(sj1));
02811 IkReal x964=((IkReal(0.327500000000000))*(sj0));
02812 IkReal x965=((IkReal(0.0750000000000000))*(sj0)*(sj1));
02813 IkReal x966=((cj0)*(px)*(sj1));
02814 IkReal x967=((cj1)*(py)*(r00));
02815 IkReal x968=((IkReal(0.0800000000000000))*(sj0)*(sj1)*(x960));
02816 if( IKabs(((gconst7)*(((IkReal(0.0982500000000000))+(((IkReal(-1.00000000000000))*(x951)*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(cj1)*(x951)*(x956)))+(((sj3)*(x949)*(x952)))+(((IkReal(-1.00000000000000))*(x958)*(x966)))+(((IkReal(-1.00000000000000))*(sj3)*(x952)*(x954)))+(((IkReal(-0.327500000000000))*(x966)))+(((IkReal(-0.0750000000000000))*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(sj0)*(x958)*(x961)))+(((IkReal(-0.327500000000000))*(x959)))+(((IkReal(-1.00000000000000))*(x954)*(x957)))+(((py)*(r00)*(x953)))+(((IkReal(-1.00000000000000))*(x961)*(x964)))+(((IkReal(0.0245625000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x950)*(x951)*(x954)))+(((x949)*(x957)))+(((cj3)*(x963)))+(((x949)*(x950)*(x951)))+(((IkReal(0.0750000000000000))*(x949)*(x950)))+(((IkReal(-1.00000000000000))*(x953)*(x956)))+(((IkReal(-0.0750000000000000))*(x950)*(x954)))+(((sj0)*(sj1)*(x951)*(x960)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x951)*(x967)))+(((IkReal(-1.00000000000000))*(x958)*(x959)))+(((x960)*(x965))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((IkReal(0.0225000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x949)*(x952)))+(((IkReal(-0.0750000000000000))*(sj0)*(x961)))+(((IkReal(-1.00000000000000))*(x951)*(x959)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-0.327500000000000))*(x967)))+(((IkReal(-1.00000000000000))*(x951)*(x966)))+(((x950)*(x954)*(x958)))+(((IkReal(0.327500000000000))*(x961)*(x962)))+(((cj3)*(x952)*(x954)))+(((IkReal(-1.00000000000000))*(pz)*(x953)))+(((IkReal(-1.00000000000000))*(sj0)*(x951)*(x961)))+(((IkReal(-0.0750000000000000))*(x966)))+(((IkReal(-1.00000000000000))*(sj0)*(sj1)*(x958)*(x960)))+(((IkReal(-0.327500000000000))*(x949)*(x950)))+(((IkReal(-1.00000000000000))*(x958)*(x967)))+(((IkReal(0.327500000000000))*(x950)*(x954)))+(((sj3)*(x963)))+(((x958)*(x961)*(x962)))+(((cj1)*(x956)*(x958)))+(((IkReal(-1.00000000000000))*(sj1)*(x960)*(x964)))+(((IkReal(-1.00000000000000))*(x949)*(x950)*(x958)))+(((IkReal(-1.00000000000000))*(x949)*(x955)))+(((IkReal(0.327500000000000))*(cj1)*(x956)))+(((IkReal(0.0240000000000000))*(sj3)))+(((x954)*(x955))))))) < IKFAST_ATAN2_MAGTHRESH )
02817     continue;
02818 j2array[0]=IKatan2(((gconst7)*(((IkReal(0.0982500000000000))+(((IkReal(-1.00000000000000))*(x951)*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(cj1)*(x951)*(x956)))+(((sj3)*(x949)*(x952)))+(((IkReal(-1.00000000000000))*(x958)*(x966)))+(((IkReal(-1.00000000000000))*(sj3)*(x952)*(x954)))+(((IkReal(-0.327500000000000))*(x966)))+(((IkReal(-0.0750000000000000))*(x961)*(x962)))+(((IkReal(-1.00000000000000))*(sj0)*(x958)*(x961)))+(((IkReal(-0.327500000000000))*(x959)))+(((IkReal(-1.00000000000000))*(x954)*(x957)))+(((py)*(r00)*(x953)))+(((IkReal(-1.00000000000000))*(x961)*(x964)))+(((IkReal(0.0245625000000000))*(sj1)))+(((IkReal(-1.00000000000000))*(x950)*(x951)*(x954)))+(((x949)*(x957)))+(((cj3)*(x963)))+(((x949)*(x950)*(x951)))+(((IkReal(0.0750000000000000))*(x949)*(x950)))+(((IkReal(-1.00000000000000))*(x953)*(x956)))+(((IkReal(-0.0750000000000000))*(x950)*(x954)))+(((sj0)*(sj1)*(x951)*(x960)))+(((IkReal(0.0240000000000000))*(cj3)))+(((x951)*(x967)))+(((IkReal(-1.00000000000000))*(x958)*(x959)))+(((x960)*(x965)))))), ((gconst7)*(((IkReal(0.0225000000000000))+(((IkReal(-1.00000000000000))*(cj3)*(x949)*(x952)))+(((IkReal(-0.0750000000000000))*(sj0)*(x961)))+(((IkReal(-1.00000000000000))*(x951)*(x959)))+(((IkReal(0.00562500000000000))*(sj1)))+(((IkReal(-0.327500000000000))*(x967)))+(((IkReal(-1.00000000000000))*(x951)*(x966)))+(((x950)*(x954)*(x958)))+(((IkReal(0.327500000000000))*(x961)*(x962)))+(((cj3)*(x952)*(x954)))+(((IkReal(-1.00000000000000))*(pz)*(x953)))+(((IkReal(-1.00000000000000))*(sj0)*(x951)*(x961)))+(((IkReal(-0.0750000000000000))*(x966)))+(((IkReal(-1.00000000000000))*(sj0)*(sj1)*(x958)*(x960)))+(((IkReal(-0.327500000000000))*(x949)*(x950)))+(((IkReal(-1.00000000000000))*(x958)*(x967)))+(((IkReal(0.327500000000000))*(x950)*(x954)))+(((sj3)*(x963)))+(((x958)*(x961)*(x962)))+(((cj1)*(x956)*(x958)))+(((IkReal(-1.00000000000000))*(sj1)*(x960)*(x964)))+(((IkReal(-1.00000000000000))*(x949)*(x950)*(x958)))+(((IkReal(-1.00000000000000))*(x949)*(x955)))+(((IkReal(0.327500000000000))*(cj1)*(x956)))+(((IkReal(0.0240000000000000))*(sj3)))+(((x954)*(x955)))))));
02819 sj2array[0]=IKsin(j2array[0]);
02820 cj2array[0]=IKcos(j2array[0]);
02821 if( j2array[0] > IKPI )
02822 {
02823     j2array[0]-=IK2PI;
02824 }
02825 else if( j2array[0] < -IKPI )
02826 {    j2array[0]+=IK2PI;
02827 }
02828 j2valid[0] = true;
02829 for(int ij2 = 0; ij2 < 1; ++ij2)
02830 {
02831 if( !j2valid[ij2] )
02832 {
02833     continue;
02834 }
02835 _ij2[0] = ij2; _ij2[1] = -1;
02836 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02837 {
02838 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02839 {
02840     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02841 }
02842 }
02843 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02844 {
02845 IkReal evalcond[4];
02846 IkReal x969=IKcos(j2);
02847 IkReal x970=IKsin(j2);
02848 IkReal x971=((IkReal(0.0800000000000000))*(sj3));
02849 IkReal x972=((cj0)*(r01));
02850 IkReal x973=((IkReal(1.00000000000000))*(px));
02851 IkReal x974=((py)*(sj1));
02852 IkReal x975=((cj0)*(r02));
02853 IkReal x976=((IkReal(0.0750000000000000))*(cj1));
02854 IkReal x977=((r02)*(sj0));
02855 IkReal x978=((IkReal(0.0750000000000000))*(sj1));
02856 IkReal x979=((cj1)*(pz));
02857 IkReal x980=((r00)*(sj0));
02858 IkReal x981=((IkReal(0.0800000000000000))*(cj3));
02859 IkReal x982=((pz)*(sj1));
02860 IkReal x983=((IkReal(1.00000000000000))*(sj0));
02861 IkReal x984=((cj1)*(py));
02862 IkReal x985=((IkReal(0.327500000000000))*(x969));
02863 IkReal x986=((IkReal(0.0750000000000000))*(x970));
02864 IkReal x987=((IkReal(0.0750000000000000))*(x969));
02865 IkReal x988=((IkReal(0.327500000000000))*(x970));
02866 IkReal x989=((sj1)*(x980));
02867 IkReal x990=((x969)*(x981));
02868 IkReal x991=((x970)*(x971));
02869 IkReal x992=((x969)*(x971));
02870 IkReal x993=((x970)*(x981));
02871 IkReal x994=((x986)+(x991));
02872 IkReal x995=((x985)+(x990));
02873 IkReal x996=((x988)+(x987)+(x993)+(x992));
02874 evalcond[0]=((((IkReal(-1.00000000000000))*(x994)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x973)))+(x976)+(x982)+(((IkReal(-1.00000000000000))*(x983)*(x984)))+(x995));
02875 evalcond[1]=((IkReal(0.300000000000000))+(x978)+(((IkReal(-1.00000000000000))*(x979)))+(((IkReal(-1.00000000000000))*(x974)*(x983)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x973)))+(x996));
02876 evalcond[2]=((((IkReal(-1.00000000000000))*(x972)*(x976)))+(((IkReal(-1.00000000000000))*(x994)))+(((x980)*(x982)))+(((IkReal(-1.00000000000000))*(r00)*(x984)))+(((cj1)*(px)*(r01)))+(((IkReal(-1.00000000000000))*(x972)*(x982)))+(((x976)*(x980)))+(((x974)*(x975)))+(((IkReal(-1.00000000000000))*(sj1)*(x973)*(x977)))+(x995));
02877 evalcond[3]=((((x979)*(x980)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x973)))+(((IkReal(-0.300000000000000))*(x980)))+(((x972)*(x978)))+(((IkReal(0.300000000000000))*(x972)))+(((IkReal(-1.00000000000000))*(x978)*(x980)))+(((IkReal(-1.00000000000000))*(x996)))+(((IkReal(-1.00000000000000))*(cj1)*(x973)*(x977)))+(((IkReal(-1.00000000000000))*(x972)*(x979)))+(((x975)*(x984)))+(((r00)*(x974))));
02878 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02879 {
02880 continue;
02881 }
02882 }
02883 
02884 {
02885 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02886 vinfos[0].jointtype = 1;
02887 vinfos[0].foffset = j0;
02888 vinfos[0].indices[0] = _ij0[0];
02889 vinfos[0].indices[1] = _ij0[1];
02890 vinfos[0].maxsolutions = _nj0;
02891 vinfos[1].jointtype = 1;
02892 vinfos[1].foffset = j1;
02893 vinfos[1].indices[0] = _ij1[0];
02894 vinfos[1].indices[1] = _ij1[1];
02895 vinfos[1].maxsolutions = _nj1;
02896 vinfos[2].jointtype = 1;
02897 vinfos[2].foffset = j2;
02898 vinfos[2].indices[0] = _ij2[0];
02899 vinfos[2].indices[1] = _ij2[1];
02900 vinfos[2].maxsolutions = _nj2;
02901 vinfos[3].jointtype = 1;
02902 vinfos[3].foffset = j3;
02903 vinfos[3].indices[0] = _ij3[0];
02904 vinfos[3].indices[1] = _ij3[1];
02905 vinfos[3].maxsolutions = _nj3;
02906 vinfos[4].jointtype = 1;
02907 vinfos[4].foffset = j4;
02908 vinfos[4].indices[0] = _ij4[0];
02909 vinfos[4].indices[1] = _ij4[1];
02910 vinfos[4].maxsolutions = _nj4;
02911 std::vector<int> vfree(0);
02912 solutions.AddSolution(vinfos,vfree);
02913 }
02914 }
02915 }
02916 
02917 }
02918 
02919 }
02920 
02921 } else
02922 {
02923 {
02924 IkReal j2array[1], cj2array[1], sj2array[1];
02925 bool j2valid[1]={false};
02926 _nj2 = 1;
02927 IkReal x997=((IkReal(0.0800000000000000))*(cj1));
02928 IkReal x998=((cj0)*(px));
02929 IkReal x999=((py)*(sj0));
02930 IkReal x1000=((IkReal(0.0750000000000000))*(cj1));
02931 IkReal x1001=((IkReal(0.327500000000000))*(cj1));
02932 IkReal x1002=((IkReal(0.327500000000000))*(sj1));
02933 IkReal x1003=((IkReal(0.0750000000000000))*(sj1));
02934 IkReal x1004=((IkReal(0.00600000000000000))*(sj1));
02935 IkReal x1005=((IkReal(0.00600000000000000))*(cj1));
02936 IkReal x1006=((IkReal(0.0800000000000000))*(sj1)*(sj3));
02937 IkReal x1007=((IkReal(0.0800000000000000))*(cj3)*(sj1));
02938 if( IKabs(((gconst6)*(((IkReal(-0.0982500000000000))+(((pz)*(x1003)))+(((IkReal(-1.00000000000000))*(x1000)*(x998)))+(((x1002)*(x998)))+(((pz)*(x1001)))+(((sj3)*(x1005)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((pz)*(x1006)))+(((cj3)*(pz)*(x997)))+(((IkReal(-1.00000000000000))*(sj3)*(x997)*(x998)))+(((x1007)*(x999)))+(((x1007)*(x998)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x1000)*(x999)))+(((IkReal(-1.00000000000000))*(cj3)*(x1004)))+(((IkReal(-1.00000000000000))*(sj3)*(x997)*(x999)))+(((x1002)*(x999))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x1007)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x997)))+(((IkReal(-1.00000000000000))*(pz)*(x1002)))+(((x1003)*(x998)))+(((x1003)*(x999)))+(((cj3)*(x997)*(x998)))+(((IkReal(-1.00000000000000))*(sj3)*(x1004)))+(((IkReal(-1.00000000000000))*(cj3)*(x1005)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x1001)*(x998)))+(((cj3)*(x997)*(x999)))+(((x1001)*(x999)))+(((x1006)*(x998)))+(((pz)*(x1000)))+(((x1006)*(x999))))))) < IKFAST_ATAN2_MAGTHRESH )
02939     continue;
02940 j2array[0]=IKatan2(((gconst6)*(((IkReal(-0.0982500000000000))+(((pz)*(x1003)))+(((IkReal(-1.00000000000000))*(x1000)*(x998)))+(((x1002)*(x998)))+(((pz)*(x1001)))+(((sj3)*(x1005)))+(((IkReal(-0.0245625000000000))*(sj1)))+(((IkReal(-0.0240000000000000))*(cj3)))+(((pz)*(x1006)))+(((cj3)*(pz)*(x997)))+(((IkReal(-1.00000000000000))*(sj3)*(x997)*(x998)))+(((x1007)*(x999)))+(((x1007)*(x998)))+(((IkReal(0.00562500000000000))*(cj1)))+(((IkReal(-1.00000000000000))*(x1000)*(x999)))+(((IkReal(-1.00000000000000))*(cj3)*(x1004)))+(((IkReal(-1.00000000000000))*(sj3)*(x997)*(x999)))+(((x1002)*(x999)))))), ((gconst6)*(((IkReal(-0.0225000000000000))+(((IkReal(-1.00000000000000))*(pz)*(x1007)))+(((IkReal(-0.0240000000000000))*(sj3)))+(((pz)*(sj3)*(x997)))+(((IkReal(-1.00000000000000))*(pz)*(x1002)))+(((x1003)*(x998)))+(((x1003)*(x999)))+(((cj3)*(x997)*(x998)))+(((IkReal(-1.00000000000000))*(sj3)*(x1004)))+(((IkReal(-1.00000000000000))*(cj3)*(x1005)))+(((IkReal(-0.0245625000000000))*(cj1)))+(((IkReal(-0.00562500000000000))*(sj1)))+(((x1001)*(x998)))+(((cj3)*(x997)*(x999)))+(((x1001)*(x999)))+(((x1006)*(x998)))+(((pz)*(x1000)))+(((x1006)*(x999)))))));
02941 sj2array[0]=IKsin(j2array[0]);
02942 cj2array[0]=IKcos(j2array[0]);
02943 if( j2array[0] > IKPI )
02944 {
02945     j2array[0]-=IK2PI;
02946 }
02947 else if( j2array[0] < -IKPI )
02948 {    j2array[0]+=IK2PI;
02949 }
02950 j2valid[0] = true;
02951 for(int ij2 = 0; ij2 < 1; ++ij2)
02952 {
02953 if( !j2valid[ij2] )
02954 {
02955     continue;
02956 }
02957 _ij2[0] = ij2; _ij2[1] = -1;
02958 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02959 {
02960 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02961 {
02962     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02963 }
02964 }
02965 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02966 {
02967 IkReal evalcond[4];
02968 IkReal x1008=IKcos(j2);
02969 IkReal x1009=IKsin(j2);
02970 IkReal x1010=((IkReal(0.0800000000000000))*(sj3));
02971 IkReal x1011=((cj0)*(r01));
02972 IkReal x1012=((IkReal(1.00000000000000))*(px));
02973 IkReal x1013=((py)*(sj1));
02974 IkReal x1014=((cj0)*(r02));
02975 IkReal x1015=((IkReal(0.0750000000000000))*(cj1));
02976 IkReal x1016=((r02)*(sj0));
02977 IkReal x1017=((IkReal(0.0750000000000000))*(sj1));
02978 IkReal x1018=((cj1)*(pz));
02979 IkReal x1019=((r00)*(sj0));
02980 IkReal x1020=((IkReal(0.0800000000000000))*(cj3));
02981 IkReal x1021=((pz)*(sj1));
02982 IkReal x1022=((IkReal(1.00000000000000))*(sj0));
02983 IkReal x1023=((cj1)*(py));
02984 IkReal x1024=((IkReal(0.327500000000000))*(x1008));
02985 IkReal x1025=((IkReal(0.0750000000000000))*(x1009));
02986 IkReal x1026=((IkReal(0.0750000000000000))*(x1008));
02987 IkReal x1027=((IkReal(0.327500000000000))*(x1009));
02988 IkReal x1028=((sj1)*(x1019));
02989 IkReal x1029=((x1008)*(x1020));
02990 IkReal x1030=((x1009)*(x1010));
02991 IkReal x1031=((x1008)*(x1010));
02992 IkReal x1032=((x1009)*(x1020));
02993 IkReal x1033=((x1030)+(x1025));
02994 IkReal x1034=((x1024)+(x1029));
02995 IkReal x1035=((x1032)+(x1031)+(x1027)+(x1026));
02996 evalcond[0]=((x1034)+(((IkReal(-1.00000000000000))*(x1033)))+(((IkReal(-1.00000000000000))*(x1022)*(x1023)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1012)))+(x1015)+(x1021));
02997 evalcond[1]=((IkReal(0.300000000000000))+(((IkReal(-1.00000000000000))*(x1013)*(x1022)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x1012)))+(x1035)+(((IkReal(-1.00000000000000))*(x1018)))+(x1017));
02998 evalcond[2]=((((x1013)*(x1014)))+(((IkReal(-1.00000000000000))*(x1011)*(x1015)))+(((IkReal(-1.00000000000000))*(r00)*(x1023)))+(((IkReal(-1.00000000000000))*(x1011)*(x1021)))+(x1034)+(((IkReal(-1.00000000000000))*(x1033)))+(((IkReal(-1.00000000000000))*(sj1)*(x1012)*(x1016)))+(((cj1)*(px)*(r01)))+(((x1019)*(x1021)))+(((x1015)*(x1019))));
02999 evalcond[3]=((((r00)*(x1013)))+(((IkReal(-1.00000000000000))*(x1017)*(x1019)))+(((x1011)*(x1017)))+(((IkReal(-1.00000000000000))*(cj1)*(x1012)*(x1016)))+(((IkReal(-1.00000000000000))*(x1011)*(x1018)))+(((x1014)*(x1023)))+(((IkReal(-0.300000000000000))*(x1019)))+(((IkReal(-1.00000000000000))*(x1035)))+(((IkReal(0.300000000000000))*(x1011)))+(((x1018)*(x1019)))+(((IkReal(-1.00000000000000))*(r01)*(sj1)*(x1012))));
03000 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03001 {
03002 continue;
03003 }
03004 }
03005 
03006 {
03007 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03008 vinfos[0].jointtype = 1;
03009 vinfos[0].foffset = j0;
03010 vinfos[0].indices[0] = _ij0[0];
03011 vinfos[0].indices[1] = _ij0[1];
03012 vinfos[0].maxsolutions = _nj0;
03013 vinfos[1].jointtype = 1;
03014 vinfos[1].foffset = j1;
03015 vinfos[1].indices[0] = _ij1[0];
03016 vinfos[1].indices[1] = _ij1[1];
03017 vinfos[1].maxsolutions = _nj1;
03018 vinfos[2].jointtype = 1;
03019 vinfos[2].foffset = j2;
03020 vinfos[2].indices[0] = _ij2[0];
03021 vinfos[2].indices[1] = _ij2[1];
03022 vinfos[2].maxsolutions = _nj2;
03023 vinfos[3].jointtype = 1;
03024 vinfos[3].foffset = j3;
03025 vinfos[3].indices[0] = _ij3[0];
03026 vinfos[3].indices[1] = _ij3[1];
03027 vinfos[3].maxsolutions = _nj3;
03028 vinfos[4].jointtype = 1;
03029 vinfos[4].foffset = j4;
03030 vinfos[4].indices[0] = _ij4[0];
03031 vinfos[4].indices[1] = _ij4[1];
03032 vinfos[4].maxsolutions = _nj4;
03033 std::vector<int> vfree(0);
03034 solutions.AddSolution(vinfos,vfree);
03035 }
03036 }
03037 }
03038 
03039 }
03040 
03041 }
03042 
03043 } else
03044 {
03045 if( 1 )
03046 {
03047 continue;
03048 
03049 } else
03050 {
03051 }
03052 }
03053 }
03054 }
03055 
03056 } else
03057 {
03058 {
03059 IkReal j2array[1], cj2array[1], sj2array[1];
03060 bool j2valid[1]={false};
03061 _nj2 = 1;
03062 IkReal x1036=((r02)*(sj1));
03063 IkReal x1037=((cj0)*(px));
03064 IkReal x1038=((IkReal(0.0800000000000000))*(sj3));
03065 IkReal x1039=((cj4)*(sj3));
03066 IkReal x1040=((pz)*(sj1));
03067 IkReal x1041=((IkReal(0.0800000000000000))*(cj3));
03068 IkReal x1042=((IkReal(1.00000000000000))*(cj1));
03069 IkReal x1043=((py)*(sj0));
03070 IkReal x1044=((cj1)*(r01)*(sj0));
03071 IkReal x1045=((cj1)*(cj3)*(cj4));
03072 IkReal x1046=((cj0)*(cj1)*(r00));
03073 IkReal x1047=((IkReal(0.0800000000000000))*(x1046));
03074 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(x1039)*(x1042)*(x1043)))+(((x1039)*(x1040)))+(((IkReal(-0.327500000000000))*(x1046)))+(((IkReal(-1.00000000000000))*(x1041)*(x1044)))+(((IkReal(-0.327500000000000))*(x1044)))+(((x1036)*(x1041)))+(((IkReal(-1.00000000000000))*(x1037)*(x1039)*(x1042)))+(((IkReal(0.0750000000000000))*(cj1)*(x1039)))+(((IkReal(-1.00000000000000))*(x1041)*(x1046)))+(((IkReal(0.327500000000000))*(x1036))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((IkReal(0.0750000000000000))*(x1036)))+(((IkReal(-1.00000000000000))*(x1038)*(x1044)))+(((x1043)*(x1045)))+(((IkReal(-0.0750000000000000))*(x1044)))+(((IkReal(-0.0750000000000000))*(x1045)))+(((IkReal(-1.00000000000000))*(x1038)*(x1046)))+(((x1036)*(x1038)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x1040)))+(((IkReal(-0.0750000000000000))*(x1046)))+(((x1037)*(x1045))))))) < IKFAST_ATAN2_MAGTHRESH )
03075     continue;
03076 j2array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(x1039)*(x1042)*(x1043)))+(((x1039)*(x1040)))+(((IkReal(-0.327500000000000))*(x1046)))+(((IkReal(-1.00000000000000))*(x1041)*(x1044)))+(((IkReal(-0.327500000000000))*(x1044)))+(((x1036)*(x1041)))+(((IkReal(-1.00000000000000))*(x1037)*(x1039)*(x1042)))+(((IkReal(0.0750000000000000))*(cj1)*(x1039)))+(((IkReal(-1.00000000000000))*(x1041)*(x1046)))+(((IkReal(0.327500000000000))*(x1036)))))), ((gconst3)*(((((IkReal(0.0750000000000000))*(x1036)))+(((IkReal(-1.00000000000000))*(x1038)*(x1044)))+(((x1043)*(x1045)))+(((IkReal(-0.0750000000000000))*(x1044)))+(((IkReal(-0.0750000000000000))*(x1045)))+(((IkReal(-1.00000000000000))*(x1038)*(x1046)))+(((x1036)*(x1038)))+(((IkReal(-1.00000000000000))*(cj3)*(cj4)*(x1040)))+(((IkReal(-0.0750000000000000))*(x1046)))+(((x1037)*(x1045)))))));
03077 sj2array[0]=IKsin(j2array[0]);
03078 cj2array[0]=IKcos(j2array[0]);
03079 if( j2array[0] > IKPI )
03080 {
03081     j2array[0]-=IK2PI;
03082 }
03083 else if( j2array[0] < -IKPI )
03084 {    j2array[0]+=IK2PI;
03085 }
03086 j2valid[0] = true;
03087 for(int ij2 = 0; ij2 < 1; ++ij2)
03088 {
03089 if( !j2valid[ij2] )
03090 {
03091     continue;
03092 }
03093 _ij2[0] = ij2; _ij2[1] = -1;
03094 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03095 {
03096 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03097 {
03098     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03099 }
03100 }
03101 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03102 {
03103 IkReal evalcond[8];
03104 IkReal x1048=IKcos(j2);
03105 IkReal x1049=IKsin(j2);
03106 IkReal x1050=(py)*(py);
03107 IkReal x1051=(px)*(px);
03108 IkReal x1052=(pz)*(pz);
03109 IkReal x1053=((sj0)*(sj1));
03110 IkReal x1054=((IkReal(1.00000000000000))*(r01));
03111 IkReal x1055=((r00)*(sj1));
03112 IkReal x1056=((IkReal(0.0750000000000000))*(r00));
03113 IkReal x1057=((IkReal(0.0491250000000000))*(sj3));
03114 IkReal x1058=((cj1)*(r01));
03115 IkReal x1059=((IkReal(0.150000000000000))*(py));
03116 IkReal x1060=((pz)*(r02));
03117 IkReal x1061=((px)*(r02));
03118 IkReal x1062=((IkReal(0.0750000000000000))*(sj4));
03119 IkReal x1063=((cj1)*(sj0));
03120 IkReal x1064=((pz)*(r00));
03121 IkReal x1065=((IkReal(0.0750000000000000))*(cj0));
03122 IkReal x1066=((IkReal(2.00000000000000))*(cj0));
03123 IkReal x1067=((cj1)*(r02));
03124 IkReal x1068=((IkReal(0.150000000000000))*(sj1));
03125 IkReal x1069=((px)*(r00));
03126 IkReal x1070=((IkReal(2.00000000000000))*(py));
03127 IkReal x1071=((r02)*(sj1));
03128 IkReal x1072=((IkReal(0.150000000000000))*(cj1));
03129 IkReal x1073=((IkReal(0.108031250000000))*(cj3));
03130 IkReal x1074=((cj0)*(py));
03131 IkReal x1075=((r01)*(sj1));
03132 IkReal x1076=((IkReal(0.0800000000000000))*(cj3));
03133 IkReal x1077=((IkReal(0.150000000000000))*(pz));
03134 IkReal x1078=((IkReal(0.0491250000000000))*(cj3));
03135 IkReal x1079=((cj1)*(pz));
03136 IkReal x1080=((IkReal(0.0952312500000000))*(sj3));
03137 IkReal x1081=((IkReal(0.600000000000000))*(py));
03138 IkReal x1082=((IkReal(1.00000000000000))*(py));
03139 IkReal x1083=((px)*(sj1));
03140 IkReal x1084=((IkReal(1.00000000000000))*(cj0));
03141 IkReal x1085=((cj0)*(r00));
03142 IkReal x1086=((IkReal(0.600000000000000))*(cj0));
03143 IkReal x1087=((IkReal(1.00000000000000))*(sj3));
03144 IkReal x1088=((pz)*(sj1));
03145 IkReal x1089=((IkReal(0.0800000000000000))*(sj3));
03146 IkReal x1090=((px)*(py));
03147 IkReal x1091=((cj1)*(r00));
03148 IkReal x1092=((r01)*(sj0));
03149 IkReal x1093=((cj1)*(px));
03150 IkReal x1094=((cj4)*(x1049));
03151 IkReal x1095=((cj4)*(x1048));
03152 IkReal x1096=((sj4)*(x1049));
03153 IkReal x1097=((IkReal(2.00000000000000))*(x1052));
03154 IkReal x1098=((sj4)*(x1048));
03155 IkReal x1099=((IkReal(2.00000000000000))*(x1050));
03156 IkReal x1100=((x1048)*(x1089));
03157 IkReal x1101=((px)*(x1060)*(x1066));
03158 evalcond[0]=((((IkReal(-1.00000000000000))*(x1084)*(x1091)))+(((IkReal(-1.00000000000000))*(x1087)*(x1095)))+(((IkReal(-1.00000000000000))*(x1054)*(x1063)))+(((IkReal(-1.00000000000000))*(cj3)*(x1094)))+(x1071));
03159 evalcond[1]=((((IkReal(-1.00000000000000))*(x1067)))+(((IkReal(-1.00000000000000))*(x1087)*(x1094)))+(((IkReal(-1.00000000000000))*(x1053)*(x1054)))+(((cj3)*(x1095)))+(((IkReal(-1.00000000000000))*(x1055)*(x1084))));
03160 evalcond[2]=((x1088)+(((IkReal(-0.0750000000000000))*(x1049)))+(((x1048)*(x1076)))+(((IkReal(-1.00000000000000))*(x1084)*(x1093)))+(((IkReal(0.327500000000000))*(x1048)))+(((IkReal(-1.00000000000000))*(x1049)*(x1089)))+(((IkReal(-1.00000000000000))*(x1063)*(x1082)))+(((IkReal(0.0750000000000000))*(cj1))));
03161 evalcond[3]=((IkReal(0.300000000000000))+(x1100)+(((IkReal(0.327500000000000))*(x1049)))+(((IkReal(-1.00000000000000))*(x1083)*(x1084)))+(((IkReal(-1.00000000000000))*(x1079)))+(((IkReal(0.0750000000000000))*(x1048)))+(((IkReal(-1.00000000000000))*(x1053)*(x1082)))+(((IkReal(0.0750000000000000))*(sj1)))+(((x1049)*(x1076))));
03162 evalcond[4]=((((IkReal(-1.00000000000000))*(x1076)*(x1098)))+(((x1089)*(x1096)))+(((x1049)*(x1062)))+(((x1053)*(x1064)))+(((x1071)*(x1074)))+(((IkReal(-1.00000000000000))*(x1082)*(x1091)))+(((IkReal(-1.00000000000000))*(x1058)*(x1065)))+(((x1056)*(x1063)))+(((px)*(x1058)))+(((IkReal(-1.00000000000000))*(cj0)*(x1054)*(x1088)))+(((IkReal(-0.327500000000000))*(x1098)))+(((IkReal(-1.00000000000000))*(x1053)*(x1061))));
03163 evalcond[5]=((((py)*(x1055)))+(((IkReal(-1.00000000000000))*(x1061)*(x1063)))+(((IkReal(-1.00000000000000))*(x1054)*(x1083)))+(((x1089)*(x1098)))+(((x1063)*(x1064)))+(((x1065)*(x1075)))+(((x1076)*(x1096)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((IkReal(-1.00000000000000))*(x1053)*(x1056)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(cj0)*(x1054)*(x1079)))+(((x1048)*(x1062)))+(((x1067)*(x1074)))+(((IkReal(0.327500000000000))*(x1096))));
03164 evalcond[6]=((((IkReal(0.0450000000000000))*(x1092)))+(((r01)*(x1053)*(x1099)))+(((IkReal(-1.00000000000000))*(x1078)*(x1094)))+(((r02)*(x1059)*(x1063)))+(((IkReal(0.0450000000000000))*(x1085)))+(((IkReal(2.00000000000000))*(x1064)*(x1093)))+(((pz)*(x1058)*(x1070)))+(((x1060)*(x1066)*(x1083)))+(((IkReal(-1.00000000000000))*(r01)*(x1081)))+(((cj0)*(x1061)*(x1072)))+(((IkReal(-1.00000000000000))*(cj0)*(x1064)*(x1072)))+(((x1080)*(x1094)))+(((IkReal(-0.600000000000000))*(x1060)))+(((x1057)*(x1095)))+(((IkReal(-1.00000000000000))*(pp)*(x1055)*(x1084)))+(((IkReal(-0.600000000000000))*(x1069)))+(((IkReal(0.0956250000000000))*(r01)*(x1053)))+(((IkReal(0.0843750000000000))*(x1067)))+(((IkReal(-1.00000000000000))*(pp)*(x1053)*(x1054)))+(((IkReal(-1.00000000000000))*(x1060)*(x1068)))+(((IkReal(0.0524000000000000))*(x1095)))+(((x1051)*(x1055)*(x1066)))+(((IkReal(-1.00000000000000))*(sj0)*(x1058)*(x1077)))+(((IkReal(-0.0120000000000000))*(x1094)))+(((x1053)*(x1060)*(x1070)))+(((IkReal(-1.00000000000000))*(pp)*(x1067)))+(((IkReal(-1.00000000000000))*(x1059)*(x1075)))+(((x1067)*(x1097)))+(((x1073)*(x1095)))+(((x1053)*(x1069)*(x1070)))+(((IkReal(-0.150000000000000))*(px)*(x1055)))+(((x1066)*(x1075)*(x1090)))+(((IkReal(0.0956250000000000))*(cj0)*(x1055))));
03165 evalcond[7]=((((x1060)*(x1063)*(x1070)))+(((IkReal(-1.00000000000000))*(x1058)*(x1059)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1081)))+(((IkReal(0.0956250000000000))*(x1071)))+(((IkReal(-1.00000000000000))*(x1060)*(x1072)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(-1.00000000000000))*(pz)*(x1070)*(x1075)))+(((x1051)*(x1066)*(x1091)))+(((IkReal(0.600000000000000))*(pz)*(x1092)))+(((x1060)*(x1066)*(x1093)))+(((r01)*(x1053)*(x1077)))+(((pp)*(x1071)))+(((x1063)*(x1069)*(x1070)))+(((IkReal(-0.0524000000000000))*(x1094)))+(((IkReal(-1.00000000000000))*(x1057)*(x1094)))+(((x1064)*(x1086)))+(((IkReal(-1.00000000000000))*(cj0)*(x1061)*(x1068)))+(((IkReal(-0.0843750000000000))*(cj1)*(x1085)))+(((IkReal(-1.00000000000000))*(x1078)*(x1095)))+(((IkReal(-1.00000000000000))*(x1073)*(x1094)))+(((IkReal(-1.00000000000000))*(x1069)*(x1072)))+(((cj0)*(x1055)*(x1077)))+(((IkReal(-2.00000000000000))*(px)*(pz)*(x1055)))+(((IkReal(-1.00000000000000))*(r02)*(x1053)*(x1059)))+(((x1080)*(x1095)))+(((sj0)*(x1058)*(x1099)))+(((IkReal(-1.00000000000000))*(x1061)*(x1086)))+(((IkReal(-1.00000000000000))*(pp)*(x1054)*(x1063)))+(((x1058)*(x1066)*(x1090)))+(((IkReal(-1.00000000000000))*(x1071)*(x1097)))+(((IkReal(-0.0120000000000000))*(x1095)))+(((IkReal(-0.0843750000000000))*(sj0)*(x1058)))+(((IkReal(-1.00000000000000))*(pp)*(x1084)*(x1091))));
03166 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  )
03167 {
03168 continue;
03169 }
03170 }
03171 
03172 {
03173 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03174 vinfos[0].jointtype = 1;
03175 vinfos[0].foffset = j0;
03176 vinfos[0].indices[0] = _ij0[0];
03177 vinfos[0].indices[1] = _ij0[1];
03178 vinfos[0].maxsolutions = _nj0;
03179 vinfos[1].jointtype = 1;
03180 vinfos[1].foffset = j1;
03181 vinfos[1].indices[0] = _ij1[0];
03182 vinfos[1].indices[1] = _ij1[1];
03183 vinfos[1].maxsolutions = _nj1;
03184 vinfos[2].jointtype = 1;
03185 vinfos[2].foffset = j2;
03186 vinfos[2].indices[0] = _ij2[0];
03187 vinfos[2].indices[1] = _ij2[1];
03188 vinfos[2].maxsolutions = _nj2;
03189 vinfos[3].jointtype = 1;
03190 vinfos[3].foffset = j3;
03191 vinfos[3].indices[0] = _ij3[0];
03192 vinfos[3].indices[1] = _ij3[1];
03193 vinfos[3].maxsolutions = _nj3;
03194 vinfos[4].jointtype = 1;
03195 vinfos[4].foffset = j4;
03196 vinfos[4].indices[0] = _ij4[0];
03197 vinfos[4].indices[1] = _ij4[1];
03198 vinfos[4].maxsolutions = _nj4;
03199 std::vector<int> vfree(0);
03200 solutions.AddSolution(vinfos,vfree);
03201 }
03202 }
03203 }
03204 
03205 }
03206 
03207 }
03208 
03209 } else
03210 {
03211 {
03212 IkReal j2array[1], cj2array[1], sj2array[1];
03213 bool j2valid[1]={false};
03214 _nj2 = 1;
03215 IkReal x1102=((IkReal(1.00000000000000))*(cj1));
03216 IkReal x1103=((cj0)*(r00));
03217 IkReal x1104=((cj3)*(r02));
03218 IkReal x1105=((sj1)*(sj3));
03219 IkReal x1106=((r01)*(sj0));
03220 IkReal x1107=((cj3)*(x1106));
03221 if( IKabs(((gconst2)*(((((sj1)*(x1104)))+(((IkReal(-1.00000000000000))*(x1103)*(x1105)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1102)))+(((IkReal(-1.00000000000000))*(x1105)*(x1106)))+(((IkReal(-1.00000000000000))*(cj3)*(x1102)*(x1103)))+(((IkReal(-1.00000000000000))*(x1102)*(x1107))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((sj1)*(x1107)))+(((r02)*(x1105)))+(((cj1)*(x1104)))+(((cj3)*(sj1)*(x1103)))+(((IkReal(-1.00000000000000))*(sj3)*(x1102)*(x1103)))+(((IkReal(-1.00000000000000))*(sj3)*(x1102)*(x1106))))))) < IKFAST_ATAN2_MAGTHRESH )
03222     continue;
03223 j2array[0]=IKatan2(((gconst2)*(((((sj1)*(x1104)))+(((IkReal(-1.00000000000000))*(x1103)*(x1105)))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x1102)))+(((IkReal(-1.00000000000000))*(x1105)*(x1106)))+(((IkReal(-1.00000000000000))*(cj3)*(x1102)*(x1103)))+(((IkReal(-1.00000000000000))*(x1102)*(x1107)))))), ((gconst2)*(((((sj1)*(x1107)))+(((r02)*(x1105)))+(((cj1)*(x1104)))+(((cj3)*(sj1)*(x1103)))+(((IkReal(-1.00000000000000))*(sj3)*(x1102)*(x1103)))+(((IkReal(-1.00000000000000))*(sj3)*(x1102)*(x1106)))))));
03224 sj2array[0]=IKsin(j2array[0]);
03225 cj2array[0]=IKcos(j2array[0]);
03226 if( j2array[0] > IKPI )
03227 {
03228     j2array[0]-=IK2PI;
03229 }
03230 else if( j2array[0] < -IKPI )
03231 {    j2array[0]+=IK2PI;
03232 }
03233 j2valid[0] = true;
03234 for(int ij2 = 0; ij2 < 1; ++ij2)
03235 {
03236 if( !j2valid[ij2] )
03237 {
03238     continue;
03239 }
03240 _ij2[0] = ij2; _ij2[1] = -1;
03241 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03242 {
03243 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03244 {
03245     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03246 }
03247 }
03248 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03249 {
03250 IkReal evalcond[8];
03251 IkReal x1108=IKcos(j2);
03252 IkReal x1109=IKsin(j2);
03253 IkReal x1110=(py)*(py);
03254 IkReal x1111=(px)*(px);
03255 IkReal x1112=(pz)*(pz);
03256 IkReal x1113=((sj0)*(sj1));
03257 IkReal x1114=((IkReal(1.00000000000000))*(r01));
03258 IkReal x1115=((r00)*(sj1));
03259 IkReal x1116=((IkReal(0.0750000000000000))*(r00));
03260 IkReal x1117=((IkReal(0.0491250000000000))*(sj3));
03261 IkReal x1118=((cj1)*(r01));
03262 IkReal x1119=((IkReal(0.150000000000000))*(py));
03263 IkReal x1120=((pz)*(r02));
03264 IkReal x1121=((px)*(r02));
03265 IkReal x1122=((IkReal(0.0750000000000000))*(sj4));
03266 IkReal x1123=((cj1)*(sj0));
03267 IkReal x1124=((pz)*(r00));
03268 IkReal x1125=((IkReal(0.0750000000000000))*(cj0));
03269 IkReal x1126=((IkReal(2.00000000000000))*(cj0));
03270 IkReal x1127=((cj1)*(r02));
03271 IkReal x1128=((IkReal(0.150000000000000))*(sj1));
03272 IkReal x1129=((px)*(r00));
03273 IkReal x1130=((IkReal(2.00000000000000))*(py));
03274 IkReal x1131=((r02)*(sj1));
03275 IkReal x1132=((IkReal(0.150000000000000))*(cj1));
03276 IkReal x1133=((IkReal(0.108031250000000))*(cj3));
03277 IkReal x1134=((cj0)*(py));
03278 IkReal x1135=((r01)*(sj1));
03279 IkReal x1136=((IkReal(0.0800000000000000))*(cj3));
03280 IkReal x1137=((IkReal(0.150000000000000))*(pz));
03281 IkReal x1138=((IkReal(0.0491250000000000))*(cj3));
03282 IkReal x1139=((cj1)*(pz));
03283 IkReal x1140=((IkReal(0.0952312500000000))*(sj3));
03284 IkReal x1141=((IkReal(0.600000000000000))*(py));
03285 IkReal x1142=((IkReal(1.00000000000000))*(py));
03286 IkReal x1143=((px)*(sj1));
03287 IkReal x1144=((IkReal(1.00000000000000))*(cj0));
03288 IkReal x1145=((cj0)*(r00));
03289 IkReal x1146=((IkReal(0.600000000000000))*(cj0));
03290 IkReal x1147=((IkReal(1.00000000000000))*(sj3));
03291 IkReal x1148=((pz)*(sj1));
03292 IkReal x1149=((IkReal(0.0800000000000000))*(sj3));
03293 IkReal x1150=((px)*(py));
03294 IkReal x1151=((cj1)*(r00));
03295 IkReal x1152=((r01)*(sj0));
03296 IkReal x1153=((cj1)*(px));
03297 IkReal x1154=((cj4)*(x1109));
03298 IkReal x1155=((cj4)*(x1108));
03299 IkReal x1156=((sj4)*(x1109));
03300 IkReal x1157=((IkReal(2.00000000000000))*(x1112));
03301 IkReal x1158=((sj4)*(x1108));
03302 IkReal x1159=((IkReal(2.00000000000000))*(x1110));
03303 IkReal x1160=((x1108)*(x1149));
03304 IkReal x1161=((px)*(x1120)*(x1126));
03305 evalcond[0]=((((IkReal(-1.00000000000000))*(x1147)*(x1155)))+(((IkReal(-1.00000000000000))*(cj3)*(x1154)))+(x1131)+(((IkReal(-1.00000000000000))*(x1144)*(x1151)))+(((IkReal(-1.00000000000000))*(x1114)*(x1123))));
03306 evalcond[1]=((((IkReal(-1.00000000000000))*(x1127)))+(((cj3)*(x1155)))+(((IkReal(-1.00000000000000))*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(x1147)*(x1154)))+(((IkReal(-1.00000000000000))*(x1115)*(x1144))));
03307 evalcond[2]=((((IkReal(-0.0750000000000000))*(x1109)))+(x1148)+(((IkReal(-1.00000000000000))*(x1144)*(x1153)))+(((x1108)*(x1136)))+(((IkReal(-1.00000000000000))*(x1123)*(x1142)))+(((IkReal(-1.00000000000000))*(x1109)*(x1149)))+(((IkReal(0.327500000000000))*(x1108)))+(((IkReal(0.0750000000000000))*(cj1))));
03308 evalcond[3]=((IkReal(0.300000000000000))+(x1160)+(((IkReal(-1.00000000000000))*(x1139)))+(((IkReal(-1.00000000000000))*(x1113)*(x1142)))+(((IkReal(-1.00000000000000))*(x1143)*(x1144)))+(((IkReal(0.327500000000000))*(x1109)))+(((IkReal(0.0750000000000000))*(x1108)))+(((IkReal(0.0750000000000000))*(sj1)))+(((x1109)*(x1136))));
03309 evalcond[4]=((((x1131)*(x1134)))+(((x1116)*(x1123)))+(((IkReal(-1.00000000000000))*(x1136)*(x1158)))+(((IkReal(-1.00000000000000))*(cj0)*(x1114)*(x1148)))+(((x1149)*(x1156)))+(((x1109)*(x1122)))+(((x1113)*(x1124)))+(((IkReal(-0.327500000000000))*(x1158)))+(((IkReal(-1.00000000000000))*(x1142)*(x1151)))+(((IkReal(-1.00000000000000))*(x1118)*(x1125)))+(((IkReal(-1.00000000000000))*(x1113)*(x1121)))+(((px)*(x1118))));
03310 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(x1114)*(x1139)))+(((x1125)*(x1135)))+(((x1136)*(x1156)))+(((IkReal(-1.00000000000000))*(x1121)*(x1123)))+(((IkReal(-0.300000000000000))*(r00)*(sj0)))+(((x1108)*(x1122)))+(((py)*(x1115)))+(((x1123)*(x1124)))+(((IkReal(-1.00000000000000))*(x1113)*(x1116)))+(((IkReal(-1.00000000000000))*(x1114)*(x1143)))+(((x1127)*(x1134)))+(((IkReal(0.300000000000000))*(cj0)*(r01)))+(((IkReal(0.327500000000000))*(x1156)))+(((x1149)*(x1158))));
03311 evalcond[6]=((((x1133)*(x1155)))+(((IkReal(-0.600000000000000))*(x1129)))+(((pz)*(x1118)*(x1130)))+(((IkReal(-1.00000000000000))*(pp)*(x1115)*(x1144)))+(((IkReal(2.00000000000000))*(x1124)*(x1153)))+(((IkReal(0.0956250000000000))*(cj0)*(x1115)))+(((x1126)*(x1135)*(x1150)))+(((r02)*(x1119)*(x1123)))+(((IkReal(0.0450000000000000))*(x1145)))+(((IkReal(0.0843750000000000))*(x1127)))+(((IkReal(-1.00000000000000))*(pp)*(x1113)*(x1114)))+(((IkReal(-1.00000000000000))*(sj0)*(x1118)*(x1137)))+(((IkReal(-1.00000000000000))*(x1138)*(x1154)))+(((IkReal(0.0450000000000000))*(x1152)))+(((IkReal(-0.0120000000000000))*(x1154)))+(((IkReal(-1.00000000000000))*(cj0)*(x1124)*(x1132)))+(((IkReal(0.0524000000000000))*(x1155)))+(((x1120)*(x1126)*(x1143)))+(((r01)*(x1113)*(x1159)))+(((IkReal(-0.150000000000000))*(px)*(x1115)))+(((x1117)*(x1155)))+(((IkReal(-1.00000000000000))*(pp)*(x1127)))+(((x1113)*(x1120)*(x1130)))+(((IkReal(-0.600000000000000))*(x1120)))+(((IkReal(-1.00000000000000))*(x1119)*(x1135)))+(((x1127)*(x1157)))+(((x1113)*(x1129)*(x1130)))+(((x1111)*(x1115)*(x1126)))+(((cj0)*(x1121)*(x1132)))+(((IkReal(-1.00000000000000))*(x1120)*(x1128)))+(((IkReal(-1.00000000000000))*(r01)*(x1141)))+(((x1140)*(x1154)))+(((IkReal(0.0956250000000000))*(r01)*(x1113))));
03312 evalcond[7]=((((IkReal(0.0956250000000000))*(x1131)))+(((x1120)*(x1123)*(x1130)))+(((x1120)*(x1126)*(x1153)))+(((IkReal(-1.00000000000000))*(x1129)*(x1132)))+(((IkReal(-1.00000000000000))*(pp)*(x1144)*(x1151)))+(((x1118)*(x1126)*(x1150)))+(((IkReal(-1.00000000000000))*(pz)*(x1130)*(x1135)))+(((IkReal(0.0450000000000000))*(r02)))+(((IkReal(0.600000000000000))*(pz)*(x1152)))+(((IkReal(-1.00000000000000))*(r02)*(x1113)*(x1119)))+(((IkReal(-1.00000000000000))*(x1118)*(x1119)))+(((cj0)*(x1115)*(x1137)))+(((x1111)*(x1126)*(x1151)))+(((IkReal(-1.00000000000000))*(r02)*(sj0)*(x1141)))+(((pp)*(x1131)))+(((IkReal(-1.00000000000000))*(x1121)*(x1146)))+(((IkReal(-1.00000000000000))*(x1131)*(x1157)))+(((IkReal(-0.0843750000000000))*(sj0)*(x1118)))+(((IkReal(-1.00000000000000))*(x1120)*(x1132)))+(((x1124)*(x1146)))+(((sj0)*(x1118)*(x1159)))+(((IkReal(-1.00000000000000))*(x1138)*(x1155)))+(((IkReal(-0.0120000000000000))*(x1155)))+(((IkReal(-1.00000000000000))*(pp)*(x1114)*(x1123)))+(((IkReal(-1.00000000000000))*(x1133)*(x1154)))+(((x1123)*(x1129)*(x1130)))+(((r01)*(x1113)*(x1137)))+(((IkReal(-1.00000000000000))*(cj0)*(x1121)*(x1128)))+(((IkReal(-0.0524000000000000))*(x1154)))+(((IkReal(-2.00000000000000))*(px)*(pz)*(x1115)))+(((x1140)*(x1155)))+(((IkReal(-1.00000000000000))*(x1117)*(x1154)))+(((IkReal(-0.0843750000000000))*(cj1)*(x1145))));
03313 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  )
03314 {
03315 continue;
03316 }
03317 }
03318 
03319 {
03320 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03321 vinfos[0].jointtype = 1;
03322 vinfos[0].foffset = j0;
03323 vinfos[0].indices[0] = _ij0[0];
03324 vinfos[0].indices[1] = _ij0[1];
03325 vinfos[0].maxsolutions = _nj0;
03326 vinfos[1].jointtype = 1;
03327 vinfos[1].foffset = j1;
03328 vinfos[1].indices[0] = _ij1[0];
03329 vinfos[1].indices[1] = _ij1[1];
03330 vinfos[1].maxsolutions = _nj1;
03331 vinfos[2].jointtype = 1;
03332 vinfos[2].foffset = j2;
03333 vinfos[2].indices[0] = _ij2[0];
03334 vinfos[2].indices[1] = _ij2[1];
03335 vinfos[2].maxsolutions = _nj2;
03336 vinfos[3].jointtype = 1;
03337 vinfos[3].foffset = j3;
03338 vinfos[3].indices[0] = _ij3[0];
03339 vinfos[3].indices[1] = _ij3[1];
03340 vinfos[3].maxsolutions = _nj3;
03341 vinfos[4].jointtype = 1;
03342 vinfos[4].foffset = j4;
03343 vinfos[4].indices[0] = _ij4[0];
03344 vinfos[4].indices[1] = _ij4[1];
03345 vinfos[4].maxsolutions = _nj4;
03346 std::vector<int> vfree(0);
03347 solutions.AddSolution(vinfos,vfree);
03348 }
03349 }
03350 }
03351 
03352 }
03353 
03354 }
03355 }
03356 }
03357 
03358 }
03359 
03360 }
03361 }
03362 }
03363     }
03364 }
03365 }
03366 }
03367 return solutions.GetNumSolutions()>0;
03368 }
03369 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
03370 {
03371     using std::complex;
03372     IKFAST_ASSERT(rawcoeffs[0] != 0);
03373     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
03374     const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
03375     complex<IkReal> coeffs[4];
03376     const int maxsteps = 110;
03377     for(int i = 0; i < 4; ++i) {
03378         coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
03379     }
03380     complex<IkReal> roots[4];
03381     IkReal err[4];
03382     roots[0] = complex<IkReal>(1,0);
03383     roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
03384     err[0] = 1.0;
03385     err[1] = 1.0;
03386     for(int i = 2; i < 4; ++i) {
03387         roots[i] = roots[i-1]*roots[1];
03388         err[i] = 1.0;
03389     }
03390     for(int step = 0; step < maxsteps; ++step) {
03391         bool changed = false;
03392         for(int i = 0; i < 4; ++i) {
03393             if ( err[i] >= tol ) {
03394                 changed = true;
03395                 // evaluate
03396                 complex<IkReal> x = roots[i] + coeffs[0];
03397                 for(int j = 1; j < 4; ++j) {
03398                     x = roots[i] * x + coeffs[j];
03399                 }
03400                 for(int j = 0; j < 4; ++j) {
03401                     if( i != j ) {
03402                         if( roots[i] != roots[j] ) {
03403                             x /= (roots[i] - roots[j]);
03404                         }
03405                     }
03406                 }
03407                 roots[i] -= x;
03408                 err[i] = abs(x);
03409             }
03410         }
03411         if( !changed ) {
03412             break;
03413         }
03414     }
03415 
03416     numroots = 0;
03417     bool visited[4] = {false};
03418     for(int i = 0; i < 4; ++i) {
03419         if( !visited[i] ) {
03420             // might be a multiple root, in which case it will have more error than the other roots
03421             // find any neighboring roots, and take the average
03422             complex<IkReal> newroot=roots[i];
03423             int n = 1;
03424             for(int j = i+1; j < 4; ++j) {
03425                 if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
03426                     newroot += roots[j];
03427                     n += 1;
03428                     visited[j] = true;
03429                 }
03430             }
03431             if( n > 1 ) {
03432                 newroot /= n;
03433             }
03434             // 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
03435             if( IKabs(imag(newroot)) < tolsqrt ) {
03436                 rawroots[numroots++] = real(newroot);
03437             }
03438         }
03439     }
03440 }
03441 };
03442 
03443 
03446 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
03447 IKSolver solver;
03448 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
03449 }
03450 
03451 IKFAST_API const char* GetKinematicsHash() { return "76eda3aa6f0ad735cb91d01eee207a60"; }
03452 
03453 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
03454 
03455 #ifdef IKFAST_NAMESPACE
03456 } // end namespace
03457 #endif
03458 
03459 #ifndef IKFAST_NO_MAIN
03460 #include <stdio.h>
03461 #include <stdlib.h>
03462 #ifdef IKFAST_NAMESPACE
03463 using namespace IKFAST_NAMESPACE;
03464 #endif
03465 int main(int argc, char** argv)
03466 {
03467     if( argc != 12+GetNumFreeParameters()+1 ) {
03468         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
03469                "Returns the ik solutions given the transformation of the end effector specified by\n"
03470                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
03471                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
03472         return 1;
03473     }
03474 
03475     IkSolutionList<IkReal> solutions;
03476     std::vector<IkReal> vfree(GetNumFreeParameters());
03477     IkReal eerot[9],eetrans[3];
03478     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
03479     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
03480     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
03481     for(std::size_t i = 0; i < vfree.size(); ++i)
03482         vfree[i] = atof(argv[13+i]);
03483     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
03484 
03485     if( !bSuccess ) {
03486         fprintf(stderr,"Failed to get ik solution\n");
03487         return -1;
03488     }
03489 
03490     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
03491     std::vector<IkReal> solvalues(GetNumJoints());
03492     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
03493         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
03494         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
03495         std::vector<IkReal> vsolfree(sol.GetFree().size());
03496         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
03497         for( std::size_t j = 0; j < solvalues.size(); ++j)
03498             printf("%.15f, ", solvalues[j]);
03499         printf("\n");
03500     }
03501     return 0;
03502 }
03503 
03504 #endif


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