turtlebot_arm_arm_ikfast_solver.cpp
Go to the documentation of this file.
00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 #define IKFAST_HAS_LIBRARY
00021 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
00022 using namespace ikfast;
00023 
00024 // check if the included ikfast version matches what this file was compiled with
00025 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
00026 IKFAST_COMPILE_ASSERT(IKFAST_VERSION==61);
00027 
00028 #include <cmath>
00029 #include <vector>
00030 #include <limits>
00031 #include <algorithm>
00032 #include <complex>
00033 
00034 #define IKFAST_STRINGIZE2(s) #s
00035 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
00036 
00037 #ifndef IKFAST_ASSERT
00038 #include <stdexcept>
00039 #include <sstream>
00040 #include <iostream>
00041 
00042 #ifdef _MSC_VER
00043 #ifndef __PRETTY_FUNCTION__
00044 #define __PRETTY_FUNCTION__ __FUNCDNAME__
00045 #endif
00046 #endif
00047 
00048 #ifndef __PRETTY_FUNCTION__
00049 #define __PRETTY_FUNCTION__ __func__
00050 #endif
00051 
00052 #define IKFAST_ASSERT(b) { if( !(b) ) { std::stringstream ss; ss << "ikfast exception: " << __FILE__ << ":" << __LINE__ << ": " <<__PRETTY_FUNCTION__ << ": Assertion '" << #b << "' failed"; throw std::runtime_error(ss.str()); } }
00053 
00054 #endif
00055 
00056 #if defined(_MSC_VER)
00057 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
00058 #else
00059 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
00060 #endif
00061 
00062 #define IK2PI  ((IkReal)6.28318530717959)
00063 #define IKPI  ((IkReal)3.14159265358979)
00064 #define IKPI_2  ((IkReal)1.57079632679490)
00065 
00066 #ifdef _MSC_VER
00067 #ifndef isnan
00068 #define isnan _isnan
00069 #endif
00070 #endif // _MSC_VER
00071 
00072 // lapack routines
00073 extern "C" {
00074   void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
00075   void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
00076   void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
00077   void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
00078   void dgetrs_(const char *trans, const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info);
00079   void dgeev_(const char *jobvl, const char *jobvr, const int *n, double *a, const int *lda, double *wr, double *wi,double *vl, const int *ldvl, double *vr, const int *ldvr, double *work, const int *lwork, int *info);
00080 }
00081 
00082 using namespace std; // necessary to get std math routines
00083 
00084 #ifdef IKFAST_NAMESPACE
00085 namespace IKFAST_NAMESPACE {
00086 #endif
00087 
00088 inline float IKabs(float f) { return fabsf(f); }
00089 inline double IKabs(double f) { return fabs(f); }
00090 
00091 inline float IKsqr(float f) { return f*f; }
00092 inline double IKsqr(double f) { return f*f; }
00093 
00094 inline float IKlog(float f) { return logf(f); }
00095 inline double IKlog(double f) { return log(f); }
00096 
00097 // allows asin and acos to exceed 1
00098 #ifndef IKFAST_SINCOS_THRESH
00099 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
00100 #endif
00101 
00102 // used to check input to atan2 for degenerate cases
00103 #ifndef IKFAST_ATAN2_MAGTHRESH
00104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
00105 #endif
00106 
00107 // minimum distance of separate solutions
00108 #ifndef IKFAST_SOLUTION_THRESH
00109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
00110 #endif
00111 
00112 inline float IKasin(float f)
00113 {
00114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00115 if( f <= -1 ) return float(-IKPI_2);
00116 else if( f >= 1 ) return float(IKPI_2);
00117 return asinf(f);
00118 }
00119 inline double IKasin(double f)
00120 {
00121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00122 if( f <= -1 ) return -IKPI_2;
00123 else if( f >= 1 ) return IKPI_2;
00124 return asin(f);
00125 }
00126 
00127 // return positive value in [0,y)
00128 inline float IKfmod(float x, float y)
00129 {
00130     while(x < 0) {
00131         x += y;
00132     }
00133     return fmodf(x,y);
00134 }
00135 
00136 // return positive value in [0,y)
00137 inline double IKfmod(double x, double y)
00138 {
00139     while(x < 0) {
00140         x += y;
00141     }
00142     return fmod(x,y);
00143 }
00144 
00145 inline float IKacos(float f)
00146 {
00147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00148 if( f <= -1 ) return float(IKPI);
00149 else if( f >= 1 ) return float(0);
00150 return acosf(f);
00151 }
00152 inline double IKacos(double f)
00153 {
00154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
00155 if( f <= -1 ) return IKPI;
00156 else if( f >= 1 ) return 0;
00157 return acos(f);
00158 }
00159 inline float IKsin(float f) { return sinf(f); }
00160 inline double IKsin(double f) { return sin(f); }
00161 inline float IKcos(float f) { return cosf(f); }
00162 inline double IKcos(double f) { return cos(f); }
00163 inline float IKtan(float f) { return tanf(f); }
00164 inline double IKtan(double f) { return tan(f); }
00165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
00166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
00167 inline float IKatan2(float fy, float fx) {
00168     if( isnan(fy) ) {
00169         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00170         return float(IKPI_2);
00171     }
00172     else if( isnan(fx) ) {
00173         return 0;
00174     }
00175     return atan2f(fy,fx);
00176 }
00177 inline double IKatan2(double fy, double fx) {
00178     if( isnan(fy) ) {
00179         IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned
00180         return IKPI_2;
00181     }
00182     else if( isnan(fx) ) {
00183         return 0;
00184     }
00185     return atan2(fy,fx);
00186 }
00187 
00188 inline float IKsign(float f) {
00189     if( f > 0 ) {
00190         return float(1);
00191     }
00192     else if( f < 0 ) {
00193         return float(-1);
00194     }
00195     return 0;
00196 }
00197 
00198 inline double IKsign(double f) {
00199     if( f > 0 ) {
00200         return 1.0;
00201     }
00202     else if( f < 0 ) {
00203         return -1.0;
00204     }
00205     return 0;
00206 }
00207 
00210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
00211 IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39;
00212 x0=IKcos(j[3]);
00213 x1=IKcos(j[2]);
00214 x2=IKsin(j[1]);
00215 x3=IKcos(j[1]);
00216 x4=IKsin(j[2]);
00217 x5=IKsin(j[3]);
00218 x6=IKsin(j[4]);
00219 x7=IKcos(j[0]);
00220 x8=IKsin(j[0]);
00221 x9=IKcos(j[4]);
00222 x10=((IkReal(0.999999985550000))*(x8));
00223 x11=((IkReal(0.000169999997543500))*(x7));
00224 x12=((IkReal(1.00000000000000))*(x4));
00225 x13=((x1)*(x3));
00226 x14=((x2)*(x4));
00227 x15=((x1)*(x2));
00228 x16=((x3)*(x4));
00229 x17=((((IkReal(-1.00000000000000))*(x10)))+(x11));
00230 x18=((((IkReal(-1.00000000000000))*(x11)))+(x10));
00231 x19=((((IkReal(0.000169999997543500))*(x8)))+(((IkReal(0.999999985550000))*(x7))));
00232 x20=((IkReal(-1.00000000000000))*(x19));
00233 x21=((x17)*(x6));
00234 x22=((x17)*(x2));
00235 x23=((x17)*(x4));
00236 x24=((((IkReal(-1.00000000000000))*(x13)))+(x14));
00237 x25=((x19)*(x2));
00238 x26=((x20)*(x6));
00239 x27=((x14)*(x17));
00240 x28=((((IkReal(1.00000000000000))*(x15)))+(((x12)*(x3))));
00241 x29=((IkReal(-1.00000000000000))*(x28));
00242 x30=((x24)*(x5));
00243 x31=((x0)*(x24));
00244 x32=((x0)*(x29));
00245 x33=((x28)*(x5));
00246 x34=((((x16)*(x17)))+(((x15)*(x17))));
00247 x35=((((x16)*(x19)))+(((x15)*(x19))));
00248 IkReal x40=((x13)*(x18));
00249 x36=((((x5)*(((((IkReal(0.000799999744000123))*(x40)))+(((IkReal(-0.999999680000154))*(x34)))+(((IkReal(0.000799999744000123))*(x27)))))))+(((x0)*(((((IkReal(-0.999999680000154))*(x40)))+(((IkReal(-0.000799999744000123))*(x34)))+(((IkReal(-0.999999680000154))*(x27))))))));
00250 x37=((x36)*(x9));
00251 IkReal x41=((x13)*(x20));
00252 x38=((((x0)*(((((IkReal(-0.999999680000154))*(x41)))+(((IkReal(-0.999999680000154))*(x14)*(x19)))+(((IkReal(-0.000799999744000123))*(x35)))))))+(((x5)*(((((IkReal(0.000799999744000123))*(x41)))+(((IkReal(-0.999999680000154))*(x35)))+(((IkReal(0.000799999744000123))*(x12)*(x25))))))));
00253 x39=((x38)*(x9));
00254 eetrans[0]=((IkReal(-6.12051650867111e-6))+(((((((IkReal(-0.999999990999352))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-0.999999990999352))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.999999990999352))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-0.999999990999352))*(((((IkReal(1.21855920251392e-11))*(IKsin(j[0]))))+(((IkReal(7.16799530890540e-8))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((IkReal(1.27211445824509e-5))*(IKsin(j[1]))*(IKsin(j[2]))))+(((((((IkReal(-8.95999418495792e-5))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-8.95999418495792e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((IkReal(-1.27211445824509e-5))*(IKcos(j[1]))))+(((((((IkReal(1.34412007677683e-5))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(1.34412007677683e-5))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-5.99891970842010e-5))*(((((IkReal(-8.95999413613176e-5))*(IKsin(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-5.99891970842010e-5))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.999999990999352))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-0.999999990999352))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-0.999999990999352))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-0.999999990999352))*(((((IkReal(8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(6.71878577340761e-6))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(6.71878577340761e-6))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(1.80199995774193e-5))*(IKsin(j[0]))))+(((IkReal(0.105999997514231))*(IKcos(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(-5.99891970842010e-5))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-5.99891970842010e-5))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(0.111999927311974))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(0.111999927311974))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-5.99891970842010e-5))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-5.99891970842010e-5))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(0.111999927311974))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(0.111999927311974))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(6.71878577340761e-6))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(6.71878577340761e-6))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-8.95999418495792e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-8.95999418495792e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((IkReal(-1.27211445824509e-5))*(IKcos(j[1]))*(IKcos(j[2]))))+(((((((IkReal(-8.60236849137173e-12))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(8.60236849137173e-12))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-5.99891970842010e-5))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-5.99891970842010e-5))*(((((IkReal(1.21855920251392e-11))*(IKcos(j[0]))))+(((IkReal(-7.16799530890540e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(1.80199995774193e-5))*(IKsin(j[0]))))+(((IkReal(0.105999997514231))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(-6.35885479903985e-6))*(IKsin(j[0]))))+(((IkReal(1.08100531583677e-9))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(-5.37502861872609e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-5.37502861872609e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(8.60236849137173e-12))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(8.60236849137173e-12))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-1.07529606142147e-8))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-1.07529606142147e-8))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(1.07529606142147e-8))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.07529606142147e-8))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-6.35885479903985e-6))*(IKsin(j[0]))))+(((IkReal(1.08100531583677e-9))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((((((IkReal(1.07529606142147e-8))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(1.07529606142147e-8))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-6.35885479903985e-6))*(IKsin(j[0]))))+(((IkReal(1.08100531583677e-9))*(IKcos(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(-5.37502861872609e-9))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-5.37502861872609e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(1.34412007677683e-5))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.34412007677683e-5))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(1.80199995774193e-5))*(IKsin(j[0]))))+(((IkReal(0.105999997514231))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((((((IkReal(1.07529606142147e-8))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-1.07529606142147e-8))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3])))));
00255 eetrans[1]=((IkReal(-2.27985057461787e-6))+(((((((IkReal(3.22579151213407e-13))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-3.22579151213407e-13))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-5.99891979482657e-5))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-5.99891979482657e-5))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-4.03223939016759e-10))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(4.03223939016759e-10))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.111999928118519))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-0.111999928118519))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.80199997071867e-5))*(IKcos(j[0]))))+(((IkReal(0.105999998277569))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((((((IkReal(1.08100533140722e-9))*(IKsin(j[0]))))+(((IkReal(6.35885489063071e-6))*(IKcos(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(-5.99891979482657e-5))*(((((IkReal(8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-5.99891979482657e-5))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-5.99891979482657e-5))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-5.99891979482657e-5))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(6.71878587018280e-6))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(6.71878587018280e-6))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(3.22579151213407e-13))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(3.22579151213407e-13))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-3.22579151213407e-13))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(3.22579151213407e-13))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(0.999999998200648))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(0.999999998200648))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(0.999999998200648))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(0.999999998200648))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-3.22579151213407e-13))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-3.22579151213407e-13))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(8.95999424948149e-5))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(8.95999424948149e-5))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(1.08100533140722e-9))*(IKsin(j[0]))))+(((IkReal(6.35885489063071e-6))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(-4.03223939016759e-10))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-4.03223939016759e-10))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(6.71878587018280e-6))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(6.71878587018280e-6))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-5.99891979482657e-5))*(((((IkReal(1.21855920251392e-11))*(IKsin(j[0]))))+(((IkReal(7.16799530890540e-8))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-5.99891979482657e-5))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((IkReal(3.81622900807933e-10))*(IKcos(j[1]))))+(((((((IkReal(8.95999424948149e-5))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(8.95999424948149e-5))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(0.999999998200648))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(0.999999998200648))*(((((IkReal(-8.95999413613176e-5))*(IKsin(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((IkReal(-3.81622900807933e-10))*(IKsin(j[1]))*(IKsin(j[2]))))+(((((((IkReal(-5.37502869614624e-9))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-5.37502869614624e-9))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-5.37502869614624e-9))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-5.37502869614624e-9))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(-2.58063320970726e-16))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-2.58063320970726e-16))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(0.999999998200648))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(0.999999998200648))*(((((IkReal(1.21855920251392e-11))*(IKcos(j[0]))))+(((IkReal(-7.16799530890540e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-1.80199997071867e-5))*(IKcos(j[0]))))+(((IkReal(0.105999998277569))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(-2.58063320970726e-16))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(2.58063320970726e-16))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.80199997071867e-5))*(IKcos(j[0]))))+(((IkReal(0.105999998277569))*(IKsin(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(-0.111999928118519))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-0.111999928118519))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((IkReal(3.81622900807933e-10))*(IKcos(j[1]))*(IKcos(j[2]))))+(((((((IkReal(1.08100533140722e-9))*(IKsin(j[0]))))+(((IkReal(6.35885489063071e-6))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2])))));
00256 eetrans[2]=((IkReal(0.0604999995301421))+(((((((IkReal(8.95999420108010e-5))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(8.95999420108010e-5))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.14475414131654e-9))*(IKsin(j[0]))))+(((IkReal(1.94608204023812e-13))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(0.105999999236663))*(IKcos(j[1]))*(IKcos(j[2]))))+(((((((IkReal(-0.111999927513501))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(0.111999927513501))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.14475414131654e-9))*(IKsin(j[0]))))+(((IkReal(1.94608204023812e-13))*(IKcos(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(2.16259453998404e-9))*(IKsin(j[0]))))+(((IkReal(1.27211443528473e-5))*(IKcos(j[0]))))))*(IKsin(j[1]))))+(((((((IkReal(-8.95999420108010e-5))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(8.95999420108010e-5))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-7.16799536086408e-8))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(7.16799536086408e-8))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.000120010797515734))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-0.000120010797515734))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(2.16259453998404e-9))*(IKsin(j[0]))))+(((IkReal(1.27211443528473e-5))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(-0.000120010797515734))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-0.000120010797515734))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(1.34412007193938e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(1.34412007193938e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.07995675269645e-8))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.07995675269645e-8))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(1.34412007193938e-5))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(1.34412007193938e-5))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-0.111999927513501))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-0.111999927513501))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-1.07529605755150e-8))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.07529605755150e-8))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(-9.67640631126014e-13))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-9.67640631126014e-13))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-7.16799536086408e-8))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-7.16799536086408e-8))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKsin(j[3]))))+(((((((IkReal(-1.07529605755150e-8))*(((((IkReal(-0.000169999997543500))*(IKsin(j[0]))))+(((IkReal(-0.999999985550000))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-1.07529605755150e-8))*(((((IkReal(0.999999985550000))*(IKcos(j[0]))))+(((IkReal(0.000169999997543500))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.000120010797515734))*(((((IkReal(-7.16799530890540e-8))*(IKcos(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(-0.000120010797515734))*(((((IkReal(1.21855920251392e-11))*(IKsin(j[0]))))+(((IkReal(7.16799530890540e-8))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-1.07995675269645e-8))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.07995675269645e-8))*(((((IkReal(-8.95999413613176e-5))*(IKsin(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-9.67640631126014e-13))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-9.67640631126014e-13))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(-1.14475414131654e-9))*(IKsin(j[0]))))+(((IkReal(1.94608204023812e-13))*(IKcos(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((((((IkReal(2.16259453998404e-9))*(IKsin(j[0]))))+(((IkReal(1.27211443528473e-5))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((((((IkReal(-1.07995675269645e-8))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))+(((IkReal(-1.07995675269645e-8))*(((((IkReal(-1.52319900314240e-8))*(IKcos(j[0]))))+(((IkReal(8.95999413613176e-5))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(1.20955078890752e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))+(((IkReal(1.20955078890752e-9))*(((((IkReal(0.999999985550000))*(IKsin(j[0]))))+(((IkReal(-0.000169999997543500))*(IKcos(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(1.20955078890752e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(1.20955078890752e-9))*(((((IkReal(0.000169999997543500))*(IKcos(j[0]))))+(((IkReal(-0.999999985550000))*(IKsin(j[0]))))))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((IkReal(0.105999999236663))*(IKcos(j[1]))))+(((IkReal(-0.105999999236663))*(IKsin(j[1]))*(IKsin(j[2]))))+(((((((IkReal(-1.07995675269645e-8))*(((((IkReal(1.21855920251392e-11))*(IKcos(j[0]))))+(((IkReal(-7.16799530890540e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-1.07995675269645e-8))*(((((IkReal(7.16799530890540e-8))*(IKsin(j[0]))))+(((IkReal(-1.21855920251392e-11))*(IKcos(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3]))))+(((((((IkReal(-8.95999420108010e-5))*(IKcos(j[1]))*(IKsin(j[2]))))+(((IkReal(-8.95999420108010e-5))*(IKcos(j[2]))*(IKsin(j[1]))))))*(IKcos(j[3]))))+(((((((IkReal(-0.000120010797515734))*(((((IkReal(-8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(-1.52319900314240e-8))*(IKsin(j[0]))))))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-0.000120010797515734))*(((((IkReal(8.95999413613176e-5))*(IKcos(j[0]))))+(((IkReal(1.52319900314240e-8))*(IKsin(j[0]))))))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKcos(j[3]))))+(((((((IkReal(8.95999420108010e-5))*(IKsin(j[1]))*(IKsin(j[2]))))+(((IkReal(-8.95999420108010e-5))*(IKcos(j[1]))*(IKcos(j[2]))))))*(IKsin(j[3])))));
00257 eerot[0]=((((IkReal(-5.99891970842010e-5))*(x26)))+(((IkReal(-0.999999990999352))*(x39)))+(((x9)*(((((IkReal(0.000120010759544213))*(x32)))+(((IkReal(0.000120010759544213))*(x30)))+(((IkReal(9.60086076353706e-8))*(x33)))+(((IkReal(9.60086076353706e-8))*(x31)))))))+(((IkReal(-5.99891970842010e-5))*(x37)))+(((IkReal(-0.999999990999352))*(x21))));
00258 eerot[1]=((((IkReal(-5.99891979482657e-5))*(x21)))+(((IkReal(-5.99891979482657e-5))*(x39)))+(((IkReal(0.999999998200648))*(x26)))+(((IkReal(0.999999998200648))*(x37)))+(((x9)*(((((IkReal(-2.88017191463142e-12))*(x33)))+(((IkReal(-2.88017191463142e-12))*(x31)))+(((IkReal(-3.60021489328928e-9))*(x32)))+(((IkReal(-3.60021489328928e-9))*(x30))))))));
00259 eerot[2]=((((IkReal(-0.000120010797515734))*(x39)))+(((x9)*(((((IkReal(-0.999999672798860))*(x30)))+(((IkReal(-0.999999672798860))*(x32)))+(((IkReal(-0.000799999738239088))*(x31)))+(((IkReal(-0.000799999738239088))*(x33)))))))+(((IkReal(-1.07995675269645e-8))*(x37)))+(((IkReal(-0.000120010797515734))*(x21)))+(((IkReal(-1.07995675269645e-8))*(x26))));
00260 }
00261 
00262 IKFAST_API int GetNumFreeParameters() { return 0; }
00263 IKFAST_API int* GetFreeParameters() { return NULL; }
00264 IKFAST_API int GetNumJoints() { return 5; }
00265 
00266 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00267 
00268 IKFAST_API int GetIkType() { return 0x56000007; }
00269 
00270 class IKSolver {
00271 public:
00272 IkReal j0,cj0,sj0,htj0,j1,cj1,sj1,htj1,j2,cj2,sj2,htj2,j3,cj3,sj3,htj3,j5,cj5,sj5,htj5,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;
00273 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij5[2], _nj5;
00274 
00275 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00276 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; j5=numeric_limits<IkReal>::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1; 
00277 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00278     solutions.Clear();
00279 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00280 
00281 r00 = eerot[0];
00282 r01 = eerot[1];
00283 r02 = eerot[2];
00284 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00285 new_r00=((((IkReal(-1.07995675269559e-8))*(r02)))+(((IkReal(0.999999998200648))*(r01)))+(((IkReal(-5.99891970842010e-5))*(r00))));
00286 new_px=((IkReal(2.28013677947483e-6))+(((IkReal(-5.99891970842010e-5))*(px)))+(((IkReal(-1.07995675269559e-8))*(pz)))+(((IkReal(0.999999998200648))*(py))));
00287 new_r01=((((IkReal(-5.99891979482657e-5))*(r01)))+(((IkReal(-0.000120010797515734))*(r02)))+(((IkReal(-0.999999990999352))*(r00))));
00288 new_py=((IkReal(1.13999997332400e-6))+(((IkReal(-0.000120010797515734))*(pz)))+(((IkReal(-5.99891979482657e-5))*(py)))+(((IkReal(-0.999999990999352))*(px))));
00289 new_r02=((((IkReal(3.60021604536983e-9))*(r01)))+(((IkReal(0.999999992798704))*(r02)))+(((IkReal(-0.000120010797947650))*(r00))));
00290 new_pz=((IkReal(-0.0604999998289836))+(((IkReal(3.60021604536983e-9))*(py)))+(((IkReal(-0.000120010797947650))*(px)))+(((IkReal(0.999999992798704))*(pz))));
00291 r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz;
00292 
00293 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
00294 {
00295 IkReal j0array[2], cj0array[2], sj0array[2];
00296 bool j0valid[2]={false};
00297 _nj0 = 2;
00298 if( IKabs(((((IkReal(-0.000169999997543500))*(py)))+(((IkReal(0.999999985550000))*(px))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(0.000169999997543500))*(px)))+(((IkReal(0.999999985550000))*(py))))) < IKFAST_ATAN2_MAGTHRESH )
00299     continue;
00300 IkReal x42=IKatan2(((((IkReal(-0.000169999997543500))*(py)))+(((IkReal(0.999999985550000))*(px)))), ((((IkReal(0.000169999997543500))*(px)))+(((IkReal(0.999999985550000))*(py)))));
00301 j0array[0]=((IkReal(-1.00000000000000))*(x42));
00302 sj0array[0]=IKsin(j0array[0]);
00303 cj0array[0]=IKcos(j0array[0]);
00304 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x42))));
00305 sj0array[1]=IKsin(j0array[1]);
00306 cj0array[1]=IKcos(j0array[1]);
00307 if( j0array[0] > IKPI )
00308 {
00309     j0array[0]-=IK2PI;
00310 }
00311 else if( j0array[0] < -IKPI )
00312 {    j0array[0]+=IK2PI;
00313 }
00314 j0valid[0] = true;
00315 if( j0array[1] > IKPI )
00316 {
00317     j0array[1]-=IK2PI;
00318 }
00319 else if( j0array[1] < -IKPI )
00320 {    j0array[1]+=IK2PI;
00321 }
00322 j0valid[1] = true;
00323 for(int ij0 = 0; ij0 < 2; ++ij0)
00324 {
00325 if( !j0valid[ij0] )
00326 {
00327     continue;
00328 }
00329 _ij0[0] = ij0; _ij0[1] = -1;
00330 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
00331 {
00332 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00333 {
00334     j0valid[iij0]=false; _ij0[1] = iij0; break; 
00335 }
00336 }
00337 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00338 
00339 IkReal op[4+1], zeror[4];
00340 int numroots;
00341 op[0]=((((IkReal(-0.000812850431382459))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(0.00531864888470676))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-0.000679999980348001))*(pz)*(r00)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(1.17456890729270e-11))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.848000000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(pz)*(r01)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(px)*((py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(5.73838480187078e-10))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.00203999994104400))*(py)*(pz)*(r00)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-9.77980785828634e-12))*(cj0)*(sj0)*((py)*(py))*((r02)*(r02))))+(((IkReal(-8.02815474597405e-5))*(cj0)*(px)*(py)*(r00)*(r02)))+(((IkReal(-8.31283667954339e-16))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(7.20799979168881e-5))*(r01)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.0397120066969557))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.29363115338308e-8))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.99999994220000))*((py)*(py))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-1.38184577328552e-7))*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.000144159995833776))*(cj0)*(pz)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.0449439712358584))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.423999987746400))*(r01)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-9.77980785828634e-12))*(px)*(py)*((cj0)*(cj0))*((r02)*(r02))))+(((IkReal(1.22535996458710e-8))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.53708957210214e-10))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.00203999994104400))*(px)*(pz)*(r01)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-5.73838480187078e-10))*((cj0)*(cj0))*((py)*(py))*((r00)*(r00))))+(((IkReal(5.73838480187078e-10))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000144159995833776))*(cj0)*(sj0)*((pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(0.423999987746400))*(pz)*((cj0)*(cj0))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-7.20799979168881e-5))*(r01)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(8.02815474597405e-5))*(cj0)*(py)*(pz)*((r01)*(r01))))+(((IkReal(-8.02815474597405e-5))*(py)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.000144159995833776))*(cj0)*(pz)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.00135999996069600))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-0.999999971100001))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.99999976880001))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.000216239993750664))*(px)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(-0.0106372977694135))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.99999982660000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-5.73838480187078e-10))*((px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000144159995833776))*(px)*(py)*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(0.0198560027746394))*((cj0)*(cj0))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.848000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.848000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.0198560027746394))*((px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.99999988440000))*(pz)*(r00)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.000432479987501328))*(cj0)*(px)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(1.44667348522452e-9))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(8.50984403073250e-6))*(px)*(sj0)*((r02)*(r02))))+(((IkReal(11.9999993064000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-4.18559726073583e-6))*(cj0)*(pp)*(r01)*(r02)))+(((IkReal(2.89334697044905e-9))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.424000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(0.00531864903841572))*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-2.88999991647900e-8))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00135999996069600))*(px)*(py)*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.423999987746400))*(pz)*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.0250879966515221))*(pp)*((r02)*(r02))))+(((IkReal(1.53347389433800e-10))*(cj0)*(r00)*(r02)))+(((IkReal(1.99999994220000))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.29363115338308e-8))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-1.15599996659160e-7))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.423999975492801))*(cj0)*(r01)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(6.75104094337739e-6))*(px)*(py)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(2.89334697044905e-9))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.0397120619298817))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.0397120044016018))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.000144159995833776))*(px)*(py)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(3.67607989376129e-8))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px)*(px)*(px))))+(((IkReal(4.00000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-0.0198560027746394))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(cj0)*(px)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-7.99999965320001))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(6.75104094337739e-6))*(cj0)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(1.53347389433800e-10))*(r01)*(r02)*(sj0)))+(((IkReal(1.14767862294149e-9))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-8.50984403073250e-6))*(cj0)*(py)*((r02)*(r02))))+(((IkReal(-2.87641407596657e-8))*((px)*(px))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.00531864919212468))*(px)*(r00)*(r02)))+(((IkReal(-6.75104094337739e-6))*(cj0)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.00531864903841572))*(py)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(1.69599990197120))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(-6.75104094337739e-6))*(cj0)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(6.75104094337739e-6))*(cj0)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(-8.02815474597405e-5))*(cj0)*(py)*(pz)*((r02)*(r02))))+(((IkReal(-2.88999991647900e-8))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.75105072318525e-6))*(cj0)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(4.18559726073583e-6))*(cj0)*(r01)*(r02)*((px)*(px))))+(((IkReal(-2.88999991647900e-8))*((px)*(px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000288319991667552))*(px)*(py)*(pz)*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(1.38184577328552e-7))*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-8.31283667954339e-16))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(0.0397120630775603))*(px)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.00407999988208800))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.140063935774761))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.0397120044016018))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.423999987746400))*((pz)*(pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(6.75105072318525e-6))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-1.69600000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(0.000144159995833776))*(cj0)*(pz)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-6.75104094337739e-6))*(px)*(py)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-7.11551534325092e-10))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.000432479987501328))*(cj0)*(py)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.00203999994104400))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(-0.847999950985601))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-1.36478630681559e-8))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.424000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(6.75105072318525e-6))*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.000679999980348001))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(9.02043467257645e-7))*(cj0)*(r01)*(r02)))+(((IkReal(8.44671447204764e-5))*(cj0)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(7.20799979168881e-5))*(r00)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.0198560315387801))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.99999988440000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-1.15599996659160e-7))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.00203999994104400))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px))*((py)*(py))))+(((IkReal(0.000679999980348001))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.000144159995833776))*(cj0)*(r01)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-5.73839311470746e-10))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py)*(py))))+(((IkReal(1.35021014463705e-5))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.000432479987501328))*(cj0)*(py)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-2.87641407596657e-8))*((cj0)*(cj0))*((py)*(py))*((r02)*(r02))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(7.60959501990047e-5))*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.000144159995833776))*(cj0)*(r00)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-3.99999982660001))*((px)*(px))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.50984403073250e-6))*(cj0)*(px)*(r00)*(r01)))+(((IkReal(1.80834067306134e-6))*(cj0)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.00135999996069600))*(cj0)*(py)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.99999994220000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(py)*((px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(1.27199992647840))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(1.15599996659160e-7))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(9.04170336530672e-7))*(py)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(0.847999950985601))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-1.36478630681559e-8))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-1.15599996659160e-7))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-7.20799979168881e-5))*(r00)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(1.44667348522452e-9))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.00203999994104400))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py)*(py)*(py))))+(((IkReal(9.04170336530672e-7))*(px)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.000406425227436919))*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.0951199645389027))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.27199996323920))*(py)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.00203999994104400))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.0397120630775603))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(1.44667348522452e-9))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-0.999999971100001))*((py)*(py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.0397120619298817))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.000679999980348001))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-3.99999976880001))*(px)*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.000679999980348001))*(py)*((px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000144159995833776))*(r00)*(r01)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-7.99999965320001))*(py)*(pz)*(r01)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-1.80834067306134e-6))*(cj0)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(6.75105072318525e-6))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(0.000216239993750664))*(px)*(r01)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.000216239993750664))*(px)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.423999987746400))*(r00)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(1.53708957210214e-10))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.36478630681559e-8))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(px)*((py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((px)*(px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-5.77999983295801e-8))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.36478630681559e-8))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.000288319991667552))*(px)*(py)*(pz)*((cj0)*(cj0))*((r02)*(r02))))+(((IkReal(-0.847999963239201))*(py)*(r01)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-1.35021014463705e-5))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(1.44667348522452e-9))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-8.44671447204764e-5))*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.848000000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-1.69600000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-3.99999976880001))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-4.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.80834067306134e-6))*(cj0)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(1.27199996323920))*(px)*(r00)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.000144159995833776))*(px)*(py)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px)*(px))))+(((IkReal(-0.00531864919212468))*(pz)*((r02)*(r02))))+(((IkReal(11.9999993064000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-9.04170336530672e-7))*(px)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(3.99999965320001))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-1.69600000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-1.22535996458710e-8))*(pz)*((cj0)*(cj0))*((py)*(py))*((r00)*(r00))))+(((IkReal(-0.848000000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(1.14767862294149e-9))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(5.77999983295801e-8))*((py)*(py))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.847999963239201))*(px)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(6.75104094337739e-6))*(px)*(py)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.000406425227436919))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.847999950985601))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-3.99999982660001))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(0.00135999996069600))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(7.99999953760001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00271999992139200))*(cj0)*(px)*(r00)*(r01)*(sj0)*((py)*(py)*(py))))+(((IkReal(-3.99999976880001))*(py)*(r00)*(r01)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.00531864903841572))*(px)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(0.00531864888470676))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.00135999996069600))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-1.22535996458710e-8))*((cj0)*(cj0))*((pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(4.18559726073583e-6))*(pp)*(r00)*(r02)*(sj0)))+(((IkReal(1.99999982660000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-7.11551534325092e-10))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(3.99999976880001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.000144159995833776))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-3.99999976880001))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(5.75282798567641e-8))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.140063935774761))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.847999975492801))*(pz)*((cj0)*(cj0))*((py)*(py))*((r02)*(r02))))+(((IkReal(1.15599996659160e-7))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-1.15599996659160e-7))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-0.000216239993750664))*(py)*(r00)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.423999963239201))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.000157351575182608))*((r02)*(r02))))+(((IkReal(1.27199992647840))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.000432479987501328))*(cj0)*(px)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.0397120066969557))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(11.9999993064000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-1.99999994220000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.00203999994104400))*(r00)*(r01)*((px)*(px))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(3.99999988440000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.22535996458710e-8))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.44667348522452e-9))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-0.423999987746400))*(pz)*((cj0)*(cj0))*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.00531864919212468))*(py)*(r01)*(r02)))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(9.77980785828634e-12))*(cj0)*(sj0)*((px)*(px))*((r02)*(r02))))+(((IkReal(-3.99999976880001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-1.27199992647840))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-1.38184577328552e-7))*(cj0)*(sj0)*((r00)*(r00))))+(((IkReal(-3.99999988440000))*((px)*(px))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(8.02815474597405e-5))*(px)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.36478630681559e-8))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.424000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(-0.000144159995833776))*(px)*(py)*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(7.11551534325092e-10))*(cj0)*(r00)*(r02)*((py)*(py))))+(((IkReal(-1.22535996458710e-8))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.99999976880001))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-0.999999971100001))*((px)*(px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-1.27199992647840))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.000144159995833776))*(cj0)*(sj0)*((pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.80834067306134e-6))*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.0898879424717168))*(px)*(py)*(r00)*(r01)))+(((IkReal(0.000679999980348001))*(px)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(8.02815474597405e-5))*(px)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(0.423999987746400))*(pz)*((px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(px)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.000679999980348001))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.423999975492801))*(cj0)*(r00)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(4.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-6.75105072318525e-6))*(px)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.0449439712358584))*((py)*(py))*((r01)*(r01))))+(((IkReal(-1.36478630681559e-8))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.000679999980348001))*(py)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-5.77999983295801e-8))*((px)*(px))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.50984403073250e-6))*(px)*(sj0)*((r00)*(r00))))+(((IkReal(3.99999976880001))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.22535996458710e-8))*(pz)*((px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.53708957210214e-10))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.70196880614650e-5))*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.000216239993750664))*(py)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(7.11551534325092e-10))*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.000216239993750664))*(py)*(r00)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-8.50984403073250e-6))*(py)*(r00)*(r01)*(sj0)))+(((IkReal(1.43594146024810e-8))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-1.22535996458710e-8))*((pz)*(pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000288319991667552))*(cj0)*(pz)*(sj0)*((py)*(py))*((r02)*(r02))))+(((IkReal(0.000679999980348001))*(py)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-0.0397120619298817))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(1.38184577328552e-7))*(cj0)*(sj0)*((r01)*(r01))))+(((IkReal(-0.423999987746400))*((cj0)*(cj0))*((pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(-3.99999988440000))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-1.44667348522452e-9))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-9.02043467257645e-7))*(r00)*(r02)*(sj0)))+(((IkReal(0.000288319991667552))*(cj0)*(pz)*(sj0)*((px)*(px))*((r02)*(r02))))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((pz)*(pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.0198560027746394))*((cj0)*(cj0))*((px)*(px))*((r01)*(r01))))+(((IkReal(0.00531864903841572))*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(6.75105072318525e-6))*(cj0)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.00271999992139200))*(cj0)*(py)*(r00)*(r01)*(sj0)*((px)*(px)*(px))))+(((IkReal(0.000216239993750664))*(px)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(3.67607989376129e-8))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(1.36478630681559e-8))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.53708957210214e-10))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-3.99999988440000))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-6.75104094337739e-6))*(px)*(py)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000144159995833776))*(cj0)*(pz)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(5.77999983295801e-8))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.00203999994104400))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(9.77980785828634e-12))*(px)*(py)*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.000216239993750664))*(py)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-2.45071992917419e-8))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(1.70196880614650e-5))*(cj0)*(pz)*(r01)*(r02)))+(((IkReal(-1.36478630681559e-8))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-0.00135999996069600))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.00407999988208800))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.17456890729270e-11))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((py)*(py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.423999963239201))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-6.75105072318525e-6))*(py)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-2.45071992917419e-8))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-4.18559726073583e-6))*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.000679999980348001))*(px)*(py)*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-5.73839311470746e-10))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0198560315387801))*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-6.75105072318525e-6))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-0.847999975492801))*(pz)*((px)*(px))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-8.02815474597405e-5))*(px)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-9.04170336530672e-7))*(py)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.80834067306134e-6))*(cj0)*(px)*(r00)*(r02)*(sj0)))+(((IkReal(1.43594146024810e-8))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-1.80834067306134e-6))*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(8.02815474597405e-5))*(cj0)*(px)*(pz)*(r00)*(r01)))+(((IkReal(3.99999965320001))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(8.50984403073250e-6))*(cj0)*(py)*((r01)*(r01))))+(((IkReal(-7.60959501990047e-5))*(cj0)*(r01)*(r02)*((py)*(py))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(3.99999976880001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.000679999980348001))*(px)*(py)*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.22535996458710e-8))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px)))));
00342 op[1]=((((IkReal(-0.000144159997916888))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-6.13389548871719e-10))*(cj0)*(sj0)*((r00)*(r00))))+(((IkReal(-0.000288319995833776))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.69599997549280))*(cj0)*(px)*(py)*(pz)*(r00)*(r02)))+(((IkReal(-0.179775997402237))*(cj0)*(py)*(pz)*((r01)*(r01))))+(((IkReal(-3.05619195583803e-5))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(5.21381116540961e-14))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-1.80834069919187e-6))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(2.89334692864019e-9))*(px)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(5.78669385728037e-9))*(cj0)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(5.78669385728037e-9))*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-1.52809597791901e-5))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.847999987746400))*(cj0)*(pz)*(r01)*(r02)*((py)*(py))))+(((IkReal(0.847999987746400))*(cj0)*(pp)*(pz)*(r01)*(r02)))+(((IkReal(-0.0898879987011184))*(pp)*(r00)*(r02)*(sj0)))+(((IkReal(1.70196878155305e-5))*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-2.54399996323920))*(cj0)*(px)*(r00)*(r01)*((py)*(py))))+(((IkReal(-0.000288319995833776))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-5.78669385728037e-9))*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.000144159997916888))*(pz)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.000288319995833776))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.847999987746400))*(pz)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.0106372982305404))*(py)*(r00)*(r01)*(sj0)))+(((IkReal(-5.78669385728037e-9))*(cj0)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-0.179775997402237))*(cj0)*(px)*(pz)*(r00)*(r01)))+(((IkReal(0.0106372982305404))*(px)*(sj0)*((r00)*(r00))))+(((IkReal(1.70196878155305e-5))*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(2.89334692864019e-9))*(py)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(0.847999987746400))*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.000144159997916888))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.179775997402237))*(px)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-0.0106372982305404))*(px)*(sj0)*((r02)*(r02))))+(((IkReal(-5.78669385728037e-9))*(cj0)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(-3.05619195583803e-5))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-3.05619195583803e-5))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(1.70196873236615e-5))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(1.52809597791901e-5))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(4.91868977868832e-13))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.847999987746400))*(r00)*(r01)*(sj0)*((py)*(py)*(py))))+(((IkReal(-3.61668139838373e-6))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.179775997402237))*(cj0)*(py)*(pz)*((r02)*(r02))))+(((IkReal(-3.05619195583803e-5))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(5.21381116540961e-14))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.847999987746400))*(cj0)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.847999987746400))*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-3.05619195583803e-5))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.80834069919187e-6))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-1.70196883073995e-5))*(px)*(r00)*(r02)))+(((IkReal(-1.70196883073995e-5))*(pz)*((r02)*(r02))))+(((IkReal(0.847999987746400))*(cj0)*(pz)*(r01)*(r02)*((px)*(px))))+(((IkReal(-3.05619195583803e-5))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.000144159997916888))*(cj0)*(px)*((py)*(py))*((r00)*(r00))))+(((IkReal(-1.70196878155305e-5))*(px)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(4.91868977868832e-13))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.847999987746400))*(cj0)*(pp)*(py)*((r02)*(r02))))+(((IkReal(-3.83368228228676e-7))*(cj0)*(r00)*(r02)))+(((IkReal(-2.89334692864019e-9))*(py)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.69599997549280))*(px)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(6.13389548871719e-10))*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-1.70196883073995e-5))*(py)*(r01)*(r02)))+(((IkReal(0.0898879987011184))*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.847999987746400))*(px)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.000144159997916888))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(1.69599997549280))*(px)*(py)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(1.80408690844623e-6))*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(1.52809597791901e-5))*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(1.80834069919187e-6))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.0898879987011184))*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(2.54399996323920))*(py)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(1.52809597791901e-5))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(-0.847999987746400))*(cj0)*(px)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-4.91868977868832e-13))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.179775997402237))*(py)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.80834069919187e-6))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.000432479993750664))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-0.0106372982305404))*(cj0)*(px)*(r00)*(r01)))+(((IkReal(-2.89334692864019e-9))*(px)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(0.179775997402237))*(px)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00225510722487456))*(cj0)*(r01)*(r02)))+(((IkReal(0.000144159997916888))*(r00)*(r01)*(sj0)*((px)*(px)*(px))))+(((IkReal(0.847999987746400))*(cj0)*(py)*((px)*(px))*((r01)*(r01))))+(((IkReal(-3.05619195583803e-5))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(5.78669385728037e-9))*(cj0)*(px)*(r00)*(r02)*(sj0)))+(((IkReal(0.847999987746400))*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.0898879987011184))*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.80408696058435e-6))*((r02)*(r02))))+(((IkReal(0.847999987746400))*(pp)*(px)*(sj0)*((r02)*(r02))))+(((IkReal(1.70196873236615e-5))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-0.000144159997916888))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.00225510722487456))*(r00)*(r02)*(sj0)))+(((IkReal(-1.80834069919187e-6))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.0898879987011184))*(cj0)*(r01)*(r02)*((py)*(py))))+(((IkReal(-1.52809597791901e-5))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.847999987746400))*(cj0)*(py)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.847999987746400))*(px)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(-0.179775997402237))*(cj0)*(px)*(py)*(r00)*(r02)))+(((IkReal(-0.000432479993750664))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.000144159997916888))*(cj0)*(pz)*(r00)*(r02)*((py)*(py))))+(((IkReal(-3.61668139838373e-6))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.000144159997916888))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-3.60817371261624e-6))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.000288319995833776))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.0212745964610808))*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.0898879987011184))*(cj0)*(r01)*(r02)*((px)*(px))))+(((IkReal(1.52809597791901e-5))*(cj0)*(r00)*(r02)*((py)*(py))))+(((IkReal(-0.000144159997916888))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-3.40393746473231e-5))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.70196878155305e-5))*(py)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-1.52809597791901e-5))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.0212745964610808))*(cj0)*(pz)*(r01)*(r02)))+(((IkReal(-3.05619195583803e-5))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(1.80408690844623e-6))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.847999987746400))*(cj0)*(r00)*(r01)*((px)*(px)*(px))))+(((IkReal(0.0898879987011184))*(cj0)*(pp)*(r01)*(r02)))+(((IkReal(0.0106372982305404))*(cj0)*(py)*((r02)*(r02))))+(((IkReal(-0.000144159997916888))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(-1.52809597791901e-5))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.000144159997916888))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-1.80834069919187e-6))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-4.91868977868832e-13))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.847999987746400))*(py)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.000144159997916888))*(py)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.000144159997916888))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.179775997402237))*(px)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(0.000144159997916888))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-0.0898879987011184))*(cj0)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-0.000144159997916888))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(-0.847999987746400))*(cj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.847999987746400))*(pp)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.69599997549280))*(cj0)*(py)*((px)*(px))*((r00)*(r00))))+(((IkReal(-3.83368228228676e-7))*(r01)*(r02)*(sj0)))+(((IkReal(-0.0106372982305404))*(cj0)*(py)*((r01)*(r01))))+(((IkReal(-6.13389548871719e-10))*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(6.13389548871719e-10))*(cj0)*(sj0)*((r01)*(r01))))+(((IkReal(0.000144159997916888))*(cj0)*(r00)*(r01)*((py)*(py)*(py)))));
00343 op[2]=((((IkReal(4.90367290720905e-7))*(cj0)*(sj0)*((r00)*(r00))))+(((IkReal(-1.99999994220000))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(0.00135999996069600))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-0.000168934289440953))*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.129600006696956))*(pp)*((r02)*(r02))))+(((IkReal(0.140063931726913))*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.000152191900398009))*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.00543999984278400))*(cj0)*(py)*(r00)*(r01)*(sj0)*((px)*(px)*(px))))+(((IkReal(23.9999986128000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-2.58726230676616e-8))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.31199993318320e-7))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(4.76217367871506e-5))*(px)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.169312070922195))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(r00)*(r01)*((py)*(py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-2.72957261363118e-8))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(8.37119452147167e-6))*(cj0)*(r01)*(r02)*((px)*(px))))+(((IkReal(-7.99999953760001))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-0.00271999992139200))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.280127970414691))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.00271999992139200))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-9.20084336602798e-10))*(r01)*(r02)*(sj0)))+(((IkReal(4.76217367871506e-5))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-1.95596157165727e-11))*(px)*(py)*((cj0)*(cj0))*((r02)*(r02))))+(((IkReal(-1.99999994220000))*((px)*(px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.00407999988208800))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.99999976880001))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py)*(py)*(py))))+(((IkReal(-4.16812197112770e-11))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-7.99999953760001))*(px)*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-7.99999953760001))*(py)*(r00)*(r01)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-5.77999983295801e-8))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.66256733590868e-15))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-7.99999953760001))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-0.0898879424717168))*((py)*(py))*((r01)*(r01))))+(((IkReal(7.99999976880001))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.000160563094919481))*(px)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(0.140063931726913))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-1.95596157165727e-11))*(cj0)*(sj0)*((py)*(py))*((r02)*(r02))))+(((IkReal(-8.37119452147167e-6))*(cj0)*(pp)*(r01)*(r02)))+(((IkReal(-7.99999976880001))*((px)*(px))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(r00)*(r01)*((pz)*(pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-7.99999965320001))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(0.000160563094919481))*(cj0)*(px)*(pz)*(r00)*(r01)))+(((IkReal(-2.72957261363118e-8))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-4.16812197112770e-11))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-2.31199993318320e-7))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(3.99999965320001))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-7.99999953760001))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.140063989255195))*((cj0)*(cj0))*((px)*(px))*((r01)*(r01))))+(((IkReal(0.00407999988208800))*(py)*(pz)*(r00)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(23.9999986128000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(4.04784928947514e-9))*((px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-7.99999953760001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-0.00135999996069600))*(px)*(py)*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.00543999984278400))*(cj0)*(px)*(r00)*(r01)*(sj0)*((py)*(py)*(py))))+(((IkReal(2.87188292049620e-8))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-8.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.280127970414691))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-4.76217563467663e-5))*(px)*(py)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.00407999988208800))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(-0.140063989255195))*((cj0)*(cj0))*((py)*(py))*((r01)*(r01))))+(((IkReal(-4.76217367871506e-5))*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.00135999996069600))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(4.90367290720905e-7))*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.000160563094919481))*(px)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-4.76217563467663e-5))*(cj0)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(0.00407999988208800))*(r00)*(r01)*((px)*(px))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.99999988440000))*((py)*(py))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(1.15599996659160e-7))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-5.77999983295801e-8))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(3.99999988440000))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-7.99999976880001))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(7.99999953760001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-7.99999976880001))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(8.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00135999996069600))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(1.95596157165727e-11))*(cj0)*(sj0)*((px)*(px))*((r02)*(r02))))+(((IkReal(0.00135999996069600))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.00288451339146642))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00135999996069600))*(px)*((py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-15.9999993064000))*(py)*(pz)*(r01)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-5.77999983295801e-8))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00135999996069600))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.280127863453827))*(px)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(4.76217367871506e-5))*(py)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-15.9999993064000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(0.00135999996069600))*(px)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(3.99999965320001))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.00135999996069600))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-2.31199993318320e-7))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.0794241284504778))*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.280127855358132))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.00407999988208800))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px))*((py)*(py))))+(((IkReal(2.72957261363118e-8))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.000160563094919481))*(cj0)*(px)*(py)*(r00)*(r02)))+(((IkReal(7.99999976880001))*(py)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-2.31199993318320e-7))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(r00)*(r01)*((px)*(px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(4.04784928947514e-9))*((cj0)*(cj0))*((py)*(py))*((r00)*(r00))))+(((IkReal(-2.72957261363118e-8))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.00271999992139200))*(cj0)*(py)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-4.90367290720905e-7))*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.00407999988208800))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(0.000160563094919481))*(px)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(4.76217563467663e-5))*(px)*(py)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-8.09569525381560e-9))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.00271999992139200))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-5.77999983295801e-8))*((px)*(px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.280127855358132))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-0.00135999996069600))*(pz)*(r00)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(7.99999953760001))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.72957261363118e-8))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.00135999996069600))*(px)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-7.99999965320001))*((px)*(px))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.280127863453827))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-5.77999983295801e-8))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px)*(px))))+(((IkReal(-3.99999988440000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(2.87188292049620e-8))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(8.00000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(4.76217563467663e-5))*(px)*(py)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00407999988208800))*(px)*(pz)*(r01)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.280127986606089))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(2.31199993318320e-7))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-9.20084336602798e-10))*(cj0)*(r00)*(r02)))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(0.00815999976417601))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.00194040410709565))*((r02)*(r02))))+(((IkReal(-2.58726230676616e-8))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.000168934289440953))*(cj0)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-0.00135999996069600))*(py)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(pz)*(r01)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-0.140063989255195))*((px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(0.00135999996069600))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-4.04784928947514e-9))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.00271999992139200))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.280127855358132))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.00144225673741443))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-7.99999953760001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(0.00135999996069600))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.000160563094919481))*(py)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00271999992139200))*(cj0)*(px)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-1.42310306865018e-9))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(0.00135999996069600))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-7.99999953760001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(7.99999953760001))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(7.99999953760001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-4.76217563467663e-5))*(cj0)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.140063989255195))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(15.9999990752000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00144225673741443))*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(0.000679999980348001))*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py)*(py))))+(((IkReal(-2.72957261363118e-8))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-2.31199993318320e-7))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.000160563094919481))*(cj0)*(py)*(pz)*((r02)*(r02))))+(((IkReal(0.00271999992139200))*(px)*(py)*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-1.15599996659160e-7))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-1.99999994220000))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(4.04784762690780e-9))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.95596157165727e-11))*(px)*(py)*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-7.99999976880001))*(pz)*(r00)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(23.9999986128000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-7.99999953760001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(1.15056559713528e-7))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(1.42310306865018e-9))*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(7.99999930640002))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-4.90367290720905e-7))*(cj0)*(sj0)*((r01)*(r01))))+(((IkReal(-5.41226080354587e-6))*(cj0)*(r01)*(r02)))+(((IkReal(4.76217563467663e-5))*(cj0)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(4.76217563467663e-5))*(cj0)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-1.99999994220000))*((py)*(py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-8.37119452147167e-6))*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-7.99999953760001))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(3.99999988440000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.0794241284504778))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.0898879424717168))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.00135999996069600))*(py)*((px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-4.04784928947514e-9))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-5.75282815193314e-8))*((px)*(px))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(4.04784762690780e-9))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.42310306865018e-9))*(cj0)*(r00)*(r02)*((py)*(py))))+(((IkReal(-9.52434735743012e-5))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.00407999988208800))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-1.66256733590868e-15))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-4.76217367871506e-5))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.179775884943434))*(px)*(py)*(r00)*(r01)))+(((IkReal(-1.99999994220000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(7.99999930640002))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.00135999996069600))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-1.99999994220000))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(5.41226080354587e-6))*(r00)*(r02)*(sj0)))+(((IkReal(1.15599996659160e-7))*((py)*(py))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(4.76217367871506e-5))*(cj0)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.00135999996069600))*(px)*((py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(9.52434735743012e-5))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-5.77999983295801e-8))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(-5.75282815193314e-8))*((cj0)*(cj0))*((py)*(py))*((r02)*(r02))))+(((IkReal(-4.76217563467663e-5))*(px)*(py)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-0.00271999992139200))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00135999996069600))*(px)*(py)*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.37119452147167e-6))*(pp)*(r00)*(r02)*(sj0)))+(((IkReal(3.99999976880001))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-4.76217367871506e-5))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.280127986606089))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.00815999976417601))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-4.76217367871506e-5))*(cj0)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(2.72957261363118e-8))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.000152191900398009))*(cj0)*(r01)*(r02)*((py)*(py))))+(((IkReal(-0.00135999996069600))*(py)*((px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.15599996659160e-7))*((px)*(px))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000160563094919481))*(cj0)*(py)*(pz)*((r01)*(r01))))+(((IkReal(2.72957261363118e-8))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-1.42310306865018e-9))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.00135999996069600))*(py)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-16.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-8.09569525381560e-9))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-3.99999976880001))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px)*(px)*(px))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02))));
00344 op[3]=((((IkReal(-0.000144159997916888))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.000288319995833776))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.69599997549280))*(cj0)*(px)*(py)*(pz)*(r00)*(r02)))+(((IkReal(0.0898879987011184))*(cj0)*(r01)*(r02)*((py)*(py))))+(((IkReal(-1.52809597791901e-5))*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-1.80834069919187e-6))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-5.21381116540961e-14))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(2.89334692864019e-9))*(px)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(5.78669385728037e-9))*(cj0)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(5.78669385728037e-9))*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.0898879987011184))*(cj0)*(r01)*(r02)*((px)*(px))))+(((IkReal(-0.847999987746400))*(cj0)*(pz)*(r01)*(r02)*((py)*(py))))+(((IkReal(0.847999987746400))*(cj0)*(pp)*(pz)*(r01)*(r02)))+(((IkReal(1.70196878155305e-5))*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-2.54399996323920))*(cj0)*(px)*(r00)*(r01)*((py)*(py))))+(((IkReal(-0.000288319995833776))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.00225510722487456))*(r00)*(r02)*(sj0)))+(((IkReal(-5.78669385728037e-9))*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.000144159997916888))*(pz)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.000288319995833776))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.847999987746400))*(pz)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.0106372982305404))*(py)*(r00)*(r01)*(sj0)))+(((IkReal(3.83368228228676e-7))*(cj0)*(r00)*(r02)))+(((IkReal(-5.78669385728037e-9))*(cj0)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(1.80408696058435e-6))*((r02)*(r02))))+(((IkReal(0.0106372982305404))*(px)*(sj0)*((r00)*(r00))))+(((IkReal(1.70196878155305e-5))*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(2.89334692864019e-9))*(py)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(0.847999987746400))*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.000144159997916888))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.179775997402237))*(cj0)*(py)*(pz)*((r01)*(r01))))+(((IkReal(3.05619195583803e-5))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.179775997402237))*(cj0)*(px)*(pz)*(r00)*(r01)))+(((IkReal(-0.0106372982305404))*(px)*(sj0)*((r02)*(r02))))+(((IkReal(-5.78669385728037e-9))*(cj0)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(3.60817371261624e-6))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(1.52809597791901e-5))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(1.70196873236615e-5))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-6.13389548871719e-10))*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(3.05619195583803e-5))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(4.91868977868832e-13))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.847999987746400))*(r00)*(r01)*(sj0)*((py)*(py)*(py))))+(((IkReal(-3.61668139838373e-6))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.847999987746400))*(cj0)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.847999987746400))*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.179775997402237))*(cj0)*(px)*(py)*(r00)*(r02)))+(((IkReal(-1.80834069919187e-6))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-1.70196883073995e-5))*(px)*(r00)*(r02)))+(((IkReal(-1.70196883073995e-5))*(pz)*((r02)*(r02))))+(((IkReal(0.847999987746400))*(cj0)*(pz)*(r01)*(r02)*((px)*(px))))+(((IkReal(0.000144159997916888))*(cj0)*(px)*((py)*(py))*((r00)*(r00))))+(((IkReal(-1.70196878155305e-5))*(px)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(6.13389548871719e-10))*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(4.91868977868832e-13))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.847999987746400))*(cj0)*(pp)*(py)*((r02)*(r02))))+(((IkReal(-1.52809597791901e-5))*(cj0)*(r00)*(r02)*((py)*(py))))+(((IkReal(-1.52809597791901e-5))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(-2.89334692864019e-9))*(py)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.52809597791901e-5))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(1.69599997549280))*(px)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.179775997402237))*(px)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-1.70196883073995e-5))*(py)*(r01)*(r02)))+(((IkReal(0.179775997402237))*(cj0)*(py)*(pz)*((r02)*(r02))))+(((IkReal(0.847999987746400))*(px)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.000144159997916888))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(1.69599997549280))*(px)*(py)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.179775997402237))*(px)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(-0.0898879987011184))*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(1.80834069919187e-6))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(1.52809597791901e-5))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.54399996323920))*(py)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(3.83368228228676e-7))*(r01)*(r02)*(sj0)))+(((IkReal(-0.847999987746400))*(cj0)*(px)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-4.91868977868832e-13))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.80834069919187e-6))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(1.52809597791901e-5))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.000432479993750664))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(3.05619195583803e-5))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.0106372982305404))*(cj0)*(px)*(r00)*(r01)))+(((IkReal(3.05619195583803e-5))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-2.89334692864019e-9))*(px)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.179775997402237))*(px)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-0.0898879987011184))*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.000144159997916888))*(r00)*(r01)*(sj0)*((px)*(px)*(px))))+(((IkReal(0.847999987746400))*(cj0)*(py)*((px)*(px))*((r01)*(r01))))+(((IkReal(5.78669385728037e-9))*(cj0)*(px)*(r00)*(r02)*(sj0)))+(((IkReal(0.847999987746400))*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.0898879987011184))*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.847999987746400))*(pp)*(px)*(sj0)*((r02)*(r02))))+(((IkReal(1.70196873236615e-5))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(6.13389548871719e-10))*(cj0)*(sj0)*((r00)*(r00))))+(((IkReal(-0.000144159997916888))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.0898879987011184))*(cj0)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-1.80834069919187e-6))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-6.13389548871719e-10))*(cj0)*(sj0)*((r01)*(r01))))+(((IkReal(-1.80408690844623e-6))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.847999987746400))*(cj0)*(py)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.847999987746400))*(px)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(3.05619195583803e-5))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.179775997402237))*(py)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.000432479993750664))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.000144159997916888))*(cj0)*(pz)*(r00)*(r02)*((py)*(py))))+(((IkReal(-3.61668139838373e-6))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.000144159997916888))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.80408690844623e-6))*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(3.05619195583803e-5))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.000288319995833776))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.0212745964610808))*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.000144159997916888))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(3.05619195583803e-5))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-3.40393746473231e-5))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.70196878155305e-5))*(py)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.0212745964610808))*(cj0)*(pz)*(r01)*(r02)))+(((IkReal(0.0898879987011184))*(pp)*(r00)*(r02)*(sj0)))+(((IkReal(-0.0898879987011184))*(cj0)*(pp)*(r01)*(r02)))+(((IkReal(0.847999987746400))*(cj0)*(r00)*(r01)*((px)*(px)*(px))))+(((IkReal(0.0106372982305404))*(cj0)*(py)*((r02)*(r02))))+(((IkReal(-0.000144159997916888))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.000144159997916888))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-1.80834069919187e-6))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-4.91868977868832e-13))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.52809597791901e-5))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(0.847999987746400))*(py)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.000144159997916888))*(py)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.000144159997916888))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.000144159997916888))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-5.21381116540961e-14))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(3.05619195583803e-5))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.000144159997916888))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-0.000144159997916888))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(-0.847999987746400))*(cj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.847999987746400))*(pp)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.69599997549280))*(cj0)*(py)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0106372982305404))*(cj0)*(py)*((r01)*(r01))))+(((IkReal(0.00225510722487456))*(cj0)*(r01)*(r02)))+(((IkReal(0.000144159997916888))*(cj0)*(r00)*(r01)*((py)*(py)*(py)))));
00345 op[4]=((((IkReal(-0.000812850431382459))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-1.53708957210214e-10))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.424000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.000144159995833776))*(cj0)*(pz)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(0.00531864903841572))*(px)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(pz)*(r00)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(1.17456890729270e-11))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(pz)*(r01)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(px)*((py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(5.73838480187078e-10))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.27199996323920))*(py)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-9.04170336530672e-7))*(px)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.00203999994104400))*(py)*(pz)*(r00)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(-9.77980785828634e-12))*(cj0)*(sj0)*((py)*(py))*((r02)*(r02))))+(((IkReal(-8.02815474597405e-5))*(cj0)*(px)*(py)*(r00)*(r02)))+(((IkReal(-8.31283667954339e-16))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.000144159995833776))*(cj0)*(sj0)*((pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(1.27199992647840))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.000432479987501328))*(cj0)*(py)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0397120066969557))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.847999950985601))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.29363115338308e-8))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.99999994220000))*((py)*(py))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-1.38184577328552e-7))*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.000432479987501328))*(cj0)*(px)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.0449439712358584))*((px)*(px))*((r00)*(r00))))+(((IkReal(-9.77980785828634e-12))*(px)*(py)*((cj0)*(cj0))*((r02)*(r02))))+(((IkReal(0.00203999994104400))*(px)*(pz)*(r01)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.44667348522452e-9))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-5.73838480187078e-10))*((cj0)*(cj0))*((py)*(py))*((r00)*(r00))))+(((IkReal(-0.000216239993750664))*(py)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(5.73838480187078e-10))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.44667348522452e-9))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(8.02815474597405e-5))*(cj0)*(py)*(pz)*((r01)*(r01))))+(((IkReal(-1.53708957210214e-10))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-8.02815474597405e-5))*(py)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00135999996069600))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-0.999999971100001))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.99999976880001))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.99999982660000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-5.73838480187078e-10))*((px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-4.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-0.848000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.0198560027746394))*((cj0)*(cj0))*((py)*(py))*((r01)*(r01))))+(((IkReal(1.53708957210214e-10))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.000144159995833776))*(r00)*(r01)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.0198560027746394))*((px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.99999988440000))*(pz)*(r00)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-8.50984403073250e-6))*(cj0)*(py)*((r01)*(r01))))+(((IkReal(8.50984403073250e-6))*(px)*(sj0)*((r00)*(r00))))+(((IkReal(1.22535996458710e-8))*((cj0)*(cj0))*((pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(11.9999993064000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-0.423999963239201))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.67607989376129e-8))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-4.18559726073583e-6))*(cj0)*(pp)*(r01)*(r02)))+(((IkReal(-0.00531864888470676))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.847999950985601))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-2.88999991647900e-8))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.44667348522452e-9))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.00135999996069600))*(px)*(py)*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.0250879966515221))*(pp)*((r02)*(r02))))+(((IkReal(0.000144159995833776))*(cj0)*(r01)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(1.53347389433800e-10))*(cj0)*(r00)*(r02)))+(((IkReal(1.99999994220000))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.29363115338308e-8))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(8.50984403073250e-6))*(py)*(r00)*(r01)*(sj0)))+(((IkReal(-1.15599996659160e-7))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.00531864903841572))*(py)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(6.75104094337739e-6))*(px)*(py)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-0.0397120619298817))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.0397120044016018))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px)*(px)*(px))))+(((IkReal(4.00000000000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-0.0198560027746394))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(cj0)*(px)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-7.99999965320001))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(6.75104094337739e-6))*(cj0)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(1.53347389433800e-10))*(r01)*(r02)*(sj0)))+(((IkReal(1.14767862294149e-9))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-2.87641407596657e-8))*((px)*(px))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-6.75104094337739e-6))*(cj0)*(sj0)*((px)*(px))*((r01)*(r01))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((pz)*(pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(-6.75104094337739e-6))*(cj0)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(6.75104094337739e-6))*(cj0)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(-8.02815474597405e-5))*(cj0)*(py)*(pz)*((r02)*(r02))))+(((IkReal(-2.88999991647900e-8))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000144159995833776))*(px)*(py)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(7.20799979168881e-5))*(r01)*(r02)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-6.75105072318525e-6))*(cj0)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(4.18559726073583e-6))*(cj0)*(r01)*(r02)*((px)*(px))))+(((IkReal(-2.88999991647900e-8))*((px)*(px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.80834067306134e-6))*(cj0)*(px)*(r00)*(r02)*(sj0)))+(((IkReal(1.38184577328552e-7))*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-8.31283667954339e-16))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(0.0397120630775603))*(px)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.00407999988208800))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.000144159995833776))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-0.140063935774761))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.0397120044016018))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.847999963239201))*(py)*(r01)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(6.75105072318525e-6))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(9.04170336530672e-7))*(py)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.22535996458710e-8))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.000144159995833776))*(px)*(py)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-6.75104094337739e-6))*(px)*(py)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-7.11551534325092e-10))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-0.00203999994104400))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(-1.36478630681559e-8))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-0.000144159995833776))*(px)*(py)*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-0.423999987746400))*(pz)*((px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(6.75105072318525e-6))*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.000679999980348001))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(9.02043467257645e-7))*(cj0)*(r01)*(r02)))+(((IkReal(8.44671447204764e-5))*(cj0)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-1.22535996458710e-8))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.80834067306134e-6))*(cj0)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.000144159995833776))*(cj0)*(pz)*(sj0)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.847999963239201))*(px)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(-0.0198560315387801))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.99999988440000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-1.15599996659160e-7))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-1.27199996323920))*(px)*(r00)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(px)*((cj0)*(cj0))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.00203999994104400))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px))*((py)*(py))))+(((IkReal(0.000679999980348001))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-5.73839311470746e-10))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py)*(py))))+(((IkReal(1.35021014463705e-5))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-3.67607989376129e-8))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-2.87641407596657e-8))*((cj0)*(cj0))*((py)*(py))*((r02)*(r02))))+(((IkReal(-1.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(7.60959501990047e-5))*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.848000000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.000216239993750664))*(px)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.00531864919212468))*(pz)*((r02)*(r02))))+(((IkReal(1.80834067306134e-6))*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-3.99999982660001))*((px)*(px))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.27199992647840))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.00135999996069600))*(cj0)*(py)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.99999994220000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(py)*((px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(2.45071992917419e-8))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(1.15599996659160e-7))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-1.36478630681559e-8))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.53708957210214e-10))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.15599996659160e-7))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.00203999994104400))*(py)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-1.99999988440000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py)*(py)*(py))))+(((IkReal(0.000406425227436919))*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.0951199645389027))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000144159995833776))*(cj0)*(r00)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(0.00203999994104400))*(cj0)*(sj0)*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.424000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(0.000432479987501328))*(cj0)*(px)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0397120630775603))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-0.999999971100001))*((py)*(py)*(py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.0397120619298817))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-7.20799979168881e-5))*(r01)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.000679999980348001))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.22535996458710e-8))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.000144159995833776))*(cj0)*(pz)*(sj0)*((py)*(py))*((r00)*(r00))))+(((IkReal(-1.27199992647840))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.00531864888470676))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-3.99999976880001))*(px)*(r00)*(r01)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.000679999980348001))*(py)*((px)*(px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-7.99999965320001))*(py)*(pz)*(r01)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(0.000216239993750664))*(py)*(r00)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(6.75105072318525e-6))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.36478630681559e-8))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-9.04170336530672e-7))*(py)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.000679999980348001))*(px)*((py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.69599990197120))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((px)*(px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(-5.77999983295801e-8))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.36478630681559e-8))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-1.35021014463705e-5))*(cj0)*(px)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.27199992647840))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-8.44671447204764e-5))*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(1.69600000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(0.000144159995833776))*(cj0)*(pz)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.847999950985601))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.000339999990174000))*(cj0)*(sj0)*((px)*(px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-3.99999976880001))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-4.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00531864903841572))*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(1.22535996458710e-8))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px)*(px))))+(((IkReal(11.9999993064000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(1.80834067306134e-6))*(cj0)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(3.99999965320001))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.423999987746400))*(pz)*((cj0)*(cj0))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.000216239993750664))*(px)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(1.14767862294149e-9))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(5.77999983295801e-8))*((py)*(py))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(6.75104094337739e-6))*(px)*(py)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(0.000406425227436919))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(1.69600000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(0.847999975492801))*(pz)*((px)*(px))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-3.99999982660001))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r00)*(r00))))+(((IkReal(0.00135999996069600))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000288319991667552))*(px)*(py)*(pz)*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(7.99999953760001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.00271999992139200))*(cj0)*(px)*(r00)*(r01)*(sj0)*((py)*(py)*(py))))+(((IkReal(0.423999975492801))*(cj0)*(r01)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-3.99999976880001))*(py)*(r00)*(r01)*((px)*(px)*(px))*((sj0)*(sj0))))+(((IkReal(0.00135999996069600))*(cj0)*(pz)*(r00)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(4.18559726073583e-6))*(pp)*(r00)*(r02)*(sj0)))+(((IkReal(1.99999982660000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-7.11551534325092e-10))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(3.99999976880001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-3.99999976880001))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(1.80834067306134e-6))*(cj0)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(0.423999987746400))*((pz)*(pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(5.75282798567641e-8))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.140063935774761))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.000216239993750664))*(py)*(r00)*(r02)*((px)*(px))*((sj0)*(sj0))))+(((IkReal(1.15599996659160e-7))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-1.15599996659160e-7))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(-0.000157351575182608))*((r02)*(r02))))+(((IkReal(0.000216239993750664))*(px)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(0.0397120066969557))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(11.9999993064000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-1.99999994220000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.000432479987501328))*(cj0)*(py)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.00203999994104400))*(r00)*(r01)*((px)*(px))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(0.00531864919212468))*(px)*(r00)*(r02)))+(((IkReal(-0.000679999980348001))*(cj0)*(sj0)*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.848000000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(3.99999988440000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(0.000679999980348001))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.423999975492801))*(cj0)*(r00)*(r02)*(sj0)*((py)*(py)*(py))))+(((IkReal(-4.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(9.77980785828634e-12))*(cj0)*(sj0)*((px)*(px))*((r02)*(r02))))+(((IkReal(-3.99999976880001))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r01)*(r01))))+(((IkReal(-1.80834067306134e-6))*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-1.38184577328552e-7))*(cj0)*(sj0)*((r00)*(r00))))+(((IkReal(-8.50984403073250e-6))*(cj0)*(px)*(r00)*(r01)))+(((IkReal(-3.99999988440000))*((px)*(px))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(8.02815474597405e-5))*(px)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.36478630681559e-8))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(0.000144159995833776))*(px)*(py)*(pz)*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.423999987746400))*(pz)*((cj0)*(cj0))*((px)*(px))*((r01)*(r01))))+(((IkReal(7.11551534325092e-10))*(cj0)*(r00)*(r02)*((py)*(py))))+(((IkReal(-3.99999976880001))*(cj0)*(pz)*(r01)*(r02)*(sj0)*((px)*(px)*(px))))+(((IkReal(-0.000288319991667552))*(cj0)*(pz)*(sj0)*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.999999971100001))*((px)*(px)*(px)*(px))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.000216239993750664))*(py)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(8.50984403073250e-6))*(cj0)*(py)*((r02)*(r02))))+(((IkReal(0.000679999980348001))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.0898879424717168))*(px)*(py)*(r00)*(r01)))+(((IkReal(0.000679999980348001))*(px)*(r01)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(8.02815474597405e-5))*(px)*(py)*(r01)*(r02)*(sj0)))+(((IkReal(-8.50984403073250e-6))*(px)*(sj0)*((r02)*(r02))))+(((IkReal(1.44667348522452e-9))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-0.000679999980348001))*(px)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-0.00135999996069600))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.22535996458710e-8))*(pz)*((px)*(px))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.000144159995833776))*(cj0)*(sj0)*((pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(0.000679999980348001))*(px)*(py)*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.423999987746400))*(pz)*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-6.75105072318525e-6))*(px)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-7.20799979168881e-5))*(r00)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(7.20799979168881e-5))*(r00)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.423999963239201))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.423999987746400))*(r01)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-0.0449439712358584))*((py)*(py))*((r01)*(r01))))+(((IkReal(-1.36478630681559e-8))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.000679999980348001))*(py)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-5.77999983295801e-8))*((px)*(px))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.44667348522452e-9))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(3.99999976880001))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.45071992917419e-8))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(7.11551534325092e-10))*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(1.43594146024810e-8))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.000679999980348001))*(py)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz)*(pz))))+(((IkReal(-0.0397120619298817))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(1.38184577328552e-7))*(cj0)*(sj0)*((r01)*(r01))))+(((IkReal(-2.89334697044905e-9))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(0.423999987746400))*((cj0)*(cj0))*((pz)*(pz)*(pz))*((r01)*(r01))))+(((IkReal(-3.99999988440000))*((cj0)*(cj0))*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.000339999990174000))*(cj0)*(sj0)*((py)*(py)*(py)*(py))*((r00)*(r00))))+(((IkReal(0.848000000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-9.02043467257645e-7))*(r00)*(r02)*(sj0)))+(((IkReal(0.000339999990174000))*(r00)*(r01)*((pz)*(pz)*(pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.848000000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0198560027746394))*((cj0)*(cj0))*((px)*(px))*((r01)*(r01))))+(((IkReal(1.70196880614650e-5))*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(6.75105072318525e-6))*(cj0)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.00271999992139200))*(cj0)*(py)*(r00)*(r01)*(sj0)*((px)*(px)*(px))))+(((IkReal(9.04170336530672e-7))*(px)*(r01)*(r02)*((cj0)*(cj0))))+(((IkReal(1.69600000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(4.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(1.22535996458710e-8))*(pz)*((cj0)*(cj0))*((py)*(py))*((r00)*(r00))))+(((IkReal(1.36478630681559e-8))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.0106372977694135))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.44667348522452e-9))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-3.99999976880001))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-3.99999988440000))*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py)*(py))))+(((IkReal(-6.75104094337739e-6))*(px)*(py)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(5.77999983295801e-8))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.00203999994104400))*(px)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((py)*(py))))+(((IkReal(9.77980785828634e-12))*(px)*(py)*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.00531864919212468))*(py)*(r01)*(r02)))+(((IkReal(-0.00531864903841572))*(pz)*((cj0)*(cj0))*((r01)*(r01))))+(((IkReal(-1.36478630681559e-8))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-0.00135999996069600))*(cj0)*(sj0)*((py)*(py))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.000216239993750664))*(px)*(r01)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.00407999988208800))*(cj0)*(py)*(pz)*(r01)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.999999971100001))*((cj0)*(cj0))*((py)*(py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.17456890729270e-11))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((py)*(py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.424000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-6.75105072318525e-6))*(py)*(pz)*(r00)*(r02)*((sj0)*(sj0))))+(((IkReal(-4.18559726073583e-6))*(r00)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.000679999980348001))*(px)*(py)*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-5.73839311470746e-10))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0198560315387801))*((cj0)*(cj0))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.70196880614650e-5))*(cj0)*(pz)*(r01)*(r02)))+(((IkReal(-0.000339999990174000))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz)*(pz)*(pz))))+(((IkReal(-6.75105072318525e-6))*(r00)*(r01)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.000288319991667552))*(px)*(py)*(pz)*((cj0)*(cj0))*((r02)*(r02))))+(((IkReal(0.847999975492801))*(pz)*((cj0)*(cj0))*((py)*(py))*((r02)*(r02))))+(((IkReal(-8.02815474597405e-5))*(px)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(1.43594146024810e-8))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(8.02815474597405e-5))*(cj0)*(px)*(pz)*(r00)*(r01)))+(((IkReal(0.000288319991667552))*(cj0)*(pz)*(sj0)*((py)*(py))*((r02)*(r02))))+(((IkReal(3.99999965320001))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.22535996458710e-8))*((pz)*(pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-2.89334697044905e-9))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-7.60959501990047e-5))*(cj0)*(r01)*(r02)*((py)*(py))))+(((IkReal(-2.88999991647900e-8))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(3.99999976880001))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.000679999980348001))*(px)*(py)*((pz)*(pz))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.000679999980348001))*(py)*((cj0)*(cj0))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.423999987746400))*(r00)*(r02)*((px)*(px)*(px))*((sj0)*(sj0)))));
00346 polyroots4(op,zeror,numroots);
00347 IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1];
00348 int numsolutions = 0;
00349 for(int ij1 = 0; ij1 < numroots; ++ij1)
00350 {
00351 IkReal htj1 = zeror[ij1];
00352 tempj1array[0]=((IkReal(2.00000000000000))*(atan(htj1)));
00353 for(int kj1 = 0; kj1 < 1; ++kj1)
00354 {
00355 j1array[numsolutions] = tempj1array[kj1];
00356 if( j1array[numsolutions] > IKPI )
00357 {
00358     j1array[numsolutions]-=IK2PI;
00359 }
00360 else if( j1array[numsolutions] < -IKPI )
00361 {
00362     j1array[numsolutions]+=IK2PI;
00363 }
00364 sj1array[numsolutions] = IKsin(j1array[numsolutions]);
00365 cj1array[numsolutions] = IKcos(j1array[numsolutions]);
00366 numsolutions++;
00367 }
00368 }
00369 bool j1valid[4]={true,true,true,true};
00370 _nj1 = 4;
00371 for(int ij1 = 0; ij1 < numsolutions; ++ij1)
00372     {
00373 if( !j1valid[ij1] )
00374 {
00375     continue;
00376 }
00377     j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
00378 htj1 = IKtan(j1/2);
00379 
00380 _ij1[0] = ij1; _ij1[1] = -1;
00381 for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1)
00382 {
00383 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00384 {
00385     j1valid[iij1]=false; _ij1[1] = iij1; break; 
00386 }
00387 }
00388 {
00389 IkReal j5array[2], cj5array[2], sj5array[2];
00390 bool j5valid[2]={false};
00391 _nj5 = 2;
00392 sj5array[0]=((((IkReal(-0.999999985550000))*(cj0)*(r00)))+(((IkReal(0.000169999997543500))*(cj0)*(r01)))+(((IkReal(-0.999999985550000))*(r01)*(sj0)))+(((IkReal(-0.000169999997543500))*(r00)*(sj0))));
00393 if( sj5array[0] >= -1-IKFAST_SINCOS_THRESH && sj5array[0] <= 1+IKFAST_SINCOS_THRESH )
00394 {
00395     j5valid[0] = j5valid[1] = true;
00396     j5array[0] = IKasin(sj5array[0]);
00397     cj5array[0] = IKcos(j5array[0]);
00398     sj5array[1] = sj5array[0];
00399     j5array[1] = j5array[0] > 0 ? (IKPI-j5array[0]) : (-IKPI-j5array[0]);
00400     cj5array[1] = -cj5array[0];
00401 }
00402 else if( isnan(sj5array[0]) )
00403 {
00404     // probably any value will work
00405     j5valid[0] = true;
00406     cj5array[0] = 1; sj5array[0] = 0; j5array[0] = 0;
00407 }
00408 for(int ij5 = 0; ij5 < 2; ++ij5)
00409 {
00410 if( !j5valid[ij5] )
00411 {
00412     continue;
00413 }
00414 _ij5[0] = ij5; _ij5[1] = -1;
00415 for(int iij5 = ij5+1; iij5 < 2; ++iij5)
00416 {
00417 if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH )
00418 {
00419     j5valid[iij5]=false; _ij5[1] = iij5; break; 
00420 }
00421 }
00422 j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5];
00423 
00424 {
00425 IkReal dummyeval[1];
00426 IkReal gconst0;
00427 gconst0=IKsign(cj5);
00428 dummyeval[0]=cj5;
00429 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00430 {
00431 {
00432 IkReal dummyeval[1];
00433 dummyeval[0]=cj5;
00434 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00435 {
00436 {
00437 IkReal dummyeval[1];
00438 dummyeval[0]=cj5;
00439 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00440 {
00441 {
00442 IkReal evalcond[9];
00443 IkReal x43=(py)*(py);
00444 IkReal x44=(pz)*(pz);
00445 IkReal x45=(px)*(px);
00446 IkReal x46=((IkReal(3.60399994792220e-5))*(pz));
00447 IkReal x47=((cj0)*(r00));
00448 IkReal x48=((r01)*(sj0));
00449 IkReal x49=((IkReal(0.000169999997543500))*(sj1));
00450 IkReal x50=((IkReal(0.000339999995087000))*(py));
00451 IkReal x51=((pz)*(sj1));
00452 IkReal x52=((r02)*(sj0));
00453 IkReal x53=((IkReal(0.000169999997543500))*(cj0));
00454 IkReal x54=((py)*(r01));
00455 IkReal x55=((IkReal(0.000169999997543500))*(pz));
00456 IkReal x56=((r00)*(sj0));
00457 IkReal x57=((px)*(r00));
00458 IkReal x58=((IkReal(0.000169999997543500))*(cj1));
00459 IkReal x59=((IkReal(1.91011997239877e-6))*(cj1));
00460 IkReal x60=((cj0)*(r01));
00461 IkReal x61=((IkReal(0.999999985550000))*(px));
00462 IkReal x62=((IkReal(0.105999998468300))*(sj1));
00463 IkReal x63=((cj1)*(r02));
00464 IkReal x64=((cj0)*(r02));
00465 IkReal x65=((IkReal(0.000339999995087000))*(px));
00466 IkReal x66=((IkReal(0.999999985550000))*(py));
00467 IkReal x67=((IkReal(0.999999985550000))*(sj1));
00468 IkReal x68=((IkReal(0.999999985550000))*(cj1));
00469 IkReal x69=((IkReal(1.80199997396110e-5))*(sj1));
00470 IkReal x70=((px)*(sj1));
00471 IkReal x71=((IkReal(0.0112359998376398))*(sj1));
00472 IkReal x72=((cj1)*(px));
00473 IkReal x73=((cj0)*(pz));
00474 IkReal x74=((r02)*(sj1));
00475 IkReal x75=((IkReal(1.99999997110000))*(py));
00476 IkReal x76=((pz)*(r02));
00477 IkReal x77=((IkReal(0.999999985550000))*(pz));
00478 IkReal x78=((IkReal(1.80199997396110e-5))*(cj1));
00479 IkReal x79=((IkReal(1.91011997239877e-6))*(sj1));
00480 IkReal x80=((cj1)*(pz));
00481 IkReal x81=((IkReal(0.211999996936600))*(pz));
00482 IkReal x82=((cj1)*(x60));
00483 IkReal x83=((px)*(x75));
00484 IkReal x84=((IkReal(2.00000000000000))*(x44));
00485 IkReal x85=((x44)*(x67));
00486 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j5)), IkReal(6.28318530717959))));
00487 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x61)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x66)))+(((py)*(x53))));
00488 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-0.000169999997543500))*(x56)))+(((r01)*(x53)))+(((IkReal(-0.999999985550000))*(x48)))+(((IkReal(-0.999999985550000))*(x47))));
00489 evalcond[3]=((((IkReal(-1.00000000000000))*(x48)*(x69)))+(((IkReal(-1.00000000000000))*(x47)*(x69)))+(((IkReal(0.106000000000000))*(x63)))+(((x56)*(x62)))+(((IkReal(-1.00000000000000))*(x76)))+(((IkReal(-1.00000000000000))*(x60)*(x62)))+(((IkReal(-1.00000000000000))*(x57)))+(((IkReal(-1.00000000000000))*(x54))));
00490 evalcond[4]=((((IkReal(-1.00000000000000))*(x56)*(x68)))+(((x60)*(x68)))+(x74)+(((x48)*(x58)))+(((x47)*(x58))));
00491 evalcond[5]=((((IkReal(-1.00000000000000))*(x48)*(x49)))+(x63)+(((x56)*(x67)))+(((IkReal(-1.00000000000000))*(x60)*(x67)))+(((IkReal(-1.00000000000000))*(x47)*(x49))));
00492 evalcond[6]=((((IkReal(-1.00000000000000))*(x52)*(x61)))+(((IkReal(0.106000000000000))*(x74)))+(((IkReal(0.000169999997543500))*(py)*(x52)))+(((IkReal(-1.00000000000000))*(x48)*(x55)))+(((x48)*(x78)))+(((IkReal(-1.00000000000000))*(x60)*(x77)))+(((x47)*(x78)))+(((x56)*(x77)))+(((IkReal(-0.105999998468300))*(cj1)*(x56)))+(((IkReal(-1.00000000000000))*(x47)*(x55)))+(((px)*(r02)*(x53)))+(((IkReal(0.105999998468300))*(x82)))+(((x64)*(x66))));
00493 evalcond[7]=((((IkReal(-1.00000000000000))*(x48)*(x70)*(x75)))+(((IkReal(-0.0112360000000000))*(x63)))+(((pp)*(x63)))+(((x51)*(x64)*(x75)))+(((IkReal(-1.00000000000000))*(x63)*(x84)))+(((x43)*(x60)*(x67)))+(((x48)*(x79)))+(((x51)*(x64)*(x65)))+(((IkReal(0.212000000000000))*(x54)))+(((IkReal(0.212000000000000))*(x57)))+(((IkReal(-2.00000000000000))*(x54)*(x80)))+(((x47)*(x79)))+(((IkReal(-1.00000000000000))*(x45)*(x60)*(x67)))+(((x56)*(x85)))+(((x60)*(x71)))+(((x43)*(x56)*(x67)))+(((IkReal(-1.00000000000000))*(x44)*(x47)*(x49)))+(((IkReal(-1.00000000000000))*(x44)*(x48)*(x49)))+(((x50)*(x60)*(x70)))+(((IkReal(-1.99999997110000))*(px)*(x51)*(x52)))+(((x43)*(x48)*(x49)))+(((IkReal(-1.00000000000000))*(x45)*(x48)*(x49)))+(((IkReal(-1.00000000000000))*(x60)*(x85)))+(((x50)*(x56)*(x70)))+(((x45)*(x47)*(x49)))+(((IkReal(0.212000000000000))*(x76)))+(((x47)*(x70)*(x75)))+(((IkReal(-1.00000000000000))*(x56)*(x71)))+(((IkReal(-1.00000000000000))*(x45)*(x56)*(x67)))+(((IkReal(-2.00000000000000))*(x57)*(x80)))+(((IkReal(-1.00000000000000))*(x43)*(x47)*(x49)))+(((x50)*(x51)*(x52))));
00494 evalcond[8]=((((x43)*(x47)*(x58)))+(((IkReal(-0.0112359998376398))*(cj1)*(x56)))+(((x44)*(x48)*(x58)))+(((IkReal(-1.00000000000000))*(x50)*(x60)*(x72)))+(((IkReal(1.99999997110000))*(pz)*(x52)*(x72)))+(((x48)*(x72)*(x75)))+(((IkReal(-1.00000000000000))*(x47)*(x72)*(x75)))+(((x44)*(x47)*(x58)))+(((IkReal(-1.00000000000000))*(x50)*(x56)*(x72)))+(((x44)*(x60)*(x68)))+(((IkReal(-0.211999996936600))*(px)*(x52)))+(((IkReal(0.0112359998376398))*(x82)))+(((x56)*(x81)))+(((IkReal(0.211999996936600))*(py)*(x64)))+(((IkReal(-1.00000000000000))*(x74)*(x84)))+(((IkReal(-1.00000000000000))*(x63)*(x65)*(x73)))+(((x48)*(x59)))+(((IkReal(-1.00000000000000))*(x43)*(x48)*(x58)))+(((IkReal(-1.00000000000000))*(x60)*(x81)))+(((IkReal(-1.00000000000000))*(x63)*(x73)*(x75)))+(((IkReal(-1.00000000000000))*(x43)*(x56)*(x68)))+(((IkReal(3.60399994792220e-5))*(px)*(x64)))+(((IkReal(-1.00000000000000))*(x43)*(x60)*(x68)))+(((IkReal(-2.00000000000000))*(x51)*(x54)))+(((IkReal(-2.00000000000000))*(x51)*(x57)))+(((pp)*(x74)))+(((x47)*(x59)))+(((x45)*(x48)*(x58)))+(((IkReal(-1.00000000000000))*(x44)*(x56)*(x68)))+(((IkReal(0.0112360000000000))*(x74)))+(((IkReal(-1.00000000000000))*(x45)*(x47)*(x58)))+(((IkReal(-1.00000000000000))*(x50)*(x52)*(x80)))+(((IkReal(-1.00000000000000))*(x46)*(x48)))+(((IkReal(-1.00000000000000))*(x46)*(x47)))+(((IkReal(3.60399994792220e-5))*(py)*(x52)))+(((x45)*(x56)*(x68)))+(((x45)*(x60)*(x68))));
00495 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  )
00496 {
00497 {
00498 IkReal j3array[2], cj3array[2], sj3array[2];
00499 bool j3valid[2]={false};
00500 _nj3 = 2;
00501 IkReal x86=((IkReal(8.92857129955357))*(sj1));
00502 IkReal x87=((IkReal(0.00151785712092411))*(sj1));
00503 cj3array[0]=((IkReal(-0.528301886792453))+(((IkReal(-8.92857142857143))*(cj1)*(pz)))+(((cj0)*(py)*(x86)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-1.00000000000000))*(px)*(sj0)*(x86)))+(((cj0)*(px)*(x87)))+(((py)*(sj0)*(x87))));
00504 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
00505 {
00506     j3valid[0] = j3valid[1] = true;
00507     j3array[0] = IKacos(cj3array[0]);
00508     sj3array[0] = IKsin(j3array[0]);
00509     cj3array[1] = cj3array[0];
00510     j3array[1] = -j3array[0];
00511     sj3array[1] = -sj3array[0];
00512 }
00513 else if( isnan(cj3array[0]) )
00514 {
00515     // probably any value will work
00516     j3valid[0] = true;
00517     cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
00518 }
00519 for(int ij3 = 0; ij3 < 2; ++ij3)
00520 {
00521 if( !j3valid[ij3] )
00522 {
00523     continue;
00524 }
00525 _ij3[0] = ij3; _ij3[1] = -1;
00526 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00527 {
00528 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00529 {
00530     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00531 }
00532 }
00533 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00534 {
00535 IkReal evalcond[1];
00536 IkReal x88=(px)*(px);
00537 IkReal x89=(py)*(py);
00538 IkReal x90=(pz)*(pz);
00539 IkReal x91=((r00)*(sj0));
00540 IkReal x92=((cj0)*(r00));
00541 IkReal x93=((IkReal(0.212000000000000))*(sj1));
00542 IkReal x94=((cj0)*(r01));
00543 IkReal x95=((r01)*(sj0));
00544 IkReal x96=((px)*(py));
00545 IkReal x97=((IkReal(0.211999996936600))*(cj1));
00546 IkReal x98=((r02)*(sj0));
00547 IkReal x99=((IkReal(3.60399994792220e-5))*(cj1));
00548 IkReal x100=((IkReal(0.999999985550000))*(x89));
00549 IkReal x101=((IkReal(0.999999985550000))*(x90));
00550 IkReal x102=((IkReal(0.000169999997543500))*(x88));
00551 IkReal x103=((cj0)*(cj1)*(r02));
00552 IkReal x104=((IkReal(0.000169999997543500))*(x89));
00553 IkReal x105=((IkReal(0.999999985550000))*(x88));
00554 IkReal x106=((cj0)*(pz)*(r02));
00555 IkReal x107=((IkReal(0.000169999997543500))*(x90));
00556 evalcond[0]=((IkReal(-0.0237800000000000))+(((IkReal(-1.00000000000000))*(py)*(x97)*(x98)))+(((IkReal(-1.00000000000000))*(pz)*(x94)*(x99)))+(((IkReal(-1.00000000000000))*(x107)*(x91)))+(((IkReal(-0.000339999995087000))*(py)*(x106)))+(((x100)*(x95)))+(((x107)*(x94)))+(((x102)*(x91)))+(((x102)*(x94)))+(((pz)*(x92)*(x97)))+(((IkReal(-1.91011997239877e-6))*(x91)))+(((pz)*(x91)*(x99)))+(((px)*(r01)*(x93)))+(((IkReal(-0.000339999995087000))*(x92)*(x96)))+(((IkReal(-1.00000000000000))*(x105)*(x95)))+(((IkReal(-1.00000000000000))*(px)*(x98)*(x99)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(r02)*(x97)))+(((IkReal(0.000339999995087000))*(x95)*(x96)))+(((IkReal(-0.0237440000000000))*(IKcos(j3))))+(((IkReal(1.99999997110000))*(x91)*(x96)))+(((IkReal(-1.00000000000000))*(x101)*(x92)))+(((IkReal(-1.00000000000000))*(x101)*(x95)))+(((IkReal(1.91011997239877e-6))*(x94)))+(((IkReal(-1.00000000000000))*(x100)*(x92)))+(((IkReal(1.99999997110000))*(py)*(pz)*(x98)))+(((IkReal(1.99999997110000))*(px)*(x106)))+(((pz)*(x95)*(x97)))+(((IkReal(0.000339999995087000))*(px)*(pz)*(x98)))+(((IkReal(-0.0112359998376398))*(x92)))+(((IkReal(-0.0112359998376398))*(x95)))+(((cj0)*(py)*(r02)*(x99)))+(((x105)*(x92)))+(((IkReal(-1.00000000000000))*(x104)*(x91)))+(((IkReal(-1.00000000000000))*(x104)*(x94)))+(((IkReal(1.99999997110000))*(x94)*(x96)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x93))));
00557 if( IKabs(evalcond[0]) > 0.000001  )
00558 {
00559 continue;
00560 }
00561 }
00562 
00563 {
00564 IkReal dummyeval[1];
00565 IkReal gconst7;
00566 gconst7=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
00567 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
00568 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00569 {
00570 {
00571 IkReal dummyeval[1];
00572 IkReal gconst8;
00573 gconst8=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
00574 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
00575 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00576 {
00577 continue;
00578 
00579 } else
00580 {
00581 {
00582 IkReal j2array[1], cj2array[1], sj2array[1];
00583 bool j2valid[1]={false};
00584 _nj2 = 1;
00585 IkReal x108=((py)*(r02));
00586 IkReal x109=((IkReal(1750.00000000000))*(cj1));
00587 IkReal x110=((px)*(sj3));
00588 IkReal x111=((cj3)*(pz));
00589 IkReal x112=((cj0)*(sj1));
00590 IkReal x113=((IkReal(1749.99997471250))*(r02));
00591 IkReal x114=((px)*(r01));
00592 IkReal x115=((r00)*(sj3));
00593 IkReal x116=((pz)*(sj3));
00594 IkReal x117=((pz)*(r01));
00595 IkReal x118=((IkReal(0.297499995701125))*(sj3));
00596 IkReal x119=((IkReal(1656.25000000000))*(cj1));
00597 IkReal x120=((IkReal(0.297499995701125))*(cj3));
00598 IkReal x121=((pz)*(r00));
00599 IkReal x122=((cj3)*(px));
00600 IkReal x123=((cj3)*(py));
00601 IkReal x124=((px)*(r02));
00602 IkReal x125=((IkReal(0.297499995701125))*(r01));
00603 IkReal x126=((sj0)*(sj1));
00604 IkReal x127=((IkReal(0.281562495931422))*(x112));
00605 IkReal x128=((IkReal(1656.24997606719))*(x126));
00606 IkReal x129=((IkReal(1749.99997471250))*(x126));
00607 IkReal x130=((py)*(x126));
00608 IkReal x131=((IkReal(0.281562495931422))*(x126));
00609 if( IKabs(((gconst8)*(((((IkReal(-1.00000000000000))*(py)*(r00)*(x119)))+(((x117)*(x127)))+(((x114)*(x119)))+(((IkReal(-185.500000000000))*(sj3)))+(((x108)*(x128)))+(((IkReal(-1656.24997606719))*(x112)*(x121)))+(((x109)*(x116)))+(((IkReal(-1.00000000000000))*(x117)*(x128)))+(((x112)*(x113)*(x122)))+(((cj3)*(x108)*(x129)))+(((x124)*(x131)))+(((x120)*(x124)*(x126)))+(((IkReal(-0.297499995701125))*(r00)*(x111)*(x126)))+(((IkReal(-0.297499995701125))*(x110)*(x112)))+(((cj3)*(x109)*(x114)))+(((IkReal(-1.00000000000000))*(x121)*(x131)))+(((IkReal(-1.00000000000000))*(r01)*(x111)*(x129)))+(((IkReal(-1.00000000000000))*(x108)*(x127)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x112)))+(((IkReal(1656.24997606719))*(x112)*(x124)))+(((IkReal(-1749.99997471250))*(r00)*(x111)*(x112)))+(((x110)*(x129)))+(((IkReal(-1.00000000000000))*(x108)*(x112)*(x120)))+(((IkReal(-1.00000000000000))*(r00)*(x109)*(x123)))+(((IkReal(-1.00000000000000))*(x118)*(x130)))+(((x111)*(x112)*(x125))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst8)*(((IkReal(175.562500000000))+(((IkReal(1656.24997606719))*(py)*(x112)))+(((IkReal(-1749.99997471250))*(pz)*(x112)*(x115)))+(((px)*(x112)*(x120)))+(((IkReal(-0.297499995701125))*(pz)*(x115)*(x126)))+(((IkReal(0.281562495931422))*(x130)))+(((sj3)*(x108)*(x129)))+(((x110)*(x112)*(x113)))+(((IkReal(-1.00000000000000))*(px)*(x128)))+(((px)*(x127)))+(((IkReal(-1.00000000000000))*(x109)*(x111)))+(((x120)*(x130)))+(((IkReal(-1.00000000000000))*(py)*(x109)*(x115)))+(((IkReal(185.500000000000))*(cj3)))+(((x112)*(x116)*(x125)))+(((r01)*(x109)*(x110)))+(((IkReal(0.297499995701125))*(r02)*(x110)*(x126)))+(((IkReal(-1.00000000000000))*(r01)*(x116)*(x129)))+(((IkReal(-1.00000000000000))*(x122)*(x129)))+(((IkReal(-1.00000000000000))*(pz)*(x119)))+(((IkReal(1749.99997471250))*(x112)*(x123)))+(((IkReal(-1.00000000000000))*(x108)*(x112)*(x118))))))) < IKFAST_ATAN2_MAGTHRESH )
00610     continue;
00611 j2array[0]=IKatan2(((gconst8)*(((((IkReal(-1.00000000000000))*(py)*(r00)*(x119)))+(((x117)*(x127)))+(((x114)*(x119)))+(((IkReal(-185.500000000000))*(sj3)))+(((x108)*(x128)))+(((IkReal(-1656.24997606719))*(x112)*(x121)))+(((x109)*(x116)))+(((IkReal(-1.00000000000000))*(x117)*(x128)))+(((x112)*(x113)*(x122)))+(((cj3)*(x108)*(x129)))+(((x124)*(x131)))+(((x120)*(x124)*(x126)))+(((IkReal(-0.297499995701125))*(r00)*(x111)*(x126)))+(((IkReal(-0.297499995701125))*(x110)*(x112)))+(((cj3)*(x109)*(x114)))+(((IkReal(-1.00000000000000))*(x121)*(x131)))+(((IkReal(-1.00000000000000))*(r01)*(x111)*(x129)))+(((IkReal(-1.00000000000000))*(x108)*(x127)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x112)))+(((IkReal(1656.24997606719))*(x112)*(x124)))+(((IkReal(-1749.99997471250))*(r00)*(x111)*(x112)))+(((x110)*(x129)))+(((IkReal(-1.00000000000000))*(x108)*(x112)*(x120)))+(((IkReal(-1.00000000000000))*(r00)*(x109)*(x123)))+(((IkReal(-1.00000000000000))*(x118)*(x130)))+(((x111)*(x112)*(x125)))))), ((gconst8)*(((IkReal(175.562500000000))+(((IkReal(1656.24997606719))*(py)*(x112)))+(((IkReal(-1749.99997471250))*(pz)*(x112)*(x115)))+(((px)*(x112)*(x120)))+(((IkReal(-0.297499995701125))*(pz)*(x115)*(x126)))+(((IkReal(0.281562495931422))*(x130)))+(((sj3)*(x108)*(x129)))+(((x110)*(x112)*(x113)))+(((IkReal(-1.00000000000000))*(px)*(x128)))+(((px)*(x127)))+(((IkReal(-1.00000000000000))*(x109)*(x111)))+(((x120)*(x130)))+(((IkReal(-1.00000000000000))*(py)*(x109)*(x115)))+(((IkReal(185.500000000000))*(cj3)))+(((x112)*(x116)*(x125)))+(((r01)*(x109)*(x110)))+(((IkReal(0.297499995701125))*(r02)*(x110)*(x126)))+(((IkReal(-1.00000000000000))*(r01)*(x116)*(x129)))+(((IkReal(-1.00000000000000))*(x122)*(x129)))+(((IkReal(-1.00000000000000))*(pz)*(x119)))+(((IkReal(1749.99997471250))*(x112)*(x123)))+(((IkReal(-1.00000000000000))*(x108)*(x112)*(x118)))))));
00612 sj2array[0]=IKsin(j2array[0]);
00613 cj2array[0]=IKcos(j2array[0]);
00614 if( j2array[0] > IKPI )
00615 {
00616     j2array[0]-=IK2PI;
00617 }
00618 else if( j2array[0] < -IKPI )
00619 {    j2array[0]+=IK2PI;
00620 }
00621 j2valid[0] = true;
00622 for(int ij2 = 0; ij2 < 1; ++ij2)
00623 {
00624 if( !j2valid[ij2] )
00625 {
00626     continue;
00627 }
00628 _ij2[0] = ij2; _ij2[1] = -1;
00629 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00630 {
00631 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00632 {
00633     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00634 }
00635 }
00636 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00637 {
00638 IkReal evalcond[4];
00639 IkReal x132=IKsin(j2);
00640 IkReal x133=IKcos(j2);
00641 IkReal x134=((r00)*(sj0));
00642 IkReal x135=((r01)*(sj0));
00643 IkReal x136=((py)*(sj1));
00644 IkReal x137=((IkReal(0.999999985550000))*(r02));
00645 IkReal x138=((px)*(sj1));
00646 IkReal x139=((IkReal(0.999999985550000))*(sj0));
00647 IkReal x140=((IkReal(0.000169999997543500))*(cj0));
00648 IkReal x141=((IkReal(0.000169999997543500))*(sj0));
00649 IkReal x142=((cj1)*(px));
00650 IkReal x143=((pz)*(sj1));
00651 IkReal x144=((cj0)*(r00));
00652 IkReal x145=((cj1)*(pz));
00653 IkReal x146=((IkReal(1.00000000000000))*(r01));
00654 IkReal x147=((cj1)*(py));
00655 IkReal x148=((IkReal(0.999999985550000))*(cj0));
00656 IkReal x149=((IkReal(0.106000000000000))*(x132));
00657 IkReal x150=((IkReal(0.106000000000000))*(x133));
00658 IkReal x151=((IkReal(0.112000000000000))*(x133));
00659 IkReal x152=((IkReal(0.112000000000000))*(x132));
00660 IkReal x153=((cj3)*(x152));
00661 IkReal x154=((sj3)*(x151));
00662 IkReal x155=((sj3)*(x152));
00663 IkReal x156=((cj3)*(x151));
00664 IkReal x157=((x156)+(x150));
00665 IkReal x158=((x154)+(x153)+(x149));
00666 evalcond[0]=((((x140)*(x142)))+(((IkReal(-1.00000000000000))*(x139)*(x142)))+(x158)+(x143)+(((x141)*(x147)))+(((x147)*(x148))));
00667 evalcond[1]=((IkReal(-0.106000000000000))+(((x138)*(x139)))+(((IkReal(-1.00000000000000))*(x157)))+(((IkReal(-1.00000000000000))*(x138)*(x140)))+(x155)+(x145)+(((IkReal(-1.00000000000000))*(x136)*(x148)))+(((IkReal(-1.00000000000000))*(x136)*(x141))));
00668 evalcond[2]=((((IkReal(0.999999985550000))*(x135)*(x143)))+(((IkReal(-1.00000000000000))*(x158)))+(((IkReal(-1.00000000000000))*(x142)*(x146)))+(((r00)*(x147)))+(((r02)*(x136)*(x140)))+(((IkReal(-1.00000000000000))*(cj0)*(x137)*(x138)))+(((IkReal(0.999999985550000))*(x143)*(x144)))+(((IkReal(-1.00000000000000))*(r01)*(x140)*(x143)))+(((IkReal(0.000169999997543500))*(x134)*(x143)))+(((IkReal(-1.00000000000000))*(r02)*(x138)*(x141)))+(((IkReal(-1.00000000000000))*(sj0)*(x136)*(x137))));
00669 evalcond[3]=((((IkReal(-1.00000000000000))*(x157)))+(((IkReal(-1.00000000000000))*(x138)*(x146)))+(((IkReal(1.80199997396110e-5))*(x134)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(0.105999998468300))*(x144)))+(((IkReal(-0.000169999997543500))*(x134)*(x145)))+(((cj0)*(x137)*(x142)))+(((sj0)*(x137)*(x147)))+(((IkReal(-0.999999985550000))*(x135)*(x145)))+(((r00)*(x136)))+(x155)+(((IkReal(0.105999998468300))*(x135)))+(((r02)*(x141)*(x142)))+(((r01)*(x140)*(x145)))+(((IkReal(-0.999999985550000))*(x144)*(x145)))+(((IkReal(-1.00000000000000))*(r02)*(x140)*(x147))));
00670 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00671 {
00672 continue;
00673 }
00674 }
00675 
00676 {
00677 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00678 vinfos[0].jointtype = 1;
00679 vinfos[0].foffset = j0;
00680 vinfos[0].indices[0] = _ij0[0];
00681 vinfos[0].indices[1] = _ij0[1];
00682 vinfos[0].maxsolutions = _nj0;
00683 vinfos[1].jointtype = 1;
00684 vinfos[1].foffset = j1;
00685 vinfos[1].indices[0] = _ij1[0];
00686 vinfos[1].indices[1] = _ij1[1];
00687 vinfos[1].maxsolutions = _nj1;
00688 vinfos[2].jointtype = 1;
00689 vinfos[2].foffset = j2;
00690 vinfos[2].indices[0] = _ij2[0];
00691 vinfos[2].indices[1] = _ij2[1];
00692 vinfos[2].maxsolutions = _nj2;
00693 vinfos[3].jointtype = 1;
00694 vinfos[3].foffset = j3;
00695 vinfos[3].indices[0] = _ij3[0];
00696 vinfos[3].indices[1] = _ij3[1];
00697 vinfos[3].maxsolutions = _nj3;
00698 vinfos[4].jointtype = 1;
00699 vinfos[4].foffset = j5;
00700 vinfos[4].indices[0] = _ij5[0];
00701 vinfos[4].indices[1] = _ij5[1];
00702 vinfos[4].maxsolutions = _nj5;
00703 std::vector<int> vfree(0);
00704 solutions.AddSolution(vinfos,vfree);
00705 }
00706 }
00707 }
00708 
00709 }
00710 
00711 }
00712 
00713 } else
00714 {
00715 {
00716 IkReal j2array[1], cj2array[1], sj2array[1];
00717 bool j2valid[1]={false};
00718 _nj2 = 1;
00719 IkReal x159=((cj0)*(sj1));
00720 IkReal x160=((IkReal(0.281562495931422))*(px));
00721 IkReal x161=((cj1)*(sj0));
00722 IkReal x162=((IkReal(0.281562495931422))*(py));
00723 IkReal x163=((IkReal(1656.24997606719))*(px));
00724 IkReal x164=((IkReal(1656.24997606719))*(py));
00725 IkReal x165=((cj0)*(cj1));
00726 IkReal x166=((IkReal(1749.99997471250))*(px));
00727 IkReal x167=((IkReal(0.297499995701125))*(px));
00728 IkReal x168=((IkReal(1749.99997471250))*(py));
00729 IkReal x169=((IkReal(0.297499995701125))*(py));
00730 IkReal x170=((sj0)*(sj1));
00731 IkReal x171=((IkReal(1656.25000000000))*(pz));
00732 IkReal x172=((IkReal(1750.00000000000))*(cj3)*(pz));
00733 IkReal x173=((IkReal(1750.00000000000))*(pz)*(sj3));
00734 IkReal x174=((sj3)*(x170));
00735 IkReal x175=((cj3)*(x170));
00736 if( IKabs(((gconst7)*(((((x161)*(x162)))+(((sj1)*(x171)))+(((sj1)*(x172)))+(((cj3)*(x161)*(x169)))+(((IkReal(-1.00000000000000))*(cj3)*(x161)*(x166)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x161)*(x163)))+(((x166)*(x174)))+(((x164)*(x165)))+(((IkReal(-1.00000000000000))*(sj3)*(x159)*(x167)))+(((IkReal(-1.00000000000000))*(sj3)*(x159)*(x168)))+(((cj1)*(x173)))+(((IkReal(-1.00000000000000))*(x169)*(x174)))+(((cj3)*(x165)*(x167)))+(((cj3)*(x165)*(x168)))+(((x160)*(x165))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst7)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(sj3)*(x161)*(x166)))+(((sj1)*(x173)))+(((x162)*(x170)))+(((IkReal(-1.00000000000000))*(x163)*(x170)))+(((x169)*(x175)))+(((sj3)*(x165)*(x167)))+(((sj3)*(x165)*(x168)))+(((sj3)*(x161)*(x169)))+(((IkReal(-1.00000000000000))*(cj1)*(x172)))+(((IkReal(-1.00000000000000))*(cj1)*(x171)))+(((IkReal(185.500000000000))*(cj3)))+(((x159)*(x160)))+(((x159)*(x164)))+(((IkReal(-1.00000000000000))*(x166)*(x175)))+(((cj3)*(x159)*(x168)))+(((cj3)*(x159)*(x167))))))) < IKFAST_ATAN2_MAGTHRESH )
00737     continue;
00738 j2array[0]=IKatan2(((gconst7)*(((((x161)*(x162)))+(((sj1)*(x171)))+(((sj1)*(x172)))+(((cj3)*(x161)*(x169)))+(((IkReal(-1.00000000000000))*(cj3)*(x161)*(x166)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x161)*(x163)))+(((x166)*(x174)))+(((x164)*(x165)))+(((IkReal(-1.00000000000000))*(sj3)*(x159)*(x167)))+(((IkReal(-1.00000000000000))*(sj3)*(x159)*(x168)))+(((cj1)*(x173)))+(((IkReal(-1.00000000000000))*(x169)*(x174)))+(((cj3)*(x165)*(x167)))+(((cj3)*(x165)*(x168)))+(((x160)*(x165)))))), ((gconst7)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(sj3)*(x161)*(x166)))+(((sj1)*(x173)))+(((x162)*(x170)))+(((IkReal(-1.00000000000000))*(x163)*(x170)))+(((x169)*(x175)))+(((sj3)*(x165)*(x167)))+(((sj3)*(x165)*(x168)))+(((sj3)*(x161)*(x169)))+(((IkReal(-1.00000000000000))*(cj1)*(x172)))+(((IkReal(-1.00000000000000))*(cj1)*(x171)))+(((IkReal(185.500000000000))*(cj3)))+(((x159)*(x160)))+(((x159)*(x164)))+(((IkReal(-1.00000000000000))*(x166)*(x175)))+(((cj3)*(x159)*(x168)))+(((cj3)*(x159)*(x167)))))));
00739 sj2array[0]=IKsin(j2array[0]);
00740 cj2array[0]=IKcos(j2array[0]);
00741 if( j2array[0] > IKPI )
00742 {
00743     j2array[0]-=IK2PI;
00744 }
00745 else if( j2array[0] < -IKPI )
00746 {    j2array[0]+=IK2PI;
00747 }
00748 j2valid[0] = true;
00749 for(int ij2 = 0; ij2 < 1; ++ij2)
00750 {
00751 if( !j2valid[ij2] )
00752 {
00753     continue;
00754 }
00755 _ij2[0] = ij2; _ij2[1] = -1;
00756 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00757 {
00758 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00759 {
00760     j2valid[iij2]=false; _ij2[1] = iij2; break; 
00761 }
00762 }
00763 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00764 {
00765 IkReal evalcond[4];
00766 IkReal x176=IKsin(j2);
00767 IkReal x177=IKcos(j2);
00768 IkReal x178=((r00)*(sj0));
00769 IkReal x179=((r01)*(sj0));
00770 IkReal x180=((py)*(sj1));
00771 IkReal x181=((IkReal(0.999999985550000))*(r02));
00772 IkReal x182=((px)*(sj1));
00773 IkReal x183=((IkReal(0.999999985550000))*(sj0));
00774 IkReal x184=((IkReal(0.000169999997543500))*(cj0));
00775 IkReal x185=((IkReal(0.000169999997543500))*(sj0));
00776 IkReal x186=((cj1)*(px));
00777 IkReal x187=((pz)*(sj1));
00778 IkReal x188=((cj0)*(r00));
00779 IkReal x189=((cj1)*(pz));
00780 IkReal x190=((IkReal(1.00000000000000))*(r01));
00781 IkReal x191=((cj1)*(py));
00782 IkReal x192=((IkReal(0.999999985550000))*(cj0));
00783 IkReal x193=((IkReal(0.106000000000000))*(x176));
00784 IkReal x194=((IkReal(0.106000000000000))*(x177));
00785 IkReal x195=((IkReal(0.112000000000000))*(x177));
00786 IkReal x196=((IkReal(0.112000000000000))*(x176));
00787 IkReal x197=((cj3)*(x196));
00788 IkReal x198=((sj3)*(x195));
00789 IkReal x199=((sj3)*(x196));
00790 IkReal x200=((cj3)*(x195));
00791 IkReal x201=((x194)+(x200));
00792 IkReal x202=((x198)+(x193)+(x197));
00793 evalcond[0]=((x187)+(((x185)*(x191)))+(((x184)*(x186)))+(x202)+(((x191)*(x192)))+(((IkReal(-1.00000000000000))*(x183)*(x186))));
00794 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x180)*(x192)))+(((IkReal(-1.00000000000000))*(x180)*(x185)))+(x199)+(x189)+(((IkReal(-1.00000000000000))*(x201)))+(((IkReal(-1.00000000000000))*(x182)*(x184)))+(((x182)*(x183))));
00795 evalcond[2]=((((r00)*(x191)))+(((IkReal(-1.00000000000000))*(x186)*(x190)))+(((IkReal(-1.00000000000000))*(cj0)*(x181)*(x182)))+(((IkReal(-1.00000000000000))*(x202)))+(((IkReal(-1.00000000000000))*(sj0)*(x180)*(x181)))+(((IkReal(-1.00000000000000))*(r01)*(x184)*(x187)))+(((IkReal(-1.00000000000000))*(r02)*(x182)*(x185)))+(((IkReal(0.999999985550000))*(x179)*(x187)))+(((IkReal(0.000169999997543500))*(x178)*(x187)))+(((r02)*(x180)*(x184)))+(((IkReal(0.999999985550000))*(x187)*(x188))));
00796 evalcond[3]=((((IkReal(-0.000169999997543500))*(x178)*(x189)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(r02)*(x184)*(x191)))+(((r02)*(x185)*(x186)))+(((IkReal(0.105999998468300))*(x188)))+(((IkReal(0.105999998468300))*(x179)))+(((r00)*(x180)))+(x199)+(((IkReal(-1.00000000000000))*(x201)))+(((IkReal(-0.999999985550000))*(x188)*(x189)))+(((IkReal(-0.999999985550000))*(x179)*(x189)))+(((sj0)*(x181)*(x191)))+(((cj0)*(x181)*(x186)))+(((IkReal(1.80199997396110e-5))*(x178)))+(((IkReal(-1.00000000000000))*(x182)*(x190)))+(((r01)*(x184)*(x189))));
00797 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00798 {
00799 continue;
00800 }
00801 }
00802 
00803 {
00804 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00805 vinfos[0].jointtype = 1;
00806 vinfos[0].foffset = j0;
00807 vinfos[0].indices[0] = _ij0[0];
00808 vinfos[0].indices[1] = _ij0[1];
00809 vinfos[0].maxsolutions = _nj0;
00810 vinfos[1].jointtype = 1;
00811 vinfos[1].foffset = j1;
00812 vinfos[1].indices[0] = _ij1[0];
00813 vinfos[1].indices[1] = _ij1[1];
00814 vinfos[1].maxsolutions = _nj1;
00815 vinfos[2].jointtype = 1;
00816 vinfos[2].foffset = j2;
00817 vinfos[2].indices[0] = _ij2[0];
00818 vinfos[2].indices[1] = _ij2[1];
00819 vinfos[2].maxsolutions = _nj2;
00820 vinfos[3].jointtype = 1;
00821 vinfos[3].foffset = j3;
00822 vinfos[3].indices[0] = _ij3[0];
00823 vinfos[3].indices[1] = _ij3[1];
00824 vinfos[3].maxsolutions = _nj3;
00825 vinfos[4].jointtype = 1;
00826 vinfos[4].foffset = j5;
00827 vinfos[4].indices[0] = _ij5[0];
00828 vinfos[4].indices[1] = _ij5[1];
00829 vinfos[4].maxsolutions = _nj5;
00830 std::vector<int> vfree(0);
00831 solutions.AddSolution(vinfos,vfree);
00832 }
00833 }
00834 }
00835 
00836 }
00837 
00838 }
00839 }
00840 }
00841 
00842 } else
00843 {
00844 IkReal x203=(py)*(py);
00845 IkReal x204=(pz)*(pz);
00846 IkReal x205=(px)*(px);
00847 IkReal x206=((IkReal(3.60399994792220e-5))*(pz));
00848 IkReal x207=((cj0)*(r00));
00849 IkReal x208=((r01)*(sj0));
00850 IkReal x209=((IkReal(0.000169999997543500))*(sj1));
00851 IkReal x210=((IkReal(0.000339999995087000))*(py));
00852 IkReal x211=((pz)*(sj1));
00853 IkReal x212=((r02)*(sj0));
00854 IkReal x213=((IkReal(0.000169999997543500))*(cj0));
00855 IkReal x214=((py)*(r01));
00856 IkReal x215=((IkReal(0.000169999997543500))*(pz));
00857 IkReal x216=((r00)*(sj0));
00858 IkReal x217=((px)*(r00));
00859 IkReal x218=((IkReal(0.000169999997543500))*(cj1));
00860 IkReal x219=((IkReal(1.91011997239877e-6))*(cj1));
00861 IkReal x220=((cj0)*(r01));
00862 IkReal x221=((IkReal(0.999999985550000))*(px));
00863 IkReal x222=((IkReal(0.105999998468300))*(sj1));
00864 IkReal x223=((cj1)*(r02));
00865 IkReal x224=((cj0)*(r02));
00866 IkReal x225=((IkReal(0.000339999995087000))*(px));
00867 IkReal x226=((IkReal(0.999999985550000))*(py));
00868 IkReal x227=((IkReal(0.999999985550000))*(sj1));
00869 IkReal x228=((IkReal(0.999999985550000))*(cj1));
00870 IkReal x229=((IkReal(1.80199997396110e-5))*(sj1));
00871 IkReal x230=((px)*(sj1));
00872 IkReal x231=((IkReal(0.0112359998376398))*(sj1));
00873 IkReal x232=((cj1)*(px));
00874 IkReal x233=((cj0)*(pz));
00875 IkReal x234=((r02)*(sj1));
00876 IkReal x235=((IkReal(1.99999997110000))*(py));
00877 IkReal x236=((pz)*(r02));
00878 IkReal x237=((IkReal(0.999999985550000))*(pz));
00879 IkReal x238=((IkReal(1.80199997396110e-5))*(cj1));
00880 IkReal x239=((IkReal(1.91011997239877e-6))*(sj1));
00881 IkReal x240=((cj1)*(pz));
00882 IkReal x241=((IkReal(0.211999996936600))*(pz));
00883 IkReal x242=((cj1)*(x220));
00884 IkReal x243=((px)*(x235));
00885 IkReal x244=((IkReal(2.00000000000000))*(x204));
00886 IkReal x245=((x204)*(x227));
00887 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j5)), IkReal(6.28318530717959))));
00888 evalcond[1]=((((py)*(x213)))+(((IkReal(-1.00000000000000))*(cj0)*(x221)))+(((IkReal(-1.00000000000000))*(sj0)*(x226)))+(((IkReal(-0.000169999997543500))*(px)*(sj0))));
00889 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-0.000169999997543500))*(x216)))+(((IkReal(-0.999999985550000))*(x208)))+(((IkReal(-0.999999985550000))*(x207)))+(((r01)*(x213))));
00890 evalcond[3]=((((IkReal(0.106000000000000))*(x223)))+(((IkReal(-1.00000000000000))*(x207)*(x229)))+(((x216)*(x222)))+(((IkReal(-1.00000000000000))*(x208)*(x229)))+(((IkReal(-1.00000000000000))*(x220)*(x222)))+(((IkReal(-1.00000000000000))*(x217)))+(((IkReal(-1.00000000000000))*(x214)))+(((IkReal(-1.00000000000000))*(x236))));
00891 evalcond[4]=((((IkReal(-1.00000000000000))*(x216)*(x228)))+(((x208)*(x218)))+(((x207)*(x218)))+(x234)+(((x220)*(x228))));
00892 evalcond[5]=((((x216)*(x227)))+(((IkReal(-1.00000000000000))*(x208)*(x209)))+(((IkReal(-1.00000000000000))*(x207)*(x209)))+(x223)+(((IkReal(-1.00000000000000))*(x220)*(x227))));
00893 evalcond[6]=((((px)*(r02)*(x213)))+(((x224)*(x226)))+(((IkReal(-0.105999998468300))*(cj1)*(x216)))+(((IkReal(-1.00000000000000))*(x207)*(x215)))+(((IkReal(0.000169999997543500))*(py)*(x212)))+(((IkReal(-1.00000000000000))*(x220)*(x237)))+(((IkReal(0.105999998468300))*(x242)))+(((IkReal(-1.00000000000000))*(x212)*(x221)))+(((IkReal(0.106000000000000))*(x234)))+(((x216)*(x237)))+(((IkReal(-1.00000000000000))*(x208)*(x215)))+(((x208)*(x238)))+(((x207)*(x238))));
00894 evalcond[7]=((((IkReal(-1.00000000000000))*(x208)*(x230)*(x235)))+(((IkReal(-1.00000000000000))*(x203)*(x207)*(x209)))+(((x207)*(x230)*(x235)))+(((IkReal(-2.00000000000000))*(x214)*(x240)))+(((IkReal(-1.00000000000000))*(x204)*(x207)*(x209)))+(((IkReal(-1.00000000000000))*(x204)*(x208)*(x209)))+(((x203)*(x208)*(x209)))+(((IkReal(-1.00000000000000))*(x220)*(x245)))+(((x211)*(x224)*(x225)))+(((x205)*(x207)*(x209)))+(((IkReal(-1.00000000000000))*(x216)*(x231)))+(((x211)*(x224)*(x235)))+(((x216)*(x245)))+(((IkReal(-1.00000000000000))*(x223)*(x244)))+(((IkReal(-1.99999997110000))*(px)*(x211)*(x212)))+(((IkReal(-1.00000000000000))*(x205)*(x208)*(x209)))+(((IkReal(-0.0112360000000000))*(x223)))+(((IkReal(0.212000000000000))*(x236)))+(((IkReal(-1.00000000000000))*(x205)*(x216)*(x227)))+(((pp)*(x223)))+(((x210)*(x220)*(x230)))+(((x203)*(x220)*(x227)))+(((IkReal(-1.00000000000000))*(x205)*(x220)*(x227)))+(((x210)*(x211)*(x212)))+(((x220)*(x231)))+(((x208)*(x239)))+(((x203)*(x216)*(x227)))+(((x207)*(x239)))+(((x210)*(x216)*(x230)))+(((IkReal(0.212000000000000))*(x214)))+(((IkReal(0.212000000000000))*(x217)))+(((IkReal(-2.00000000000000))*(x217)*(x240))));
00895 evalcond[8]=((((IkReal(0.0112359998376398))*(x242)))+(((pp)*(x234)))+(((IkReal(-1.00000000000000))*(x210)*(x212)*(x240)))+(((IkReal(0.0112360000000000))*(x234)))+(((x205)*(x216)*(x228)))+(((IkReal(-1.00000000000000))*(x207)*(x232)*(x235)))+(((IkReal(3.60399994792220e-5))*(py)*(x212)))+(((IkReal(-1.00000000000000))*(x220)*(x241)))+(((IkReal(-1.00000000000000))*(x210)*(x216)*(x232)))+(((IkReal(-1.00000000000000))*(x203)*(x220)*(x228)))+(((x204)*(x207)*(x218)))+(((IkReal(-1.00000000000000))*(x203)*(x216)*(x228)))+(((IkReal(-2.00000000000000))*(x211)*(x214)))+(((IkReal(-2.00000000000000))*(x211)*(x217)))+(((x208)*(x219)))+(((x207)*(x219)))+(((IkReal(-1.00000000000000))*(x204)*(x216)*(x228)))+(((IkReal(-1.00000000000000))*(x234)*(x244)))+(((IkReal(-1.00000000000000))*(x206)*(x208)))+(((IkReal(-1.00000000000000))*(x206)*(x207)))+(((x216)*(x241)))+(((IkReal(-1.00000000000000))*(x205)*(x207)*(x218)))+(((x205)*(x220)*(x228)))+(((IkReal(-1.00000000000000))*(x223)*(x233)*(x235)))+(((IkReal(3.60399994792220e-5))*(px)*(x224)))+(((IkReal(0.211999996936600))*(py)*(x224)))+(((x205)*(x208)*(x218)))+(((x204)*(x220)*(x228)))+(((IkReal(-0.0112359998376398))*(cj1)*(x216)))+(((x203)*(x207)*(x218)))+(((IkReal(-1.00000000000000))*(x210)*(x220)*(x232)))+(((IkReal(-0.211999996936600))*(px)*(x212)))+(((x208)*(x232)*(x235)))+(((IkReal(1.99999997110000))*(pz)*(x212)*(x232)))+(((x204)*(x208)*(x218)))+(((IkReal(-1.00000000000000))*(x203)*(x208)*(x218)))+(((IkReal(-1.00000000000000))*(x223)*(x225)*(x233))));
00896 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  )
00897 {
00898 {
00899 IkReal j3array[2], cj3array[2], sj3array[2];
00900 bool j3valid[2]={false};
00901 _nj3 = 2;
00902 IkReal x246=((IkReal(8.92857129955357))*(sj1));
00903 IkReal x247=((IkReal(0.00151785712092411))*(sj1));
00904 cj3array[0]=((IkReal(-0.528301886792453))+(((cj0)*(py)*(x246)))+(((IkReal(-8.92857142857143))*(cj1)*(pz)))+(((py)*(sj0)*(x247)))+(((cj0)*(px)*(x247)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-1.00000000000000))*(px)*(sj0)*(x246))));
00905 if( cj3array[0] >= -1-IKFAST_SINCOS_THRESH && cj3array[0] <= 1+IKFAST_SINCOS_THRESH )
00906 {
00907     j3valid[0] = j3valid[1] = true;
00908     j3array[0] = IKacos(cj3array[0]);
00909     sj3array[0] = IKsin(j3array[0]);
00910     cj3array[1] = cj3array[0];
00911     j3array[1] = -j3array[0];
00912     sj3array[1] = -sj3array[0];
00913 }
00914 else if( isnan(cj3array[0]) )
00915 {
00916     // probably any value will work
00917     j3valid[0] = true;
00918     cj3array[0] = 1; sj3array[0] = 0; j3array[0] = 0;
00919 }
00920 for(int ij3 = 0; ij3 < 2; ++ij3)
00921 {
00922 if( !j3valid[ij3] )
00923 {
00924     continue;
00925 }
00926 _ij3[0] = ij3; _ij3[1] = -1;
00927 for(int iij3 = ij3+1; iij3 < 2; ++iij3)
00928 {
00929 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00930 {
00931     j3valid[iij3]=false; _ij3[1] = iij3; break; 
00932 }
00933 }
00934 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00935 {
00936 IkReal evalcond[1];
00937 IkReal x248=(px)*(px);
00938 IkReal x249=(py)*(py);
00939 IkReal x250=(pz)*(pz);
00940 IkReal x251=((r00)*(sj0));
00941 IkReal x252=((cj0)*(r00));
00942 IkReal x253=((IkReal(0.212000000000000))*(sj1));
00943 IkReal x254=((cj0)*(r01));
00944 IkReal x255=((r01)*(sj0));
00945 IkReal x256=((px)*(py));
00946 IkReal x257=((IkReal(0.211999996936600))*(cj1));
00947 IkReal x258=((r02)*(sj0));
00948 IkReal x259=((IkReal(3.60399994792220e-5))*(cj1));
00949 IkReal x260=((IkReal(0.999999985550000))*(x249));
00950 IkReal x261=((IkReal(0.999999985550000))*(x250));
00951 IkReal x262=((IkReal(0.000169999997543500))*(x248));
00952 IkReal x263=((cj0)*(cj1)*(r02));
00953 IkReal x264=((IkReal(0.000169999997543500))*(x249));
00954 IkReal x265=((IkReal(0.999999985550000))*(x248));
00955 IkReal x266=((cj0)*(pz)*(r02));
00956 IkReal x267=((IkReal(0.000169999997543500))*(x250));
00957 evalcond[0]=((IkReal(0.0237800000000000))+(((IkReal(-1.00000000000000))*(x255)*(x265)))+(((IkReal(-1.00000000000000))*(x255)*(x261)))+(((pz)*(x252)*(x257)))+(((IkReal(1.91011997239877e-6))*(x254)))+(((IkReal(1.99999997110000))*(x254)*(x256)))+(((IkReal(-0.000339999995087000))*(x252)*(x256)))+(((cj0)*(py)*(r02)*(x259)))+(((pz)*(x251)*(x259)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x253)))+(((IkReal(-1.00000000000000))*(py)*(x257)*(x258)))+(((pz)*(x255)*(x257)))+(((IkReal(-1.00000000000000))*(pz)*(x254)*(x259)))+(((IkReal(1.99999997110000))*(x251)*(x256)))+(((IkReal(1.99999997110000))*(px)*(x266)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(r02)*(x257)))+(((IkReal(1.99999997110000))*(py)*(pz)*(x258)))+(((IkReal(-0.000339999995087000))*(py)*(x266)))+(((IkReal(-1.91011997239877e-6))*(x251)))+(((x252)*(x265)))+(((px)*(r01)*(x253)))+(((x254)*(x262)))+(((x254)*(x267)))+(((IkReal(-1.00000000000000))*(x251)*(x267)))+(((IkReal(-1.00000000000000))*(x251)*(x264)))+(((x255)*(x260)))+(((IkReal(-1.00000000000000))*(px)*(x258)*(x259)))+(((IkReal(0.000339999995087000))*(px)*(pz)*(x258)))+(((IkReal(0.0237440000000000))*(IKcos(j3))))+(((IkReal(-0.0112359998376398))*(x252)))+(((IkReal(-0.0112359998376398))*(x255)))+(((IkReal(-1.00000000000000))*(x252)*(x260)))+(((IkReal(-1.00000000000000))*(x252)*(x261)))+(((IkReal(0.000339999995087000))*(x255)*(x256)))+(((x251)*(x262)))+(((IkReal(-1.00000000000000))*(x254)*(x264))));
00958 if( IKabs(evalcond[0]) > 0.000001  )
00959 {
00960 continue;
00961 }
00962 }
00963 
00964 {
00965 IkReal dummyeval[1];
00966 IkReal gconst9;
00967 gconst9=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
00968 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
00969 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00970 {
00971 {
00972 IkReal dummyeval[1];
00973 IkReal gconst10;
00974 gconst10=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
00975 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
00976 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00977 {
00978 continue;
00979 
00980 } else
00981 {
00982 {
00983 IkReal j2array[1], cj2array[1], sj2array[1];
00984 bool j2valid[1]={false};
00985 _nj2 = 1;
00986 IkReal x268=((py)*(r02));
00987 IkReal x269=((cj0)*(sj1));
00988 IkReal x270=((px)*(r01));
00989 IkReal x271=((py)*(r00));
00990 IkReal x272=((pz)*(r01));
00991 IkReal x273=((IkReal(0.297499995701125))*(py));
00992 IkReal x274=((sj0)*(sj1));
00993 IkReal x275=((IkReal(1656.25000000000))*(cj1));
00994 IkReal x276=((IkReal(0.297499995701125))*(px));
00995 IkReal x277=((pz)*(r00));
00996 IkReal x278=((IkReal(1749.99997471250))*(px));
00997 IkReal x279=((IkReal(1749.99997471250))*(py));
00998 IkReal x280=((px)*(r02));
00999 IkReal x281=((IkReal(1749.99997471250))*(sj3));
01000 IkReal x282=((IkReal(0.297499995701125))*(cj3));
01001 IkReal x283=((IkReal(0.297499995701125))*(sj3));
01002 IkReal x284=((IkReal(0.281562495931422))*(x269));
01003 IkReal x285=((IkReal(1750.00000000000))*(cj1)*(cj3));
01004 IkReal x286=((IkReal(1656.24997606719))*(x274));
01005 IkReal x287=((sj3)*(x278));
01006 IkReal x288=((IkReal(1750.00000000000))*(cj1)*(sj3));
01007 IkReal x289=((cj3)*(x274));
01008 IkReal x290=((IkReal(1749.99997471250))*(x277));
01009 if( IKabs(((gconst10)*(((((x268)*(x284)))+(((IkReal(-1.00000000000000))*(x270)*(x285)))+(((x271)*(x275)))+(((x268)*(x269)*(x282)))+(((IkReal(1656.24997606719))*(x269)*(x277)))+(((x274)*(x287)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj3)*(x269)*(x290)))+(((x271)*(x285)))+(((IkReal(-1656.24997606719))*(x269)*(x280)))+(((x272)*(x286)))+(((IkReal(1749.99997471250))*(x272)*(x289)))+(((IkReal(0.281562495931422))*(x274)*(x277)))+(((IkReal(-1.00000000000000))*(cj3)*(r02)*(x269)*(x278)))+(((IkReal(-0.281562495931422))*(x274)*(x280)))+(((IkReal(-1.00000000000000))*(sj3)*(x269)*(x276)))+(((IkReal(-1.00000000000000))*(sj3)*(x269)*(x279)))+(((IkReal(-1.00000000000000))*(x268)*(x286)))+(((IkReal(-1.00000000000000))*(x269)*(x272)*(x282)))+(((IkReal(-1749.99997471250))*(x268)*(x289)))+(((IkReal(-1.00000000000000))*(x270)*(x275)))+(((x274)*(x277)*(x282)))+(((IkReal(-1.00000000000000))*(x272)*(x284)))+(((IkReal(-1.00000000000000))*(r02)*(x276)*(x289)))+(((IkReal(-1.00000000000000))*(sj3)*(x273)*(x274)))+(((pz)*(x288))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst10)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x274)*(x276)))+(((IkReal(-1.00000000000000))*(pz)*(x275)))+(((IkReal(-1.00000000000000))*(x270)*(x288)))+(((x272)*(x274)*(x281)))+(((x268)*(x269)*(x283)))+(((IkReal(-1.00000000000000))*(px)*(x286)))+(((x269)*(x277)*(x281)))+(((IkReal(-1.00000000000000))*(x268)*(x274)*(x281)))+(((x271)*(x288)))+(((IkReal(0.281562495931422))*(py)*(x274)))+(((x273)*(x289)))+(((IkReal(-1.00000000000000))*(x269)*(x272)*(x283)))+(((IkReal(1656.24997606719))*(py)*(x269)))+(((IkReal(-1.00000000000000))*(pz)*(x285)))+(((IkReal(185.500000000000))*(cj3)))+(((x274)*(x277)*(x283)))+(((cj3)*(x269)*(x279)))+(((cj3)*(x269)*(x276)))+(((px)*(x284)))+(((IkReal(-1.00000000000000))*(x278)*(x289)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x287))))))) < IKFAST_ATAN2_MAGTHRESH )
01010     continue;
01011 j2array[0]=IKatan2(((gconst10)*(((((x268)*(x284)))+(((IkReal(-1.00000000000000))*(x270)*(x285)))+(((x271)*(x275)))+(((x268)*(x269)*(x282)))+(((IkReal(1656.24997606719))*(x269)*(x277)))+(((x274)*(x287)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj3)*(x269)*(x290)))+(((x271)*(x285)))+(((IkReal(-1656.24997606719))*(x269)*(x280)))+(((x272)*(x286)))+(((IkReal(1749.99997471250))*(x272)*(x289)))+(((IkReal(0.281562495931422))*(x274)*(x277)))+(((IkReal(-1.00000000000000))*(cj3)*(r02)*(x269)*(x278)))+(((IkReal(-0.281562495931422))*(x274)*(x280)))+(((IkReal(-1.00000000000000))*(sj3)*(x269)*(x276)))+(((IkReal(-1.00000000000000))*(sj3)*(x269)*(x279)))+(((IkReal(-1.00000000000000))*(x268)*(x286)))+(((IkReal(-1.00000000000000))*(x269)*(x272)*(x282)))+(((IkReal(-1749.99997471250))*(x268)*(x289)))+(((IkReal(-1.00000000000000))*(x270)*(x275)))+(((x274)*(x277)*(x282)))+(((IkReal(-1.00000000000000))*(x272)*(x284)))+(((IkReal(-1.00000000000000))*(r02)*(x276)*(x289)))+(((IkReal(-1.00000000000000))*(sj3)*(x273)*(x274)))+(((pz)*(x288)))))), ((gconst10)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(r02)*(sj3)*(x274)*(x276)))+(((IkReal(-1.00000000000000))*(pz)*(x275)))+(((IkReal(-1.00000000000000))*(x270)*(x288)))+(((x272)*(x274)*(x281)))+(((x268)*(x269)*(x283)))+(((IkReal(-1.00000000000000))*(px)*(x286)))+(((x269)*(x277)*(x281)))+(((IkReal(-1.00000000000000))*(x268)*(x274)*(x281)))+(((x271)*(x288)))+(((IkReal(0.281562495931422))*(py)*(x274)))+(((x273)*(x289)))+(((IkReal(-1.00000000000000))*(x269)*(x272)*(x283)))+(((IkReal(1656.24997606719))*(py)*(x269)))+(((IkReal(-1.00000000000000))*(pz)*(x285)))+(((IkReal(185.500000000000))*(cj3)))+(((x274)*(x277)*(x283)))+(((cj3)*(x269)*(x279)))+(((cj3)*(x269)*(x276)))+(((px)*(x284)))+(((IkReal(-1.00000000000000))*(x278)*(x289)))+(((IkReal(-1.00000000000000))*(r02)*(x269)*(x287)))))));
01012 sj2array[0]=IKsin(j2array[0]);
01013 cj2array[0]=IKcos(j2array[0]);
01014 if( j2array[0] > IKPI )
01015 {
01016     j2array[0]-=IK2PI;
01017 }
01018 else if( j2array[0] < -IKPI )
01019 {    j2array[0]+=IK2PI;
01020 }
01021 j2valid[0] = true;
01022 for(int ij2 = 0; ij2 < 1; ++ij2)
01023 {
01024 if( !j2valid[ij2] )
01025 {
01026     continue;
01027 }
01028 _ij2[0] = ij2; _ij2[1] = -1;
01029 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01030 {
01031 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01032 {
01033     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01034 }
01035 }
01036 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01037 {
01038 IkReal evalcond[4];
01039 IkReal x291=IKsin(j2);
01040 IkReal x292=IKcos(j2);
01041 IkReal x293=((r00)*(sj0));
01042 IkReal x294=((r01)*(sj0));
01043 IkReal x295=((py)*(sj1));
01044 IkReal x296=((IkReal(0.999999985550000))*(r02));
01045 IkReal x297=((px)*(sj1));
01046 IkReal x298=((IkReal(0.999999985550000))*(sj0));
01047 IkReal x299=((IkReal(0.000169999997543500))*(cj0));
01048 IkReal x300=((IkReal(0.000169999997543500))*(sj0));
01049 IkReal x301=((cj1)*(px));
01050 IkReal x302=((pz)*(sj1));
01051 IkReal x303=((cj0)*(r00));
01052 IkReal x304=((cj1)*(pz));
01053 IkReal x305=((IkReal(1.00000000000000))*(r01));
01054 IkReal x306=((cj1)*(py));
01055 IkReal x307=((IkReal(0.999999985550000))*(cj0));
01056 IkReal x308=((IkReal(0.106000000000000))*(x291));
01057 IkReal x309=((IkReal(0.106000000000000))*(x292));
01058 IkReal x310=((IkReal(0.112000000000000))*(x292));
01059 IkReal x311=((IkReal(0.112000000000000))*(x291));
01060 IkReal x312=((cj3)*(x311));
01061 IkReal x313=((sj3)*(x310));
01062 IkReal x314=((cj3)*(x310));
01063 IkReal x315=((sj3)*(x311));
01064 IkReal x316=((x309)+(x314));
01065 IkReal x317=((x308)+(x313)+(x312));
01066 evalcond[0]=((((IkReal(-1.00000000000000))*(x298)*(x301)))+(((x299)*(x301)))+(x302)+(x317)+(((x300)*(x306)))+(((x306)*(x307))));
01067 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x297)*(x299)))+(((IkReal(-1.00000000000000))*(x295)*(x307)))+(((IkReal(-1.00000000000000))*(x295)*(x300)))+(x304)+(x315)+(((IkReal(-1.00000000000000))*(x316)))+(((x297)*(x298))));
01068 evalcond[2]=((((IkReal(0.999999985550000))*(x294)*(x302)))+(((IkReal(-1.00000000000000))*(x301)*(x305)))+(((IkReal(0.999999985550000))*(x302)*(x303)))+(x317)+(((IkReal(-1.00000000000000))*(cj0)*(x296)*(x297)))+(((r02)*(x295)*(x299)))+(((IkReal(0.000169999997543500))*(x293)*(x302)))+(((IkReal(-1.00000000000000))*(sj0)*(x295)*(x296)))+(((IkReal(-1.00000000000000))*(r01)*(x299)*(x302)))+(((IkReal(-1.00000000000000))*(r02)*(x297)*(x300)))+(((r00)*(x306))));
01069 evalcond[3]=((((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((cj0)*(x296)*(x301)))+(((IkReal(0.105999998468300))*(x294)))+(((IkReal(0.105999998468300))*(x303)))+(((IkReal(-1.00000000000000))*(x297)*(x305)))+(((IkReal(1.80199997396110e-5))*(x293)))+(((r02)*(x300)*(x301)))+(((r01)*(x299)*(x304)))+(((sj0)*(x296)*(x306)))+(x316)+(((IkReal(-1.00000000000000))*(x315)))+(((IkReal(-0.000169999997543500))*(x293)*(x304)))+(((IkReal(-0.999999985550000))*(x303)*(x304)))+(((r00)*(x295)))+(((IkReal(-1.00000000000000))*(r02)*(x299)*(x306)))+(((IkReal(-0.999999985550000))*(x294)*(x304))));
01070 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01071 {
01072 continue;
01073 }
01074 }
01075 
01076 {
01077 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01078 vinfos[0].jointtype = 1;
01079 vinfos[0].foffset = j0;
01080 vinfos[0].indices[0] = _ij0[0];
01081 vinfos[0].indices[1] = _ij0[1];
01082 vinfos[0].maxsolutions = _nj0;
01083 vinfos[1].jointtype = 1;
01084 vinfos[1].foffset = j1;
01085 vinfos[1].indices[0] = _ij1[0];
01086 vinfos[1].indices[1] = _ij1[1];
01087 vinfos[1].maxsolutions = _nj1;
01088 vinfos[2].jointtype = 1;
01089 vinfos[2].foffset = j2;
01090 vinfos[2].indices[0] = _ij2[0];
01091 vinfos[2].indices[1] = _ij2[1];
01092 vinfos[2].maxsolutions = _nj2;
01093 vinfos[3].jointtype = 1;
01094 vinfos[3].foffset = j3;
01095 vinfos[3].indices[0] = _ij3[0];
01096 vinfos[3].indices[1] = _ij3[1];
01097 vinfos[3].maxsolutions = _nj3;
01098 vinfos[4].jointtype = 1;
01099 vinfos[4].foffset = j5;
01100 vinfos[4].indices[0] = _ij5[0];
01101 vinfos[4].indices[1] = _ij5[1];
01102 vinfos[4].maxsolutions = _nj5;
01103 std::vector<int> vfree(0);
01104 solutions.AddSolution(vinfos,vfree);
01105 }
01106 }
01107 }
01108 
01109 }
01110 
01111 }
01112 
01113 } else
01114 {
01115 {
01116 IkReal j2array[1], cj2array[1], sj2array[1];
01117 bool j2valid[1]={false};
01118 _nj2 = 1;
01119 IkReal x318=((px)*(sj1));
01120 IkReal x319=((IkReal(0.281562495931422))*(cj0));
01121 IkReal x320=((cj1)*(sj0));
01122 IkReal x321=((IkReal(0.281562495931422))*(py));
01123 IkReal x322=((IkReal(1749.99997471250))*(sj3));
01124 IkReal x323=((IkReal(1749.99997471250))*(cj3));
01125 IkReal x324=((cj0)*(cj1));
01126 IkReal x325=((IkReal(0.297499995701125))*(sj3));
01127 IkReal x326=((IkReal(0.297499995701125))*(cj3));
01128 IkReal x327=((IkReal(1656.25000000000))*(pz));
01129 IkReal x328=((IkReal(1750.00000000000))*(cj3)*(pz));
01130 IkReal x329=((IkReal(1750.00000000000))*(pz)*(sj3));
01131 IkReal x330=((IkReal(1656.24997606719))*(cj0)*(py));
01132 IkReal x331=((py)*(sj0)*(sj1));
01133 IkReal x332=((cj0)*(py)*(sj1));
01134 if( IKabs(((gconst9)*(((((IkReal(-1656.24997606719))*(px)*(x320)))+(((IkReal(-1.00000000000000))*(px)*(x320)*(x323)))+(((cj1)*(x329)))+(((cj1)*(px)*(x319)))+(((IkReal(-1.00000000000000))*(cj0)*(x318)*(x325)))+(((sj0)*(x318)*(x322)))+(((x320)*(x321)))+(((IkReal(1656.24997606719))*(py)*(x324)))+(((IkReal(-185.500000000000))*(sj3)))+(((px)*(x324)*(x326)))+(((py)*(x323)*(x324)))+(((py)*(x320)*(x326)))+(((sj1)*(x328)))+(((sj1)*(x327)))+(((IkReal(-1.00000000000000))*(x322)*(x332)))+(((IkReal(-1.00000000000000))*(x325)*(x331))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst9)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(px)*(x320)*(x322)))+(((IkReal(-1.00000000000000))*(cj1)*(x327)))+(((IkReal(-1.00000000000000))*(cj1)*(x328)))+(((IkReal(-1656.24997606719))*(sj0)*(x318)))+(((px)*(x324)*(x325)))+(((py)*(x322)*(x324)))+(((py)*(x320)*(x325)))+(((cj0)*(x318)*(x326)))+(((sj1)*(x329)))+(((x323)*(x332)))+(((IkReal(185.500000000000))*(cj3)))+(((x326)*(x331)))+(((IkReal(-1.00000000000000))*(sj0)*(x318)*(x323)))+(((sj0)*(sj1)*(x321)))+(((x318)*(x319)))+(((sj1)*(x330))))))) < IKFAST_ATAN2_MAGTHRESH )
01135     continue;
01136 j2array[0]=IKatan2(((gconst9)*(((((IkReal(-1656.24997606719))*(px)*(x320)))+(((IkReal(-1.00000000000000))*(px)*(x320)*(x323)))+(((cj1)*(x329)))+(((cj1)*(px)*(x319)))+(((IkReal(-1.00000000000000))*(cj0)*(x318)*(x325)))+(((sj0)*(x318)*(x322)))+(((x320)*(x321)))+(((IkReal(1656.24997606719))*(py)*(x324)))+(((IkReal(-185.500000000000))*(sj3)))+(((px)*(x324)*(x326)))+(((py)*(x323)*(x324)))+(((py)*(x320)*(x326)))+(((sj1)*(x328)))+(((sj1)*(x327)))+(((IkReal(-1.00000000000000))*(x322)*(x332)))+(((IkReal(-1.00000000000000))*(x325)*(x331)))))), ((gconst9)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(px)*(x320)*(x322)))+(((IkReal(-1.00000000000000))*(cj1)*(x327)))+(((IkReal(-1.00000000000000))*(cj1)*(x328)))+(((IkReal(-1656.24997606719))*(sj0)*(x318)))+(((px)*(x324)*(x325)))+(((py)*(x322)*(x324)))+(((py)*(x320)*(x325)))+(((cj0)*(x318)*(x326)))+(((sj1)*(x329)))+(((x323)*(x332)))+(((IkReal(185.500000000000))*(cj3)))+(((x326)*(x331)))+(((IkReal(-1.00000000000000))*(sj0)*(x318)*(x323)))+(((sj0)*(sj1)*(x321)))+(((x318)*(x319)))+(((sj1)*(x330)))))));
01137 sj2array[0]=IKsin(j2array[0]);
01138 cj2array[0]=IKcos(j2array[0]);
01139 if( j2array[0] > IKPI )
01140 {
01141     j2array[0]-=IK2PI;
01142 }
01143 else if( j2array[0] < -IKPI )
01144 {    j2array[0]+=IK2PI;
01145 }
01146 j2valid[0] = true;
01147 for(int ij2 = 0; ij2 < 1; ++ij2)
01148 {
01149 if( !j2valid[ij2] )
01150 {
01151     continue;
01152 }
01153 _ij2[0] = ij2; _ij2[1] = -1;
01154 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01155 {
01156 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01157 {
01158     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01159 }
01160 }
01161 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01162 {
01163 IkReal evalcond[4];
01164 IkReal x333=IKsin(j2);
01165 IkReal x334=IKcos(j2);
01166 IkReal x335=((r00)*(sj0));
01167 IkReal x336=((r01)*(sj0));
01168 IkReal x337=((py)*(sj1));
01169 IkReal x338=((IkReal(0.999999985550000))*(r02));
01170 IkReal x339=((px)*(sj1));
01171 IkReal x340=((IkReal(0.999999985550000))*(sj0));
01172 IkReal x341=((IkReal(0.000169999997543500))*(cj0));
01173 IkReal x342=((IkReal(0.000169999997543500))*(sj0));
01174 IkReal x343=((cj1)*(px));
01175 IkReal x344=((pz)*(sj1));
01176 IkReal x345=((cj0)*(r00));
01177 IkReal x346=((cj1)*(pz));
01178 IkReal x347=((IkReal(1.00000000000000))*(r01));
01179 IkReal x348=((cj1)*(py));
01180 IkReal x349=((IkReal(0.999999985550000))*(cj0));
01181 IkReal x350=((IkReal(0.106000000000000))*(x333));
01182 IkReal x351=((IkReal(0.106000000000000))*(x334));
01183 IkReal x352=((IkReal(0.112000000000000))*(x334));
01184 IkReal x353=((IkReal(0.112000000000000))*(x333));
01185 IkReal x354=((cj3)*(x353));
01186 IkReal x355=((sj3)*(x352));
01187 IkReal x356=((cj3)*(x352));
01188 IkReal x357=((sj3)*(x353));
01189 IkReal x358=((x351)+(x356));
01190 IkReal x359=((x350)+(x355)+(x354));
01191 evalcond[0]=((((x348)*(x349)))+(x359)+(x344)+(((IkReal(-1.00000000000000))*(x340)*(x343)))+(((x341)*(x343)))+(((x342)*(x348))));
01192 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x337)*(x349)))+(((IkReal(-1.00000000000000))*(x337)*(x342)))+(((IkReal(-1.00000000000000))*(x358)))+(x357)+(x346)+(((x339)*(x340)))+(((IkReal(-1.00000000000000))*(x339)*(x341))));
01193 evalcond[2]=((((IkReal(0.999999985550000))*(x336)*(x344)))+(((IkReal(-1.00000000000000))*(r02)*(x339)*(x342)))+(((r00)*(x348)))+(x359)+(((IkReal(0.000169999997543500))*(x335)*(x344)))+(((IkReal(-1.00000000000000))*(cj0)*(x338)*(x339)))+(((IkReal(0.999999985550000))*(x344)*(x345)))+(((IkReal(-1.00000000000000))*(sj0)*(x337)*(x338)))+(((IkReal(-1.00000000000000))*(x343)*(x347)))+(((IkReal(-1.00000000000000))*(r01)*(x341)*(x344)))+(((r02)*(x337)*(x341))));
01194 evalcond[3]=((((IkReal(0.105999998468300))*(x336)))+(((r00)*(x337)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(1.80199997396110e-5))*(x335)))+(((IkReal(-1.00000000000000))*(x357)))+(((cj0)*(x338)*(x343)))+(((IkReal(-0.000169999997543500))*(x335)*(x346)))+(((sj0)*(x338)*(x348)))+(((IkReal(0.105999998468300))*(x345)))+(((r02)*(x342)*(x343)))+(x358)+(((IkReal(-0.999999985550000))*(x336)*(x346)))+(((r01)*(x341)*(x346)))+(((IkReal(-0.999999985550000))*(x345)*(x346)))+(((IkReal(-1.00000000000000))*(r02)*(x341)*(x348)))+(((IkReal(-1.00000000000000))*(x339)*(x347))));
01195 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01196 {
01197 continue;
01198 }
01199 }
01200 
01201 {
01202 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01203 vinfos[0].jointtype = 1;
01204 vinfos[0].foffset = j0;
01205 vinfos[0].indices[0] = _ij0[0];
01206 vinfos[0].indices[1] = _ij0[1];
01207 vinfos[0].maxsolutions = _nj0;
01208 vinfos[1].jointtype = 1;
01209 vinfos[1].foffset = j1;
01210 vinfos[1].indices[0] = _ij1[0];
01211 vinfos[1].indices[1] = _ij1[1];
01212 vinfos[1].maxsolutions = _nj1;
01213 vinfos[2].jointtype = 1;
01214 vinfos[2].foffset = j2;
01215 vinfos[2].indices[0] = _ij2[0];
01216 vinfos[2].indices[1] = _ij2[1];
01217 vinfos[2].maxsolutions = _nj2;
01218 vinfos[3].jointtype = 1;
01219 vinfos[3].foffset = j3;
01220 vinfos[3].indices[0] = _ij3[0];
01221 vinfos[3].indices[1] = _ij3[1];
01222 vinfos[3].maxsolutions = _nj3;
01223 vinfos[4].jointtype = 1;
01224 vinfos[4].foffset = j5;
01225 vinfos[4].indices[0] = _ij5[0];
01226 vinfos[4].indices[1] = _ij5[1];
01227 vinfos[4].maxsolutions = _nj5;
01228 std::vector<int> vfree(0);
01229 solutions.AddSolution(vinfos,vfree);
01230 }
01231 }
01232 }
01233 
01234 }
01235 
01236 }
01237 }
01238 }
01239 
01240 } else
01241 {
01242 if( 1 )
01243 {
01244 continue;
01245 
01246 } else
01247 {
01248 }
01249 }
01250 }
01251 }
01252 
01253 } else
01254 {
01255 {
01256 IkReal j3array[1], cj3array[1], sj3array[1];
01257 bool j3valid[1]={false};
01258 _nj3 = 1;
01259 IkReal x360=((sj0)*(sj1));
01260 IkReal x361=((IkReal(743.750227252771))*(cj0));
01261 IkReal x362=((pz)*(r00));
01262 IkReal x363=((cj0)*(r01));
01263 IkReal x364=((IkReal(463750.141698787))*(cj1));
01264 IkReal x365=((px)*(r02));
01265 IkReal x366=((cj1)*(pz));
01266 IkReal x367=((cj5)*(py));
01267 IkReal x368=((cj0)*(sj1));
01268 IkReal x369=((r01)*(sj0));
01269 IkReal x370=((IkReal(78.8375240887937))*(cj1));
01270 IkReal x371=((cj5)*(px));
01271 IkReal x372=((py)*(r02));
01272 IkReal x373=((IkReal(4375001.33678101))*(sj0));
01273 if( IKabs(((IkReal(0.00269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((x361)*(x365)))+(((IkReal(4375001.33678101))*(cj0)*(x372)))+(((IkReal(4140624.94016797))*(x367)*(x368)))+(((IkReal(703.906239828555))*(x360)*(x367)))+(((IkReal(-1.00000000000000))*(x361)*(x362)))+(((IkReal(-4140625.00000000))*(cj5)*(x366)))+(((IkReal(743.750227252771))*(sj0)*(x372)))+(((x369)*(x370)))+(((IkReal(-1.00000000000000))*(r00)*(sj0)*(x364)))+(((IkReal(19531250.0000000))*(cj5)*(pp)))+(((IkReal(463750.148399976))*(r02)*(sj1)))+(((IkReal(-4375001.33678101))*(pz)*(x363)))+(((cj0)*(r00)*(x370)))+(((IkReal(245000.000000000))*(cj5)))+(((IkReal(-743.750227252771))*(pz)*(x369)))+(((IkReal(-4140624.94016797))*(x360)*(x371)))+(((x363)*(x364)))+(((IkReal(703.906239828555))*(x368)*(x371)))+(((x362)*(x373)))+(((IkReal(-1.00000000000000))*(x365)*(x373))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x360)))+(((IkReal(8.92857129955357))*(py)*(x368)))+(((IkReal(0.00151785712092411))*(px)*(x368)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857129955357))*(px)*(x360)))+(((IkReal(-8.92857142857143))*(x366))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.00269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((x361)*(x365)))+(((IkReal(4375001.33678101))*(cj0)*(x372)))+(((IkReal(4140624.94016797))*(x367)*(x368)))+(((IkReal(703.906239828555))*(x360)*(x367)))+(((IkReal(-1.00000000000000))*(x361)*(x362)))+(((IkReal(-4140625.00000000))*(cj5)*(x366)))+(((IkReal(743.750227252771))*(sj0)*(x372)))+(((x369)*(x370)))+(((IkReal(-1.00000000000000))*(r00)*(sj0)*(x364)))+(((IkReal(19531250.0000000))*(cj5)*(pp)))+(((IkReal(463750.148399976))*(r02)*(sj1)))+(((IkReal(-4375001.33678101))*(pz)*(x363)))+(((cj0)*(r00)*(x370)))+(((IkReal(245000.000000000))*(cj5)))+(((IkReal(-743.750227252771))*(pz)*(x369)))+(((IkReal(-4140624.94016797))*(x360)*(x371)))+(((x363)*(x364)))+(((IkReal(703.906239828555))*(x368)*(x371)))+(((x362)*(x373)))+(((IkReal(-1.00000000000000))*(x365)*(x373)))))))+IKsqr(((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x360)))+(((IkReal(8.92857129955357))*(py)*(x368)))+(((IkReal(0.00151785712092411))*(px)*(x368)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857129955357))*(px)*(x360)))+(((IkReal(-8.92857142857143))*(x366)))))-1) <= IKFAST_SINCOS_THRESH )
01274     continue;
01275 j3array[0]=IKatan2(((IkReal(0.00269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((x361)*(x365)))+(((IkReal(4375001.33678101))*(cj0)*(x372)))+(((IkReal(4140624.94016797))*(x367)*(x368)))+(((IkReal(703.906239828555))*(x360)*(x367)))+(((IkReal(-1.00000000000000))*(x361)*(x362)))+(((IkReal(-4140625.00000000))*(cj5)*(x366)))+(((IkReal(743.750227252771))*(sj0)*(x372)))+(((x369)*(x370)))+(((IkReal(-1.00000000000000))*(r00)*(sj0)*(x364)))+(((IkReal(19531250.0000000))*(cj5)*(pp)))+(((IkReal(463750.148399976))*(r02)*(sj1)))+(((IkReal(-4375001.33678101))*(pz)*(x363)))+(((cj0)*(r00)*(x370)))+(((IkReal(245000.000000000))*(cj5)))+(((IkReal(-743.750227252771))*(pz)*(x369)))+(((IkReal(-4140624.94016797))*(x360)*(x371)))+(((x363)*(x364)))+(((IkReal(703.906239828555))*(x368)*(x371)))+(((x362)*(x373)))+(((IkReal(-1.00000000000000))*(x365)*(x373)))))), ((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x360)))+(((IkReal(8.92857129955357))*(py)*(x368)))+(((IkReal(0.00151785712092411))*(px)*(x368)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857129955357))*(px)*(x360)))+(((IkReal(-8.92857142857143))*(x366)))));
01276 sj3array[0]=IKsin(j3array[0]);
01277 cj3array[0]=IKcos(j3array[0]);
01278 if( j3array[0] > IKPI )
01279 {
01280     j3array[0]-=IK2PI;
01281 }
01282 else if( j3array[0] < -IKPI )
01283 {    j3array[0]+=IK2PI;
01284 }
01285 j3valid[0] = true;
01286 for(int ij3 = 0; ij3 < 1; ++ij3)
01287 {
01288 if( !j3valid[ij3] )
01289 {
01290     continue;
01291 }
01292 _ij3[0] = ij3; _ij3[1] = -1;
01293 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01294 {
01295 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01296 {
01297     j3valid[iij3]=false; _ij3[1] = iij3; break; 
01298 }
01299 }
01300 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01301 {
01302 IkReal evalcond[4];
01303 IkReal x374=IKcos(j3);
01304 IkReal x375=IKsin(j3);
01305 IkReal x376=(px)*(px);
01306 IkReal x377=(py)*(py);
01307 IkReal x378=(pz)*(pz);
01308 IkReal x379=((r00)*(sj0));
01309 IkReal x380=((cj0)*(r00));
01310 IkReal x381=((py)*(sj1));
01311 IkReal x382=((cj1)*(pz));
01312 IkReal x383=((cj0)*(r01));
01313 IkReal x384=((px)*(py));
01314 IkReal x385=((r01)*(sj0));
01315 IkReal x386=((IkReal(1.80199997396110e-5))*(sj1));
01316 IkReal x387=((cj0)*(r02));
01317 IkReal x388=((IkReal(3.60399994792220e-5))*(cj1));
01318 IkReal x389=((IkReal(0.105999966080016))*(cj5));
01319 IkReal x390=((IkReal(0.999999985550000))*(pz));
01320 IkReal x391=((px)*(sj1));
01321 IkReal x392=((IkReal(0.106000000000000))*(r02));
01322 IkReal x393=((IkReal(8.47999728640130e-5))*(cj5));
01323 IkReal x394=((IkReal(0.000169999997543500))*(pz));
01324 IkReal x395=((IkReal(0.211999996936600))*(cj1));
01325 IkReal x396=((IkReal(0.000339999995087000))*(pz));
01326 IkReal x397=((IkReal(0.105999998468300))*(cj1));
01327 IkReal x398=((IkReal(1.80199997396110e-5))*(cj1));
01328 IkReal x399=((IkReal(1.99999997110000))*(pz));
01329 IkReal x400=((IkReal(0.105999998468300))*(sj1));
01330 IkReal x401=((IkReal(0.999999985550000))*(x377));
01331 IkReal x402=((IkReal(0.999999985550000))*(x378));
01332 IkReal x403=((IkReal(0.000169999997543500))*(x376));
01333 IkReal x404=((IkReal(0.000169999997543500))*(x377));
01334 IkReal x405=((IkReal(0.000169999997543500))*(x378));
01335 IkReal x406=((px)*(r02)*(sj0));
01336 IkReal x407=((IkReal(0.999999985550000))*(x376));
01337 IkReal x408=((py)*(r02)*(sj0));
01338 IkReal x409=((IkReal(0.0237440000000000))*(x374));
01339 evalcond[0]=((IkReal(0.0125440000000000))+(((IkReal(0.211999996936600))*(sj0)*(x391)))+(((IkReal(-3.60399994792220e-5))*(cj0)*(x391)))+(((IkReal(0.212000000000000))*(x382)))+(((IkReal(-3.60399994792220e-5))*(sj0)*(x381)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(-0.211999996936600))*(cj0)*(x381)))+(x409));
01340 evalcond[1]=((((IkReal(-1.00000000000000))*(x383)*(x400)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((IkReal(-1.00000000000000))*(x380)*(x386)))+(((IkReal(8.95999713280138e-5))*(cj5)))+(((x379)*(x400)))+(((IkReal(-1.00000000000000))*(pz)*(r02)))+(((cj1)*(x392)))+(((IkReal(-1.00000000000000))*(py)*(r01)))+(((IkReal(-1.00000000000000))*(x385)*(x386)))+(((x375)*(x389)))+(((x374)*(x393))));
01341 evalcond[2]=((((x385)*(x398)))+(((x379)*(x390)))+(((IkReal(0.999999985550000))*(py)*(x387)))+(((x380)*(x398)))+(((IkReal(-1.00000000000000))*(x385)*(x394)))+(((sj1)*(x392)))+(((x374)*(x389)))+(((IkReal(-1.00000000000000))*(x383)*(x390)))+(((IkReal(-0.999999985550000))*(x406)))+(((IkReal(0.000169999997543500))*(x408)))+(((IkReal(-1.00000000000000))*(x380)*(x394)))+(((IkReal(0.000169999997543500))*(px)*(x387)))+(((IkReal(0.111999964160017))*(cj5)))+(((IkReal(-1.00000000000000))*(x379)*(x397)))+(((IkReal(-1.00000000000000))*(x375)*(x393)))+(((x383)*(x397))));
01342 evalcond[3]=((((IkReal(-1.00000000000000))*(x383)*(x404)))+(((x380)*(x407)))+(((IkReal(-0.0112359998376398))*(x380)))+(((IkReal(-0.0112359998376398))*(x385)))+(((IkReal(-1.00000000000000))*(sj5)*(x409)))+(((IkReal(-1.00000000000000))*(x380)*(x402)))+(((IkReal(-1.00000000000000))*(x380)*(x401)))+(((IkReal(-0.000339999995087000))*(x380)*(x384)))+(((IkReal(1.99999997110000))*(x379)*(x384)))+(((IkReal(-0.212000000000000))*(r00)*(x381)))+(((IkReal(3.60399994792220e-5))*(x379)*(x382)))+(((IkReal(0.211999996936600))*(x380)*(x382)))+(((IkReal(-1.00000000000000))*(x379)*(x404)))+(((IkReal(-1.00000000000000))*(x379)*(x405)))+(((IkReal(-1.00000000000000))*(x395)*(x408)))+(((IkReal(-3.60399994792220e-5))*(x382)*(x383)))+(((IkReal(1.99999997110000))*(x383)*(x384)))+(((px)*(x387)*(x399)))+(((IkReal(-0.0237800000000000))*(sj5)))+(((x379)*(x403)))+(((IkReal(-1.00000000000000))*(py)*(x387)*(x396)))+(((IkReal(-1.00000000000000))*(px)*(x387)*(x395)))+(((x383)*(x405)))+(((x383)*(x403)))+(((IkReal(0.211999996936600))*(x382)*(x385)))+(((x399)*(x408)))+(((py)*(x387)*(x388)))+(((IkReal(0.212000000000000))*(r01)*(x391)))+(((x385)*(x401)))+(((IkReal(-1.00000000000000))*(x385)*(x407)))+(((IkReal(-1.00000000000000))*(x385)*(x402)))+(((IkReal(-1.00000000000000))*(x388)*(x406)))+(((IkReal(0.000339999995087000))*(x384)*(x385)))+(((x396)*(x406)))+(((IkReal(-1.91011997239877e-6))*(x379)))+(((IkReal(1.91011997239877e-6))*(x383))));
01343 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01344 {
01345 continue;
01346 }
01347 }
01348 
01349 {
01350 IkReal dummyeval[1];
01351 IkReal gconst1;
01352 gconst1=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
01353 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
01354 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01355 {
01356 {
01357 IkReal dummyeval[1];
01358 IkReal gconst2;
01359 IkReal x410=((IkReal(13.9999955200021))*(cj5));
01360 gconst2=IKsign(((((IkReal(0.0105999966080016))*(cj5)*(sj3)))+(((IkReal(-13.2499957600020))*(cj3)*(cj5)))+(((IkReal(-1.00000000000000))*(x410)*((sj3)*(sj3))))+(((IkReal(-1.00000000000000))*(x410)*((cj3)*(cj3))))));
01361 IkReal x411=((IkReal(1320.75471698113))*(cj5));
01362 dummyeval[0]=((((IkReal(-1.00000000000000))*(x411)*((cj3)*(cj3))))+(((cj5)*(sj3)))+(((IkReal(-1.00000000000000))*(x411)*((sj3)*(sj3))))+(((IkReal(-1250.00000000000))*(cj3)*(cj5))));
01363 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01364 {
01365 {
01366 IkReal evalcond[11];
01367 IkReal x412=(px)*(px);
01368 IkReal x413=(py)*(py);
01369 IkReal x414=(pz)*(pz);
01370 IkReal x415=((IkReal(0.0237440000000000))*(cj3));
01371 IkReal x416=((IkReal(3.60399994792220e-5))*(pz));
01372 IkReal x417=((cj0)*(r00));
01373 IkReal x418=((r01)*(sj0));
01374 IkReal x419=((IkReal(0.000169999997543500))*(sj1));
01375 IkReal x420=((IkReal(0.000339999995087000))*(py));
01376 IkReal x421=((pz)*(sj1));
01377 IkReal x422=((r02)*(sj0));
01378 IkReal x423=((cj0)*(px));
01379 IkReal x424=((cj1)*(r01));
01380 IkReal x425=((IkReal(0.000169999997543500))*(cj0));
01381 IkReal x426=((IkReal(3.60399994792220e-5))*(sj1));
01382 IkReal x427=((py)*(r01));
01383 IkReal x428=((r00)*(sj0));
01384 IkReal x429=((IkReal(0.000169999997543500))*(pz));
01385 IkReal x430=((IkReal(0.105999998468300))*(cj0));
01386 IkReal x431=((px)*(r00));
01387 IkReal x432=((IkReal(1.99999997110000))*(pz));
01388 IkReal x433=((IkReal(1.91011997239877e-6))*(cj1));
01389 IkReal x434=((r01)*(sj1));
01390 IkReal x435=((cj1)*(r02));
01391 IkReal x436=((r02)*(sj1));
01392 IkReal x437=((IkReal(0.999999985550000))*(py));
01393 IkReal x438=((IkReal(0.999999985550000))*(cj0));
01394 IkReal x439=((IkReal(0.211999996936600))*(px));
01395 IkReal x440=((IkReal(0.0112359998376398))*(cj0));
01396 IkReal x441=((cj0)*(r02));
01397 IkReal x442=((IkReal(1.80199997396110e-5))*(sj1));
01398 IkReal x443=((IkReal(0.211999996936600))*(py));
01399 IkReal x444=((cj1)*(px));
01400 IkReal x445=((IkReal(0.000339999995087000))*(pz));
01401 IkReal x446=((IkReal(0.999999985550000))*(cj1));
01402 IkReal x447=((IkReal(0.000169999997543500))*(cj1));
01403 IkReal x448=((cj0)*(py));
01404 IkReal x449=((pz)*(r02));
01405 IkReal x450=((IkReal(0.211999996936600))*(pz));
01406 IkReal x451=((cj1)*(pz));
01407 IkReal x452=((IkReal(0.999999985550000))*(sj1));
01408 IkReal x453=((IkReal(1.80199997396110e-5))*(cj1));
01409 IkReal x454=((cj0)*(r01));
01410 IkReal x455=((IkReal(1.91011997239877e-6))*(sj1));
01411 IkReal x456=((IkReal(0.999999985550000))*(x414));
01412 IkReal x457=((IkReal(0.000169999997543500))*(x413));
01413 IkReal x458=((IkReal(0.999999985550000))*(x412));
01414 IkReal x459=((IkReal(0.000169999997543500))*(x414));
01415 IkReal x460=((IkReal(1.99999997110000))*(px)*(py));
01416 IkReal x461=((IkReal(0.000169999997543500))*(x412));
01417 IkReal x462=((IkReal(2.00000000000000))*(x414));
01418 IkReal x463=((IkReal(0.999999985550000))*(x413));
01419 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j5)), IkReal(6.28318530717959))));
01420 evalcond[1]=((((IkReal(-1.00000000000000))*(sj0)*(x437)))+(((py)*(x425)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((IkReal(-0.999999985550000))*(x423))));
01421 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-0.000169999997543500))*(x428)))+(((r01)*(x425)))+(((IkReal(-0.999999985550000))*(x417)))+(((IkReal(-0.999999985550000))*(x418))));
01422 evalcond[3]=((IkReal(0.0125440000000000))+(((IkReal(-1.00000000000000))*(pp)))+(((sj0)*(sj1)*(x439)))+(x415)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x443)))+(((IkReal(-1.00000000000000))*(x423)*(x426)))+(((IkReal(0.212000000000000))*(x451)))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x426))));
01423 evalcond[4]=((((IkReal(-1.00000000000000))*(x430)*(x434)))+(((IkReal(-1.00000000000000))*(x427)))+(((IkReal(-1.00000000000000))*(x431)))+(((IkReal(0.105999998468300))*(sj1)*(x428)))+(((IkReal(-1.00000000000000))*(x449)))+(((IkReal(0.106000000000000))*(x435)))+(((IkReal(-1.00000000000000))*(x417)*(x442)))+(((IkReal(-1.00000000000000))*(x418)*(x442))));
01424 evalcond[5]=((((x424)*(x438)))+(x436)+(((x418)*(x447)))+(((x417)*(x447)))+(((IkReal(-1.00000000000000))*(x428)*(x446))));
01425 evalcond[6]=((((IkReal(-1.00000000000000))*(x417)*(x419)))+(((IkReal(-1.00000000000000))*(x418)*(x419)))+(((x428)*(x452)))+(((IkReal(-1.00000000000000))*(x434)*(x438)))+(x435));
01426 evalcond[7]=((((x424)*(x430)))+(((IkReal(0.000169999997543500))*(py)*(x422)))+(((x418)*(x453)))+(((x417)*(x453)))+(((IkReal(0.106000000000000))*(x436)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x438)))+(((IkReal(0.999999985550000))*(pz)*(x428)))+(((IkReal(-0.105999998468300))*(cj1)*(x428)))+(((IkReal(-1.00000000000000))*(x417)*(x429)))+(((IkReal(-1.00000000000000))*(x418)*(x429)))+(((IkReal(0.000169999997543500))*(r02)*(x423)))+(((IkReal(-0.999999985550000))*(px)*(x422)))+(((x437)*(x441))));
01427 evalcond[8]=((IkReal(-0.0237800000000000))+(((r01)*(x414)*(x425)))+(((IkReal(-1.00000000000000))*(cj1)*(x422)*(x443)))+(((IkReal(-1.91011997239877e-6))*(x428)))+(((IkReal(-0.211999996936600))*(x423)*(x435)))+(((IkReal(-1.00000000000000))*(cj0)*(x416)*(x424)))+(((px)*(x418)*(x420)))+(((IkReal(-1.00000000000000))*(pz)*(x420)*(x441)))+(((x428)*(x460)))+(((x428)*(x461)))+(((cj1)*(x417)*(x450)))+(((r01)*(x412)*(x425)))+(((IkReal(1.91011997239877e-6))*(x454)))+(((x418)*(x463)))+(((IkReal(1.99999997110000))*(x423)*(x427)))+(((IkReal(3.60399994792220e-5))*(x435)*(x448)))+(((x417)*(x458)))+(((IkReal(-1.00000000000000))*(px)*(x417)*(x420)))+(((IkReal(-1.00000000000000))*(x417)*(x456)))+(((IkReal(-1.00000000000000))*(x428)*(x457)))+(((IkReal(-1.00000000000000))*(x428)*(x459)))+(((cj1)*(x418)*(x450)))+(((IkReal(-1.00000000000000))*(r01)*(x413)*(x425)))+(((IkReal(-1.00000000000000))*(x417)*(x463)))+(((cj1)*(x416)*(x428)))+(((IkReal(-1.00000000000000))*(x418)*(x458)))+(((IkReal(-1.00000000000000))*(x418)*(x456)))+(((IkReal(-3.60399994792220e-5))*(x422)*(x444)))+(((IkReal(-0.0112359998376398))*(x418)))+(((IkReal(-0.0112359998376398))*(x417)))+(((IkReal(0.212000000000000))*(px)*(x434)))+(((px)*(x422)*(x445)))+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((py)*(x422)*(x432)))+(((IkReal(-1.00000000000000))*(x415)))+(((r02)*(x423)*(x432))));
01428 evalcond[9]=((((x434)*(x440)))+(((px)*(sj1)*(x420)*(x428)))+(((IkReal(-1.00000000000000))*(x435)*(x462)))+(((x418)*(x455)))+(((x417)*(x455)))+(((IkReal(-1.00000000000000))*(x412)*(x428)*(x452)))+(((pp)*(x435)))+(((x412)*(x417)*(x419)))+(((IkReal(-1.00000000000000))*(x412)*(x418)*(x419)))+(((IkReal(-1.00000000000000))*(x412)*(x434)*(x438)))+(((IkReal(0.000339999995087000))*(r02)*(x421)*(x423)))+(((IkReal(-1.00000000000000))*(x414)*(x418)*(x419)))+(((x420)*(x421)*(x422)))+(((x413)*(x418)*(x419)))+(((IkReal(-0.0112359998376398))*(sj1)*(x428)))+(((IkReal(0.212000000000000))*(x427)))+(((IkReal(-1.00000000000000))*(x413)*(x417)*(x419)))+(((IkReal(-1.00000000000000))*(x414)*(x417)*(x419)))+(((x420)*(x423)*(x434)))+(((IkReal(0.212000000000000))*(x449)))+(((IkReal(-2.00000000000000))*(x431)*(x451)))+(((IkReal(0.212000000000000))*(x431)))+(((IkReal(-1.00000000000000))*(sj1)*(x418)*(x460)))+(((IkReal(1.99999997110000))*(py)*(x421)*(x441)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(x424)))+(((IkReal(-0.0112360000000000))*(x435)))+(((sj1)*(x417)*(x460)))+(((x413)*(x428)*(x452)))+(((x414)*(x428)*(x452)))+(((IkReal(-1.99999997110000))*(px)*(x421)*(x422)))+(((IkReal(-1.00000000000000))*(x414)*(x434)*(x438)))+(((x413)*(x434)*(x438))));
01429 evalcond[10]=((((x428)*(x450)))+(((IkReal(1.99999997110000))*(py)*(x418)*(x444)))+(((x424)*(x440)))+(((IkReal(-1.99999997110000))*(py)*(x417)*(x444)))+(((IkReal(3.60399994792220e-5))*(py)*(x422)))+(((x422)*(x432)*(x444)))+(((x414)*(x417)*(x447)))+(((IkReal(-1.00000000000000))*(x413)*(x418)*(x447)))+(((IkReal(-1.00000000000000))*(x420)*(x428)*(x444)))+(((IkReal(-1.00000000000000))*(x420)*(x422)*(x451)))+(((pp)*(x436)))+(((x413)*(x417)*(x447)))+(((x412)*(x424)*(x438)))+(((IkReal(-1.00000000000000))*(x412)*(x417)*(x447)))+(((IkReal(-1.00000000000000))*(x423)*(x435)*(x445)))+(((IkReal(3.60399994792220e-5))*(r02)*(x423)))+(((IkReal(-2.00000000000000))*(x421)*(x427)))+(((IkReal(-1.00000000000000))*(x413)*(x424)*(x438)))+(((x412)*(x418)*(x447)))+(((x418)*(x433)))+(((x441)*(x443)))+(((IkReal(-1.00000000000000))*(x416)*(x418)))+(((IkReal(-1.00000000000000))*(x416)*(x417)))+(((IkReal(-1.00000000000000))*(x436)*(x462)))+(((IkReal(-2.00000000000000))*(x421)*(x431)))+(((IkReal(-1.00000000000000))*(x450)*(x454)))+(((IkReal(-1.00000000000000))*(x420)*(x423)*(x424)))+(((IkReal(-1.00000000000000))*(x432)*(x435)*(x448)))+(((IkReal(0.0112360000000000))*(x436)))+(((x412)*(x428)*(x446)))+(((IkReal(-1.00000000000000))*(x414)*(x428)*(x446)))+(((IkReal(-1.00000000000000))*(x422)*(x439)))+(((x414)*(x424)*(x438)))+(((x414)*(x418)*(x447)))+(((IkReal(-1.00000000000000))*(x413)*(x428)*(x446)))+(((IkReal(-0.0112359998376398))*(cj1)*(x428)))+(((x417)*(x433))));
01430 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  )
01431 {
01432 {
01433 IkReal dummyeval[1];
01434 IkReal gconst3;
01435 gconst3=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
01436 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
01437 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01438 {
01439 {
01440 IkReal dummyeval[1];
01441 IkReal gconst4;
01442 gconst4=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
01443 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
01444 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01445 {
01446 continue;
01447 
01448 } else
01449 {
01450 {
01451 IkReal j2array[1], cj2array[1], sj2array[1];
01452 bool j2valid[1]={false};
01453 _nj2 = 1;
01454 IkReal x464=((py)*(r02));
01455 IkReal x465=((IkReal(1750.00000000000))*(cj1));
01456 IkReal x466=((px)*(sj3));
01457 IkReal x467=((cj3)*(pz));
01458 IkReal x468=((cj0)*(sj1));
01459 IkReal x469=((IkReal(1749.99997471250))*(r02));
01460 IkReal x470=((px)*(r01));
01461 IkReal x471=((r00)*(sj3));
01462 IkReal x472=((pz)*(sj3));
01463 IkReal x473=((pz)*(r01));
01464 IkReal x474=((IkReal(0.297499995701125))*(sj3));
01465 IkReal x475=((IkReal(1656.25000000000))*(cj1));
01466 IkReal x476=((IkReal(0.297499995701125))*(cj3));
01467 IkReal x477=((pz)*(r00));
01468 IkReal x478=((cj3)*(px));
01469 IkReal x479=((cj3)*(py));
01470 IkReal x480=((px)*(r02));
01471 IkReal x481=((IkReal(0.297499995701125))*(r01));
01472 IkReal x482=((sj0)*(sj1));
01473 IkReal x483=((IkReal(0.281562495931422))*(x468));
01474 IkReal x484=((IkReal(1656.24997606719))*(x482));
01475 IkReal x485=((IkReal(1749.99997471250))*(x482));
01476 IkReal x486=((py)*(x482));
01477 IkReal x487=((IkReal(0.281562495931422))*(x482));
01478 if( IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(py)*(r00)*(x475)))+(((IkReal(-1749.99997471250))*(r00)*(x467)*(x468)))+(((IkReal(-0.297499995701125))*(r00)*(x467)*(x482)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x468)))+(((x476)*(x480)*(x482)))+(((x470)*(x475)))+(((IkReal(-1.00000000000000))*(x464)*(x483)))+(((IkReal(-1.00000000000000))*(x474)*(x486)))+(((IkReal(-185.500000000000))*(sj3)))+(((x465)*(x472)))+(((x467)*(x468)*(x481)))+(((x468)*(x469)*(x478)))+(((x464)*(x484)))+(((IkReal(-1.00000000000000))*(r00)*(x465)*(x479)))+(((IkReal(-1656.24997606719))*(x468)*(x477)))+(((IkReal(1656.24997606719))*(x468)*(x480)))+(((x480)*(x487)))+(((IkReal(-1.00000000000000))*(x464)*(x468)*(x476)))+(((IkReal(-1.00000000000000))*(r01)*(x467)*(x485)))+(((IkReal(-1.00000000000000))*(x477)*(x487)))+(((IkReal(-0.297499995701125))*(x466)*(x468)))+(((cj3)*(x465)*(x470)))+(((x466)*(x485)))+(((cj3)*(x464)*(x485)))+(((x473)*(x483)))+(((IkReal(-1.00000000000000))*(x473)*(x484))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(175.562500000000))+(((x466)*(x468)*(x469)))+(((IkReal(-1.00000000000000))*(x465)*(x467)))+(((IkReal(-1.00000000000000))*(py)*(x465)*(x471)))+(((px)*(x468)*(x476)))+(((x476)*(x486)))+(((IkReal(1749.99997471250))*(x468)*(x479)))+(((IkReal(-0.297499995701125))*(pz)*(x471)*(x482)))+(((x468)*(x472)*(x481)))+(((IkReal(0.297499995701125))*(r02)*(x466)*(x482)))+(((IkReal(-1.00000000000000))*(pz)*(x475)))+(((px)*(x483)))+(((IkReal(-1.00000000000000))*(r01)*(x472)*(x485)))+(((IkReal(1656.24997606719))*(py)*(x468)))+(((IkReal(-1.00000000000000))*(px)*(x484)))+(((IkReal(-1749.99997471250))*(pz)*(x468)*(x471)))+(((IkReal(-1.00000000000000))*(x464)*(x468)*(x474)))+(((sj3)*(x464)*(x485)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(0.281562495931422))*(x486)))+(((r01)*(x465)*(x466)))+(((IkReal(-1.00000000000000))*(x478)*(x485))))))) < IKFAST_ATAN2_MAGTHRESH )
01479     continue;
01480 j2array[0]=IKatan2(((gconst4)*(((((IkReal(-1.00000000000000))*(py)*(r00)*(x475)))+(((IkReal(-1749.99997471250))*(r00)*(x467)*(x468)))+(((IkReal(-0.297499995701125))*(r00)*(x467)*(x482)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x468)))+(((x476)*(x480)*(x482)))+(((x470)*(x475)))+(((IkReal(-1.00000000000000))*(x464)*(x483)))+(((IkReal(-1.00000000000000))*(x474)*(x486)))+(((IkReal(-185.500000000000))*(sj3)))+(((x465)*(x472)))+(((x467)*(x468)*(x481)))+(((x468)*(x469)*(x478)))+(((x464)*(x484)))+(((IkReal(-1.00000000000000))*(r00)*(x465)*(x479)))+(((IkReal(-1656.24997606719))*(x468)*(x477)))+(((IkReal(1656.24997606719))*(x468)*(x480)))+(((x480)*(x487)))+(((IkReal(-1.00000000000000))*(x464)*(x468)*(x476)))+(((IkReal(-1.00000000000000))*(r01)*(x467)*(x485)))+(((IkReal(-1.00000000000000))*(x477)*(x487)))+(((IkReal(-0.297499995701125))*(x466)*(x468)))+(((cj3)*(x465)*(x470)))+(((x466)*(x485)))+(((cj3)*(x464)*(x485)))+(((x473)*(x483)))+(((IkReal(-1.00000000000000))*(x473)*(x484)))))), ((gconst4)*(((IkReal(175.562500000000))+(((x466)*(x468)*(x469)))+(((IkReal(-1.00000000000000))*(x465)*(x467)))+(((IkReal(-1.00000000000000))*(py)*(x465)*(x471)))+(((px)*(x468)*(x476)))+(((x476)*(x486)))+(((IkReal(1749.99997471250))*(x468)*(x479)))+(((IkReal(-0.297499995701125))*(pz)*(x471)*(x482)))+(((x468)*(x472)*(x481)))+(((IkReal(0.297499995701125))*(r02)*(x466)*(x482)))+(((IkReal(-1.00000000000000))*(pz)*(x475)))+(((px)*(x483)))+(((IkReal(-1.00000000000000))*(r01)*(x472)*(x485)))+(((IkReal(1656.24997606719))*(py)*(x468)))+(((IkReal(-1.00000000000000))*(px)*(x484)))+(((IkReal(-1749.99997471250))*(pz)*(x468)*(x471)))+(((IkReal(-1.00000000000000))*(x464)*(x468)*(x474)))+(((sj3)*(x464)*(x485)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(0.281562495931422))*(x486)))+(((r01)*(x465)*(x466)))+(((IkReal(-1.00000000000000))*(x478)*(x485)))))));
01481 sj2array[0]=IKsin(j2array[0]);
01482 cj2array[0]=IKcos(j2array[0]);
01483 if( j2array[0] > IKPI )
01484 {
01485     j2array[0]-=IK2PI;
01486 }
01487 else if( j2array[0] < -IKPI )
01488 {    j2array[0]+=IK2PI;
01489 }
01490 j2valid[0] = true;
01491 for(int ij2 = 0; ij2 < 1; ++ij2)
01492 {
01493 if( !j2valid[ij2] )
01494 {
01495     continue;
01496 }
01497 _ij2[0] = ij2; _ij2[1] = -1;
01498 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01499 {
01500 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01501 {
01502     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01503 }
01504 }
01505 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01506 {
01507 IkReal evalcond[4];
01508 IkReal x488=IKsin(j2);
01509 IkReal x489=IKcos(j2);
01510 IkReal x490=((r00)*(sj0));
01511 IkReal x491=((r01)*(sj0));
01512 IkReal x492=((py)*(sj1));
01513 IkReal x493=((IkReal(0.999999985550000))*(r02));
01514 IkReal x494=((px)*(sj1));
01515 IkReal x495=((IkReal(0.999999985550000))*(sj0));
01516 IkReal x496=((IkReal(0.000169999997543500))*(cj0));
01517 IkReal x497=((IkReal(0.000169999997543500))*(sj0));
01518 IkReal x498=((cj1)*(px));
01519 IkReal x499=((pz)*(sj1));
01520 IkReal x500=((cj0)*(r00));
01521 IkReal x501=((cj1)*(pz));
01522 IkReal x502=((IkReal(1.00000000000000))*(r01));
01523 IkReal x503=((cj1)*(py));
01524 IkReal x504=((IkReal(0.999999985550000))*(cj0));
01525 IkReal x505=((IkReal(0.106000000000000))*(x488));
01526 IkReal x506=((IkReal(0.106000000000000))*(x489));
01527 IkReal x507=((IkReal(0.112000000000000))*(x489));
01528 IkReal x508=((IkReal(0.112000000000000))*(x488));
01529 IkReal x509=((cj3)*(x508));
01530 IkReal x510=((sj3)*(x507));
01531 IkReal x511=((sj3)*(x508));
01532 IkReal x512=((cj3)*(x507));
01533 IkReal x513=((x506)+(x512));
01534 IkReal x514=((x509)+(x505)+(x510));
01535 evalcond[0]=((((IkReal(-1.00000000000000))*(x495)*(x498)))+(((x497)*(x503)))+(((x496)*(x498)))+(x499)+(x514)+(((x503)*(x504))));
01536 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x494)*(x496)))+(((x494)*(x495)))+(x501)+(x511)+(((IkReal(-1.00000000000000))*(x492)*(x504)))+(((IkReal(-1.00000000000000))*(x513)))+(((IkReal(-1.00000000000000))*(x492)*(x497))));
01537 evalcond[2]=((((IkReal(0.999999985550000))*(x499)*(x500)))+(((IkReal(-1.00000000000000))*(sj0)*(x492)*(x493)))+(((IkReal(0.999999985550000))*(x491)*(x499)))+(((r02)*(x492)*(x496)))+(((IkReal(-1.00000000000000))*(cj0)*(x493)*(x494)))+(((IkReal(0.000169999997543500))*(x490)*(x499)))+(((r00)*(x503)))+(((IkReal(-1.00000000000000))*(r01)*(x496)*(x499)))+(((IkReal(-1.00000000000000))*(x514)))+(((IkReal(-1.00000000000000))*(x498)*(x502)))+(((IkReal(-1.00000000000000))*(r02)*(x494)*(x497))));
01538 evalcond[3]=((((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(1.80199997396110e-5))*(x490)))+(((sj0)*(x493)*(x503)))+(((IkReal(-0.999999985550000))*(x500)*(x501)))+(((IkReal(-1.00000000000000))*(x494)*(x502)))+(((IkReal(-0.999999985550000))*(x491)*(x501)))+(x511)+(((IkReal(0.105999998468300))*(x500)))+(((IkReal(-0.000169999997543500))*(x490)*(x501)))+(((r00)*(x492)))+(((IkReal(-1.00000000000000))*(r02)*(x496)*(x503)))+(((IkReal(-1.00000000000000))*(x513)))+(((r02)*(x497)*(x498)))+(((cj0)*(x493)*(x498)))+(((r01)*(x496)*(x501)))+(((IkReal(0.105999998468300))*(x491))));
01539 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01540 {
01541 continue;
01542 }
01543 }
01544 
01545 {
01546 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01547 vinfos[0].jointtype = 1;
01548 vinfos[0].foffset = j0;
01549 vinfos[0].indices[0] = _ij0[0];
01550 vinfos[0].indices[1] = _ij0[1];
01551 vinfos[0].maxsolutions = _nj0;
01552 vinfos[1].jointtype = 1;
01553 vinfos[1].foffset = j1;
01554 vinfos[1].indices[0] = _ij1[0];
01555 vinfos[1].indices[1] = _ij1[1];
01556 vinfos[1].maxsolutions = _nj1;
01557 vinfos[2].jointtype = 1;
01558 vinfos[2].foffset = j2;
01559 vinfos[2].indices[0] = _ij2[0];
01560 vinfos[2].indices[1] = _ij2[1];
01561 vinfos[2].maxsolutions = _nj2;
01562 vinfos[3].jointtype = 1;
01563 vinfos[3].foffset = j3;
01564 vinfos[3].indices[0] = _ij3[0];
01565 vinfos[3].indices[1] = _ij3[1];
01566 vinfos[3].maxsolutions = _nj3;
01567 vinfos[4].jointtype = 1;
01568 vinfos[4].foffset = j5;
01569 vinfos[4].indices[0] = _ij5[0];
01570 vinfos[4].indices[1] = _ij5[1];
01571 vinfos[4].maxsolutions = _nj5;
01572 std::vector<int> vfree(0);
01573 solutions.AddSolution(vinfos,vfree);
01574 }
01575 }
01576 }
01577 
01578 }
01579 
01580 }
01581 
01582 } else
01583 {
01584 {
01585 IkReal j2array[1], cj2array[1], sj2array[1];
01586 bool j2valid[1]={false};
01587 _nj2 = 1;
01588 IkReal x515=((px)*(sj1));
01589 IkReal x516=((IkReal(0.281562495931422))*(cj0));
01590 IkReal x517=((cj1)*(sj0));
01591 IkReal x518=((IkReal(0.281562495931422))*(py));
01592 IkReal x519=((IkReal(1749.99997471250))*(sj3));
01593 IkReal x520=((IkReal(1749.99997471250))*(cj3));
01594 IkReal x521=((cj0)*(cj1));
01595 IkReal x522=((IkReal(0.297499995701125))*(sj3));
01596 IkReal x523=((IkReal(0.297499995701125))*(cj3));
01597 IkReal x524=((IkReal(1656.25000000000))*(pz));
01598 IkReal x525=((IkReal(1750.00000000000))*(cj3)*(pz));
01599 IkReal x526=((IkReal(1750.00000000000))*(pz)*(sj3));
01600 IkReal x527=((IkReal(1656.24997606719))*(cj0)*(py));
01601 IkReal x528=((py)*(sj0)*(sj1));
01602 IkReal x529=((cj0)*(py)*(sj1));
01603 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(px)*(x517)*(x520)))+(((sj1)*(x525)))+(((sj1)*(x524)))+(((py)*(x517)*(x523)))+(((IkReal(1656.24997606719))*(py)*(x521)))+(((IkReal(-1656.24997606719))*(px)*(x517)))+(((IkReal(-1.00000000000000))*(cj0)*(x515)*(x522)))+(((sj0)*(x515)*(x519)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj1)*(px)*(x516)))+(((x517)*(x518)))+(((cj1)*(x526)))+(((IkReal(-1.00000000000000))*(x522)*(x528)))+(((py)*(x520)*(x521)))+(((px)*(x521)*(x523)))+(((IkReal(-1.00000000000000))*(x519)*(x529))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((IkReal(175.562500000000))+(((sj0)*(sj1)*(x518)))+(((cj0)*(x515)*(x523)))+(((sj1)*(x527)))+(((sj1)*(x526)))+(((py)*(x517)*(x522)))+(((IkReal(-1.00000000000000))*(cj1)*(x525)))+(((IkReal(-1.00000000000000))*(cj1)*(x524)))+(((py)*(x519)*(x521)))+(((x520)*(x529)))+(((x515)*(x516)))+(((x523)*(x528)))+(((IkReal(-1656.24997606719))*(sj0)*(x515)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj0)*(x515)*(x520)))+(((px)*(x521)*(x522)))+(((IkReal(-1.00000000000000))*(px)*(x517)*(x519))))))) < IKFAST_ATAN2_MAGTHRESH )
01604     continue;
01605 j2array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(px)*(x517)*(x520)))+(((sj1)*(x525)))+(((sj1)*(x524)))+(((py)*(x517)*(x523)))+(((IkReal(1656.24997606719))*(py)*(x521)))+(((IkReal(-1656.24997606719))*(px)*(x517)))+(((IkReal(-1.00000000000000))*(cj0)*(x515)*(x522)))+(((sj0)*(x515)*(x519)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj1)*(px)*(x516)))+(((x517)*(x518)))+(((cj1)*(x526)))+(((IkReal(-1.00000000000000))*(x522)*(x528)))+(((py)*(x520)*(x521)))+(((px)*(x521)*(x523)))+(((IkReal(-1.00000000000000))*(x519)*(x529)))))), ((gconst3)*(((IkReal(175.562500000000))+(((sj0)*(sj1)*(x518)))+(((cj0)*(x515)*(x523)))+(((sj1)*(x527)))+(((sj1)*(x526)))+(((py)*(x517)*(x522)))+(((IkReal(-1.00000000000000))*(cj1)*(x525)))+(((IkReal(-1.00000000000000))*(cj1)*(x524)))+(((py)*(x519)*(x521)))+(((x520)*(x529)))+(((x515)*(x516)))+(((x523)*(x528)))+(((IkReal(-1656.24997606719))*(sj0)*(x515)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj0)*(x515)*(x520)))+(((px)*(x521)*(x522)))+(((IkReal(-1.00000000000000))*(px)*(x517)*(x519)))))));
01606 sj2array[0]=IKsin(j2array[0]);
01607 cj2array[0]=IKcos(j2array[0]);
01608 if( j2array[0] > IKPI )
01609 {
01610     j2array[0]-=IK2PI;
01611 }
01612 else if( j2array[0] < -IKPI )
01613 {    j2array[0]+=IK2PI;
01614 }
01615 j2valid[0] = true;
01616 for(int ij2 = 0; ij2 < 1; ++ij2)
01617 {
01618 if( !j2valid[ij2] )
01619 {
01620     continue;
01621 }
01622 _ij2[0] = ij2; _ij2[1] = -1;
01623 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01624 {
01625 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01626 {
01627     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01628 }
01629 }
01630 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01631 {
01632 IkReal evalcond[4];
01633 IkReal x530=IKsin(j2);
01634 IkReal x531=IKcos(j2);
01635 IkReal x532=((r00)*(sj0));
01636 IkReal x533=((r01)*(sj0));
01637 IkReal x534=((py)*(sj1));
01638 IkReal x535=((IkReal(0.999999985550000))*(r02));
01639 IkReal x536=((px)*(sj1));
01640 IkReal x537=((IkReal(0.999999985550000))*(sj0));
01641 IkReal x538=((IkReal(0.000169999997543500))*(cj0));
01642 IkReal x539=((IkReal(0.000169999997543500))*(sj0));
01643 IkReal x540=((cj1)*(px));
01644 IkReal x541=((pz)*(sj1));
01645 IkReal x542=((cj0)*(r00));
01646 IkReal x543=((cj1)*(pz));
01647 IkReal x544=((IkReal(1.00000000000000))*(r01));
01648 IkReal x545=((cj1)*(py));
01649 IkReal x546=((IkReal(0.999999985550000))*(cj0));
01650 IkReal x547=((IkReal(0.106000000000000))*(x530));
01651 IkReal x548=((IkReal(0.106000000000000))*(x531));
01652 IkReal x549=((IkReal(0.112000000000000))*(x531));
01653 IkReal x550=((IkReal(0.112000000000000))*(x530));
01654 IkReal x551=((cj3)*(x550));
01655 IkReal x552=((sj3)*(x549));
01656 IkReal x553=((sj3)*(x550));
01657 IkReal x554=((cj3)*(x549));
01658 IkReal x555=((x554)+(x548));
01659 IkReal x556=((x552)+(x551)+(x547));
01660 evalcond[0]=((((x539)*(x545)))+(((IkReal(-1.00000000000000))*(x537)*(x540)))+(x556)+(x541)+(((x538)*(x540)))+(((x545)*(x546))));
01661 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x534)*(x546)))+(((IkReal(-1.00000000000000))*(x534)*(x539)))+(((IkReal(-1.00000000000000))*(x555)))+(((x536)*(x537)))+(x553)+(x543)+(((IkReal(-1.00000000000000))*(x536)*(x538))));
01662 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x536)*(x539)))+(((IkReal(-1.00000000000000))*(sj0)*(x534)*(x535)))+(((IkReal(-1.00000000000000))*(x540)*(x544)))+(((IkReal(-1.00000000000000))*(x556)))+(((IkReal(0.000169999997543500))*(x532)*(x541)))+(((IkReal(-1.00000000000000))*(r01)*(x538)*(x541)))+(((IkReal(0.999999985550000))*(x541)*(x542)))+(((IkReal(0.999999985550000))*(x533)*(x541)))+(((r00)*(x545)))+(((IkReal(-1.00000000000000))*(cj0)*(x535)*(x536)))+(((r02)*(x534)*(x538))));
01663 evalcond[3]=((((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((r02)*(x539)*(x540)))+(((IkReal(-1.00000000000000))*(r02)*(x538)*(x545)))+(((r01)*(x538)*(x543)))+(((IkReal(-0.999999985550000))*(x533)*(x543)))+(((IkReal(-0.000169999997543500))*(x532)*(x543)))+(((IkReal(-1.00000000000000))*(x555)))+(((IkReal(-0.999999985550000))*(x542)*(x543)))+(x553)+(((IkReal(1.80199997396110e-5))*(x532)))+(((sj0)*(x535)*(x545)))+(((IkReal(0.105999998468300))*(x542)))+(((IkReal(-1.00000000000000))*(x536)*(x544)))+(((IkReal(0.105999998468300))*(x533)))+(((r00)*(x534)))+(((cj0)*(x535)*(x540))));
01664 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01665 {
01666 continue;
01667 }
01668 }
01669 
01670 {
01671 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01672 vinfos[0].jointtype = 1;
01673 vinfos[0].foffset = j0;
01674 vinfos[0].indices[0] = _ij0[0];
01675 vinfos[0].indices[1] = _ij0[1];
01676 vinfos[0].maxsolutions = _nj0;
01677 vinfos[1].jointtype = 1;
01678 vinfos[1].foffset = j1;
01679 vinfos[1].indices[0] = _ij1[0];
01680 vinfos[1].indices[1] = _ij1[1];
01681 vinfos[1].maxsolutions = _nj1;
01682 vinfos[2].jointtype = 1;
01683 vinfos[2].foffset = j2;
01684 vinfos[2].indices[0] = _ij2[0];
01685 vinfos[2].indices[1] = _ij2[1];
01686 vinfos[2].maxsolutions = _nj2;
01687 vinfos[3].jointtype = 1;
01688 vinfos[3].foffset = j3;
01689 vinfos[3].indices[0] = _ij3[0];
01690 vinfos[3].indices[1] = _ij3[1];
01691 vinfos[3].maxsolutions = _nj3;
01692 vinfos[4].jointtype = 1;
01693 vinfos[4].foffset = j5;
01694 vinfos[4].indices[0] = _ij5[0];
01695 vinfos[4].indices[1] = _ij5[1];
01696 vinfos[4].maxsolutions = _nj5;
01697 std::vector<int> vfree(0);
01698 solutions.AddSolution(vinfos,vfree);
01699 }
01700 }
01701 }
01702 
01703 }
01704 
01705 }
01706 
01707 } else
01708 {
01709 IkReal x557=(px)*(px);
01710 IkReal x558=((IkReal(0.0237440000000000))*(cj3));
01711 IkReal x559=(py)*(py);
01712 IkReal x560=(pz)*(pz);
01713 IkReal x561=((IkReal(3.60399994792220e-5))*(pz));
01714 IkReal x562=((cj0)*(r00));
01715 IkReal x563=((r01)*(sj0));
01716 IkReal x564=((IkReal(0.000169999997543500))*(sj1));
01717 IkReal x565=((IkReal(0.000339999995087000))*(py));
01718 IkReal x566=((pz)*(sj1));
01719 IkReal x567=((r02)*(sj0));
01720 IkReal x568=((cj0)*(px));
01721 IkReal x569=((cj1)*(r01));
01722 IkReal x570=((IkReal(0.000169999997543500))*(cj0));
01723 IkReal x571=((IkReal(3.60399994792220e-5))*(sj1));
01724 IkReal x572=((py)*(r01));
01725 IkReal x573=((r00)*(sj0));
01726 IkReal x574=((IkReal(0.000169999997543500))*(pz));
01727 IkReal x575=((IkReal(0.105999998468300))*(cj0));
01728 IkReal x576=((px)*(r00));
01729 IkReal x577=((IkReal(1.99999997110000))*(pz));
01730 IkReal x578=((IkReal(1.91011997239877e-6))*(cj1));
01731 IkReal x579=((r01)*(sj1));
01732 IkReal x580=((cj1)*(r02));
01733 IkReal x581=((r02)*(sj1));
01734 IkReal x582=((IkReal(0.999999985550000))*(py));
01735 IkReal x583=((IkReal(0.999999985550000))*(cj0));
01736 IkReal x584=((IkReal(0.211999996936600))*(px));
01737 IkReal x585=((IkReal(0.0112359998376398))*(cj0));
01738 IkReal x586=((cj0)*(r02));
01739 IkReal x587=((IkReal(1.80199997396110e-5))*(sj1));
01740 IkReal x588=((IkReal(0.211999996936600))*(py));
01741 IkReal x589=((cj1)*(px));
01742 IkReal x590=((IkReal(0.000339999995087000))*(pz));
01743 IkReal x591=((IkReal(0.999999985550000))*(cj1));
01744 IkReal x592=((IkReal(0.000169999997543500))*(cj1));
01745 IkReal x593=((cj0)*(py));
01746 IkReal x594=((pz)*(r02));
01747 IkReal x595=((IkReal(0.211999996936600))*(pz));
01748 IkReal x596=((cj1)*(pz));
01749 IkReal x597=((IkReal(0.999999985550000))*(sj1));
01750 IkReal x598=((IkReal(1.80199997396110e-5))*(cj1));
01751 IkReal x599=((cj0)*(r01));
01752 IkReal x600=((IkReal(1.91011997239877e-6))*(sj1));
01753 IkReal x601=((IkReal(0.999999985550000))*(x560));
01754 IkReal x602=((IkReal(0.000169999997543500))*(x559));
01755 IkReal x603=((IkReal(0.999999985550000))*(x557));
01756 IkReal x604=((IkReal(0.000169999997543500))*(x560));
01757 IkReal x605=((IkReal(1.99999997110000))*(px)*(py));
01758 IkReal x606=((IkReal(0.000169999997543500))*(x557));
01759 IkReal x607=((IkReal(2.00000000000000))*(x560));
01760 IkReal x608=((IkReal(0.999999985550000))*(x559));
01761 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j5)), IkReal(6.28318530717959))));
01762 evalcond[1]=((((py)*(x570)))+(((IkReal(-0.999999985550000))*(x568)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x582))));
01763 evalcond[2]=((IkReal(1.00000000000000))+(((r01)*(x570)))+(((IkReal(-0.999999985550000))*(x563)))+(((IkReal(-0.999999985550000))*(x562)))+(((IkReal(-0.000169999997543500))*(x573))));
01764 evalcond[3]=((IkReal(0.0125440000000000))+(((sj0)*(sj1)*(x584)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x588)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x571)))+(x558)+(((IkReal(-1.00000000000000))*(x568)*(x571)))+(((IkReal(0.212000000000000))*(x596))));
01765 evalcond[4]=((((IkReal(0.105999998468300))*(sj1)*(x573)))+(((IkReal(0.106000000000000))*(x580)))+(((IkReal(-1.00000000000000))*(x594)))+(((IkReal(-1.00000000000000))*(x563)*(x587)))+(((IkReal(-1.00000000000000))*(x572)))+(((IkReal(-1.00000000000000))*(x576)))+(((IkReal(-1.00000000000000))*(x575)*(x579)))+(((IkReal(-1.00000000000000))*(x562)*(x587))));
01766 evalcond[5]=((((IkReal(-1.00000000000000))*(x573)*(x591)))+(((x562)*(x592)))+(x581)+(((x569)*(x583)))+(((x563)*(x592))));
01767 evalcond[6]=((((x573)*(x597)))+(((IkReal(-1.00000000000000))*(x579)*(x583)))+(((IkReal(-1.00000000000000))*(x562)*(x564)))+(x580)+(((IkReal(-1.00000000000000))*(x563)*(x564))));
01768 evalcond[7]=((((IkReal(0.999999985550000))*(pz)*(x573)))+(((IkReal(0.000169999997543500))*(py)*(x567)))+(((x582)*(x586)))+(((IkReal(-0.999999985550000))*(px)*(x567)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x583)))+(((IkReal(0.106000000000000))*(x581)))+(((IkReal(0.000169999997543500))*(r02)*(x568)))+(((x562)*(x598)))+(((IkReal(-1.00000000000000))*(x563)*(x574)))+(((x569)*(x575)))+(((IkReal(-0.105999998468300))*(cj1)*(x573)))+(((x563)*(x598)))+(((IkReal(-1.00000000000000))*(x562)*(x574))));
01769 evalcond[8]=((IkReal(0.0237800000000000))+(((IkReal(-1.00000000000000))*(px)*(x562)*(x565)))+(((x563)*(x608)))+(((IkReal(-1.00000000000000))*(r01)*(x559)*(x570)))+(((IkReal(-1.00000000000000))*(x573)*(x604)))+(((IkReal(-1.00000000000000))*(x573)*(x602)))+(((IkReal(3.60399994792220e-5))*(x580)*(x593)))+(((cj1)*(x561)*(x573)))+(((cj1)*(x563)*(x595)))+(((px)*(x567)*(x590)))+(((IkReal(-1.00000000000000))*(cj0)*(x561)*(x569)))+(((r01)*(x560)*(x570)))+(((x562)*(x603)))+(((cj1)*(x562)*(x595)))+(((r02)*(x568)*(x577)))+(((IkReal(-0.0112359998376398))*(x563)))+(((IkReal(-0.0112359998376398))*(x562)))+(((IkReal(-1.00000000000000))*(cj1)*(x567)*(x588)))+(((px)*(x563)*(x565)))+(((r01)*(x557)*(x570)))+(x558)+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((IkReal(-1.00000000000000))*(x562)*(x608)))+(((IkReal(-1.00000000000000))*(x562)*(x601)))+(((IkReal(1.91011997239877e-6))*(x599)))+(((IkReal(-3.60399994792220e-5))*(x567)*(x589)))+(((IkReal(-0.211999996936600))*(x568)*(x580)))+(((py)*(x567)*(x577)))+(((IkReal(1.99999997110000))*(x568)*(x572)))+(((IkReal(-1.00000000000000))*(x563)*(x601)))+(((IkReal(-1.00000000000000))*(x563)*(x603)))+(((x573)*(x605)))+(((x573)*(x606)))+(((IkReal(-1.91011997239877e-6))*(x573)))+(((IkReal(0.212000000000000))*(px)*(x579)))+(((IkReal(-1.00000000000000))*(pz)*(x565)*(x586))));
01770 evalcond[9]=((((IkReal(-2.00000000000000))*(py)*(pz)*(x569)))+(((IkReal(-2.00000000000000))*(x576)*(x596)))+(((x563)*(x600)))+(((pp)*(x580)))+(((x579)*(x585)))+(((IkReal(-1.99999997110000))*(px)*(x566)*(x567)))+(((IkReal(0.212000000000000))*(x572)))+(((IkReal(0.212000000000000))*(x576)))+(((IkReal(0.000339999995087000))*(r02)*(x566)*(x568)))+(((IkReal(-0.0112360000000000))*(x580)))+(((IkReal(1.99999997110000))*(py)*(x566)*(x586)))+(((IkReal(-0.0112359998376398))*(sj1)*(x573)))+(((x562)*(x600)))+(((sj1)*(x562)*(x605)))+(((IkReal(-1.00000000000000))*(x560)*(x562)*(x564)))+(((IkReal(-1.00000000000000))*(x560)*(x579)*(x583)))+(((IkReal(-1.00000000000000))*(x557)*(x573)*(x597)))+(((IkReal(-1.00000000000000))*(x557)*(x563)*(x564)))+(((IkReal(-1.00000000000000))*(x557)*(x579)*(x583)))+(((x565)*(x568)*(x579)))+(((IkReal(-1.00000000000000))*(sj1)*(x563)*(x605)))+(((x557)*(x562)*(x564)))+(((IkReal(-1.00000000000000))*(x560)*(x563)*(x564)))+(((x560)*(x573)*(x597)))+(((x559)*(x579)*(x583)))+(((px)*(sj1)*(x565)*(x573)))+(((x559)*(x563)*(x564)))+(((IkReal(-1.00000000000000))*(x559)*(x562)*(x564)))+(((IkReal(-1.00000000000000))*(x580)*(x607)))+(((x565)*(x566)*(x567)))+(((IkReal(0.212000000000000))*(x594)))+(((x559)*(x573)*(x597))));
01771 evalcond[10]=((((IkReal(3.60399994792220e-5))*(r02)*(x568)))+(((IkReal(-1.00000000000000))*(x565)*(x567)*(x596)))+(((IkReal(1.99999997110000))*(py)*(x563)*(x589)))+(((IkReal(-1.00000000000000))*(x559)*(x573)*(x591)))+(((x573)*(x595)))+(((pp)*(x581)))+(((IkReal(-1.00000000000000))*(x577)*(x580)*(x593)))+(((IkReal(-1.00000000000000))*(x559)*(x563)*(x592)))+(((x563)*(x578)))+(((x560)*(x563)*(x592)))+(((IkReal(0.0112360000000000))*(x581)))+(((x557)*(x563)*(x592)))+(((x557)*(x573)*(x591)))+(((IkReal(-1.99999997110000))*(py)*(x562)*(x589)))+(((x557)*(x569)*(x583)))+(((IkReal(-0.0112359998376398))*(cj1)*(x573)))+(((x560)*(x569)*(x583)))+(((IkReal(-2.00000000000000))*(x566)*(x572)))+(((IkReal(-2.00000000000000))*(x566)*(x576)))+(((x586)*(x588)))+(((x562)*(x578)))+(((x560)*(x562)*(x592)))+(((IkReal(-1.00000000000000))*(x565)*(x573)*(x589)))+(((x559)*(x562)*(x592)))+(((IkReal(-1.00000000000000))*(x557)*(x562)*(x592)))+(((IkReal(-1.00000000000000))*(x559)*(x569)*(x583)))+(((IkReal(3.60399994792220e-5))*(py)*(x567)))+(((IkReal(-1.00000000000000))*(x595)*(x599)))+(((x569)*(x585)))+(((IkReal(-1.00000000000000))*(x560)*(x573)*(x591)))+(((x567)*(x577)*(x589)))+(((IkReal(-1.00000000000000))*(x581)*(x607)))+(((IkReal(-1.00000000000000))*(x568)*(x580)*(x590)))+(((IkReal(-1.00000000000000))*(x561)*(x563)))+(((IkReal(-1.00000000000000))*(x561)*(x562)))+(((IkReal(-1.00000000000000))*(x567)*(x584)))+(((IkReal(-1.00000000000000))*(x565)*(x568)*(x569))));
01772 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  )
01773 {
01774 {
01775 IkReal dummyeval[1];
01776 IkReal gconst5;
01777 gconst5=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
01778 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
01779 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01780 {
01781 {
01782 IkReal dummyeval[1];
01783 IkReal gconst6;
01784 gconst6=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
01785 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
01786 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01787 {
01788 continue;
01789 
01790 } else
01791 {
01792 {
01793 IkReal j2array[1], cj2array[1], sj2array[1];
01794 bool j2valid[1]={false};
01795 _nj2 = 1;
01796 IkReal x609=((cj0)*(sj1));
01797 IkReal x610=((IkReal(1656.24997606719))*(pz));
01798 IkReal x611=((py)*(r02));
01799 IkReal x612=((IkReal(1750.00000000000))*(cj1));
01800 IkReal x613=((px)*(sj3));
01801 IkReal x614=((cj3)*(pz));
01802 IkReal x615=((sj0)*(sj1));
01803 IkReal x616=((IkReal(1749.99997471250))*(r02));
01804 IkReal x617=((px)*(r01));
01805 IkReal x618=((py)*(sj3));
01806 IkReal x619=((pz)*(sj3));
01807 IkReal x620=((IkReal(0.281562495931422))*(px));
01808 IkReal x621=((IkReal(0.297499995701125))*(cj3));
01809 IkReal x622=((IkReal(1749.99997471250))*(r01));
01810 IkReal x623=((IkReal(1749.99997471250))*(r00));
01811 IkReal x624=((IkReal(1656.25000000000))*(cj1));
01812 IkReal x625=((IkReal(0.281562495931422))*(pz));
01813 IkReal x626=((IkReal(1749.99997471250))*(cj3));
01814 IkReal x627=((IkReal(1656.24997606719))*(px));
01815 IkReal x628=((IkReal(0.297499995701125))*(r01));
01816 IkReal x629=((py)*(r00));
01817 IkReal x630=((IkReal(0.297499995701125))*(r00));
01818 if( IKabs(((gconst6)*(((((x609)*(x611)*(x621)))+(((IkReal(-1.00000000000000))*(x611)*(x615)*(x626)))+(((IkReal(-1656.24997606719))*(x611)*(x615)))+(((r00)*(x615)*(x625)))+(((IkReal(-1.00000000000000))*(r02)*(x615)*(x620)))+(((IkReal(0.281562495931422))*(x609)*(x611)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x609)*(x616)))+(((IkReal(-1.00000000000000))*(cj3)*(x612)*(x617)))+(((IkReal(-0.297499995701125))*(x615)*(x618)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj3)*(x612)*(x629)))+(((x612)*(x619)))+(((IkReal(-1.00000000000000))*(x617)*(x624)))+(((r00)*(x609)*(x610)))+(((IkReal(-0.297499995701125))*(x609)*(x613)))+(((x614)*(x615)*(x622)))+(((IkReal(-1.00000000000000))*(x609)*(x614)*(x628)))+(((x614)*(x615)*(x630)))+(((IkReal(-1.00000000000000))*(r01)*(x609)*(x625)))+(((x624)*(x629)))+(((IkReal(1749.99997471250))*(x613)*(x615)))+(((IkReal(-1.00000000000000))*(r02)*(x609)*(x627)))+(((r01)*(x610)*(x615)))+(((x609)*(x614)*(x623)))+(((IkReal(-1749.99997471250))*(x609)*(x618)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x615)*(x621))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x612)*(x614)))+(((IkReal(-1.00000000000000))*(pz)*(x624)))+(((IkReal(-1.00000000000000))*(x609)*(x613)*(x616)))+(((IkReal(-1.00000000000000))*(x609)*(x619)*(x628)))+(((py)*(x609)*(x626)))+(((x609)*(x619)*(x623)))+(((r00)*(x612)*(x618)))+(((IkReal(-1749.99997471250))*(sj3)*(x611)*(x615)))+(((x615)*(x619)*(x622)))+(((IkReal(-1.00000000000000))*(r01)*(x612)*(x613)))+(((IkReal(0.281562495931422))*(py)*(x615)))+(((x609)*(x620)))+(((x615)*(x619)*(x630)))+(((IkReal(-0.297499995701125))*(r02)*(x613)*(x615)))+(((IkReal(1656.24997606719))*(py)*(x609)))+(((IkReal(0.297499995701125))*(sj3)*(x609)*(x611)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x615)*(x626)))+(((px)*(x609)*(x621)))+(((py)*(x615)*(x621)))+(((IkReal(-1.00000000000000))*(x615)*(x627))))))) < IKFAST_ATAN2_MAGTHRESH )
01819     continue;
01820 j2array[0]=IKatan2(((gconst6)*(((((x609)*(x611)*(x621)))+(((IkReal(-1.00000000000000))*(x611)*(x615)*(x626)))+(((IkReal(-1656.24997606719))*(x611)*(x615)))+(((r00)*(x615)*(x625)))+(((IkReal(-1.00000000000000))*(r02)*(x615)*(x620)))+(((IkReal(0.281562495931422))*(x609)*(x611)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x609)*(x616)))+(((IkReal(-1.00000000000000))*(cj3)*(x612)*(x617)))+(((IkReal(-0.297499995701125))*(x615)*(x618)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj3)*(x612)*(x629)))+(((x612)*(x619)))+(((IkReal(-1.00000000000000))*(x617)*(x624)))+(((r00)*(x609)*(x610)))+(((IkReal(-0.297499995701125))*(x609)*(x613)))+(((x614)*(x615)*(x622)))+(((IkReal(-1.00000000000000))*(x609)*(x614)*(x628)))+(((x614)*(x615)*(x630)))+(((IkReal(-1.00000000000000))*(r01)*(x609)*(x625)))+(((x624)*(x629)))+(((IkReal(1749.99997471250))*(x613)*(x615)))+(((IkReal(-1.00000000000000))*(r02)*(x609)*(x627)))+(((r01)*(x610)*(x615)))+(((x609)*(x614)*(x623)))+(((IkReal(-1749.99997471250))*(x609)*(x618)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x615)*(x621)))))), ((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x612)*(x614)))+(((IkReal(-1.00000000000000))*(pz)*(x624)))+(((IkReal(-1.00000000000000))*(x609)*(x613)*(x616)))+(((IkReal(-1.00000000000000))*(x609)*(x619)*(x628)))+(((py)*(x609)*(x626)))+(((x609)*(x619)*(x623)))+(((r00)*(x612)*(x618)))+(((IkReal(-1749.99997471250))*(sj3)*(x611)*(x615)))+(((x615)*(x619)*(x622)))+(((IkReal(-1.00000000000000))*(r01)*(x612)*(x613)))+(((IkReal(0.281562495931422))*(py)*(x615)))+(((x609)*(x620)))+(((x615)*(x619)*(x630)))+(((IkReal(-0.297499995701125))*(r02)*(x613)*(x615)))+(((IkReal(1656.24997606719))*(py)*(x609)))+(((IkReal(0.297499995701125))*(sj3)*(x609)*(x611)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x615)*(x626)))+(((px)*(x609)*(x621)))+(((py)*(x615)*(x621)))+(((IkReal(-1.00000000000000))*(x615)*(x627)))))));
01821 sj2array[0]=IKsin(j2array[0]);
01822 cj2array[0]=IKcos(j2array[0]);
01823 if( j2array[0] > IKPI )
01824 {
01825     j2array[0]-=IK2PI;
01826 }
01827 else if( j2array[0] < -IKPI )
01828 {    j2array[0]+=IK2PI;
01829 }
01830 j2valid[0] = true;
01831 for(int ij2 = 0; ij2 < 1; ++ij2)
01832 {
01833 if( !j2valid[ij2] )
01834 {
01835     continue;
01836 }
01837 _ij2[0] = ij2; _ij2[1] = -1;
01838 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01839 {
01840 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01841 {
01842     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01843 }
01844 }
01845 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01846 {
01847 IkReal evalcond[4];
01848 IkReal x631=IKsin(j2);
01849 IkReal x632=IKcos(j2);
01850 IkReal x633=((r00)*(sj0));
01851 IkReal x634=((r01)*(sj0));
01852 IkReal x635=((py)*(sj1));
01853 IkReal x636=((IkReal(0.999999985550000))*(r02));
01854 IkReal x637=((px)*(sj1));
01855 IkReal x638=((IkReal(0.999999985550000))*(sj0));
01856 IkReal x639=((IkReal(0.000169999997543500))*(cj0));
01857 IkReal x640=((IkReal(0.000169999997543500))*(sj0));
01858 IkReal x641=((cj1)*(px));
01859 IkReal x642=((pz)*(sj1));
01860 IkReal x643=((cj0)*(r00));
01861 IkReal x644=((cj1)*(pz));
01862 IkReal x645=((IkReal(1.00000000000000))*(r01));
01863 IkReal x646=((cj1)*(py));
01864 IkReal x647=((IkReal(0.999999985550000))*(cj0));
01865 IkReal x648=((IkReal(0.106000000000000))*(x631));
01866 IkReal x649=((IkReal(0.106000000000000))*(x632));
01867 IkReal x650=((IkReal(0.112000000000000))*(x632));
01868 IkReal x651=((IkReal(0.112000000000000))*(x631));
01869 IkReal x652=((cj3)*(x651));
01870 IkReal x653=((sj3)*(x650));
01871 IkReal x654=((cj3)*(x650));
01872 IkReal x655=((sj3)*(x651));
01873 IkReal x656=((x649)+(x654));
01874 IkReal x657=((x648)+(x652)+(x653));
01875 evalcond[0]=((((x639)*(x641)))+(((x640)*(x646)))+(x642)+(x657)+(((x646)*(x647)))+(((IkReal(-1.00000000000000))*(x638)*(x641))));
01876 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x637)*(x639)))+(((IkReal(-1.00000000000000))*(x656)))+(((IkReal(-1.00000000000000))*(x635)*(x640)))+(((IkReal(-1.00000000000000))*(x635)*(x647)))+(x644)+(x655)+(((x637)*(x638))));
01877 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(x636)*(x637)))+(((IkReal(0.999999985550000))*(x642)*(x643)))+(((IkReal(-1.00000000000000))*(x641)*(x645)))+(((IkReal(-1.00000000000000))*(sj0)*(x635)*(x636)))+(((IkReal(0.999999985550000))*(x634)*(x642)))+(((IkReal(-1.00000000000000))*(r01)*(x639)*(x642)))+(x657)+(((r00)*(x646)))+(((IkReal(-1.00000000000000))*(r02)*(x637)*(x640)))+(((r02)*(x635)*(x639)))+(((IkReal(0.000169999997543500))*(x633)*(x642))));
01878 evalcond[3]=((((IkReal(-0.999999985550000))*(x634)*(x644)))+(((r01)*(x639)*(x644)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-0.000169999997543500))*(x633)*(x644)))+(((IkReal(1.80199997396110e-5))*(x633)))+(((IkReal(0.105999998468300))*(x634)))+(((IkReal(-1.00000000000000))*(x655)))+(((sj0)*(x636)*(x646)))+(((IkReal(0.105999998468300))*(x643)))+(((r00)*(x635)))+(x656)+(((IkReal(-1.00000000000000))*(x637)*(x645)))+(((cj0)*(x636)*(x641)))+(((IkReal(-1.00000000000000))*(r02)*(x639)*(x646)))+(((IkReal(-0.999999985550000))*(x643)*(x644)))+(((r02)*(x640)*(x641))));
01879 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01880 {
01881 continue;
01882 }
01883 }
01884 
01885 {
01886 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01887 vinfos[0].jointtype = 1;
01888 vinfos[0].foffset = j0;
01889 vinfos[0].indices[0] = _ij0[0];
01890 vinfos[0].indices[1] = _ij0[1];
01891 vinfos[0].maxsolutions = _nj0;
01892 vinfos[1].jointtype = 1;
01893 vinfos[1].foffset = j1;
01894 vinfos[1].indices[0] = _ij1[0];
01895 vinfos[1].indices[1] = _ij1[1];
01896 vinfos[1].maxsolutions = _nj1;
01897 vinfos[2].jointtype = 1;
01898 vinfos[2].foffset = j2;
01899 vinfos[2].indices[0] = _ij2[0];
01900 vinfos[2].indices[1] = _ij2[1];
01901 vinfos[2].maxsolutions = _nj2;
01902 vinfos[3].jointtype = 1;
01903 vinfos[3].foffset = j3;
01904 vinfos[3].indices[0] = _ij3[0];
01905 vinfos[3].indices[1] = _ij3[1];
01906 vinfos[3].maxsolutions = _nj3;
01907 vinfos[4].jointtype = 1;
01908 vinfos[4].foffset = j5;
01909 vinfos[4].indices[0] = _ij5[0];
01910 vinfos[4].indices[1] = _ij5[1];
01911 vinfos[4].maxsolutions = _nj5;
01912 std::vector<int> vfree(0);
01913 solutions.AddSolution(vinfos,vfree);
01914 }
01915 }
01916 }
01917 
01918 }
01919 
01920 }
01921 
01922 } else
01923 {
01924 {
01925 IkReal j2array[1], cj2array[1], sj2array[1];
01926 bool j2valid[1]={false};
01927 _nj2 = 1;
01928 IkReal x658=((cj0)*(sj1));
01929 IkReal x659=((IkReal(0.281562495931422))*(px));
01930 IkReal x660=((cj1)*(sj0));
01931 IkReal x661=((IkReal(0.281562495931422))*(py));
01932 IkReal x662=((IkReal(1656.24997606719))*(px));
01933 IkReal x663=((IkReal(1656.24997606719))*(py));
01934 IkReal x664=((cj0)*(cj1));
01935 IkReal x665=((IkReal(1749.99997471250))*(px));
01936 IkReal x666=((IkReal(0.297499995701125))*(px));
01937 IkReal x667=((IkReal(1749.99997471250))*(py));
01938 IkReal x668=((IkReal(0.297499995701125))*(py));
01939 IkReal x669=((sj0)*(sj1));
01940 IkReal x670=((IkReal(1656.25000000000))*(pz));
01941 IkReal x671=((IkReal(1750.00000000000))*(cj3)*(pz));
01942 IkReal x672=((IkReal(1750.00000000000))*(pz)*(sj3));
01943 IkReal x673=((sj3)*(x669));
01944 IkReal x674=((cj3)*(x669));
01945 if( IKabs(((gconst5)*(((((x665)*(x673)))+(((IkReal(-1.00000000000000))*(x660)*(x662)))+(((x663)*(x664)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x668)*(x673)))+(((cj3)*(x660)*(x668)))+(((x660)*(x661)))+(((x659)*(x664)))+(((sj1)*(x671)))+(((sj1)*(x670)))+(((IkReal(-1.00000000000000))*(cj3)*(x660)*(x665)))+(((cj3)*(x664)*(x666)))+(((cj3)*(x664)*(x667)))+(((cj1)*(x672)))+(((IkReal(-1.00000000000000))*(sj3)*(x658)*(x667)))+(((IkReal(-1.00000000000000))*(sj3)*(x658)*(x666))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(175.562500000000))+(((sj3)*(x660)*(x668)))+(((IkReal(-1.00000000000000))*(x662)*(x669)))+(((sj3)*(x664)*(x667)))+(((sj3)*(x664)*(x666)))+(((IkReal(-1.00000000000000))*(x665)*(x674)))+(((IkReal(-1.00000000000000))*(sj3)*(x660)*(x665)))+(((IkReal(-1.00000000000000))*(cj1)*(x671)))+(((IkReal(-1.00000000000000))*(cj1)*(x670)))+(((x668)*(x674)))+(((x661)*(x669)))+(((IkReal(185.500000000000))*(cj3)))+(((sj1)*(x672)))+(((x658)*(x663)))+(((x658)*(x659)))+(((cj3)*(x658)*(x667)))+(((cj3)*(x658)*(x666))))))) < IKFAST_ATAN2_MAGTHRESH )
01946     continue;
01947 j2array[0]=IKatan2(((gconst5)*(((((x665)*(x673)))+(((IkReal(-1.00000000000000))*(x660)*(x662)))+(((x663)*(x664)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(x668)*(x673)))+(((cj3)*(x660)*(x668)))+(((x660)*(x661)))+(((x659)*(x664)))+(((sj1)*(x671)))+(((sj1)*(x670)))+(((IkReal(-1.00000000000000))*(cj3)*(x660)*(x665)))+(((cj3)*(x664)*(x666)))+(((cj3)*(x664)*(x667)))+(((cj1)*(x672)))+(((IkReal(-1.00000000000000))*(sj3)*(x658)*(x667)))+(((IkReal(-1.00000000000000))*(sj3)*(x658)*(x666)))))), ((gconst5)*(((IkReal(175.562500000000))+(((sj3)*(x660)*(x668)))+(((IkReal(-1.00000000000000))*(x662)*(x669)))+(((sj3)*(x664)*(x667)))+(((sj3)*(x664)*(x666)))+(((IkReal(-1.00000000000000))*(x665)*(x674)))+(((IkReal(-1.00000000000000))*(sj3)*(x660)*(x665)))+(((IkReal(-1.00000000000000))*(cj1)*(x671)))+(((IkReal(-1.00000000000000))*(cj1)*(x670)))+(((x668)*(x674)))+(((x661)*(x669)))+(((IkReal(185.500000000000))*(cj3)))+(((sj1)*(x672)))+(((x658)*(x663)))+(((x658)*(x659)))+(((cj3)*(x658)*(x667)))+(((cj3)*(x658)*(x666)))))));
01948 sj2array[0]=IKsin(j2array[0]);
01949 cj2array[0]=IKcos(j2array[0]);
01950 if( j2array[0] > IKPI )
01951 {
01952     j2array[0]-=IK2PI;
01953 }
01954 else if( j2array[0] < -IKPI )
01955 {    j2array[0]+=IK2PI;
01956 }
01957 j2valid[0] = true;
01958 for(int ij2 = 0; ij2 < 1; ++ij2)
01959 {
01960 if( !j2valid[ij2] )
01961 {
01962     continue;
01963 }
01964 _ij2[0] = ij2; _ij2[1] = -1;
01965 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
01966 {
01967 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
01968 {
01969     j2valid[iij2]=false; _ij2[1] = iij2; break; 
01970 }
01971 }
01972 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
01973 {
01974 IkReal evalcond[4];
01975 IkReal x675=IKsin(j2);
01976 IkReal x676=IKcos(j2);
01977 IkReal x677=((r00)*(sj0));
01978 IkReal x678=((r01)*(sj0));
01979 IkReal x679=((py)*(sj1));
01980 IkReal x680=((IkReal(0.999999985550000))*(r02));
01981 IkReal x681=((px)*(sj1));
01982 IkReal x682=((IkReal(0.999999985550000))*(sj0));
01983 IkReal x683=((IkReal(0.000169999997543500))*(cj0));
01984 IkReal x684=((IkReal(0.000169999997543500))*(sj0));
01985 IkReal x685=((cj1)*(px));
01986 IkReal x686=((pz)*(sj1));
01987 IkReal x687=((cj0)*(r00));
01988 IkReal x688=((cj1)*(pz));
01989 IkReal x689=((IkReal(1.00000000000000))*(r01));
01990 IkReal x690=((cj1)*(py));
01991 IkReal x691=((IkReal(0.999999985550000))*(cj0));
01992 IkReal x692=((IkReal(0.106000000000000))*(x675));
01993 IkReal x693=((IkReal(0.106000000000000))*(x676));
01994 IkReal x694=((IkReal(0.112000000000000))*(x676));
01995 IkReal x695=((IkReal(0.112000000000000))*(x675));
01996 IkReal x696=((cj3)*(x695));
01997 IkReal x697=((sj3)*(x694));
01998 IkReal x698=((cj3)*(x694));
01999 IkReal x699=((sj3)*(x695));
02000 IkReal x700=((x693)+(x698));
02001 IkReal x701=((x696)+(x697)+(x692));
02002 evalcond[0]=((((x690)*(x691)))+(((x683)*(x685)))+(((x684)*(x690)))+(x686)+(((IkReal(-1.00000000000000))*(x682)*(x685)))+(x701));
02003 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x681)*(x683)))+(((IkReal(-1.00000000000000))*(x679)*(x684)))+(((IkReal(-1.00000000000000))*(x700)))+(((x681)*(x682)))+(x688)+(x699)+(((IkReal(-1.00000000000000))*(x679)*(x691))));
02004 evalcond[2]=((((IkReal(-1.00000000000000))*(cj0)*(x680)*(x681)))+(((IkReal(-1.00000000000000))*(x685)*(x689)))+(((IkReal(0.000169999997543500))*(x677)*(x686)))+(((IkReal(-1.00000000000000))*(r02)*(x681)*(x684)))+(((IkReal(0.999999985550000))*(x686)*(x687)))+(((IkReal(0.999999985550000))*(x678)*(x686)))+(((IkReal(-1.00000000000000))*(sj0)*(x679)*(x680)))+(x701)+(((r00)*(x690)))+(((IkReal(-1.00000000000000))*(r01)*(x683)*(x686)))+(((r02)*(x679)*(x683))));
02005 evalcond[3]=((((IkReal(1.80199997396110e-5))*(x677)))+(((IkReal(0.105999998468300))*(x687)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(x681)*(x689)))+(((IkReal(0.105999998468300))*(x678)))+(((r00)*(x679)))+(((IkReal(-1.00000000000000))*(r02)*(x683)*(x690)))+(((IkReal(-0.000169999997543500))*(x677)*(x688)))+(((IkReal(-0.999999985550000))*(x687)*(x688)))+(((sj0)*(x680)*(x690)))+(((IkReal(-1.00000000000000))*(x699)))+(x700)+(((cj0)*(x680)*(x685)))+(((r01)*(x683)*(x688)))+(((r02)*(x684)*(x685)))+(((IkReal(-0.999999985550000))*(x678)*(x688))));
02006 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02007 {
02008 continue;
02009 }
02010 }
02011 
02012 {
02013 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02014 vinfos[0].jointtype = 1;
02015 vinfos[0].foffset = j0;
02016 vinfos[0].indices[0] = _ij0[0];
02017 vinfos[0].indices[1] = _ij0[1];
02018 vinfos[0].maxsolutions = _nj0;
02019 vinfos[1].jointtype = 1;
02020 vinfos[1].foffset = j1;
02021 vinfos[1].indices[0] = _ij1[0];
02022 vinfos[1].indices[1] = _ij1[1];
02023 vinfos[1].maxsolutions = _nj1;
02024 vinfos[2].jointtype = 1;
02025 vinfos[2].foffset = j2;
02026 vinfos[2].indices[0] = _ij2[0];
02027 vinfos[2].indices[1] = _ij2[1];
02028 vinfos[2].maxsolutions = _nj2;
02029 vinfos[3].jointtype = 1;
02030 vinfos[3].foffset = j3;
02031 vinfos[3].indices[0] = _ij3[0];
02032 vinfos[3].indices[1] = _ij3[1];
02033 vinfos[3].maxsolutions = _nj3;
02034 vinfos[4].jointtype = 1;
02035 vinfos[4].foffset = j5;
02036 vinfos[4].indices[0] = _ij5[0];
02037 vinfos[4].indices[1] = _ij5[1];
02038 vinfos[4].maxsolutions = _nj5;
02039 std::vector<int> vfree(0);
02040 solutions.AddSolution(vinfos,vfree);
02041 }
02042 }
02043 }
02044 
02045 }
02046 
02047 }
02048 
02049 } else
02050 {
02051 if( 1 )
02052 {
02053 continue;
02054 
02055 } else
02056 {
02057 }
02058 }
02059 }
02060 }
02061 
02062 } else
02063 {
02064 {
02065 IkReal j2array[1], cj2array[1], sj2array[1];
02066 bool j2valid[1]={false};
02067 _nj2 = 1;
02068 IkReal x702=((cj0)*(py));
02069 IkReal x703=((r02)*(sj1));
02070 IkReal x704=((px)*(sj0));
02071 IkReal x705=((IkReal(13.9999997977000))*(r00));
02072 IkReal x706=((IkReal(1.69999943143527e-5))*(cj5));
02073 IkReal x707=((cj0)*(cj1));
02074 IkReal x708=((IkReal(0.00237999996560900))*(r01));
02075 IkReal x709=((cj3)*(px));
02076 IkReal x710=((IkReal(13.9999997977000))*(r01));
02077 IkReal x711=((cj1)*(sj0));
02078 IkReal x712=((px)*(sj3));
02079 IkReal x713=((IkReal(0.00237999996560900))*(r00));
02080 IkReal x714=((IkReal(0.0212499928929409))*(cj5));
02081 IkReal x715=((cj3)*(py));
02082 IkReal x716=((sj3)*(x711));
02083 IkReal x717=((IkReal(0.0999999665550159))*(cj1)*(cj5)*(sj3));
02084 IkReal x718=((cj5)*(pz)*(sj1)*(sj3));
02085 IkReal x719=((IkReal(0.0999999665550159))*(cj1)*(cj3)*(cj5));
02086 IkReal x720=((cj3)*(cj5)*(pz)*(sj1));
02087 IkReal x721=((IkReal(124.999958193770))*(cj1)*(cj5)*(sj3));
02088 IkReal x722=((IkReal(124.999958193770))*(cj1)*(cj3)*(cj5));
02089 if( IKabs(((gconst2)*(((((x702)*(x722)))+(((IkReal(-1.00000000000000))*(x706)*(x707)*(x712)))+(((sj3)*(x707)*(x713)))+(((sj3)*(x707)*(x710)))+(((IkReal(-1.00000000000000))*(x702)*(x717)))+(((x711)*(x714)*(x715)))+(((x707)*(x709)*(x714)))+(((IkReal(-1.00000000000000))*(x704)*(x722)))+(((IkReal(14.0000000000000))*(sj3)*(x703)))+(((IkReal(124.999960000019))*(x720)))+(((IkReal(-1.00000000000000))*(x705)*(x716)))+(((IkReal(-0.0999999680000154))*(x718)))+(((x704)*(x717)))+(((IkReal(-1.00000000000000))*(py)*(x706)*(x716)))+(((x708)*(x716))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((x702)*(x721)))+(((x706)*(x711)*(x715)))+(((IkReal(-14.0000000000000))*(cj3)*(x703)))+(((x706)*(x707)*(x709)))+(((IkReal(-0.00225249996745138))*(r00)*(x707)))+(((x702)*(x719)))+(((py)*(x714)*(x716)))+(((IkReal(124.999960000019))*(x718)))+(((IkReal(-1.00000000000000))*(x704)*(x721)))+(((IkReal(13.2499998085375))*(r00)*(x711)))+(((cj3)*(x705)*(x711)))+(((x707)*(x712)*(x714)))+(((IkReal(0.0999999680000154))*(x720)))+(((IkReal(-1.00000000000000))*(cj3)*(x707)*(x710)))+(((IkReal(-1.00000000000000))*(cj3)*(x707)*(x713)))+(((IkReal(-1.00000000000000))*(x704)*(x719)))+(((IkReal(-13.2499998085375))*(r01)*(x707)))+(((IkReal(-13.2500000000000))*(x703)))+(((IkReal(-1.00000000000000))*(cj3)*(x708)*(x711)))+(((IkReal(-0.00225249996745138))*(r01)*(x711))))))) < IKFAST_ATAN2_MAGTHRESH )
02090     continue;
02091 j2array[0]=IKatan2(((gconst2)*(((((x702)*(x722)))+(((IkReal(-1.00000000000000))*(x706)*(x707)*(x712)))+(((sj3)*(x707)*(x713)))+(((sj3)*(x707)*(x710)))+(((IkReal(-1.00000000000000))*(x702)*(x717)))+(((x711)*(x714)*(x715)))+(((x707)*(x709)*(x714)))+(((IkReal(-1.00000000000000))*(x704)*(x722)))+(((IkReal(14.0000000000000))*(sj3)*(x703)))+(((IkReal(124.999960000019))*(x720)))+(((IkReal(-1.00000000000000))*(x705)*(x716)))+(((IkReal(-0.0999999680000154))*(x718)))+(((x704)*(x717)))+(((IkReal(-1.00000000000000))*(py)*(x706)*(x716)))+(((x708)*(x716)))))), ((gconst2)*(((((x702)*(x721)))+(((x706)*(x711)*(x715)))+(((IkReal(-14.0000000000000))*(cj3)*(x703)))+(((x706)*(x707)*(x709)))+(((IkReal(-0.00225249996745138))*(r00)*(x707)))+(((x702)*(x719)))+(((py)*(x714)*(x716)))+(((IkReal(124.999960000019))*(x718)))+(((IkReal(-1.00000000000000))*(x704)*(x721)))+(((IkReal(13.2499998085375))*(r00)*(x711)))+(((cj3)*(x705)*(x711)))+(((x707)*(x712)*(x714)))+(((IkReal(0.0999999680000154))*(x720)))+(((IkReal(-1.00000000000000))*(cj3)*(x707)*(x710)))+(((IkReal(-1.00000000000000))*(cj3)*(x707)*(x713)))+(((IkReal(-1.00000000000000))*(x704)*(x719)))+(((IkReal(-13.2499998085375))*(r01)*(x707)))+(((IkReal(-13.2500000000000))*(x703)))+(((IkReal(-1.00000000000000))*(cj3)*(x708)*(x711)))+(((IkReal(-0.00225249996745138))*(r01)*(x711)))))));
02092 sj2array[0]=IKsin(j2array[0]);
02093 cj2array[0]=IKcos(j2array[0]);
02094 if( j2array[0] > IKPI )
02095 {
02096     j2array[0]-=IK2PI;
02097 }
02098 else if( j2array[0] < -IKPI )
02099 {    j2array[0]+=IK2PI;
02100 }
02101 j2valid[0] = true;
02102 for(int ij2 = 0; ij2 < 1; ++ij2)
02103 {
02104 if( !j2valid[ij2] )
02105 {
02106     continue;
02107 }
02108 _ij2[0] = ij2; _ij2[1] = -1;
02109 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02110 {
02111 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02112 {
02113     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02114 }
02115 }
02116 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02117 {
02118 IkReal evalcond[8];
02119 IkReal x723=IKsin(j2);
02120 IkReal x724=IKcos(j2);
02121 IkReal x725=(py)*(py);
02122 IkReal x726=(pz)*(pz);
02123 IkReal x727=(px)*(px);
02124 IkReal x728=((cj0)*(r00));
02125 IkReal x729=((IkReal(3.60399994792220e-5))*(pz));
02126 IkReal x730=((r01)*(sj0));
02127 IkReal x731=((cj3)*(cj5));
02128 IkReal x732=((sj0)*(sj1));
02129 IkReal x733=((IkReal(0.999999985550000))*(px));
02130 IkReal x734=((IkReal(0.000339999995087000))*(py));
02131 IkReal x735=((pz)*(r02));
02132 IkReal x736=((py)*(sj1));
02133 IkReal x737=((IkReal(0.000169999997543500))*(sj1));
02134 IkReal x738=((IkReal(0.999999680000154))*(cj5));
02135 IkReal x739=((px)*(r00));
02136 IkReal x740=((IkReal(0.000799999744000123))*(cj5));
02137 IkReal x741=((IkReal(0.000169999997543500))*(cj1));
02138 IkReal x742=((cj0)*(sj1));
02139 IkReal x743=((IkReal(1.99999997110000))*(px));
02140 IkReal x744=((IkReal(0.000169999997543500))*(pz));
02141 IkReal x745=((IkReal(0.112000000000000))*(sj5));
02142 IkReal x746=((cj1)*(r02));
02143 IkReal x747=((IkReal(0.106000000000000))*(sj5));
02144 IkReal x748=((IkReal(0.000339999995087000))*(px));
02145 IkReal x749=((IkReal(0.112000000000000))*(cj3));
02146 IkReal x750=((cj1)*(py));
02147 IkReal x751=((py)*(r02));
02148 IkReal x752=((cj0)*(px));
02149 IkReal x753=((px)*(r01));
02150 IkReal x754=((cj0)*(r01));
02151 IkReal x755=((IkReal(0.999999985550000))*(r01));
02152 IkReal x756=((IkReal(0.999999985550000))*(pz));
02153 IkReal x757=((r02)*(sj1));
02154 IkReal x758=((cj1)*(sj0));
02155 IkReal x759=((IkReal(1.99999997110000))*(cj0));
02156 IkReal x760=((IkReal(0.000169999997543500))*(r02));
02157 IkReal x761=((IkReal(1.04639966515216e-6))*(cj5));
02158 IkReal x762=((IkReal(0.999999985550000))*(cj0));
02159 IkReal x763=((IkReal(0.999999985550000))*(cj1));
02160 IkReal x764=((cj1)*(pz));
02161 IkReal x765=((py)*(sj0));
02162 IkReal x766=((r00)*(sj0));
02163 IkReal x767=((IkReal(1.91011997239877e-6))*(cj1));
02164 IkReal x768=((IkReal(1.91011997239877e-6))*(sj1));
02165 IkReal x769=((IkReal(0.00130799958144020))*(cj5));
02166 IkReal x770=((IkReal(0.211999996936600))*(pz));
02167 IkReal x771=((pz)*(sj1));
02168 IkReal x772=((sj3)*(x724));
02169 IkReal x773=((cj1)*(x753));
02170 IkReal x774=((r00)*(x758));
02171 IkReal x775=((IkReal(0.999999985550000))*(x726));
02172 IkReal x776=((IkReal(2.00000000000000))*(pz)*(r01));
02173 IkReal x777=((sj3)*(x723));
02174 IkReal x778=((cj5)*(x724));
02175 IkReal x779=((IkReal(0.999999985550000))*(x725));
02176 IkReal x780=((IkReal(2.00000000000000))*(x726));
02177 IkReal x781=((IkReal(0.999999985550000))*(x727));
02178 IkReal x782=((px)*(r02)*(sj0));
02179 IkReal x783=((cj5)*(x723));
02180 evalcond[0]=((((IkReal(0.112000000000000))*(x772)))+(((IkReal(0.106000000000000))*(x723)))+(((IkReal(-1.00000000000000))*(x733)*(x758)))+(((x741)*(x765)))+(((x723)*(x749)))+(((x741)*(x752)))+(x771)+(((x750)*(x762))));
02181 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(0.112000000000000))*(x777)))+(((IkReal(-1.00000000000000))*(x736)*(x762)))+(((IkReal(-1.00000000000000))*(x737)*(x752)))+(((IkReal(-0.106000000000000))*(x724)))+(x764)+(((IkReal(-0.000169999997543500))*(py)*(x732)))+(((x732)*(x733)))+(((IkReal(-1.00000000000000))*(x724)*(x749))));
02182 evalcond[2]=((((IkReal(-0.999999680000154))*(x724)*(x731)))+(((x738)*(x777)))+(((IkReal(-0.999999985550000))*(x774)))+(((x730)*(x741)))+(((IkReal(0.000799999744000123))*(x723)*(x731)))+(((x740)*(x772)))+(x757)+(((x728)*(x741)))+(((x754)*(x763))));
02183 evalcond[3]=((((IkReal(-0.999999680000154))*(x723)*(x731)))+(((IkReal(-1.00000000000000))*(x742)*(x755)))+(((IkReal(-0.000799999744000123))*(x724)*(x731)))+(((x740)*(x777)))+(((IkReal(-1.00000000000000))*(x738)*(x772)))+(((IkReal(-1.00000000000000))*(x730)*(x737)))+(x746)+(((IkReal(-1.00000000000000))*(x728)*(x737)))+(((IkReal(0.999999985550000))*(r00)*(x732))));
02184 evalcond[4]=((((r00)*(x732)*(x744)))+(((IkReal(-1.00000000000000))*(x745)*(x772)))+(((r00)*(x750)))+(((IkReal(-1.00000000000000))*(px)*(x732)*(x760)))+(((IkReal(-1.00000000000000))*(x773)))+(((IkReal(-1.00000000000000))*(pz)*(x737)*(x754)))+(((IkReal(-1.00000000000000))*(r02)*(x733)*(x742)))+(((cj0)*(x736)*(x760)))+(((sj1)*(x728)*(x756)))+(((IkReal(-1.00000000000000))*(x723)*(x747)))+(((sj1)*(x730)*(x756)))+(((IkReal(-1.00000000000000))*(cj3)*(x723)*(x745)))+(((IkReal(-0.999999985550000))*(x732)*(x751))));
02185 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(x741)*(x751)))+(((IkReal(-1.00000000000000))*(cj3)*(x724)*(x745)))+(((IkReal(-1.00000000000000))*(cj1)*(x730)*(x756)))+(((x745)*(x777)))+(((IkReal(-1.00000000000000))*(cj1)*(x728)*(x756)))+(((IkReal(1.80199997396110e-5))*(x766)))+(((IkReal(-1.00000000000000))*(pz)*(x741)*(x766)))+(((IkReal(-1.00000000000000))*(sj1)*(x753)))+(((x741)*(x782)))+(((r00)*(x736)))+(((IkReal(0.105999998468300))*(x730)))+(((IkReal(0.105999998468300))*(x728)))+(((IkReal(0.999999985550000))*(x746)*(x765)))+(((cj0)*(x733)*(x746)))+(((pz)*(x741)*(x754)))+(((IkReal(-1.80199997396110e-5))*(x754)))+(((IkReal(-1.00000000000000))*(x724)*(x747))));
02186 evalcond[6]=((((IkReal(-1.00000000000000))*(x726)*(x730)*(x737)))+(((IkReal(1.90239939123229e-5))*(x724)*(x731)))+(((r00)*(x732)*(x779)))+(((r00)*(x732)*(x775)))+(((IkReal(-1.00000000000000))*(x725)*(x728)*(x737)))+(((IkReal(-0.0237799923904037))*(x723)*(x731)))+(((x727)*(x728)*(x737)))+(((IkReal(-0.0112359998376398))*(r00)*(x732)))+(((x735)*(x742)*(x748)))+(((IkReal(-1.00000000000000))*(x750)*(x776)))+(((IkReal(-0.0112360000000000))*(x746)))+(((IkReal(-1.00000000000000))*(x746)*(x780)))+(((pp)*(x746)))+(((x728)*(x736)*(x743)))+(((x735)*(x736)*(x759)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((IkReal(-1.00000000000000))*(x727)*(x730)*(x737)))+(((IkReal(-0.0237439924019236))*(x783)))+(((x725)*(x730)*(x737)))+(((IkReal(-1.00000000000000))*(x769)*(x772)))+(((IkReal(-1.00000000000000))*(x730)*(x736)*(x743)))+(((IkReal(-1.00000000000000))*(x726)*(x728)*(x737)))+(((IkReal(-1.00000000000000))*(x732)*(x735)*(x743)))+(((x734)*(x742)*(x753)))+(((IkReal(-1.00000000000000))*(r00)*(x732)*(x781)))+(((IkReal(1.89951939215389e-5))*(x778)))+(((IkReal(0.212000000000000))*(x739)))+(((IkReal(0.212000000000000))*(x735)))+(((x732)*(x734)*(x735)))+(((x732)*(x734)*(x739)))+(((IkReal(-1.00000000000000))*(x726)*(x742)*(x755)))+(((x728)*(x768)))+(((IkReal(-1.00000000000000))*(x761)*(x777)))+(((IkReal(-2.00000000000000))*(x739)*(x764)))+(((x725)*(x742)*(x755)))+(((IkReal(-1.00000000000000))*(x727)*(x742)*(x755)))+(((IkReal(0.0112359998376398))*(r01)*(x742)))+(((x730)*(x768))));
02187 evalcond[7]=((((IkReal(-0.0237439924019236))*(x778)))+(((IkReal(3.60399994792220e-5))*(r02)*(x752)))+(((x725)*(x728)*(x741)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x735)*(x748)))+(((x735)*(x743)*(x758)))+(((x727)*(x730)*(x741)))+(((IkReal(-1.89951939215389e-5))*(x783)))+(((IkReal(-1.00000000000000))*(x754)*(x770)))+(((IkReal(-1.00000000000000))*(x774)*(x775)))+(((IkReal(-1.00000000000000))*(x774)*(x779)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x734)*(x752)))+(((x774)*(x781)))+(((IkReal(-2.00000000000000))*(x739)*(x771)))+(((pp)*(x757)))+(((x730)*(x743)*(x750)))+(((x727)*(x754)*(x763)))+(((IkReal(-1.00000000000000))*(x727)*(x728)*(x741)))+(((IkReal(0.0112359998376398))*(cj1)*(x754)))+(((x769)*(x777)))+(((IkReal(0.0112360000000000))*(x757)))+(((IkReal(-1.00000000000000))*(x735)*(x750)*(x759)))+(((IkReal(-0.211999996936600))*(x782)))+(((IkReal(0.211999996936600))*(cj0)*(x751)))+(((x766)*(x770)))+(((IkReal(-1.00000000000000))*(x728)*(x743)*(x750)))+(((x726)*(x754)*(x763)))+(((x726)*(x728)*(x741)))+(((x726)*(x730)*(x741)))+(((IkReal(-1.00000000000000))*(x757)*(x780)))+(((IkReal(-1.00000000000000))*(x734)*(x739)*(x758)))+(((IkReal(-1.00000000000000))*(x725)*(x730)*(x741)))+(((IkReal(-0.0112359998376398))*(x774)))+(((IkReal(-1.00000000000000))*(x734)*(x735)*(x758)))+(((IkReal(3.60399994792220e-5))*(sj0)*(x751)))+(((IkReal(-1.00000000000000))*(x736)*(x776)))+(((x728)*(x767)))+(((IkReal(-1.00000000000000))*(x761)*(x772)))+(((IkReal(-1.00000000000000))*(x725)*(x754)*(x763)))+(((IkReal(-0.0237799923904037))*(x724)*(x731)))+(((IkReal(-1.00000000000000))*(x729)*(x730)))+(((IkReal(-1.00000000000000))*(x728)*(x729)))+(((IkReal(-1.90239939123229e-5))*(x723)*(x731)))+(((x730)*(x767))));
02188 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  )
02189 {
02190 continue;
02191 }
02192 }
02193 
02194 {
02195 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02196 vinfos[0].jointtype = 1;
02197 vinfos[0].foffset = j0;
02198 vinfos[0].indices[0] = _ij0[0];
02199 vinfos[0].indices[1] = _ij0[1];
02200 vinfos[0].maxsolutions = _nj0;
02201 vinfos[1].jointtype = 1;
02202 vinfos[1].foffset = j1;
02203 vinfos[1].indices[0] = _ij1[0];
02204 vinfos[1].indices[1] = _ij1[1];
02205 vinfos[1].maxsolutions = _nj1;
02206 vinfos[2].jointtype = 1;
02207 vinfos[2].foffset = j2;
02208 vinfos[2].indices[0] = _ij2[0];
02209 vinfos[2].indices[1] = _ij2[1];
02210 vinfos[2].maxsolutions = _nj2;
02211 vinfos[3].jointtype = 1;
02212 vinfos[3].foffset = j3;
02213 vinfos[3].indices[0] = _ij3[0];
02214 vinfos[3].indices[1] = _ij3[1];
02215 vinfos[3].maxsolutions = _nj3;
02216 vinfos[4].jointtype = 1;
02217 vinfos[4].foffset = j5;
02218 vinfos[4].indices[0] = _ij5[0];
02219 vinfos[4].indices[1] = _ij5[1];
02220 vinfos[4].maxsolutions = _nj5;
02221 std::vector<int> vfree(0);
02222 solutions.AddSolution(vinfos,vfree);
02223 }
02224 }
02225 }
02226 
02227 }
02228 
02229 }
02230 
02231 } else
02232 {
02233 {
02234 IkReal j2array[1], cj2array[1], sj2array[1];
02235 bool j2valid[1]={false};
02236 _nj2 = 1;
02237 IkReal x784=((cj0)*(sj1));
02238 IkReal x785=((IkReal(0.281562495931422))*(px));
02239 IkReal x786=((IkReal(1750.00000000000))*(pz));
02240 IkReal x787=((sj1)*(sj3));
02241 IkReal x788=((cj1)*(cj3));
02242 IkReal x789=((IkReal(1656.24997606719))*(cj1));
02243 IkReal x790=((px)*(sj0));
02244 IkReal x791=((cj3)*(sj1));
02245 IkReal x792=((cj0)*(py));
02246 IkReal x793=((cj1)*(sj3));
02247 IkReal x794=((py)*(sj0));
02248 IkReal x795=((IkReal(0.297499995701125))*(px));
02249 IkReal x796=((IkReal(1749.99997471250))*(py));
02250 IkReal x797=((IkReal(1656.25000000000))*(pz));
02251 if( IKabs(((gconst1)*(((((IkReal(1749.99997471250))*(x787)*(x790)))+(((IkReal(-0.297499995701125))*(x787)*(x794)))+(((x786)*(x793)))+(((x786)*(x791)))+(((IkReal(0.281562495931422))*(cj1)*(x794)))+(((sj1)*(x797)))+(((IkReal(-1749.99997471250))*(x788)*(x790)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj0)*(x788)*(x795)))+(((IkReal(-1.00000000000000))*(sj3)*(x784)*(x795)))+(((IkReal(-1.00000000000000))*(sj3)*(x784)*(x796)))+(((cj0)*(cj1)*(x785)))+(((IkReal(-1.00000000000000))*(x789)*(x790)))+(((IkReal(0.297499995701125))*(x788)*(x794)))+(((IkReal(1749.99997471250))*(x788)*(x792)))+(((x789)*(x792))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((IkReal(175.562500000000))+(((x786)*(x787)))+(((IkReal(0.297499995701125))*(x793)*(x794)))+(((cj0)*(x793)*(x795)))+(((IkReal(1749.99997471250))*(x792)*(x793)))+(((x784)*(x785)))+(((IkReal(-1.00000000000000))*(cj1)*(x797)))+(((IkReal(1656.24997606719))*(py)*(x784)))+(((IkReal(-1.00000000000000))*(x786)*(x788)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1656.24997606719))*(sj1)*(x790)))+(((IkReal(-1749.99997471250))*(x790)*(x791)))+(((IkReal(-1749.99997471250))*(x790)*(x793)))+(((IkReal(0.297499995701125))*(x791)*(x794)))+(((cj3)*(x784)*(x796)))+(((cj3)*(x784)*(x795)))+(((IkReal(0.281562495931422))*(sj1)*(x794))))))) < IKFAST_ATAN2_MAGTHRESH )
02252     continue;
02253 j2array[0]=IKatan2(((gconst1)*(((((IkReal(1749.99997471250))*(x787)*(x790)))+(((IkReal(-0.297499995701125))*(x787)*(x794)))+(((x786)*(x793)))+(((x786)*(x791)))+(((IkReal(0.281562495931422))*(cj1)*(x794)))+(((sj1)*(x797)))+(((IkReal(-1749.99997471250))*(x788)*(x790)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj0)*(x788)*(x795)))+(((IkReal(-1.00000000000000))*(sj3)*(x784)*(x795)))+(((IkReal(-1.00000000000000))*(sj3)*(x784)*(x796)))+(((cj0)*(cj1)*(x785)))+(((IkReal(-1.00000000000000))*(x789)*(x790)))+(((IkReal(0.297499995701125))*(x788)*(x794)))+(((IkReal(1749.99997471250))*(x788)*(x792)))+(((x789)*(x792)))))), ((gconst1)*(((IkReal(175.562500000000))+(((x786)*(x787)))+(((IkReal(0.297499995701125))*(x793)*(x794)))+(((cj0)*(x793)*(x795)))+(((IkReal(1749.99997471250))*(x792)*(x793)))+(((x784)*(x785)))+(((IkReal(-1.00000000000000))*(cj1)*(x797)))+(((IkReal(1656.24997606719))*(py)*(x784)))+(((IkReal(-1.00000000000000))*(x786)*(x788)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1656.24997606719))*(sj1)*(x790)))+(((IkReal(-1749.99997471250))*(x790)*(x791)))+(((IkReal(-1749.99997471250))*(x790)*(x793)))+(((IkReal(0.297499995701125))*(x791)*(x794)))+(((cj3)*(x784)*(x796)))+(((cj3)*(x784)*(x795)))+(((IkReal(0.281562495931422))*(sj1)*(x794)))))));
02254 sj2array[0]=IKsin(j2array[0]);
02255 cj2array[0]=IKcos(j2array[0]);
02256 if( j2array[0] > IKPI )
02257 {
02258     j2array[0]-=IK2PI;
02259 }
02260 else if( j2array[0] < -IKPI )
02261 {    j2array[0]+=IK2PI;
02262 }
02263 j2valid[0] = true;
02264 for(int ij2 = 0; ij2 < 1; ++ij2)
02265 {
02266 if( !j2valid[ij2] )
02267 {
02268     continue;
02269 }
02270 _ij2[0] = ij2; _ij2[1] = -1;
02271 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02272 {
02273 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02274 {
02275     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02276 }
02277 }
02278 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02279 {
02280 IkReal evalcond[8];
02281 IkReal x798=IKsin(j2);
02282 IkReal x799=IKcos(j2);
02283 IkReal x800=(py)*(py);
02284 IkReal x801=(pz)*(pz);
02285 IkReal x802=(px)*(px);
02286 IkReal x803=((cj0)*(r00));
02287 IkReal x804=((IkReal(3.60399994792220e-5))*(pz));
02288 IkReal x805=((r01)*(sj0));
02289 IkReal x806=((cj3)*(cj5));
02290 IkReal x807=((sj0)*(sj1));
02291 IkReal x808=((IkReal(0.999999985550000))*(px));
02292 IkReal x809=((IkReal(0.000339999995087000))*(py));
02293 IkReal x810=((pz)*(r02));
02294 IkReal x811=((py)*(sj1));
02295 IkReal x812=((IkReal(0.000169999997543500))*(sj1));
02296 IkReal x813=((IkReal(0.999999680000154))*(cj5));
02297 IkReal x814=((px)*(r00));
02298 IkReal x815=((IkReal(0.000799999744000123))*(cj5));
02299 IkReal x816=((IkReal(0.000169999997543500))*(cj1));
02300 IkReal x817=((cj0)*(sj1));
02301 IkReal x818=((IkReal(1.99999997110000))*(px));
02302 IkReal x819=((IkReal(0.000169999997543500))*(pz));
02303 IkReal x820=((IkReal(0.112000000000000))*(sj5));
02304 IkReal x821=((cj1)*(r02));
02305 IkReal x822=((IkReal(0.106000000000000))*(sj5));
02306 IkReal x823=((IkReal(0.000339999995087000))*(px));
02307 IkReal x824=((IkReal(0.112000000000000))*(cj3));
02308 IkReal x825=((cj1)*(py));
02309 IkReal x826=((py)*(r02));
02310 IkReal x827=((cj0)*(px));
02311 IkReal x828=((px)*(r01));
02312 IkReal x829=((cj0)*(r01));
02313 IkReal x830=((IkReal(0.999999985550000))*(r01));
02314 IkReal x831=((IkReal(0.999999985550000))*(pz));
02315 IkReal x832=((r02)*(sj1));
02316 IkReal x833=((cj1)*(sj0));
02317 IkReal x834=((IkReal(1.99999997110000))*(cj0));
02318 IkReal x835=((IkReal(0.000169999997543500))*(r02));
02319 IkReal x836=((IkReal(1.04639966515216e-6))*(cj5));
02320 IkReal x837=((IkReal(0.999999985550000))*(cj0));
02321 IkReal x838=((IkReal(0.999999985550000))*(cj1));
02322 IkReal x839=((cj1)*(pz));
02323 IkReal x840=((py)*(sj0));
02324 IkReal x841=((r00)*(sj0));
02325 IkReal x842=((IkReal(1.91011997239877e-6))*(cj1));
02326 IkReal x843=((IkReal(1.91011997239877e-6))*(sj1));
02327 IkReal x844=((IkReal(0.00130799958144020))*(cj5));
02328 IkReal x845=((IkReal(0.211999996936600))*(pz));
02329 IkReal x846=((pz)*(sj1));
02330 IkReal x847=((sj3)*(x799));
02331 IkReal x848=((cj1)*(x828));
02332 IkReal x849=((r00)*(x833));
02333 IkReal x850=((IkReal(0.999999985550000))*(x801));
02334 IkReal x851=((IkReal(2.00000000000000))*(pz)*(r01));
02335 IkReal x852=((sj3)*(x798));
02336 IkReal x853=((cj5)*(x799));
02337 IkReal x854=((IkReal(0.999999985550000))*(x800));
02338 IkReal x855=((IkReal(2.00000000000000))*(x801));
02339 IkReal x856=((IkReal(0.999999985550000))*(x802));
02340 IkReal x857=((px)*(r02)*(sj0));
02341 IkReal x858=((cj5)*(x798));
02342 evalcond[0]=((((x798)*(x824)))+(((x816)*(x840)))+(((IkReal(-1.00000000000000))*(x808)*(x833)))+(((x816)*(x827)))+(((IkReal(0.106000000000000))*(x798)))+(x846)+(((IkReal(0.112000000000000))*(x847)))+(((x825)*(x837))));
02343 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x812)*(x827)))+(((IkReal(0.112000000000000))*(x852)))+(((IkReal(-1.00000000000000))*(x799)*(x824)))+(((IkReal(-1.00000000000000))*(x811)*(x837)))+(((IkReal(-0.000169999997543500))*(py)*(x807)))+(((IkReal(-0.106000000000000))*(x799)))+(x839)+(((x807)*(x808))));
02344 evalcond[2]=((((x813)*(x852)))+(((x829)*(x838)))+(((IkReal(-0.999999985550000))*(x849)))+(x832)+(((x805)*(x816)))+(((x815)*(x847)))+(((IkReal(-0.999999680000154))*(x799)*(x806)))+(((x803)*(x816)))+(((IkReal(0.000799999744000123))*(x798)*(x806))));
02345 evalcond[3]=((((IkReal(-1.00000000000000))*(x803)*(x812)))+(((IkReal(-0.999999680000154))*(x798)*(x806)))+(((IkReal(-1.00000000000000))*(x813)*(x847)))+(((IkReal(-0.000799999744000123))*(x799)*(x806)))+(((x815)*(x852)))+(((IkReal(-1.00000000000000))*(x817)*(x830)))+(x821)+(((IkReal(-1.00000000000000))*(x805)*(x812)))+(((IkReal(0.999999985550000))*(r00)*(x807))));
02346 evalcond[4]=((((IkReal(-1.00000000000000))*(px)*(x807)*(x835)))+(((IkReal(-1.00000000000000))*(r02)*(x808)*(x817)))+(((IkReal(-0.999999985550000))*(x807)*(x826)))+(((cj0)*(x811)*(x835)))+(((sj1)*(x805)*(x831)))+(((r00)*(x825)))+(((IkReal(-1.00000000000000))*(pz)*(x812)*(x829)))+(((IkReal(-1.00000000000000))*(x798)*(x822)))+(((IkReal(-1.00000000000000))*(x848)))+(((r00)*(x807)*(x819)))+(((sj1)*(x803)*(x831)))+(((IkReal(-1.00000000000000))*(cj3)*(x798)*(x820)))+(((IkReal(-1.00000000000000))*(x820)*(x847))));
02347 evalcond[5]=((((IkReal(0.105999998468300))*(x803)))+(((IkReal(0.105999998468300))*(x805)))+(((IkReal(-1.80199997396110e-5))*(x829)))+(((IkReal(-1.00000000000000))*(pz)*(x816)*(x841)))+(((IkReal(-1.00000000000000))*(cj0)*(x816)*(x826)))+(((IkReal(-1.00000000000000))*(sj1)*(x828)))+(((IkReal(1.80199997396110e-5))*(x841)))+(((r00)*(x811)))+(((IkReal(-1.00000000000000))*(cj1)*(x803)*(x831)))+(((IkReal(-1.00000000000000))*(cj1)*(x805)*(x831)))+(((IkReal(-1.00000000000000))*(x799)*(x822)))+(((x816)*(x857)))+(((x820)*(x852)))+(((IkReal(0.999999985550000))*(x821)*(x840)))+(((cj0)*(x808)*(x821)))+(((IkReal(-1.00000000000000))*(cj3)*(x799)*(x820)))+(((pz)*(x816)*(x829))));
02348 evalcond[6]=((((r00)*(x807)*(x854)))+(((r00)*(x807)*(x850)))+(((IkReal(-0.0237799923904037))*(x798)*(x806)))+(((x807)*(x809)*(x810)))+(((x807)*(x809)*(x814)))+(((IkReal(-1.00000000000000))*(x802)*(x817)*(x830)))+(((IkReal(-1.00000000000000))*(r00)*(x807)*(x856)))+(((IkReal(-1.00000000000000))*(x825)*(x851)))+(((IkReal(0.212000000000000))*(x814)))+(((IkReal(0.212000000000000))*(x810)))+(((IkReal(-0.0112360000000000))*(x821)))+(((IkReal(-1.00000000000000))*(x821)*(x855)))+(((x810)*(x811)*(x834)))+(((x800)*(x805)*(x812)))+(((x803)*(x811)*(x818)))+(((IkReal(-0.0112359998376398))*(r00)*(x807)))+(((IkReal(1.89951939215389e-5))*(x853)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((x800)*(x817)*(x830)))+(((IkReal(-1.00000000000000))*(x801)*(x805)*(x812)))+(((IkReal(-1.00000000000000))*(x801)*(x817)*(x830)))+(((x810)*(x817)*(x823)))+(((IkReal(-1.00000000000000))*(x802)*(x805)*(x812)))+(((IkReal(-1.00000000000000))*(x844)*(x847)))+(((x809)*(x817)*(x828)))+(((IkReal(-1.00000000000000))*(x836)*(x852)))+(((IkReal(-1.00000000000000))*(x807)*(x810)*(x818)))+(((x805)*(x843)))+(((x803)*(x843)))+(((pp)*(x821)))+(((IkReal(-2.00000000000000))*(x814)*(x839)))+(((IkReal(0.0112359998376398))*(r01)*(x817)))+(((x802)*(x803)*(x812)))+(((IkReal(-1.00000000000000))*(x800)*(x803)*(x812)))+(((IkReal(1.90239939123229e-5))*(x799)*(x806)))+(((IkReal(-0.0237439924019236))*(x858)))+(((IkReal(-1.00000000000000))*(x805)*(x811)*(x818)))+(((IkReal(-1.00000000000000))*(x801)*(x803)*(x812))));
02349 evalcond[7]=((((IkReal(-1.00000000000000))*(x811)*(x851)))+(((IkReal(-1.00000000000000))*(x809)*(x814)*(x833)))+(((IkReal(-1.00000000000000))*(x800)*(x805)*(x816)))+(((IkReal(-1.00000000000000))*(x804)*(x805)))+(((x801)*(x805)*(x816)))+(((x802)*(x829)*(x838)))+(((IkReal(0.211999996936600))*(cj0)*(x826)))+(((x802)*(x805)*(x816)))+(((IkReal(-1.00000000000000))*(x836)*(x847)))+(((IkReal(3.60399994792220e-5))*(sj0)*(x826)))+(((IkReal(-1.00000000000000))*(x810)*(x825)*(x834)))+(((IkReal(-1.00000000000000))*(x802)*(x803)*(x816)))+(((IkReal(-1.00000000000000))*(x849)*(x854)))+(((IkReal(-1.00000000000000))*(x849)*(x850)))+(((IkReal(-1.00000000000000))*(x803)*(x818)*(x825)))+(((IkReal(0.0112359998376398))*(cj1)*(x829)))+(((x844)*(x852)))+(((IkReal(3.60399994792220e-5))*(r02)*(x827)))+(((pp)*(x832)))+(((IkReal(-1.90239939123229e-5))*(x798)*(x806)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x809)*(x827)))+(((IkReal(-1.00000000000000))*(x832)*(x855)))+(((x800)*(x803)*(x816)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x810)*(x823)))+(((IkReal(-0.0237799923904037))*(x799)*(x806)))+(((IkReal(0.0112360000000000))*(x832)))+(((IkReal(-2.00000000000000))*(x814)*(x846)))+(((IkReal(-1.00000000000000))*(x803)*(x804)))+(((x805)*(x842)))+(((x803)*(x842)))+(((x801)*(x829)*(x838)))+(((IkReal(-0.211999996936600))*(x857)))+(((x801)*(x803)*(x816)))+(((x810)*(x818)*(x833)))+(((x805)*(x818)*(x825)))+(((IkReal(-1.00000000000000))*(x829)*(x845)))+(((x849)*(x856)))+(((IkReal(-1.00000000000000))*(x809)*(x810)*(x833)))+(((IkReal(-1.00000000000000))*(x800)*(x829)*(x838)))+(((IkReal(-0.0112359998376398))*(x849)))+(((x841)*(x845)))+(((IkReal(-1.89951939215389e-5))*(x858)))+(((IkReal(-0.0237439924019236))*(x853))));
02350 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  )
02351 {
02352 continue;
02353 }
02354 }
02355 
02356 {
02357 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02358 vinfos[0].jointtype = 1;
02359 vinfos[0].foffset = j0;
02360 vinfos[0].indices[0] = _ij0[0];
02361 vinfos[0].indices[1] = _ij0[1];
02362 vinfos[0].maxsolutions = _nj0;
02363 vinfos[1].jointtype = 1;
02364 vinfos[1].foffset = j1;
02365 vinfos[1].indices[0] = _ij1[0];
02366 vinfos[1].indices[1] = _ij1[1];
02367 vinfos[1].maxsolutions = _nj1;
02368 vinfos[2].jointtype = 1;
02369 vinfos[2].foffset = j2;
02370 vinfos[2].indices[0] = _ij2[0];
02371 vinfos[2].indices[1] = _ij2[1];
02372 vinfos[2].maxsolutions = _nj2;
02373 vinfos[3].jointtype = 1;
02374 vinfos[3].foffset = j3;
02375 vinfos[3].indices[0] = _ij3[0];
02376 vinfos[3].indices[1] = _ij3[1];
02377 vinfos[3].maxsolutions = _nj3;
02378 vinfos[4].jointtype = 1;
02379 vinfos[4].foffset = j5;
02380 vinfos[4].indices[0] = _ij5[0];
02381 vinfos[4].indices[1] = _ij5[1];
02382 vinfos[4].maxsolutions = _nj5;
02383 std::vector<int> vfree(0);
02384 solutions.AddSolution(vinfos,vfree);
02385 }
02386 }
02387 }
02388 
02389 }
02390 
02391 }
02392 }
02393 }
02394 
02395 }
02396 
02397 }
02398 
02399 } else
02400 {
02401 {
02402 IkReal j3array[1], cj3array[1], sj3array[1];
02403 bool j3valid[1]={false};
02404 _nj3 = 1;
02405 IkReal x859=((IkReal(26.4999996170750))*(cj5));
02406 IkReal x860=((sj0)*(sj1));
02407 IkReal x861=((cj0)*(sj1));
02408 IkReal x862=((IkReal(0.00450499993490275))*(cj5));
02409 IkReal x863=((cj1)*(pz));
02410 IkReal x864=((px)*(x860));
02411 if( IKabs(((IkReal(0.000269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((IkReal(3710.00113359029))*(r01)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x859)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x860)*(x862)))+(((IkReal(26.5000000000000))*(cj5)*(x863)))+(((IkReal(-1.56800000000000))*(cj5)))+(((IkReal(-125.000000000000))*(cj5)*(pp)))+(((IkReal(35000.0111999982))*(px)*(r00)))+(((x859)*(x864)))+(((IkReal(-1.00000000000000))*(px)*(x861)*(x862)))+(((IkReal(0.630700192710350))*(r01)*(x860)))+(((IkReal(-3710.00118719981))*(cj1)*(r02)))+(((IkReal(0.630700192710350))*(r00)*(x861)))+(((IkReal(-3710.00113359029))*(r00)*(x860)))+(((IkReal(35000.0111999982))*(pz)*(r02)))+(((IkReal(35000.0111999982))*(py)*(r01))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x860)))+(((IkReal(8.92857129955357))*(py)*(x861)))+(((IkReal(-8.92857129955357))*(x864)))+(((IkReal(0.00151785712092411))*(px)*(x861)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857142857143))*(x863))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((IkReal(0.000269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((IkReal(3710.00113359029))*(r01)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x859)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x860)*(x862)))+(((IkReal(26.5000000000000))*(cj5)*(x863)))+(((IkReal(-1.56800000000000))*(cj5)))+(((IkReal(-125.000000000000))*(cj5)*(pp)))+(((IkReal(35000.0111999982))*(px)*(r00)))+(((x859)*(x864)))+(((IkReal(-1.00000000000000))*(px)*(x861)*(x862)))+(((IkReal(0.630700192710350))*(r01)*(x860)))+(((IkReal(-3710.00118719981))*(cj1)*(r02)))+(((IkReal(0.630700192710350))*(r00)*(x861)))+(((IkReal(-3710.00113359029))*(r00)*(x860)))+(((IkReal(35000.0111999982))*(pz)*(r02)))+(((IkReal(35000.0111999982))*(py)*(r01)))))))+IKsqr(((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x860)))+(((IkReal(8.92857129955357))*(py)*(x861)))+(((IkReal(-8.92857129955357))*(x864)))+(((IkReal(0.00151785712092411))*(px)*(x861)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857142857143))*(x863)))))-1) <= IKFAST_SINCOS_THRESH )
02412     continue;
02413 j3array[0]=IKatan2(((IkReal(0.000269541778975741))*(((IKabs(cj5) != 0)?((IkReal)1/(cj5)):(IkReal)1.0e30))*(((((IkReal(3710.00113359029))*(r01)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x859)*(x861)))+(((IkReal(-1.00000000000000))*(py)*(x860)*(x862)))+(((IkReal(26.5000000000000))*(cj5)*(x863)))+(((IkReal(-1.56800000000000))*(cj5)))+(((IkReal(-125.000000000000))*(cj5)*(pp)))+(((IkReal(35000.0111999982))*(px)*(r00)))+(((x859)*(x864)))+(((IkReal(-1.00000000000000))*(px)*(x861)*(x862)))+(((IkReal(0.630700192710350))*(r01)*(x860)))+(((IkReal(-3710.00118719981))*(cj1)*(r02)))+(((IkReal(0.630700192710350))*(r00)*(x861)))+(((IkReal(-3710.00113359029))*(r00)*(x860)))+(((IkReal(35000.0111999982))*(pz)*(r02)))+(((IkReal(35000.0111999982))*(py)*(r01)))))), ((IkReal(-0.528301886792453))+(((IkReal(0.00151785712092411))*(py)*(x860)))+(((IkReal(8.92857129955357))*(py)*(x861)))+(((IkReal(-8.92857129955357))*(x864)))+(((IkReal(0.00151785712092411))*(px)*(x861)))+(((IkReal(42.1159029649596))*(pp)))+(((IkReal(-8.92857142857143))*(x863)))));
02414 sj3array[0]=IKsin(j3array[0]);
02415 cj3array[0]=IKcos(j3array[0]);
02416 if( j3array[0] > IKPI )
02417 {
02418     j3array[0]-=IK2PI;
02419 }
02420 else if( j3array[0] < -IKPI )
02421 {    j3array[0]+=IK2PI;
02422 }
02423 j3valid[0] = true;
02424 for(int ij3 = 0; ij3 < 1; ++ij3)
02425 {
02426 if( !j3valid[ij3] )
02427 {
02428     continue;
02429 }
02430 _ij3[0] = ij3; _ij3[1] = -1;
02431 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
02432 {
02433 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
02434 {
02435     j3valid[iij3]=false; _ij3[1] = iij3; break; 
02436 }
02437 }
02438 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
02439 {
02440 IkReal evalcond[4];
02441 IkReal x865=IKcos(j3);
02442 IkReal x866=IKsin(j3);
02443 IkReal x867=(px)*(px);
02444 IkReal x868=(py)*(py);
02445 IkReal x869=(pz)*(pz);
02446 IkReal x870=((r00)*(sj0));
02447 IkReal x871=((cj0)*(r00));
02448 IkReal x872=((py)*(sj1));
02449 IkReal x873=((cj1)*(pz));
02450 IkReal x874=((cj0)*(r01));
02451 IkReal x875=((px)*(py));
02452 IkReal x876=((r01)*(sj0));
02453 IkReal x877=((IkReal(1.80199997396110e-5))*(sj1));
02454 IkReal x878=((cj0)*(r02));
02455 IkReal x879=((IkReal(3.60399994792220e-5))*(cj1));
02456 IkReal x880=((IkReal(0.105999966080016))*(cj5));
02457 IkReal x881=((IkReal(0.999999985550000))*(pz));
02458 IkReal x882=((px)*(sj1));
02459 IkReal x883=((IkReal(0.106000000000000))*(r02));
02460 IkReal x884=((IkReal(8.47999728640130e-5))*(cj5));
02461 IkReal x885=((IkReal(0.000169999997543500))*(pz));
02462 IkReal x886=((IkReal(0.211999996936600))*(cj1));
02463 IkReal x887=((IkReal(0.000339999995087000))*(pz));
02464 IkReal x888=((IkReal(0.105999998468300))*(cj1));
02465 IkReal x889=((IkReal(1.80199997396110e-5))*(cj1));
02466 IkReal x890=((IkReal(1.99999997110000))*(pz));
02467 IkReal x891=((IkReal(0.105999998468300))*(sj1));
02468 IkReal x892=((IkReal(0.999999985550000))*(x868));
02469 IkReal x893=((IkReal(0.999999985550000))*(x869));
02470 IkReal x894=((IkReal(0.000169999997543500))*(x867));
02471 IkReal x895=((IkReal(0.000169999997543500))*(x868));
02472 IkReal x896=((IkReal(0.000169999997543500))*(x869));
02473 IkReal x897=((px)*(r02)*(sj0));
02474 IkReal x898=((IkReal(0.999999985550000))*(x867));
02475 IkReal x899=((py)*(r02)*(sj0));
02476 IkReal x900=((IkReal(0.0237440000000000))*(x865));
02477 evalcond[0]=((IkReal(0.0125440000000000))+(((IkReal(-3.60399994792220e-5))*(cj0)*(x882)))+(((IkReal(-3.60399994792220e-5))*(sj0)*(x872)))+(((IkReal(0.211999996936600))*(sj0)*(x882)))+(((IkReal(0.212000000000000))*(x873)))+(((IkReal(-1.00000000000000))*(pp)))+(x900)+(((IkReal(-0.211999996936600))*(cj0)*(x872))));
02478 evalcond[1]=((((IkReal(-1.00000000000000))*(x876)*(x877)))+(((IkReal(-1.00000000000000))*(x871)*(x877)))+(((IkReal(-1.00000000000000))*(px)*(r00)))+(((x865)*(x884)))+(((IkReal(8.95999713280138e-5))*(cj5)))+(((IkReal(-1.00000000000000))*(pz)*(r02)))+(((cj1)*(x883)))+(((x870)*(x891)))+(((IkReal(-1.00000000000000))*(py)*(r01)))+(((x866)*(x880)))+(((IkReal(-1.00000000000000))*(x874)*(x891))));
02479 evalcond[2]=((((sj1)*(x883)))+(((x874)*(x888)))+(((IkReal(-1.00000000000000))*(x870)*(x888)))+(((x876)*(x889)))+(((x865)*(x880)))+(((IkReal(-1.00000000000000))*(x876)*(x885)))+(((IkReal(0.000169999997543500))*(x899)))+(((IkReal(-0.999999985550000))*(x897)))+(((x870)*(x881)))+(((IkReal(0.999999985550000))*(py)*(x878)))+(((IkReal(-1.00000000000000))*(x871)*(x885)))+(((x871)*(x889)))+(((IkReal(0.000169999997543500))*(px)*(x878)))+(((IkReal(-1.00000000000000))*(x866)*(x884)))+(((IkReal(0.111999964160017))*(cj5)))+(((IkReal(-1.00000000000000))*(x874)*(x881))));
02480 evalcond[3]=((((x874)*(x894)))+(((x874)*(x896)))+(((IkReal(-0.212000000000000))*(r00)*(x872)))+(((IkReal(-1.00000000000000))*(py)*(x878)*(x887)))+(((IkReal(0.211999996936600))*(x871)*(x873)))+(((IkReal(-1.00000000000000))*(x870)*(x896)))+(((IkReal(-1.00000000000000))*(x870)*(x895)))+(((IkReal(-1.00000000000000))*(x879)*(x897)))+(((x876)*(x892)))+(((IkReal(3.60399994792220e-5))*(x870)*(x873)))+(((py)*(x878)*(x879)))+(((IkReal(1.99999997110000))*(x870)*(x875)))+(((IkReal(-0.0112359998376398))*(x876)))+(((IkReal(-0.0112359998376398))*(x871)))+(((IkReal(-1.00000000000000))*(px)*(x878)*(x886)))+(((IkReal(-1.00000000000000))*(x876)*(x893)))+(((IkReal(-1.00000000000000))*(x876)*(x898)))+(((IkReal(-0.0237800000000000))*(sj5)))+(((IkReal(-1.00000000000000))*(sj5)*(x900)))+(((IkReal(-3.60399994792220e-5))*(x873)*(x874)))+(((IkReal(0.211999996936600))*(x873)*(x876)))+(((px)*(x878)*(x890)))+(((IkReal(0.000339999995087000))*(x875)*(x876)))+(((x871)*(x898)))+(((IkReal(1.91011997239877e-6))*(x874)))+(((x870)*(x894)))+(((IkReal(-0.000339999995087000))*(x871)*(x875)))+(((IkReal(-1.91011997239877e-6))*(x870)))+(((IkReal(0.212000000000000))*(r01)*(x882)))+(((x890)*(x899)))+(((IkReal(-1.00000000000000))*(x871)*(x892)))+(((IkReal(-1.00000000000000))*(x871)*(x893)))+(((IkReal(1.99999997110000))*(x874)*(x875)))+(((IkReal(-1.00000000000000))*(x874)*(x895)))+(((x887)*(x897)))+(((IkReal(-1.00000000000000))*(x886)*(x899))));
02481 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02482 {
02483 continue;
02484 }
02485 }
02486 
02487 {
02488 IkReal dummyeval[1];
02489 IkReal gconst1;
02490 gconst1=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
02491 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
02492 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02493 {
02494 {
02495 IkReal dummyeval[1];
02496 IkReal gconst2;
02497 IkReal x901=((IkReal(13.9999955200021))*(cj5));
02498 gconst2=IKsign(((((IkReal(-1.00000000000000))*(x901)*((cj3)*(cj3))))+(((IkReal(-1.00000000000000))*(x901)*((sj3)*(sj3))))+(((IkReal(0.0105999966080016))*(cj5)*(sj3)))+(((IkReal(-13.2499957600020))*(cj3)*(cj5)))));
02499 IkReal x902=((IkReal(1320.75471698113))*(cj5));
02500 dummyeval[0]=((((cj5)*(sj3)))+(((IkReal(-1.00000000000000))*(x902)*((sj3)*(sj3))))+(((IkReal(-1.00000000000000))*(x902)*((cj3)*(cj3))))+(((IkReal(-1250.00000000000))*(cj3)*(cj5))));
02501 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02502 {
02503 {
02504 IkReal evalcond[11];
02505 IkReal x903=(px)*(px);
02506 IkReal x904=(py)*(py);
02507 IkReal x905=(pz)*(pz);
02508 IkReal x906=((IkReal(0.0237440000000000))*(cj3));
02509 IkReal x907=((IkReal(3.60399994792220e-5))*(pz));
02510 IkReal x908=((cj0)*(r00));
02511 IkReal x909=((r01)*(sj0));
02512 IkReal x910=((IkReal(0.000169999997543500))*(sj1));
02513 IkReal x911=((IkReal(0.000339999995087000))*(py));
02514 IkReal x912=((pz)*(sj1));
02515 IkReal x913=((r02)*(sj0));
02516 IkReal x914=((cj0)*(px));
02517 IkReal x915=((cj1)*(r01));
02518 IkReal x916=((IkReal(0.000169999997543500))*(cj0));
02519 IkReal x917=((IkReal(3.60399994792220e-5))*(sj1));
02520 IkReal x918=((py)*(r01));
02521 IkReal x919=((r00)*(sj0));
02522 IkReal x920=((IkReal(0.000169999997543500))*(pz));
02523 IkReal x921=((IkReal(0.105999998468300))*(cj0));
02524 IkReal x922=((px)*(r00));
02525 IkReal x923=((IkReal(1.99999997110000))*(pz));
02526 IkReal x924=((IkReal(1.91011997239877e-6))*(cj1));
02527 IkReal x925=((r01)*(sj1));
02528 IkReal x926=((cj1)*(r02));
02529 IkReal x927=((r02)*(sj1));
02530 IkReal x928=((IkReal(0.999999985550000))*(py));
02531 IkReal x929=((IkReal(0.999999985550000))*(cj0));
02532 IkReal x930=((IkReal(0.211999996936600))*(px));
02533 IkReal x931=((IkReal(0.0112359998376398))*(cj0));
02534 IkReal x932=((cj0)*(r02));
02535 IkReal x933=((IkReal(1.80199997396110e-5))*(sj1));
02536 IkReal x934=((IkReal(0.211999996936600))*(py));
02537 IkReal x935=((cj1)*(px));
02538 IkReal x936=((IkReal(0.000339999995087000))*(pz));
02539 IkReal x937=((IkReal(0.999999985550000))*(cj1));
02540 IkReal x938=((IkReal(0.000169999997543500))*(cj1));
02541 IkReal x939=((cj0)*(py));
02542 IkReal x940=((pz)*(r02));
02543 IkReal x941=((IkReal(0.211999996936600))*(pz));
02544 IkReal x942=((cj1)*(pz));
02545 IkReal x943=((IkReal(0.999999985550000))*(sj1));
02546 IkReal x944=((IkReal(1.80199997396110e-5))*(cj1));
02547 IkReal x945=((cj0)*(r01));
02548 IkReal x946=((IkReal(1.91011997239877e-6))*(sj1));
02549 IkReal x947=((IkReal(0.999999985550000))*(x905));
02550 IkReal x948=((IkReal(0.000169999997543500))*(x904));
02551 IkReal x949=((IkReal(0.999999985550000))*(x903));
02552 IkReal x950=((IkReal(0.000169999997543500))*(x905));
02553 IkReal x951=((IkReal(1.99999997110000))*(px)*(py));
02554 IkReal x952=((IkReal(0.000169999997543500))*(x903));
02555 IkReal x953=((IkReal(2.00000000000000))*(x905));
02556 IkReal x954=((IkReal(0.999999985550000))*(x904));
02557 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j5)), IkReal(6.28318530717959))));
02558 evalcond[1]=((((IkReal(-0.999999985550000))*(x914)))+(((IkReal(-1.00000000000000))*(sj0)*(x928)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((py)*(x916))));
02559 evalcond[2]=((IkReal(-1.00000000000000))+(((IkReal(-0.999999985550000))*(x909)))+(((IkReal(-0.999999985550000))*(x908)))+(((IkReal(-0.000169999997543500))*(x919)))+(((r01)*(x916))));
02560 evalcond[3]=((IkReal(0.0125440000000000))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x917)))+(((IkReal(-1.00000000000000))*(pp)))+(((sj0)*(sj1)*(x930)))+(((IkReal(-1.00000000000000))*(x914)*(x917)))+(((IkReal(0.212000000000000))*(x942)))+(x906)+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x934))));
02561 evalcond[4]=((((IkReal(0.106000000000000))*(x926)))+(((IkReal(-1.00000000000000))*(x909)*(x933)))+(((IkReal(-1.00000000000000))*(x940)))+(((IkReal(-1.00000000000000))*(x922)))+(((IkReal(-1.00000000000000))*(x918)))+(((IkReal(-1.00000000000000))*(x921)*(x925)))+(((IkReal(-1.00000000000000))*(x908)*(x933)))+(((IkReal(0.105999998468300))*(sj1)*(x919))));
02562 evalcond[5]=((((x915)*(x929)))+(((x908)*(x938)))+(((x909)*(x938)))+(((IkReal(-1.00000000000000))*(x919)*(x937)))+(x927));
02563 evalcond[6]=((((x919)*(x943)))+(((IkReal(-1.00000000000000))*(x925)*(x929)))+(((IkReal(-1.00000000000000))*(x908)*(x910)))+(x926)+(((IkReal(-1.00000000000000))*(x909)*(x910))));
02564 evalcond[7]=((((IkReal(0.106000000000000))*(x927)))+(((IkReal(-0.105999998468300))*(cj1)*(x919)))+(((x915)*(x921)))+(((IkReal(0.999999985550000))*(pz)*(x919)))+(((x928)*(x932)))+(((IkReal(-0.999999985550000))*(px)*(x913)))+(((IkReal(0.000169999997543500))*(py)*(x913)))+(((x909)*(x944)))+(((IkReal(-1.00000000000000))*(x909)*(x920)))+(((IkReal(-1.00000000000000))*(x908)*(x920)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x929)))+(((IkReal(0.000169999997543500))*(r02)*(x914)))+(((x908)*(x944))));
02565 evalcond[8]=((IkReal(-0.0237800000000000))+(((x919)*(x951)))+(((x919)*(x952)))+(((IkReal(-1.00000000000000))*(cj0)*(x907)*(x915)))+(((IkReal(1.91011997239877e-6))*(x945)))+(((IkReal(-1.00000000000000))*(cj1)*(x913)*(x934)))+(((IkReal(-0.211999996936600))*(x914)*(x926)))+(((IkReal(3.60399994792220e-5))*(x926)*(x939)))+(((IkReal(-1.00000000000000))*(x908)*(x954)))+(((IkReal(-1.00000000000000))*(x906)))+(((IkReal(-1.00000000000000))*(x909)*(x947)))+(((IkReal(-1.00000000000000))*(x909)*(x949)))+(((IkReal(0.212000000000000))*(px)*(x925)))+(((IkReal(-1.91011997239877e-6))*(x919)))+(((cj1)*(x907)*(x919)))+(((IkReal(1.99999997110000))*(x914)*(x918)))+(((py)*(x913)*(x923)))+(((cj1)*(x909)*(x941)))+(((IkReal(-1.00000000000000))*(r01)*(x904)*(x916)))+(((IkReal(-3.60399994792220e-5))*(x913)*(x935)))+(((IkReal(-1.00000000000000))*(px)*(x908)*(x911)))+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((IkReal(-1.00000000000000))*(x919)*(x948)))+(((r02)*(x914)*(x923)))+(((IkReal(-1.00000000000000))*(x908)*(x947)))+(((x909)*(x954)))+(((IkReal(-1.00000000000000))*(x919)*(x950)))+(((IkReal(-1.00000000000000))*(pz)*(x911)*(x932)))+(((px)*(x909)*(x911)))+(((px)*(x913)*(x936)))+(((IkReal(-0.0112359998376398))*(x909)))+(((IkReal(-0.0112359998376398))*(x908)))+(((r01)*(x905)*(x916)))+(((x908)*(x949)))+(((cj1)*(x908)*(x941)))+(((r01)*(x903)*(x916))));
02566 evalcond[9]=((((IkReal(-1.00000000000000))*(x905)*(x925)*(x929)))+(((IkReal(-1.00000000000000))*(sj1)*(x909)*(x951)))+(((x904)*(x925)*(x929)))+(((IkReal(-1.00000000000000))*(x903)*(x925)*(x929)))+(((x911)*(x914)*(x925)))+(((IkReal(-1.00000000000000))*(x904)*(x908)*(x910)))+(((IkReal(-1.00000000000000))*(x905)*(x908)*(x910)))+(((sj1)*(x908)*(x951)))+(((IkReal(-0.0112360000000000))*(x926)))+(((IkReal(0.000339999995087000))*(r02)*(x912)*(x914)))+(((x909)*(x946)))+(((x903)*(x908)*(x910)))+(((x904)*(x919)*(x943)))+(((x904)*(x909)*(x910)))+(((pp)*(x926)))+(((IkReal(-1.00000000000000))*(x903)*(x919)*(x943)))+(((IkReal(-1.00000000000000))*(x926)*(x953)))+(((IkReal(1.99999997110000))*(py)*(x912)*(x932)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(x915)))+(((x905)*(x919)*(x943)))+(((IkReal(-1.00000000000000))*(x903)*(x909)*(x910)))+(((IkReal(-2.00000000000000))*(x922)*(x942)))+(((x925)*(x931)))+(((IkReal(0.212000000000000))*(x940)))+(((px)*(sj1)*(x911)*(x919)))+(((IkReal(0.212000000000000))*(x922)))+(((IkReal(-0.0112359998376398))*(sj1)*(x919)))+(((IkReal(-1.00000000000000))*(x905)*(x909)*(x910)))+(((x911)*(x912)*(x913)))+(((x908)*(x946)))+(((IkReal(-1.99999997110000))*(px)*(x912)*(x913)))+(((IkReal(0.212000000000000))*(x918))));
02567 evalcond[10]=((((IkReal(-1.00000000000000))*(x904)*(x919)*(x937)))+(((x919)*(x941)))+(((IkReal(-1.00000000000000))*(x911)*(x913)*(x942)))+(((x915)*(x931)))+(((x905)*(x915)*(x929)))+(((IkReal(-1.00000000000000))*(x904)*(x915)*(x929)))+(((x908)*(x924)))+(((x904)*(x908)*(x938)))+(((IkReal(-1.00000000000000))*(x914)*(x926)*(x936)))+(((IkReal(-1.99999997110000))*(py)*(x908)*(x935)))+(((IkReal(3.60399994792220e-5))*(py)*(x913)))+(((IkReal(-1.00000000000000))*(x911)*(x919)*(x935)))+(((IkReal(-2.00000000000000))*(x912)*(x922)))+(((x903)*(x919)*(x937)))+(((IkReal(-1.00000000000000))*(x911)*(x914)*(x915)))+(((x905)*(x909)*(x938)))+(((x913)*(x923)*(x935)))+(((IkReal(-1.00000000000000))*(x927)*(x953)))+(((pp)*(x927)))+(((IkReal(-1.00000000000000))*(x941)*(x945)))+(((x905)*(x908)*(x938)))+(((x909)*(x924)))+(((IkReal(-0.0112359998376398))*(cj1)*(x919)))+(((IkReal(-1.00000000000000))*(x903)*(x908)*(x938)))+(((IkReal(0.0112360000000000))*(x927)))+(((IkReal(-1.00000000000000))*(x913)*(x930)))+(((IkReal(-2.00000000000000))*(x912)*(x918)))+(((IkReal(-1.00000000000000))*(x905)*(x919)*(x937)))+(((IkReal(1.99999997110000))*(py)*(x909)*(x935)))+(((x903)*(x909)*(x938)))+(((IkReal(-1.00000000000000))*(x904)*(x909)*(x938)))+(((x903)*(x915)*(x929)))+(((IkReal(3.60399994792220e-5))*(r02)*(x914)))+(((IkReal(-1.00000000000000))*(x923)*(x926)*(x939)))+(((IkReal(-1.00000000000000))*(x907)*(x909)))+(((IkReal(-1.00000000000000))*(x907)*(x908)))+(((x932)*(x934))));
02568 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  )
02569 {
02570 {
02571 IkReal dummyeval[1];
02572 IkReal gconst3;
02573 gconst3=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
02574 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
02575 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02576 {
02577 {
02578 IkReal dummyeval[1];
02579 IkReal gconst4;
02580 gconst4=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
02581 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
02582 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02583 {
02584 continue;
02585 
02586 } else
02587 {
02588 {
02589 IkReal j2array[1], cj2array[1], sj2array[1];
02590 bool j2valid[1]={false};
02591 _nj2 = 1;
02592 IkReal x955=((py)*(r02));
02593 IkReal x956=((IkReal(1750.00000000000))*(cj1));
02594 IkReal x957=((px)*(sj3));
02595 IkReal x958=((cj3)*(pz));
02596 IkReal x959=((cj0)*(sj1));
02597 IkReal x960=((IkReal(1749.99997471250))*(r02));
02598 IkReal x961=((px)*(r01));
02599 IkReal x962=((r00)*(sj3));
02600 IkReal x963=((pz)*(sj3));
02601 IkReal x964=((pz)*(r01));
02602 IkReal x965=((IkReal(0.297499995701125))*(sj3));
02603 IkReal x966=((IkReal(1656.25000000000))*(cj1));
02604 IkReal x967=((IkReal(0.297499995701125))*(cj3));
02605 IkReal x968=((pz)*(r00));
02606 IkReal x969=((cj3)*(px));
02607 IkReal x970=((cj3)*(py));
02608 IkReal x971=((px)*(r02));
02609 IkReal x972=((IkReal(0.297499995701125))*(r01));
02610 IkReal x973=((sj0)*(sj1));
02611 IkReal x974=((IkReal(0.281562495931422))*(x959));
02612 IkReal x975=((IkReal(1656.24997606719))*(x973));
02613 IkReal x976=((IkReal(1749.99997471250))*(x973));
02614 IkReal x977=((py)*(x973));
02615 IkReal x978=((IkReal(0.281562495931422))*(x973));
02616 if( IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(r00)*(x956)*(x970)))+(((IkReal(-0.297499995701125))*(r00)*(x958)*(x973)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x966)))+(((IkReal(-1.00000000000000))*(x955)*(x974)))+(((IkReal(-1.00000000000000))*(x965)*(x977)))+(((x958)*(x959)*(x972)))+(((x961)*(x966)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r01)*(x958)*(x976)))+(((IkReal(-1749.99997471250))*(r00)*(x958)*(x959)))+(((IkReal(-1.00000000000000))*(x964)*(x975)))+(((IkReal(-1656.24997606719))*(x959)*(x968)))+(((IkReal(1656.24997606719))*(x959)*(x971)))+(((IkReal(-1.00000000000000))*(x955)*(x959)*(x967)))+(((cj3)*(x956)*(x961)))+(((x956)*(x963)))+(((x971)*(x978)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x959)))+(((x967)*(x971)*(x973)))+(((x964)*(x974)))+(((x957)*(x976)))+(((x959)*(x960)*(x969)))+(((cj3)*(x955)*(x976)))+(((x955)*(x975)))+(((IkReal(-1.00000000000000))*(x968)*(x978)))+(((IkReal(-0.297499995701125))*(x957)*(x959))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(px)*(x975)))+(((IkReal(-0.297499995701125))*(pz)*(x962)*(x973)))+(((IkReal(-1.00000000000000))*(pz)*(x966)))+(((IkReal(-1.00000000000000))*(py)*(x956)*(x962)))+(((IkReal(1749.99997471250))*(x959)*(x970)))+(((IkReal(-1.00000000000000))*(x969)*(x976)))+(((x959)*(x963)*(x972)))+(((IkReal(-1749.99997471250))*(pz)*(x959)*(x962)))+(((IkReal(1656.24997606719))*(py)*(x959)))+(((x957)*(x959)*(x960)))+(((px)*(x959)*(x967)))+(((IkReal(0.281562495931422))*(x977)))+(((IkReal(-1.00000000000000))*(x955)*(x959)*(x965)))+(((IkReal(-1.00000000000000))*(x956)*(x958)))+(((IkReal(-1.00000000000000))*(r01)*(x963)*(x976)))+(((r01)*(x956)*(x957)))+(((sj3)*(x955)*(x976)))+(((IkReal(185.500000000000))*(cj3)))+(((x967)*(x977)))+(((IkReal(0.297499995701125))*(r02)*(x957)*(x973)))+(((px)*(x974))))))) < IKFAST_ATAN2_MAGTHRESH )
02617     continue;
02618 j2array[0]=IKatan2(((gconst4)*(((((IkReal(-1.00000000000000))*(r00)*(x956)*(x970)))+(((IkReal(-0.297499995701125))*(r00)*(x958)*(x973)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x966)))+(((IkReal(-1.00000000000000))*(x955)*(x974)))+(((IkReal(-1.00000000000000))*(x965)*(x977)))+(((x958)*(x959)*(x972)))+(((x961)*(x966)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r01)*(x958)*(x976)))+(((IkReal(-1749.99997471250))*(r00)*(x958)*(x959)))+(((IkReal(-1.00000000000000))*(x964)*(x975)))+(((IkReal(-1656.24997606719))*(x959)*(x968)))+(((IkReal(1656.24997606719))*(x959)*(x971)))+(((IkReal(-1.00000000000000))*(x955)*(x959)*(x967)))+(((cj3)*(x956)*(x961)))+(((x956)*(x963)))+(((x971)*(x978)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x959)))+(((x967)*(x971)*(x973)))+(((x964)*(x974)))+(((x957)*(x976)))+(((x959)*(x960)*(x969)))+(((cj3)*(x955)*(x976)))+(((x955)*(x975)))+(((IkReal(-1.00000000000000))*(x968)*(x978)))+(((IkReal(-0.297499995701125))*(x957)*(x959)))))), ((gconst4)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(px)*(x975)))+(((IkReal(-0.297499995701125))*(pz)*(x962)*(x973)))+(((IkReal(-1.00000000000000))*(pz)*(x966)))+(((IkReal(-1.00000000000000))*(py)*(x956)*(x962)))+(((IkReal(1749.99997471250))*(x959)*(x970)))+(((IkReal(-1.00000000000000))*(x969)*(x976)))+(((x959)*(x963)*(x972)))+(((IkReal(-1749.99997471250))*(pz)*(x959)*(x962)))+(((IkReal(1656.24997606719))*(py)*(x959)))+(((x957)*(x959)*(x960)))+(((px)*(x959)*(x967)))+(((IkReal(0.281562495931422))*(x977)))+(((IkReal(-1.00000000000000))*(x955)*(x959)*(x965)))+(((IkReal(-1.00000000000000))*(x956)*(x958)))+(((IkReal(-1.00000000000000))*(r01)*(x963)*(x976)))+(((r01)*(x956)*(x957)))+(((sj3)*(x955)*(x976)))+(((IkReal(185.500000000000))*(cj3)))+(((x967)*(x977)))+(((IkReal(0.297499995701125))*(r02)*(x957)*(x973)))+(((px)*(x974)))))));
02619 sj2array[0]=IKsin(j2array[0]);
02620 cj2array[0]=IKcos(j2array[0]);
02621 if( j2array[0] > IKPI )
02622 {
02623     j2array[0]-=IK2PI;
02624 }
02625 else if( j2array[0] < -IKPI )
02626 {    j2array[0]+=IK2PI;
02627 }
02628 j2valid[0] = true;
02629 for(int ij2 = 0; ij2 < 1; ++ij2)
02630 {
02631 if( !j2valid[ij2] )
02632 {
02633     continue;
02634 }
02635 _ij2[0] = ij2; _ij2[1] = -1;
02636 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02637 {
02638 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02639 {
02640     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02641 }
02642 }
02643 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02644 {
02645 IkReal evalcond[4];
02646 IkReal x979=IKsin(j2);
02647 IkReal x980=IKcos(j2);
02648 IkReal x981=((r00)*(sj0));
02649 IkReal x982=((r01)*(sj0));
02650 IkReal x983=((py)*(sj1));
02651 IkReal x984=((IkReal(0.999999985550000))*(r02));
02652 IkReal x985=((px)*(sj1));
02653 IkReal x986=((IkReal(0.999999985550000))*(sj0));
02654 IkReal x987=((IkReal(0.000169999997543500))*(cj0));
02655 IkReal x988=((IkReal(0.000169999997543500))*(sj0));
02656 IkReal x989=((cj1)*(px));
02657 IkReal x990=((pz)*(sj1));
02658 IkReal x991=((cj0)*(r00));
02659 IkReal x992=((cj1)*(pz));
02660 IkReal x993=((IkReal(1.00000000000000))*(r01));
02661 IkReal x994=((cj1)*(py));
02662 IkReal x995=((IkReal(0.999999985550000))*(cj0));
02663 IkReal x996=((IkReal(0.106000000000000))*(x979));
02664 IkReal x997=((IkReal(0.106000000000000))*(x980));
02665 IkReal x998=((IkReal(0.112000000000000))*(x980));
02666 IkReal x999=((IkReal(0.112000000000000))*(x979));
02667 IkReal x1000=((cj3)*(x999));
02668 IkReal x1001=((sj3)*(x998));
02669 IkReal x1002=((sj3)*(x999));
02670 IkReal x1003=((cj3)*(x998));
02671 IkReal x1004=((x1003)+(x997));
02672 IkReal x1005=((x1001)+(x1000)+(x996));
02673 evalcond[0]=((((x994)*(x995)))+(x1005)+(((x988)*(x994)))+(((IkReal(-1.00000000000000))*(x986)*(x989)))+(((x987)*(x989)))+(x990));
02674 evalcond[1]=((IkReal(-0.106000000000000))+(x1002)+(((IkReal(-1.00000000000000))*(x1004)))+(((IkReal(-1.00000000000000))*(x983)*(x995)))+(((x985)*(x986)))+(x992)+(((IkReal(-1.00000000000000))*(x985)*(x987)))+(((IkReal(-1.00000000000000))*(x983)*(x988))));
02675 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x987)*(x990)))+(((IkReal(-1.00000000000000))*(x1005)))+(((IkReal(0.999999985550000))*(x982)*(x990)))+(((IkReal(-1.00000000000000))*(sj0)*(x983)*(x984)))+(((r00)*(x994)))+(((IkReal(-1.00000000000000))*(cj0)*(x984)*(x985)))+(((r02)*(x983)*(x987)))+(((IkReal(0.000169999997543500))*(x981)*(x990)))+(((IkReal(0.999999985550000))*(x990)*(x991)))+(((IkReal(-1.00000000000000))*(x989)*(x993)))+(((IkReal(-1.00000000000000))*(r02)*(x985)*(x988))));
02676 evalcond[3]=((((IkReal(0.105999998468300))*(x991)))+(((IkReal(-0.999999985550000))*(x991)*(x992)))+(((IkReal(-0.000169999997543500))*(x981)*(x992)))+(((r01)*(x987)*(x992)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(x1002)+(((IkReal(-1.00000000000000))*(x1004)))+(((sj0)*(x984)*(x994)))+(((IkReal(-1.00000000000000))*(r02)*(x987)*(x994)))+(((IkReal(1.80199997396110e-5))*(x981)))+(((IkReal(0.105999998468300))*(x982)))+(((r00)*(x983)))+(((IkReal(-1.00000000000000))*(x985)*(x993)))+(((cj0)*(x984)*(x989)))+(((r02)*(x988)*(x989)))+(((IkReal(-0.999999985550000))*(x982)*(x992))));
02677 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02678 {
02679 continue;
02680 }
02681 }
02682 
02683 {
02684 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02685 vinfos[0].jointtype = 1;
02686 vinfos[0].foffset = j0;
02687 vinfos[0].indices[0] = _ij0[0];
02688 vinfos[0].indices[1] = _ij0[1];
02689 vinfos[0].maxsolutions = _nj0;
02690 vinfos[1].jointtype = 1;
02691 vinfos[1].foffset = j1;
02692 vinfos[1].indices[0] = _ij1[0];
02693 vinfos[1].indices[1] = _ij1[1];
02694 vinfos[1].maxsolutions = _nj1;
02695 vinfos[2].jointtype = 1;
02696 vinfos[2].foffset = j2;
02697 vinfos[2].indices[0] = _ij2[0];
02698 vinfos[2].indices[1] = _ij2[1];
02699 vinfos[2].maxsolutions = _nj2;
02700 vinfos[3].jointtype = 1;
02701 vinfos[3].foffset = j3;
02702 vinfos[3].indices[0] = _ij3[0];
02703 vinfos[3].indices[1] = _ij3[1];
02704 vinfos[3].maxsolutions = _nj3;
02705 vinfos[4].jointtype = 1;
02706 vinfos[4].foffset = j5;
02707 vinfos[4].indices[0] = _ij5[0];
02708 vinfos[4].indices[1] = _ij5[1];
02709 vinfos[4].maxsolutions = _nj5;
02710 std::vector<int> vfree(0);
02711 solutions.AddSolution(vinfos,vfree);
02712 }
02713 }
02714 }
02715 
02716 }
02717 
02718 }
02719 
02720 } else
02721 {
02722 {
02723 IkReal j2array[1], cj2array[1], sj2array[1];
02724 bool j2valid[1]={false};
02725 _nj2 = 1;
02726 IkReal x1006=((px)*(sj1));
02727 IkReal x1007=((IkReal(0.281562495931422))*(cj0));
02728 IkReal x1008=((cj1)*(sj0));
02729 IkReal x1009=((IkReal(0.281562495931422))*(py));
02730 IkReal x1010=((IkReal(1749.99997471250))*(sj3));
02731 IkReal x1011=((IkReal(1749.99997471250))*(cj3));
02732 IkReal x1012=((cj0)*(cj1));
02733 IkReal x1013=((IkReal(0.297499995701125))*(sj3));
02734 IkReal x1014=((IkReal(0.297499995701125))*(cj3));
02735 IkReal x1015=((IkReal(1656.25000000000))*(pz));
02736 IkReal x1016=((IkReal(1750.00000000000))*(cj3)*(pz));
02737 IkReal x1017=((IkReal(1750.00000000000))*(pz)*(sj3));
02738 IkReal x1018=((IkReal(1656.24997606719))*(cj0)*(py));
02739 IkReal x1019=((py)*(sj0)*(sj1));
02740 IkReal x1020=((cj0)*(py)*(sj1));
02741 if( IKabs(((gconst3)*(((((py)*(x1011)*(x1012)))+(((x1008)*(x1009)))+(((IkReal(-1656.24997606719))*(px)*(x1008)))+(((px)*(x1012)*(x1014)))+(((sj1)*(x1016)))+(((sj1)*(x1015)))+(((IkReal(-185.500000000000))*(sj3)))+(((py)*(x1008)*(x1014)))+(((IkReal(-1.00000000000000))*(cj0)*(x1006)*(x1013)))+(((sj0)*(x1006)*(x1010)))+(((IkReal(-1.00000000000000))*(x1013)*(x1019)))+(((cj1)*(x1017)))+(((IkReal(1656.24997606719))*(py)*(x1012)))+(((IkReal(-1.00000000000000))*(px)*(x1008)*(x1011)))+(((IkReal(-1.00000000000000))*(x1010)*(x1020)))+(((cj1)*(px)*(x1007))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((IkReal(175.562500000000))+(((x1014)*(x1019)))+(((x1011)*(x1020)))+(((py)*(x1010)*(x1012)))+(((px)*(x1012)*(x1013)))+(((sj0)*(sj1)*(x1009)))+(((sj1)*(x1017)))+(((sj1)*(x1018)))+(((cj0)*(x1006)*(x1014)))+(((py)*(x1008)*(x1013)))+(((IkReal(-1.00000000000000))*(sj0)*(x1006)*(x1011)))+(((IkReal(-1.00000000000000))*(cj1)*(x1016)))+(((IkReal(-1.00000000000000))*(cj1)*(x1015)))+(((x1006)*(x1007)))+(((IkReal(-1656.24997606719))*(sj0)*(x1006)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x1008)*(x1010))))))) < IKFAST_ATAN2_MAGTHRESH )
02742     continue;
02743 j2array[0]=IKatan2(((gconst3)*(((((py)*(x1011)*(x1012)))+(((x1008)*(x1009)))+(((IkReal(-1656.24997606719))*(px)*(x1008)))+(((px)*(x1012)*(x1014)))+(((sj1)*(x1016)))+(((sj1)*(x1015)))+(((IkReal(-185.500000000000))*(sj3)))+(((py)*(x1008)*(x1014)))+(((IkReal(-1.00000000000000))*(cj0)*(x1006)*(x1013)))+(((sj0)*(x1006)*(x1010)))+(((IkReal(-1.00000000000000))*(x1013)*(x1019)))+(((cj1)*(x1017)))+(((IkReal(1656.24997606719))*(py)*(x1012)))+(((IkReal(-1.00000000000000))*(px)*(x1008)*(x1011)))+(((IkReal(-1.00000000000000))*(x1010)*(x1020)))+(((cj1)*(px)*(x1007)))))), ((gconst3)*(((IkReal(175.562500000000))+(((x1014)*(x1019)))+(((x1011)*(x1020)))+(((py)*(x1010)*(x1012)))+(((px)*(x1012)*(x1013)))+(((sj0)*(sj1)*(x1009)))+(((sj1)*(x1017)))+(((sj1)*(x1018)))+(((cj0)*(x1006)*(x1014)))+(((py)*(x1008)*(x1013)))+(((IkReal(-1.00000000000000))*(sj0)*(x1006)*(x1011)))+(((IkReal(-1.00000000000000))*(cj1)*(x1016)))+(((IkReal(-1.00000000000000))*(cj1)*(x1015)))+(((x1006)*(x1007)))+(((IkReal(-1656.24997606719))*(sj0)*(x1006)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x1008)*(x1010)))))));
02744 sj2array[0]=IKsin(j2array[0]);
02745 cj2array[0]=IKcos(j2array[0]);
02746 if( j2array[0] > IKPI )
02747 {
02748     j2array[0]-=IK2PI;
02749 }
02750 else if( j2array[0] < -IKPI )
02751 {    j2array[0]+=IK2PI;
02752 }
02753 j2valid[0] = true;
02754 for(int ij2 = 0; ij2 < 1; ++ij2)
02755 {
02756 if( !j2valid[ij2] )
02757 {
02758     continue;
02759 }
02760 _ij2[0] = ij2; _ij2[1] = -1;
02761 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02762 {
02763 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02764 {
02765     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02766 }
02767 }
02768 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02769 {
02770 IkReal evalcond[4];
02771 IkReal x1021=IKsin(j2);
02772 IkReal x1022=IKcos(j2);
02773 IkReal x1023=((r00)*(sj0));
02774 IkReal x1024=((r01)*(sj0));
02775 IkReal x1025=((py)*(sj1));
02776 IkReal x1026=((IkReal(0.999999985550000))*(r02));
02777 IkReal x1027=((px)*(sj1));
02778 IkReal x1028=((IkReal(0.999999985550000))*(sj0));
02779 IkReal x1029=((IkReal(0.000169999997543500))*(cj0));
02780 IkReal x1030=((IkReal(0.000169999997543500))*(sj0));
02781 IkReal x1031=((cj1)*(px));
02782 IkReal x1032=((pz)*(sj1));
02783 IkReal x1033=((cj0)*(r00));
02784 IkReal x1034=((cj1)*(pz));
02785 IkReal x1035=((IkReal(1.00000000000000))*(r01));
02786 IkReal x1036=((cj1)*(py));
02787 IkReal x1037=((IkReal(0.999999985550000))*(cj0));
02788 IkReal x1038=((IkReal(0.106000000000000))*(x1021));
02789 IkReal x1039=((IkReal(0.106000000000000))*(x1022));
02790 IkReal x1040=((IkReal(0.112000000000000))*(x1022));
02791 IkReal x1041=((IkReal(0.112000000000000))*(x1021));
02792 IkReal x1042=((cj3)*(x1041));
02793 IkReal x1043=((sj3)*(x1040));
02794 IkReal x1044=((sj3)*(x1041));
02795 IkReal x1045=((cj3)*(x1040));
02796 IkReal x1046=((x1045)+(x1039));
02797 IkReal x1047=((x1043)+(x1042)+(x1038));
02798 evalcond[0]=((((x1036)*(x1037)))+(((x1030)*(x1036)))+(((IkReal(-1.00000000000000))*(x1028)*(x1031)))+(x1047)+(x1032)+(((x1029)*(x1031))));
02799 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x1025)*(x1030)))+(((IkReal(-1.00000000000000))*(x1025)*(x1037)))+(x1044)+(x1034)+(((x1027)*(x1028)))+(((IkReal(-1.00000000000000))*(x1027)*(x1029)))+(((IkReal(-1.00000000000000))*(x1046))));
02800 evalcond[2]=((((r00)*(x1036)))+(((IkReal(-1.00000000000000))*(r01)*(x1029)*(x1032)))+(((r02)*(x1025)*(x1029)))+(((IkReal(0.999999985550000))*(x1032)*(x1033)))+(((IkReal(0.000169999997543500))*(x1023)*(x1032)))+(((IkReal(-1.00000000000000))*(x1031)*(x1035)))+(((IkReal(0.999999985550000))*(x1024)*(x1032)))+(((IkReal(-1.00000000000000))*(cj0)*(x1026)*(x1027)))+(((IkReal(-1.00000000000000))*(r02)*(x1027)*(x1030)))+(((IkReal(-1.00000000000000))*(sj0)*(x1025)*(x1026)))+(((IkReal(-1.00000000000000))*(x1047))));
02801 evalcond[3]=((((IkReal(-1.00000000000000))*(x1027)*(x1035)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(r02)*(x1029)*(x1036)))+(x1044)+(((sj0)*(x1026)*(x1036)))+(((IkReal(-0.999999985550000))*(x1033)*(x1034)))+(((IkReal(0.105999998468300))*(x1033)))+(((r01)*(x1029)*(x1034)))+(((IkReal(-0.999999985550000))*(x1024)*(x1034)))+(((IkReal(0.105999998468300))*(x1024)))+(((r02)*(x1030)*(x1031)))+(((IkReal(-0.000169999997543500))*(x1023)*(x1034)))+(((IkReal(1.80199997396110e-5))*(x1023)))+(((cj0)*(x1026)*(x1031)))+(((IkReal(-1.00000000000000))*(x1046)))+(((r00)*(x1025))));
02802 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
02803 {
02804 continue;
02805 }
02806 }
02807 
02808 {
02809 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
02810 vinfos[0].jointtype = 1;
02811 vinfos[0].foffset = j0;
02812 vinfos[0].indices[0] = _ij0[0];
02813 vinfos[0].indices[1] = _ij0[1];
02814 vinfos[0].maxsolutions = _nj0;
02815 vinfos[1].jointtype = 1;
02816 vinfos[1].foffset = j1;
02817 vinfos[1].indices[0] = _ij1[0];
02818 vinfos[1].indices[1] = _ij1[1];
02819 vinfos[1].maxsolutions = _nj1;
02820 vinfos[2].jointtype = 1;
02821 vinfos[2].foffset = j2;
02822 vinfos[2].indices[0] = _ij2[0];
02823 vinfos[2].indices[1] = _ij2[1];
02824 vinfos[2].maxsolutions = _nj2;
02825 vinfos[3].jointtype = 1;
02826 vinfos[3].foffset = j3;
02827 vinfos[3].indices[0] = _ij3[0];
02828 vinfos[3].indices[1] = _ij3[1];
02829 vinfos[3].maxsolutions = _nj3;
02830 vinfos[4].jointtype = 1;
02831 vinfos[4].foffset = j5;
02832 vinfos[4].indices[0] = _ij5[0];
02833 vinfos[4].indices[1] = _ij5[1];
02834 vinfos[4].maxsolutions = _nj5;
02835 std::vector<int> vfree(0);
02836 solutions.AddSolution(vinfos,vfree);
02837 }
02838 }
02839 }
02840 
02841 }
02842 
02843 }
02844 
02845 } else
02846 {
02847 IkReal x1048=(px)*(px);
02848 IkReal x1049=((IkReal(0.0237440000000000))*(cj3));
02849 IkReal x1050=(py)*(py);
02850 IkReal x1051=(pz)*(pz);
02851 IkReal x1052=((IkReal(3.60399994792220e-5))*(pz));
02852 IkReal x1053=((cj0)*(r00));
02853 IkReal x1054=((r01)*(sj0));
02854 IkReal x1055=((IkReal(0.000169999997543500))*(sj1));
02855 IkReal x1056=((IkReal(0.000339999995087000))*(py));
02856 IkReal x1057=((pz)*(sj1));
02857 IkReal x1058=((r02)*(sj0));
02858 IkReal x1059=((cj0)*(px));
02859 IkReal x1060=((cj1)*(r01));
02860 IkReal x1061=((IkReal(0.000169999997543500))*(cj0));
02861 IkReal x1062=((IkReal(3.60399994792220e-5))*(sj1));
02862 IkReal x1063=((py)*(r01));
02863 IkReal x1064=((r00)*(sj0));
02864 IkReal x1065=((IkReal(0.000169999997543500))*(pz));
02865 IkReal x1066=((IkReal(0.105999998468300))*(cj0));
02866 IkReal x1067=((px)*(r00));
02867 IkReal x1068=((IkReal(1.99999997110000))*(pz));
02868 IkReal x1069=((IkReal(1.91011997239877e-6))*(cj1));
02869 IkReal x1070=((r01)*(sj1));
02870 IkReal x1071=((cj1)*(r02));
02871 IkReal x1072=((r02)*(sj1));
02872 IkReal x1073=((IkReal(0.999999985550000))*(py));
02873 IkReal x1074=((IkReal(0.999999985550000))*(cj0));
02874 IkReal x1075=((IkReal(0.211999996936600))*(px));
02875 IkReal x1076=((IkReal(0.0112359998376398))*(cj0));
02876 IkReal x1077=((cj0)*(r02));
02877 IkReal x1078=((IkReal(1.80199997396110e-5))*(sj1));
02878 IkReal x1079=((IkReal(0.211999996936600))*(py));
02879 IkReal x1080=((cj1)*(px));
02880 IkReal x1081=((IkReal(0.000339999995087000))*(pz));
02881 IkReal x1082=((IkReal(0.999999985550000))*(cj1));
02882 IkReal x1083=((IkReal(0.000169999997543500))*(cj1));
02883 IkReal x1084=((cj0)*(py));
02884 IkReal x1085=((pz)*(r02));
02885 IkReal x1086=((IkReal(0.211999996936600))*(pz));
02886 IkReal x1087=((cj1)*(pz));
02887 IkReal x1088=((IkReal(0.999999985550000))*(sj1));
02888 IkReal x1089=((IkReal(1.80199997396110e-5))*(cj1));
02889 IkReal x1090=((cj0)*(r01));
02890 IkReal x1091=((IkReal(1.91011997239877e-6))*(sj1));
02891 IkReal x1092=((IkReal(0.999999985550000))*(x1051));
02892 IkReal x1093=((IkReal(0.000169999997543500))*(x1050));
02893 IkReal x1094=((IkReal(0.999999985550000))*(x1048));
02894 IkReal x1095=((IkReal(0.000169999997543500))*(x1051));
02895 IkReal x1096=((IkReal(1.99999997110000))*(px)*(py));
02896 IkReal x1097=((IkReal(0.000169999997543500))*(x1048));
02897 IkReal x1098=((IkReal(2.00000000000000))*(x1051));
02898 IkReal x1099=((IkReal(0.999999985550000))*(x1050));
02899 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j5)), IkReal(6.28318530717959))));
02900 evalcond[1]=((((py)*(x1061)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((IkReal(-1.00000000000000))*(sj0)*(x1073)))+(((IkReal(-0.999999985550000))*(x1059))));
02901 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-0.000169999997543500))*(x1064)))+(((r01)*(x1061)))+(((IkReal(-0.999999985550000))*(x1054)))+(((IkReal(-0.999999985550000))*(x1053))));
02902 evalcond[3]=((IkReal(0.0125440000000000))+(x1049)+(((IkReal(-1.00000000000000))*(x1059)*(x1062)))+(((IkReal(0.212000000000000))*(x1087)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x1079)))+(((sj0)*(sj1)*(x1075)))+(((IkReal(-1.00000000000000))*(pp)))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x1062))));
02903 evalcond[4]=((((IkReal(0.106000000000000))*(x1071)))+(((IkReal(0.105999998468300))*(sj1)*(x1064)))+(((IkReal(-1.00000000000000))*(x1085)))+(((IkReal(-1.00000000000000))*(x1054)*(x1078)))+(((IkReal(-1.00000000000000))*(x1066)*(x1070)))+(((IkReal(-1.00000000000000))*(x1067)))+(((IkReal(-1.00000000000000))*(x1063)))+(((IkReal(-1.00000000000000))*(x1053)*(x1078))));
02904 evalcond[5]=((((x1053)*(x1083)))+(x1072)+(((IkReal(-1.00000000000000))*(x1064)*(x1082)))+(((x1060)*(x1074)))+(((x1054)*(x1083))));
02905 evalcond[6]=((x1071)+(((IkReal(-1.00000000000000))*(x1070)*(x1074)))+(((IkReal(-1.00000000000000))*(x1054)*(x1055)))+(((IkReal(-1.00000000000000))*(x1053)*(x1055)))+(((x1064)*(x1088))));
02906 evalcond[7]=((((IkReal(0.106000000000000))*(x1072)))+(((x1053)*(x1089)))+(((IkReal(-0.105999998468300))*(cj1)*(x1064)))+(((x1060)*(x1066)))+(((IkReal(0.999999985550000))*(pz)*(x1064)))+(((IkReal(0.000169999997543500))*(r02)*(x1059)))+(((IkReal(0.000169999997543500))*(py)*(x1058)))+(((IkReal(-0.999999985550000))*(px)*(x1058)))+(((x1073)*(x1077)))+(((IkReal(-1.00000000000000))*(x1054)*(x1065)))+(((x1054)*(x1089)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x1074)))+(((IkReal(-1.00000000000000))*(x1053)*(x1065))));
02907 evalcond[8]=((IkReal(0.0237800000000000))+(((IkReal(-1.00000000000000))*(cj0)*(x1052)*(x1060)))+(((r01)*(x1051)*(x1061)))+(x1049)+(((IkReal(-1.00000000000000))*(cj1)*(x1058)*(x1079)))+(((IkReal(3.60399994792220e-5))*(x1071)*(x1084)))+(((cj1)*(x1054)*(x1086)))+(((IkReal(0.212000000000000))*(px)*(x1070)))+(((IkReal(-1.00000000000000))*(px)*(x1053)*(x1056)))+(((IkReal(-3.60399994792220e-5))*(x1058)*(x1080)))+(((x1064)*(x1097)))+(((x1064)*(x1096)))+(((IkReal(-1.00000000000000))*(x1054)*(x1094)))+(((IkReal(-1.00000000000000))*(x1054)*(x1092)))+(((IkReal(-1.00000000000000))*(x1064)*(x1095)))+(((IkReal(-1.00000000000000))*(x1064)*(x1093)))+(((cj1)*(x1052)*(x1064)))+(((r01)*(x1048)*(x1061)))+(((IkReal(-1.00000000000000))*(r01)*(x1050)*(x1061)))+(((x1054)*(x1099)))+(((IkReal(1.99999997110000))*(x1059)*(x1063)))+(((px)*(x1054)*(x1056)))+(((IkReal(-1.00000000000000))*(x1053)*(x1092)))+(((IkReal(-1.00000000000000))*(x1053)*(x1099)))+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((py)*(x1058)*(x1068)))+(((px)*(x1058)*(x1081)))+(((cj1)*(x1053)*(x1086)))+(((IkReal(-0.0112359998376398))*(x1054)))+(((IkReal(-0.0112359998376398))*(x1053)))+(((IkReal(-0.211999996936600))*(x1059)*(x1071)))+(((IkReal(-1.91011997239877e-6))*(x1064)))+(((IkReal(1.91011997239877e-6))*(x1090)))+(((IkReal(-1.00000000000000))*(pz)*(x1056)*(x1077)))+(((x1053)*(x1094)))+(((r02)*(x1059)*(x1068))));
02908 evalcond[9]=((((IkReal(-1.00000000000000))*(x1071)*(x1098)))+(((IkReal(-1.00000000000000))*(x1051)*(x1054)*(x1055)))+(((IkReal(-1.00000000000000))*(x1048)*(x1064)*(x1088)))+(((x1070)*(x1076)))+(((x1050)*(x1070)*(x1074)))+(((IkReal(0.212000000000000))*(x1085)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(x1060)))+(((IkReal(-1.00000000000000))*(x1048)*(x1070)*(x1074)))+(((IkReal(-1.00000000000000))*(x1050)*(x1053)*(x1055)))+(((IkReal(-1.99999997110000))*(px)*(x1057)*(x1058)))+(((IkReal(-1.00000000000000))*(x1051)*(x1070)*(x1074)))+(((x1056)*(x1057)*(x1058)))+(((IkReal(0.212000000000000))*(x1063)))+(((IkReal(0.212000000000000))*(x1067)))+(((IkReal(-1.00000000000000))*(x1051)*(x1053)*(x1055)))+(((IkReal(-1.00000000000000))*(x1048)*(x1054)*(x1055)))+(((px)*(sj1)*(x1056)*(x1064)))+(((x1056)*(x1059)*(x1070)))+(((x1048)*(x1053)*(x1055)))+(((x1050)*(x1064)*(x1088)))+(((IkReal(-0.0112359998376398))*(sj1)*(x1064)))+(((x1054)*(x1091)))+(((IkReal(0.000339999995087000))*(r02)*(x1057)*(x1059)))+(((IkReal(-1.00000000000000))*(sj1)*(x1054)*(x1096)))+(((x1050)*(x1054)*(x1055)))+(((IkReal(-2.00000000000000))*(x1067)*(x1087)))+(((pp)*(x1071)))+(((x1051)*(x1064)*(x1088)))+(((IkReal(1.99999997110000))*(py)*(x1057)*(x1077)))+(((IkReal(-0.0112360000000000))*(x1071)))+(((x1053)*(x1091)))+(((sj1)*(x1053)*(x1096))));
02909 evalcond[10]=((((IkReal(-1.00000000000000))*(x1086)*(x1090)))+(((x1077)*(x1079)))+(((x1048)*(x1064)*(x1082)))+(((IkReal(-1.00000000000000))*(x1052)*(x1053)))+(((IkReal(-1.00000000000000))*(x1052)*(x1054)))+(((IkReal(-1.00000000000000))*(x1056)*(x1059)*(x1060)))+(((IkReal(-1.00000000000000))*(x1050)*(x1054)*(x1083)))+(((x1054)*(x1069)))+(((IkReal(-1.00000000000000))*(x1050)*(x1060)*(x1074)))+(((x1060)*(x1076)))+(((IkReal(0.0112360000000000))*(x1072)))+(((IkReal(-1.00000000000000))*(x1056)*(x1058)*(x1087)))+(((IkReal(-1.00000000000000))*(x1051)*(x1064)*(x1082)))+(((x1058)*(x1068)*(x1080)))+(((IkReal(-1.00000000000000))*(x1059)*(x1071)*(x1081)))+(((IkReal(-1.00000000000000))*(x1058)*(x1075)))+(((IkReal(1.99999997110000))*(py)*(x1054)*(x1080)))+(((x1048)*(x1060)*(x1074)))+(((x1053)*(x1069)))+(((IkReal(3.60399994792220e-5))*(py)*(x1058)))+(((IkReal(-1.00000000000000))*(x1050)*(x1064)*(x1082)))+(((x1051)*(x1060)*(x1074)))+(((IkReal(-1.99999997110000))*(py)*(x1053)*(x1080)))+(((IkReal(-0.0112359998376398))*(cj1)*(x1064)))+(((IkReal(-1.00000000000000))*(x1072)*(x1098)))+(((IkReal(-1.00000000000000))*(x1048)*(x1053)*(x1083)))+(((IkReal(-1.00000000000000))*(x1068)*(x1071)*(x1084)))+(((x1051)*(x1053)*(x1083)))+(((x1048)*(x1054)*(x1083)))+(((IkReal(-1.00000000000000))*(x1056)*(x1064)*(x1080)))+(((pp)*(x1072)))+(((x1051)*(x1054)*(x1083)))+(((IkReal(-2.00000000000000))*(x1057)*(x1067)))+(((IkReal(-2.00000000000000))*(x1057)*(x1063)))+(((x1050)*(x1053)*(x1083)))+(((x1064)*(x1086)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1059))));
02910 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  )
02911 {
02912 {
02913 IkReal dummyeval[1];
02914 IkReal gconst5;
02915 gconst5=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
02916 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
02917 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02918 {
02919 {
02920 IkReal dummyeval[1];
02921 IkReal gconst6;
02922 gconst6=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
02923 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
02924 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
02925 {
02926 continue;
02927 
02928 } else
02929 {
02930 {
02931 IkReal j2array[1], cj2array[1], sj2array[1];
02932 bool j2valid[1]={false};
02933 _nj2 = 1;
02934 IkReal x1100=((cj0)*(sj1));
02935 IkReal x1101=((IkReal(1656.24997606719))*(pz));
02936 IkReal x1102=((py)*(r02));
02937 IkReal x1103=((IkReal(1750.00000000000))*(cj1));
02938 IkReal x1104=((px)*(sj3));
02939 IkReal x1105=((cj3)*(pz));
02940 IkReal x1106=((sj0)*(sj1));
02941 IkReal x1107=((IkReal(1749.99997471250))*(r02));
02942 IkReal x1108=((px)*(r01));
02943 IkReal x1109=((py)*(sj3));
02944 IkReal x1110=((pz)*(sj3));
02945 IkReal x1111=((IkReal(0.281562495931422))*(px));
02946 IkReal x1112=((IkReal(0.297499995701125))*(cj3));
02947 IkReal x1113=((IkReal(1749.99997471250))*(r01));
02948 IkReal x1114=((IkReal(1749.99997471250))*(r00));
02949 IkReal x1115=((IkReal(1656.25000000000))*(cj1));
02950 IkReal x1116=((IkReal(0.281562495931422))*(pz));
02951 IkReal x1117=((IkReal(1749.99997471250))*(cj3));
02952 IkReal x1118=((IkReal(1656.24997606719))*(px));
02953 IkReal x1119=((IkReal(0.297499995701125))*(r01));
02954 IkReal x1120=((py)*(r00));
02955 IkReal x1121=((IkReal(0.297499995701125))*(r00));
02956 if( IKabs(((gconst6)*(((((IkReal(-1.00000000000000))*(r02)*(x1100)*(x1118)))+(((IkReal(1749.99997471250))*(x1104)*(x1106)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x1100)*(x1107)))+(((IkReal(-1.00000000000000))*(x1100)*(x1105)*(x1119)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x1106)*(x1112)))+(((r01)*(x1101)*(x1106)))+(((IkReal(-1.00000000000000))*(r02)*(x1106)*(x1111)))+(((r00)*(x1100)*(x1101)))+(((IkReal(-1.00000000000000))*(cj3)*(x1103)*(x1108)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-0.297499995701125))*(x1106)*(x1109)))+(((IkReal(-1749.99997471250))*(x1100)*(x1109)))+(((IkReal(-1.00000000000000))*(x1102)*(x1106)*(x1117)))+(((IkReal(-1656.24997606719))*(x1102)*(x1106)))+(((x1105)*(x1106)*(x1113)))+(((IkReal(-1.00000000000000))*(x1108)*(x1115)))+(((IkReal(-1.00000000000000))*(r01)*(x1100)*(x1116)))+(((IkReal(-0.297499995701125))*(x1100)*(x1104)))+(((cj3)*(x1103)*(x1120)))+(((x1105)*(x1106)*(x1121)))+(((x1103)*(x1110)))+(((r00)*(x1106)*(x1116)))+(((x1100)*(x1102)*(x1112)))+(((IkReal(0.281562495931422))*(x1100)*(x1102)))+(((x1100)*(x1105)*(x1114)))+(((x1115)*(x1120))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x1103)*(x1105)))+(((IkReal(-1.00000000000000))*(x1100)*(x1104)*(x1107)))+(((IkReal(-1.00000000000000))*(x1100)*(x1110)*(x1119)))+(((px)*(x1100)*(x1112)))+(((IkReal(-1.00000000000000))*(r01)*(x1103)*(x1104)))+(((x1100)*(x1110)*(x1114)))+(((x1106)*(x1110)*(x1113)))+(((x1106)*(x1110)*(x1121)))+(((IkReal(-0.297499995701125))*(r02)*(x1104)*(x1106)))+(((IkReal(1656.24997606719))*(py)*(x1100)))+(((IkReal(-1.00000000000000))*(pz)*(x1115)))+(((py)*(x1106)*(x1112)))+(((IkReal(-1749.99997471250))*(sj3)*(x1102)*(x1106)))+(((IkReal(-1.00000000000000))*(x1106)*(x1118)))+(((r00)*(x1103)*(x1109)))+(((py)*(x1100)*(x1117)))+(((x1100)*(x1111)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x1106)*(x1117)))+(((IkReal(0.297499995701125))*(sj3)*(x1100)*(x1102)))+(((IkReal(0.281562495931422))*(py)*(x1106))))))) < IKFAST_ATAN2_MAGTHRESH )
02957     continue;
02958 j2array[0]=IKatan2(((gconst6)*(((((IkReal(-1.00000000000000))*(r02)*(x1100)*(x1118)))+(((IkReal(1749.99997471250))*(x1104)*(x1106)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x1100)*(x1107)))+(((IkReal(-1.00000000000000))*(x1100)*(x1105)*(x1119)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x1106)*(x1112)))+(((r01)*(x1101)*(x1106)))+(((IkReal(-1.00000000000000))*(r02)*(x1106)*(x1111)))+(((r00)*(x1100)*(x1101)))+(((IkReal(-1.00000000000000))*(cj3)*(x1103)*(x1108)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-0.297499995701125))*(x1106)*(x1109)))+(((IkReal(-1749.99997471250))*(x1100)*(x1109)))+(((IkReal(-1.00000000000000))*(x1102)*(x1106)*(x1117)))+(((IkReal(-1656.24997606719))*(x1102)*(x1106)))+(((x1105)*(x1106)*(x1113)))+(((IkReal(-1.00000000000000))*(x1108)*(x1115)))+(((IkReal(-1.00000000000000))*(r01)*(x1100)*(x1116)))+(((IkReal(-0.297499995701125))*(x1100)*(x1104)))+(((cj3)*(x1103)*(x1120)))+(((x1105)*(x1106)*(x1121)))+(((x1103)*(x1110)))+(((r00)*(x1106)*(x1116)))+(((x1100)*(x1102)*(x1112)))+(((IkReal(0.281562495931422))*(x1100)*(x1102)))+(((x1100)*(x1105)*(x1114)))+(((x1115)*(x1120)))))), ((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x1103)*(x1105)))+(((IkReal(-1.00000000000000))*(x1100)*(x1104)*(x1107)))+(((IkReal(-1.00000000000000))*(x1100)*(x1110)*(x1119)))+(((px)*(x1100)*(x1112)))+(((IkReal(-1.00000000000000))*(r01)*(x1103)*(x1104)))+(((x1100)*(x1110)*(x1114)))+(((x1106)*(x1110)*(x1113)))+(((x1106)*(x1110)*(x1121)))+(((IkReal(-0.297499995701125))*(r02)*(x1104)*(x1106)))+(((IkReal(1656.24997606719))*(py)*(x1100)))+(((IkReal(-1.00000000000000))*(pz)*(x1115)))+(((py)*(x1106)*(x1112)))+(((IkReal(-1749.99997471250))*(sj3)*(x1102)*(x1106)))+(((IkReal(-1.00000000000000))*(x1106)*(x1118)))+(((r00)*(x1103)*(x1109)))+(((py)*(x1100)*(x1117)))+(((x1100)*(x1111)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(px)*(x1106)*(x1117)))+(((IkReal(0.297499995701125))*(sj3)*(x1100)*(x1102)))+(((IkReal(0.281562495931422))*(py)*(x1106)))))));
02959 sj2array[0]=IKsin(j2array[0]);
02960 cj2array[0]=IKcos(j2array[0]);
02961 if( j2array[0] > IKPI )
02962 {
02963     j2array[0]-=IK2PI;
02964 }
02965 else if( j2array[0] < -IKPI )
02966 {    j2array[0]+=IK2PI;
02967 }
02968 j2valid[0] = true;
02969 for(int ij2 = 0; ij2 < 1; ++ij2)
02970 {
02971 if( !j2valid[ij2] )
02972 {
02973     continue;
02974 }
02975 _ij2[0] = ij2; _ij2[1] = -1;
02976 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
02977 {
02978 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
02979 {
02980     j2valid[iij2]=false; _ij2[1] = iij2; break; 
02981 }
02982 }
02983 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
02984 {
02985 IkReal evalcond[4];
02986 IkReal x1122=IKsin(j2);
02987 IkReal x1123=IKcos(j2);
02988 IkReal x1124=((r00)*(sj0));
02989 IkReal x1125=((r01)*(sj0));
02990 IkReal x1126=((py)*(sj1));
02991 IkReal x1127=((IkReal(0.999999985550000))*(r02));
02992 IkReal x1128=((px)*(sj1));
02993 IkReal x1129=((IkReal(0.999999985550000))*(sj0));
02994 IkReal x1130=((IkReal(0.000169999997543500))*(cj0));
02995 IkReal x1131=((IkReal(0.000169999997543500))*(sj0));
02996 IkReal x1132=((cj1)*(px));
02997 IkReal x1133=((pz)*(sj1));
02998 IkReal x1134=((cj0)*(r00));
02999 IkReal x1135=((cj1)*(pz));
03000 IkReal x1136=((IkReal(1.00000000000000))*(r01));
03001 IkReal x1137=((cj1)*(py));
03002 IkReal x1138=((IkReal(0.999999985550000))*(cj0));
03003 IkReal x1139=((IkReal(0.106000000000000))*(x1122));
03004 IkReal x1140=((IkReal(0.106000000000000))*(x1123));
03005 IkReal x1141=((IkReal(0.112000000000000))*(x1123));
03006 IkReal x1142=((IkReal(0.112000000000000))*(x1122));
03007 IkReal x1143=((cj3)*(x1142));
03008 IkReal x1144=((sj3)*(x1141));
03009 IkReal x1145=((cj3)*(x1141));
03010 IkReal x1146=((sj3)*(x1142));
03011 IkReal x1147=((x1140)+(x1145));
03012 IkReal x1148=((x1143)+(x1144)+(x1139));
03013 evalcond[0]=((x1148)+(x1133)+(((x1130)*(x1132)))+(((x1131)*(x1137)))+(((x1137)*(x1138)))+(((IkReal(-1.00000000000000))*(x1129)*(x1132))));
03014 evalcond[1]=((IkReal(-0.106000000000000))+(x1146)+(x1135)+(((IkReal(-1.00000000000000))*(x1147)))+(((IkReal(-1.00000000000000))*(x1126)*(x1131)))+(((IkReal(-1.00000000000000))*(x1126)*(x1138)))+(((x1128)*(x1129)))+(((IkReal(-1.00000000000000))*(x1128)*(x1130))));
03015 evalcond[2]=((((r02)*(x1126)*(x1130)))+(x1148)+(((r00)*(x1137)))+(((IkReal(-1.00000000000000))*(r01)*(x1130)*(x1133)))+(((IkReal(0.000169999997543500))*(x1124)*(x1133)))+(((IkReal(-1.00000000000000))*(r02)*(x1128)*(x1131)))+(((IkReal(0.999999985550000))*(x1125)*(x1133)))+(((IkReal(-1.00000000000000))*(sj0)*(x1126)*(x1127)))+(((IkReal(-1.00000000000000))*(x1132)*(x1136)))+(((IkReal(0.999999985550000))*(x1133)*(x1134)))+(((IkReal(-1.00000000000000))*(cj0)*(x1127)*(x1128))));
03016 evalcond[3]=((x1147)+(((r00)*(x1126)))+(((IkReal(-0.999999985550000))*(x1134)*(x1135)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(1.80199997396110e-5))*(x1124)))+(((r02)*(x1131)*(x1132)))+(((cj0)*(x1127)*(x1132)))+(((IkReal(0.105999998468300))*(x1125)))+(((IkReal(0.105999998468300))*(x1134)))+(((r01)*(x1130)*(x1135)))+(((IkReal(-1.00000000000000))*(x1146)))+(((IkReal(-1.00000000000000))*(r02)*(x1130)*(x1137)))+(((IkReal(-0.000169999997543500))*(x1124)*(x1135)))+(((IkReal(-1.00000000000000))*(x1128)*(x1136)))+(((IkReal(-0.999999985550000))*(x1125)*(x1135)))+(((sj0)*(x1127)*(x1137))));
03017 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03018 {
03019 continue;
03020 }
03021 }
03022 
03023 {
03024 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03025 vinfos[0].jointtype = 1;
03026 vinfos[0].foffset = j0;
03027 vinfos[0].indices[0] = _ij0[0];
03028 vinfos[0].indices[1] = _ij0[1];
03029 vinfos[0].maxsolutions = _nj0;
03030 vinfos[1].jointtype = 1;
03031 vinfos[1].foffset = j1;
03032 vinfos[1].indices[0] = _ij1[0];
03033 vinfos[1].indices[1] = _ij1[1];
03034 vinfos[1].maxsolutions = _nj1;
03035 vinfos[2].jointtype = 1;
03036 vinfos[2].foffset = j2;
03037 vinfos[2].indices[0] = _ij2[0];
03038 vinfos[2].indices[1] = _ij2[1];
03039 vinfos[2].maxsolutions = _nj2;
03040 vinfos[3].jointtype = 1;
03041 vinfos[3].foffset = j3;
03042 vinfos[3].indices[0] = _ij3[0];
03043 vinfos[3].indices[1] = _ij3[1];
03044 vinfos[3].maxsolutions = _nj3;
03045 vinfos[4].jointtype = 1;
03046 vinfos[4].foffset = j5;
03047 vinfos[4].indices[0] = _ij5[0];
03048 vinfos[4].indices[1] = _ij5[1];
03049 vinfos[4].maxsolutions = _nj5;
03050 std::vector<int> vfree(0);
03051 solutions.AddSolution(vinfos,vfree);
03052 }
03053 }
03054 }
03055 
03056 }
03057 
03058 }
03059 
03060 } else
03061 {
03062 {
03063 IkReal j2array[1], cj2array[1], sj2array[1];
03064 bool j2valid[1]={false};
03065 _nj2 = 1;
03066 IkReal x1149=((cj0)*(sj1));
03067 IkReal x1150=((IkReal(0.281562495931422))*(px));
03068 IkReal x1151=((cj1)*(sj0));
03069 IkReal x1152=((IkReal(0.281562495931422))*(py));
03070 IkReal x1153=((IkReal(1656.24997606719))*(px));
03071 IkReal x1154=((IkReal(1656.24997606719))*(py));
03072 IkReal x1155=((cj0)*(cj1));
03073 IkReal x1156=((IkReal(1749.99997471250))*(px));
03074 IkReal x1157=((IkReal(0.297499995701125))*(px));
03075 IkReal x1158=((IkReal(1749.99997471250))*(py));
03076 IkReal x1159=((IkReal(0.297499995701125))*(py));
03077 IkReal x1160=((sj0)*(sj1));
03078 IkReal x1161=((IkReal(1656.25000000000))*(pz));
03079 IkReal x1162=((IkReal(1750.00000000000))*(cj3)*(pz));
03080 IkReal x1163=((IkReal(1750.00000000000))*(pz)*(sj3));
03081 IkReal x1164=((sj3)*(x1160));
03082 IkReal x1165=((cj3)*(x1160));
03083 if( IKabs(((gconst5)*(((((cj1)*(x1163)))+(((sj1)*(x1162)))+(((sj1)*(x1161)))+(((IkReal(-1.00000000000000))*(x1159)*(x1164)))+(((IkReal(-185.500000000000))*(sj3)))+(((x1156)*(x1164)))+(((x1150)*(x1155)))+(((x1151)*(x1152)))+(((cj3)*(x1151)*(x1159)))+(((IkReal(-1.00000000000000))*(sj3)*(x1149)*(x1157)))+(((IkReal(-1.00000000000000))*(sj3)*(x1149)*(x1158)))+(((cj3)*(x1155)*(x1157)))+(((cj3)*(x1155)*(x1158)))+(((IkReal(-1.00000000000000))*(x1151)*(x1153)))+(((x1154)*(x1155)))+(((IkReal(-1.00000000000000))*(cj3)*(x1151)*(x1156))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x1156)*(x1165)))+(((x1159)*(x1165)))+(((x1149)*(x1154)))+(((x1149)*(x1150)))+(((sj1)*(x1163)))+(((cj3)*(x1149)*(x1158)))+(((cj3)*(x1149)*(x1157)))+(((sj3)*(x1155)*(x1157)))+(((sj3)*(x1155)*(x1158)))+(((sj3)*(x1151)*(x1159)))+(((IkReal(-1.00000000000000))*(x1153)*(x1160)))+(((IkReal(-1.00000000000000))*(cj1)*(x1161)))+(((IkReal(-1.00000000000000))*(cj1)*(x1162)))+(((x1152)*(x1160)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1151)*(x1156))))))) < IKFAST_ATAN2_MAGTHRESH )
03084     continue;
03085 j2array[0]=IKatan2(((gconst5)*(((((cj1)*(x1163)))+(((sj1)*(x1162)))+(((sj1)*(x1161)))+(((IkReal(-1.00000000000000))*(x1159)*(x1164)))+(((IkReal(-185.500000000000))*(sj3)))+(((x1156)*(x1164)))+(((x1150)*(x1155)))+(((x1151)*(x1152)))+(((cj3)*(x1151)*(x1159)))+(((IkReal(-1.00000000000000))*(sj3)*(x1149)*(x1157)))+(((IkReal(-1.00000000000000))*(sj3)*(x1149)*(x1158)))+(((cj3)*(x1155)*(x1157)))+(((cj3)*(x1155)*(x1158)))+(((IkReal(-1.00000000000000))*(x1151)*(x1153)))+(((x1154)*(x1155)))+(((IkReal(-1.00000000000000))*(cj3)*(x1151)*(x1156)))))), ((gconst5)*(((IkReal(175.562500000000))+(((IkReal(-1.00000000000000))*(x1156)*(x1165)))+(((x1159)*(x1165)))+(((x1149)*(x1154)))+(((x1149)*(x1150)))+(((sj1)*(x1163)))+(((cj3)*(x1149)*(x1158)))+(((cj3)*(x1149)*(x1157)))+(((sj3)*(x1155)*(x1157)))+(((sj3)*(x1155)*(x1158)))+(((sj3)*(x1151)*(x1159)))+(((IkReal(-1.00000000000000))*(x1153)*(x1160)))+(((IkReal(-1.00000000000000))*(cj1)*(x1161)))+(((IkReal(-1.00000000000000))*(cj1)*(x1162)))+(((x1152)*(x1160)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1151)*(x1156)))))));
03086 sj2array[0]=IKsin(j2array[0]);
03087 cj2array[0]=IKcos(j2array[0]);
03088 if( j2array[0] > IKPI )
03089 {
03090     j2array[0]-=IK2PI;
03091 }
03092 else if( j2array[0] < -IKPI )
03093 {    j2array[0]+=IK2PI;
03094 }
03095 j2valid[0] = true;
03096 for(int ij2 = 0; ij2 < 1; ++ij2)
03097 {
03098 if( !j2valid[ij2] )
03099 {
03100     continue;
03101 }
03102 _ij2[0] = ij2; _ij2[1] = -1;
03103 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03104 {
03105 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03106 {
03107     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03108 }
03109 }
03110 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03111 {
03112 IkReal evalcond[4];
03113 IkReal x1166=IKsin(j2);
03114 IkReal x1167=IKcos(j2);
03115 IkReal x1168=((r00)*(sj0));
03116 IkReal x1169=((r01)*(sj0));
03117 IkReal x1170=((py)*(sj1));
03118 IkReal x1171=((IkReal(0.999999985550000))*(r02));
03119 IkReal x1172=((px)*(sj1));
03120 IkReal x1173=((IkReal(0.999999985550000))*(sj0));
03121 IkReal x1174=((IkReal(0.000169999997543500))*(cj0));
03122 IkReal x1175=((IkReal(0.000169999997543500))*(sj0));
03123 IkReal x1176=((cj1)*(px));
03124 IkReal x1177=((pz)*(sj1));
03125 IkReal x1178=((cj0)*(r00));
03126 IkReal x1179=((cj1)*(pz));
03127 IkReal x1180=((IkReal(1.00000000000000))*(r01));
03128 IkReal x1181=((cj1)*(py));
03129 IkReal x1182=((IkReal(0.999999985550000))*(cj0));
03130 IkReal x1183=((IkReal(0.106000000000000))*(x1166));
03131 IkReal x1184=((IkReal(0.106000000000000))*(x1167));
03132 IkReal x1185=((IkReal(0.112000000000000))*(x1167));
03133 IkReal x1186=((IkReal(0.112000000000000))*(x1166));
03134 IkReal x1187=((cj3)*(x1186));
03135 IkReal x1188=((sj3)*(x1185));
03136 IkReal x1189=((cj3)*(x1185));
03137 IkReal x1190=((sj3)*(x1186));
03138 IkReal x1191=((x1189)+(x1184));
03139 IkReal x1192=((x1188)+(x1187)+(x1183));
03140 evalcond[0]=((x1192)+(x1177)+(((IkReal(-1.00000000000000))*(x1173)*(x1176)))+(((x1174)*(x1176)))+(((x1175)*(x1181)))+(((x1181)*(x1182))));
03141 evalcond[1]=((IkReal(-0.106000000000000))+(x1190)+(x1179)+(((IkReal(-1.00000000000000))*(x1172)*(x1174)))+(((IkReal(-1.00000000000000))*(x1191)))+(((x1172)*(x1173)))+(((IkReal(-1.00000000000000))*(x1170)*(x1175)))+(((IkReal(-1.00000000000000))*(x1170)*(x1182))));
03142 evalcond[2]=((((IkReal(-1.00000000000000))*(x1176)*(x1180)))+(x1192)+(((IkReal(-1.00000000000000))*(r02)*(x1172)*(x1175)))+(((r00)*(x1181)))+(((IkReal(-1.00000000000000))*(r01)*(x1174)*(x1177)))+(((IkReal(0.000169999997543500))*(x1168)*(x1177)))+(((r02)*(x1170)*(x1174)))+(((IkReal(-1.00000000000000))*(sj0)*(x1170)*(x1171)))+(((IkReal(0.999999985550000))*(x1177)*(x1178)))+(((IkReal(-1.00000000000000))*(cj0)*(x1171)*(x1172)))+(((IkReal(0.999999985550000))*(x1169)*(x1177))));
03143 evalcond[3]=((((IkReal(-0.999999985550000))*(x1169)*(x1179)))+(x1191)+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(r02)*(x1174)*(x1181)))+(((r00)*(x1170)))+(((IkReal(1.80199997396110e-5))*(x1168)))+(((IkReal(-1.00000000000000))*(x1190)))+(((sj0)*(x1171)*(x1181)))+(((IkReal(0.105999998468300))*(x1169)))+(((IkReal(-1.00000000000000))*(x1172)*(x1180)))+(((IkReal(0.105999998468300))*(x1178)))+(((cj0)*(x1171)*(x1176)))+(((IkReal(-0.999999985550000))*(x1178)*(x1179)))+(((IkReal(-0.000169999997543500))*(x1168)*(x1179)))+(((r01)*(x1174)*(x1179)))+(((r02)*(x1175)*(x1176))));
03144 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03145 {
03146 continue;
03147 }
03148 }
03149 
03150 {
03151 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03152 vinfos[0].jointtype = 1;
03153 vinfos[0].foffset = j0;
03154 vinfos[0].indices[0] = _ij0[0];
03155 vinfos[0].indices[1] = _ij0[1];
03156 vinfos[0].maxsolutions = _nj0;
03157 vinfos[1].jointtype = 1;
03158 vinfos[1].foffset = j1;
03159 vinfos[1].indices[0] = _ij1[0];
03160 vinfos[1].indices[1] = _ij1[1];
03161 vinfos[1].maxsolutions = _nj1;
03162 vinfos[2].jointtype = 1;
03163 vinfos[2].foffset = j2;
03164 vinfos[2].indices[0] = _ij2[0];
03165 vinfos[2].indices[1] = _ij2[1];
03166 vinfos[2].maxsolutions = _nj2;
03167 vinfos[3].jointtype = 1;
03168 vinfos[3].foffset = j3;
03169 vinfos[3].indices[0] = _ij3[0];
03170 vinfos[3].indices[1] = _ij3[1];
03171 vinfos[3].maxsolutions = _nj3;
03172 vinfos[4].jointtype = 1;
03173 vinfos[4].foffset = j5;
03174 vinfos[4].indices[0] = _ij5[0];
03175 vinfos[4].indices[1] = _ij5[1];
03176 vinfos[4].maxsolutions = _nj5;
03177 std::vector<int> vfree(0);
03178 solutions.AddSolution(vinfos,vfree);
03179 }
03180 }
03181 }
03182 
03183 }
03184 
03185 }
03186 
03187 } else
03188 {
03189 if( 1 )
03190 {
03191 continue;
03192 
03193 } else
03194 {
03195 }
03196 }
03197 }
03198 }
03199 
03200 } else
03201 {
03202 {
03203 IkReal j2array[1], cj2array[1], sj2array[1];
03204 bool j2valid[1]={false};
03205 _nj2 = 1;
03206 IkReal x1193=((cj0)*(py));
03207 IkReal x1194=((r02)*(sj1));
03208 IkReal x1195=((px)*(sj0));
03209 IkReal x1196=((IkReal(13.9999997977000))*(r00));
03210 IkReal x1197=((IkReal(1.69999943143527e-5))*(cj5));
03211 IkReal x1198=((cj0)*(cj1));
03212 IkReal x1199=((IkReal(0.00237999996560900))*(r01));
03213 IkReal x1200=((cj3)*(px));
03214 IkReal x1201=((IkReal(13.9999997977000))*(r01));
03215 IkReal x1202=((cj1)*(sj0));
03216 IkReal x1203=((px)*(sj3));
03217 IkReal x1204=((IkReal(0.00237999996560900))*(r00));
03218 IkReal x1205=((IkReal(0.0212499928929409))*(cj5));
03219 IkReal x1206=((cj3)*(py));
03220 IkReal x1207=((sj3)*(x1202));
03221 IkReal x1208=((IkReal(0.0999999665550159))*(cj1)*(cj5)*(sj3));
03222 IkReal x1209=((cj5)*(pz)*(sj1)*(sj3));
03223 IkReal x1210=((IkReal(0.0999999665550159))*(cj1)*(cj3)*(cj5));
03224 IkReal x1211=((cj3)*(cj5)*(pz)*(sj1));
03225 IkReal x1212=((IkReal(124.999958193770))*(cj1)*(cj5)*(sj3));
03226 IkReal x1213=((IkReal(124.999958193770))*(cj1)*(cj3)*(cj5));
03227 if( IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x1197)*(x1198)*(x1203)))+(((IkReal(14.0000000000000))*(sj3)*(x1194)))+(((sj3)*(x1198)*(x1201)))+(((sj3)*(x1198)*(x1204)))+(((IkReal(-0.0999999680000154))*(x1209)))+(((IkReal(-1.00000000000000))*(x1196)*(x1207)))+(((x1202)*(x1205)*(x1206)))+(((x1193)*(x1213)))+(((x1199)*(x1207)))+(((IkReal(-1.00000000000000))*(py)*(x1197)*(x1207)))+(((x1195)*(x1208)))+(((x1198)*(x1200)*(x1205)))+(((IkReal(-1.00000000000000))*(x1195)*(x1213)))+(((IkReal(124.999960000019))*(x1211)))+(((IkReal(-1.00000000000000))*(x1193)*(x1208))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-14.0000000000000))*(cj3)*(x1194)))+(((IkReal(124.999960000019))*(x1209)))+(((x1193)*(x1210)))+(((x1193)*(x1212)))+(((IkReal(-1.00000000000000))*(cj3)*(x1199)*(x1202)))+(((py)*(x1205)*(x1207)))+(((IkReal(0.0999999680000154))*(x1211)))+(((x1197)*(x1198)*(x1200)))+(((x1198)*(x1203)*(x1205)))+(((IkReal(13.2499998085375))*(r00)*(x1202)))+(((IkReal(-13.2499998085375))*(r01)*(x1198)))+(((x1197)*(x1202)*(x1206)))+(((IkReal(-0.00225249996745138))*(r00)*(x1198)))+(((IkReal(-0.00225249996745138))*(r01)*(x1202)))+(((IkReal(-1.00000000000000))*(x1195)*(x1212)))+(((IkReal(-1.00000000000000))*(x1195)*(x1210)))+(((cj3)*(x1196)*(x1202)))+(((IkReal(-13.2500000000000))*(x1194)))+(((IkReal(-1.00000000000000))*(cj3)*(x1198)*(x1201)))+(((IkReal(-1.00000000000000))*(cj3)*(x1198)*(x1204))))))) < IKFAST_ATAN2_MAGTHRESH )
03228     continue;
03229 j2array[0]=IKatan2(((gconst2)*(((((IkReal(-1.00000000000000))*(x1197)*(x1198)*(x1203)))+(((IkReal(14.0000000000000))*(sj3)*(x1194)))+(((sj3)*(x1198)*(x1201)))+(((sj3)*(x1198)*(x1204)))+(((IkReal(-0.0999999680000154))*(x1209)))+(((IkReal(-1.00000000000000))*(x1196)*(x1207)))+(((x1202)*(x1205)*(x1206)))+(((x1193)*(x1213)))+(((x1199)*(x1207)))+(((IkReal(-1.00000000000000))*(py)*(x1197)*(x1207)))+(((x1195)*(x1208)))+(((x1198)*(x1200)*(x1205)))+(((IkReal(-1.00000000000000))*(x1195)*(x1213)))+(((IkReal(124.999960000019))*(x1211)))+(((IkReal(-1.00000000000000))*(x1193)*(x1208)))))), ((gconst2)*(((((IkReal(-14.0000000000000))*(cj3)*(x1194)))+(((IkReal(124.999960000019))*(x1209)))+(((x1193)*(x1210)))+(((x1193)*(x1212)))+(((IkReal(-1.00000000000000))*(cj3)*(x1199)*(x1202)))+(((py)*(x1205)*(x1207)))+(((IkReal(0.0999999680000154))*(x1211)))+(((x1197)*(x1198)*(x1200)))+(((x1198)*(x1203)*(x1205)))+(((IkReal(13.2499998085375))*(r00)*(x1202)))+(((IkReal(-13.2499998085375))*(r01)*(x1198)))+(((x1197)*(x1202)*(x1206)))+(((IkReal(-0.00225249996745138))*(r00)*(x1198)))+(((IkReal(-0.00225249996745138))*(r01)*(x1202)))+(((IkReal(-1.00000000000000))*(x1195)*(x1212)))+(((IkReal(-1.00000000000000))*(x1195)*(x1210)))+(((cj3)*(x1196)*(x1202)))+(((IkReal(-13.2500000000000))*(x1194)))+(((IkReal(-1.00000000000000))*(cj3)*(x1198)*(x1201)))+(((IkReal(-1.00000000000000))*(cj3)*(x1198)*(x1204)))))));
03230 sj2array[0]=IKsin(j2array[0]);
03231 cj2array[0]=IKcos(j2array[0]);
03232 if( j2array[0] > IKPI )
03233 {
03234     j2array[0]-=IK2PI;
03235 }
03236 else if( j2array[0] < -IKPI )
03237 {    j2array[0]+=IK2PI;
03238 }
03239 j2valid[0] = true;
03240 for(int ij2 = 0; ij2 < 1; ++ij2)
03241 {
03242 if( !j2valid[ij2] )
03243 {
03244     continue;
03245 }
03246 _ij2[0] = ij2; _ij2[1] = -1;
03247 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03248 {
03249 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03250 {
03251     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03252 }
03253 }
03254 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03255 {
03256 IkReal evalcond[8];
03257 IkReal x1214=IKsin(j2);
03258 IkReal x1215=IKcos(j2);
03259 IkReal x1216=(py)*(py);
03260 IkReal x1217=(pz)*(pz);
03261 IkReal x1218=(px)*(px);
03262 IkReal x1219=((cj0)*(r00));
03263 IkReal x1220=((IkReal(3.60399994792220e-5))*(pz));
03264 IkReal x1221=((r01)*(sj0));
03265 IkReal x1222=((cj3)*(cj5));
03266 IkReal x1223=((sj0)*(sj1));
03267 IkReal x1224=((IkReal(0.999999985550000))*(px));
03268 IkReal x1225=((IkReal(0.000339999995087000))*(py));
03269 IkReal x1226=((pz)*(r02));
03270 IkReal x1227=((py)*(sj1));
03271 IkReal x1228=((IkReal(0.000169999997543500))*(sj1));
03272 IkReal x1229=((IkReal(0.999999680000154))*(cj5));
03273 IkReal x1230=((px)*(r00));
03274 IkReal x1231=((IkReal(0.000799999744000123))*(cj5));
03275 IkReal x1232=((IkReal(0.000169999997543500))*(cj1));
03276 IkReal x1233=((cj0)*(sj1));
03277 IkReal x1234=((IkReal(1.99999997110000))*(px));
03278 IkReal x1235=((IkReal(0.000169999997543500))*(pz));
03279 IkReal x1236=((IkReal(0.112000000000000))*(sj5));
03280 IkReal x1237=((cj1)*(r02));
03281 IkReal x1238=((IkReal(0.106000000000000))*(sj5));
03282 IkReal x1239=((IkReal(0.000339999995087000))*(px));
03283 IkReal x1240=((IkReal(0.112000000000000))*(cj3));
03284 IkReal x1241=((cj1)*(py));
03285 IkReal x1242=((py)*(r02));
03286 IkReal x1243=((cj0)*(px));
03287 IkReal x1244=((px)*(r01));
03288 IkReal x1245=((cj0)*(r01));
03289 IkReal x1246=((IkReal(0.999999985550000))*(r01));
03290 IkReal x1247=((IkReal(0.999999985550000))*(pz));
03291 IkReal x1248=((r02)*(sj1));
03292 IkReal x1249=((cj1)*(sj0));
03293 IkReal x1250=((IkReal(1.99999997110000))*(cj0));
03294 IkReal x1251=((IkReal(0.000169999997543500))*(r02));
03295 IkReal x1252=((IkReal(1.04639966515216e-6))*(cj5));
03296 IkReal x1253=((IkReal(0.999999985550000))*(cj0));
03297 IkReal x1254=((IkReal(0.999999985550000))*(cj1));
03298 IkReal x1255=((cj1)*(pz));
03299 IkReal x1256=((py)*(sj0));
03300 IkReal x1257=((r00)*(sj0));
03301 IkReal x1258=((IkReal(1.91011997239877e-6))*(cj1));
03302 IkReal x1259=((IkReal(1.91011997239877e-6))*(sj1));
03303 IkReal x1260=((IkReal(0.00130799958144020))*(cj5));
03304 IkReal x1261=((IkReal(0.211999996936600))*(pz));
03305 IkReal x1262=((pz)*(sj1));
03306 IkReal x1263=((sj3)*(x1215));
03307 IkReal x1264=((cj1)*(x1244));
03308 IkReal x1265=((r00)*(x1249));
03309 IkReal x1266=((IkReal(0.999999985550000))*(x1217));
03310 IkReal x1267=((IkReal(2.00000000000000))*(pz)*(r01));
03311 IkReal x1268=((sj3)*(x1214));
03312 IkReal x1269=((cj5)*(x1215));
03313 IkReal x1270=((IkReal(0.999999985550000))*(x1216));
03314 IkReal x1271=((IkReal(2.00000000000000))*(x1217));
03315 IkReal x1272=((IkReal(0.999999985550000))*(x1218));
03316 IkReal x1273=((px)*(r02)*(sj0));
03317 IkReal x1274=((cj5)*(x1214));
03318 evalcond[0]=((((x1232)*(x1256)))+(x1262)+(((x1241)*(x1253)))+(((IkReal(0.112000000000000))*(x1263)))+(((x1232)*(x1243)))+(((x1214)*(x1240)))+(((IkReal(0.106000000000000))*(x1214)))+(((IkReal(-1.00000000000000))*(x1224)*(x1249))));
03319 evalcond[1]=((IkReal(-0.106000000000000))+(x1255)+(((x1223)*(x1224)))+(((IkReal(-1.00000000000000))*(x1227)*(x1253)))+(((IkReal(-1.00000000000000))*(x1228)*(x1243)))+(((IkReal(-0.000169999997543500))*(py)*(x1223)))+(((IkReal(-0.106000000000000))*(x1215)))+(((IkReal(0.112000000000000))*(x1268)))+(((IkReal(-1.00000000000000))*(x1215)*(x1240))));
03320 evalcond[2]=((((x1231)*(x1263)))+(x1248)+(((x1219)*(x1232)))+(((x1245)*(x1254)))+(((IkReal(-0.999999680000154))*(x1215)*(x1222)))+(((IkReal(-0.999999985550000))*(x1265)))+(((IkReal(0.000799999744000123))*(x1214)*(x1222)))+(((x1229)*(x1268)))+(((x1221)*(x1232))));
03321 evalcond[3]=((((x1231)*(x1268)))+(((IkReal(-0.999999680000154))*(x1214)*(x1222)))+(((IkReal(-1.00000000000000))*(x1229)*(x1263)))+(x1237)+(((IkReal(0.999999985550000))*(r00)*(x1223)))+(((IkReal(-1.00000000000000))*(x1233)*(x1246)))+(((IkReal(-1.00000000000000))*(x1221)*(x1228)))+(((IkReal(-0.000799999744000123))*(x1215)*(x1222)))+(((IkReal(-1.00000000000000))*(x1219)*(x1228))));
03322 evalcond[4]=((((IkReal(-0.999999985550000))*(x1223)*(x1242)))+(((IkReal(-1.00000000000000))*(x1214)*(x1238)))+(((IkReal(-1.00000000000000))*(px)*(x1223)*(x1251)))+(((r00)*(x1223)*(x1235)))+(((sj1)*(x1219)*(x1247)))+(((IkReal(-1.00000000000000))*(r02)*(x1224)*(x1233)))+(((r00)*(x1241)))+(((IkReal(-1.00000000000000))*(cj3)*(x1214)*(x1236)))+(((IkReal(-1.00000000000000))*(pz)*(x1228)*(x1245)))+(((IkReal(-1.00000000000000))*(x1264)))+(((cj0)*(x1227)*(x1251)))+(((sj1)*(x1221)*(x1247)))+(((IkReal(-1.00000000000000))*(x1236)*(x1263))));
03323 evalcond[5]=((((IkReal(1.80199997396110e-5))*(x1257)))+(((IkReal(-1.80199997396110e-5))*(x1245)))+(((IkReal(-1.00000000000000))*(cj0)*(x1232)*(x1242)))+(((r00)*(x1227)))+(((IkReal(-1.00000000000000))*(cj1)*(x1221)*(x1247)))+(((IkReal(-1.00000000000000))*(cj1)*(x1219)*(x1247)))+(((IkReal(-1.00000000000000))*(pz)*(x1232)*(x1257)))+(((IkReal(-1.00000000000000))*(x1215)*(x1238)))+(((IkReal(-1.00000000000000))*(cj3)*(x1215)*(x1236)))+(((IkReal(0.105999998468300))*(x1219)))+(((x1236)*(x1268)))+(((cj0)*(x1224)*(x1237)))+(((IkReal(0.999999985550000))*(x1237)*(x1256)))+(((x1232)*(x1273)))+(((pz)*(x1232)*(x1245)))+(((IkReal(-1.00000000000000))*(sj1)*(x1244)))+(((IkReal(0.105999998468300))*(x1221))));
03324 evalcond[6]=((((x1218)*(x1219)*(x1228)))+(((IkReal(1.89951939215389e-5))*(x1269)))+(((IkReal(-0.0237799923904037))*(x1214)*(x1222)))+(((IkReal(-1.00000000000000))*(x1216)*(x1219)*(x1228)))+(((IkReal(-1.00000000000000))*(x1218)*(x1221)*(x1228)))+(((IkReal(-0.0237439924019236))*(x1274)))+(((x1216)*(x1233)*(x1246)))+(((IkReal(-1.00000000000000))*(x1260)*(x1263)))+(((IkReal(-1.00000000000000))*(x1217)*(x1233)*(x1246)))+(((IkReal(-0.0112360000000000))*(x1237)))+(((x1219)*(x1227)*(x1234)))+(((IkReal(-1.00000000000000))*(x1241)*(x1267)))+(((IkReal(-1.00000000000000))*(x1218)*(x1233)*(x1246)))+(((x1221)*(x1259)))+(((IkReal(-0.0112359998376398))*(r00)*(x1223)))+(((r00)*(x1223)*(x1270)))+(((IkReal(-2.00000000000000))*(x1230)*(x1255)))+(((IkReal(-1.00000000000000))*(x1252)*(x1268)))+(((x1225)*(x1233)*(x1244)))+(((IkReal(-1.00000000000000))*(r00)*(x1223)*(x1272)))+(((IkReal(0.0112359998376398))*(r01)*(x1233)))+(((IkReal(-1.00000000000000))*(x1221)*(x1227)*(x1234)))+(((x1223)*(x1225)*(x1226)))+(((r00)*(x1223)*(x1266)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((IkReal(0.212000000000000))*(x1226)))+(((x1223)*(x1225)*(x1230)))+(((IkReal(-1.00000000000000))*(x1217)*(x1221)*(x1228)))+(((IkReal(1.90239939123229e-5))*(x1215)*(x1222)))+(((pp)*(x1237)))+(((x1226)*(x1227)*(x1250)))+(((IkReal(0.212000000000000))*(x1230)))+(((x1216)*(x1221)*(x1228)))+(((IkReal(-1.00000000000000))*(x1217)*(x1219)*(x1228)))+(((x1226)*(x1233)*(x1239)))+(((IkReal(-1.00000000000000))*(x1223)*(x1226)*(x1234)))+(((x1219)*(x1259)))+(((IkReal(-1.00000000000000))*(x1237)*(x1271))));
03325 evalcond[7]=((((IkReal(-1.89951939215389e-5))*(x1274)))+(((x1221)*(x1234)*(x1241)))+(((IkReal(-0.0237439924019236))*(x1269)))+(((x1265)*(x1272)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x1225)*(x1243)))+(((IkReal(3.60399994792220e-5))*(sj0)*(x1242)))+(((IkReal(-1.00000000000000))*(x1225)*(x1226)*(x1249)))+(((IkReal(-1.00000000000000))*(x1226)*(x1241)*(x1250)))+(((IkReal(-1.00000000000000))*(x1227)*(x1267)))+(((IkReal(-1.00000000000000))*(x1248)*(x1271)))+(((IkReal(-1.00000000000000))*(x1216)*(x1245)*(x1254)))+(((x1217)*(x1221)*(x1232)))+(((IkReal(-1.00000000000000))*(x1220)*(x1221)))+(((IkReal(-1.00000000000000))*(x1219)*(x1234)*(x1241)))+(((IkReal(-2.00000000000000))*(x1230)*(x1262)))+(((x1221)*(x1258)))+(((IkReal(0.211999996936600))*(cj0)*(x1242)))+(((pp)*(x1248)))+(((IkReal(-1.00000000000000))*(x1252)*(x1263)))+(((x1218)*(x1245)*(x1254)))+(((IkReal(-0.0112359998376398))*(x1265)))+(((x1217)*(x1245)*(x1254)))+(((x1216)*(x1219)*(x1232)))+(((IkReal(-1.00000000000000))*(x1245)*(x1261)))+(((x1260)*(x1268)))+(((IkReal(0.0112360000000000))*(x1248)))+(((IkReal(-1.00000000000000))*(x1216)*(x1221)*(x1232)))+(((x1217)*(x1219)*(x1232)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1243)))+(((IkReal(-1.00000000000000))*(x1265)*(x1266)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1226)*(x1239)))+(((IkReal(-0.211999996936600))*(x1273)))+(((IkReal(-0.0237799923904037))*(x1215)*(x1222)))+(((x1257)*(x1261)))+(((IkReal(-1.90239939123229e-5))*(x1214)*(x1222)))+(((IkReal(-1.00000000000000))*(x1265)*(x1270)))+(((IkReal(-1.00000000000000))*(x1218)*(x1219)*(x1232)))+(((IkReal(-1.00000000000000))*(x1219)*(x1220)))+(((IkReal(-1.00000000000000))*(x1225)*(x1230)*(x1249)))+(((x1219)*(x1258)))+(((x1218)*(x1221)*(x1232)))+(((IkReal(0.0112359998376398))*(cj1)*(x1245)))+(((x1226)*(x1234)*(x1249))));
03326 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  )
03327 {
03328 continue;
03329 }
03330 }
03331 
03332 {
03333 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03334 vinfos[0].jointtype = 1;
03335 vinfos[0].foffset = j0;
03336 vinfos[0].indices[0] = _ij0[0];
03337 vinfos[0].indices[1] = _ij0[1];
03338 vinfos[0].maxsolutions = _nj0;
03339 vinfos[1].jointtype = 1;
03340 vinfos[1].foffset = j1;
03341 vinfos[1].indices[0] = _ij1[0];
03342 vinfos[1].indices[1] = _ij1[1];
03343 vinfos[1].maxsolutions = _nj1;
03344 vinfos[2].jointtype = 1;
03345 vinfos[2].foffset = j2;
03346 vinfos[2].indices[0] = _ij2[0];
03347 vinfos[2].indices[1] = _ij2[1];
03348 vinfos[2].maxsolutions = _nj2;
03349 vinfos[3].jointtype = 1;
03350 vinfos[3].foffset = j3;
03351 vinfos[3].indices[0] = _ij3[0];
03352 vinfos[3].indices[1] = _ij3[1];
03353 vinfos[3].maxsolutions = _nj3;
03354 vinfos[4].jointtype = 1;
03355 vinfos[4].foffset = j5;
03356 vinfos[4].indices[0] = _ij5[0];
03357 vinfos[4].indices[1] = _ij5[1];
03358 vinfos[4].maxsolutions = _nj5;
03359 std::vector<int> vfree(0);
03360 solutions.AddSolution(vinfos,vfree);
03361 }
03362 }
03363 }
03364 
03365 }
03366 
03367 }
03368 
03369 } else
03370 {
03371 {
03372 IkReal j2array[1], cj2array[1], sj2array[1];
03373 bool j2valid[1]={false};
03374 _nj2 = 1;
03375 IkReal x1275=((cj0)*(sj1));
03376 IkReal x1276=((IkReal(0.281562495931422))*(px));
03377 IkReal x1277=((IkReal(1750.00000000000))*(pz));
03378 IkReal x1278=((sj1)*(sj3));
03379 IkReal x1279=((cj1)*(cj3));
03380 IkReal x1280=((IkReal(1656.24997606719))*(cj1));
03381 IkReal x1281=((px)*(sj0));
03382 IkReal x1282=((cj3)*(sj1));
03383 IkReal x1283=((cj0)*(py));
03384 IkReal x1284=((cj1)*(sj3));
03385 IkReal x1285=((py)*(sj0));
03386 IkReal x1286=((IkReal(0.297499995701125))*(px));
03387 IkReal x1287=((IkReal(1749.99997471250))*(py));
03388 IkReal x1288=((IkReal(1656.25000000000))*(pz));
03389 if( IKabs(((gconst1)*(((((IkReal(1749.99997471250))*(x1278)*(x1281)))+(((IkReal(1749.99997471250))*(x1279)*(x1283)))+(((IkReal(-1749.99997471250))*(x1279)*(x1281)))+(((cj0)*(x1279)*(x1286)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1275)*(x1287)))+(((IkReal(-1.00000000000000))*(sj3)*(x1275)*(x1286)))+(((cj0)*(cj1)*(x1276)))+(((IkReal(0.297499995701125))*(x1279)*(x1285)))+(((x1277)*(x1284)))+(((x1277)*(x1282)))+(((IkReal(-0.297499995701125))*(x1278)*(x1285)))+(((sj1)*(x1288)))+(((x1280)*(x1283)))+(((IkReal(0.281562495931422))*(cj1)*(x1285)))+(((IkReal(-1.00000000000000))*(x1280)*(x1281))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((IkReal(175.562500000000))+(((x1275)*(x1276)))+(((x1277)*(x1278)))+(((IkReal(0.297499995701125))*(x1282)*(x1285)))+(((cj3)*(x1275)*(x1286)))+(((cj3)*(x1275)*(x1287)))+(((IkReal(0.281562495931422))*(sj1)*(x1285)))+(((IkReal(-1656.24997606719))*(sj1)*(x1281)))+(((IkReal(-1.00000000000000))*(cj1)*(x1288)))+(((IkReal(-1.00000000000000))*(x1277)*(x1279)))+(((IkReal(0.297499995701125))*(x1284)*(x1285)))+(((IkReal(1656.24997606719))*(py)*(x1275)))+(((IkReal(-1749.99997471250))*(x1281)*(x1282)))+(((IkReal(-1749.99997471250))*(x1281)*(x1284)))+(((IkReal(1749.99997471250))*(x1283)*(x1284)))+(((IkReal(185.500000000000))*(cj3)))+(((cj0)*(x1284)*(x1286))))))) < IKFAST_ATAN2_MAGTHRESH )
03390     continue;
03391 j2array[0]=IKatan2(((gconst1)*(((((IkReal(1749.99997471250))*(x1278)*(x1281)))+(((IkReal(1749.99997471250))*(x1279)*(x1283)))+(((IkReal(-1749.99997471250))*(x1279)*(x1281)))+(((cj0)*(x1279)*(x1286)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1275)*(x1287)))+(((IkReal(-1.00000000000000))*(sj3)*(x1275)*(x1286)))+(((cj0)*(cj1)*(x1276)))+(((IkReal(0.297499995701125))*(x1279)*(x1285)))+(((x1277)*(x1284)))+(((x1277)*(x1282)))+(((IkReal(-0.297499995701125))*(x1278)*(x1285)))+(((sj1)*(x1288)))+(((x1280)*(x1283)))+(((IkReal(0.281562495931422))*(cj1)*(x1285)))+(((IkReal(-1.00000000000000))*(x1280)*(x1281)))))), ((gconst1)*(((IkReal(175.562500000000))+(((x1275)*(x1276)))+(((x1277)*(x1278)))+(((IkReal(0.297499995701125))*(x1282)*(x1285)))+(((cj3)*(x1275)*(x1286)))+(((cj3)*(x1275)*(x1287)))+(((IkReal(0.281562495931422))*(sj1)*(x1285)))+(((IkReal(-1656.24997606719))*(sj1)*(x1281)))+(((IkReal(-1.00000000000000))*(cj1)*(x1288)))+(((IkReal(-1.00000000000000))*(x1277)*(x1279)))+(((IkReal(0.297499995701125))*(x1284)*(x1285)))+(((IkReal(1656.24997606719))*(py)*(x1275)))+(((IkReal(-1749.99997471250))*(x1281)*(x1282)))+(((IkReal(-1749.99997471250))*(x1281)*(x1284)))+(((IkReal(1749.99997471250))*(x1283)*(x1284)))+(((IkReal(185.500000000000))*(cj3)))+(((cj0)*(x1284)*(x1286)))))));
03392 sj2array[0]=IKsin(j2array[0]);
03393 cj2array[0]=IKcos(j2array[0]);
03394 if( j2array[0] > IKPI )
03395 {
03396     j2array[0]-=IK2PI;
03397 }
03398 else if( j2array[0] < -IKPI )
03399 {    j2array[0]+=IK2PI;
03400 }
03401 j2valid[0] = true;
03402 for(int ij2 = 0; ij2 < 1; ++ij2)
03403 {
03404 if( !j2valid[ij2] )
03405 {
03406     continue;
03407 }
03408 _ij2[0] = ij2; _ij2[1] = -1;
03409 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03410 {
03411 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03412 {
03413     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03414 }
03415 }
03416 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03417 {
03418 IkReal evalcond[8];
03419 IkReal x1289=IKsin(j2);
03420 IkReal x1290=IKcos(j2);
03421 IkReal x1291=(py)*(py);
03422 IkReal x1292=(pz)*(pz);
03423 IkReal x1293=(px)*(px);
03424 IkReal x1294=((cj0)*(r00));
03425 IkReal x1295=((IkReal(3.60399994792220e-5))*(pz));
03426 IkReal x1296=((r01)*(sj0));
03427 IkReal x1297=((cj3)*(cj5));
03428 IkReal x1298=((sj0)*(sj1));
03429 IkReal x1299=((IkReal(0.999999985550000))*(px));
03430 IkReal x1300=((IkReal(0.000339999995087000))*(py));
03431 IkReal x1301=((pz)*(r02));
03432 IkReal x1302=((py)*(sj1));
03433 IkReal x1303=((IkReal(0.000169999997543500))*(sj1));
03434 IkReal x1304=((IkReal(0.999999680000154))*(cj5));
03435 IkReal x1305=((px)*(r00));
03436 IkReal x1306=((IkReal(0.000799999744000123))*(cj5));
03437 IkReal x1307=((IkReal(0.000169999997543500))*(cj1));
03438 IkReal x1308=((cj0)*(sj1));
03439 IkReal x1309=((IkReal(1.99999997110000))*(px));
03440 IkReal x1310=((IkReal(0.000169999997543500))*(pz));
03441 IkReal x1311=((IkReal(0.112000000000000))*(sj5));
03442 IkReal x1312=((cj1)*(r02));
03443 IkReal x1313=((IkReal(0.106000000000000))*(sj5));
03444 IkReal x1314=((IkReal(0.000339999995087000))*(px));
03445 IkReal x1315=((IkReal(0.112000000000000))*(cj3));
03446 IkReal x1316=((cj1)*(py));
03447 IkReal x1317=((py)*(r02));
03448 IkReal x1318=((cj0)*(px));
03449 IkReal x1319=((px)*(r01));
03450 IkReal x1320=((cj0)*(r01));
03451 IkReal x1321=((IkReal(0.999999985550000))*(r01));
03452 IkReal x1322=((IkReal(0.999999985550000))*(pz));
03453 IkReal x1323=((r02)*(sj1));
03454 IkReal x1324=((cj1)*(sj0));
03455 IkReal x1325=((IkReal(1.99999997110000))*(cj0));
03456 IkReal x1326=((IkReal(0.000169999997543500))*(r02));
03457 IkReal x1327=((IkReal(1.04639966515216e-6))*(cj5));
03458 IkReal x1328=((IkReal(0.999999985550000))*(cj0));
03459 IkReal x1329=((IkReal(0.999999985550000))*(cj1));
03460 IkReal x1330=((cj1)*(pz));
03461 IkReal x1331=((py)*(sj0));
03462 IkReal x1332=((r00)*(sj0));
03463 IkReal x1333=((IkReal(1.91011997239877e-6))*(cj1));
03464 IkReal x1334=((IkReal(1.91011997239877e-6))*(sj1));
03465 IkReal x1335=((IkReal(0.00130799958144020))*(cj5));
03466 IkReal x1336=((IkReal(0.211999996936600))*(pz));
03467 IkReal x1337=((pz)*(sj1));
03468 IkReal x1338=((sj3)*(x1290));
03469 IkReal x1339=((cj1)*(x1319));
03470 IkReal x1340=((r00)*(x1324));
03471 IkReal x1341=((IkReal(0.999999985550000))*(x1292));
03472 IkReal x1342=((IkReal(2.00000000000000))*(pz)*(r01));
03473 IkReal x1343=((sj3)*(x1289));
03474 IkReal x1344=((cj5)*(x1290));
03475 IkReal x1345=((IkReal(0.999999985550000))*(x1291));
03476 IkReal x1346=((IkReal(2.00000000000000))*(x1292));
03477 IkReal x1347=((IkReal(0.999999985550000))*(x1293));
03478 IkReal x1348=((px)*(r02)*(sj0));
03479 IkReal x1349=((cj5)*(x1289));
03480 evalcond[0]=((x1337)+(((x1316)*(x1328)))+(((IkReal(0.112000000000000))*(x1338)))+(((x1289)*(x1315)))+(((x1307)*(x1318)))+(((x1307)*(x1331)))+(((IkReal(-1.00000000000000))*(x1299)*(x1324)))+(((IkReal(0.106000000000000))*(x1289))));
03481 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-0.106000000000000))*(x1290)))+(x1330)+(((IkReal(-0.000169999997543500))*(py)*(x1298)))+(((IkReal(0.112000000000000))*(x1343)))+(((IkReal(-1.00000000000000))*(x1303)*(x1318)))+(((IkReal(-1.00000000000000))*(x1290)*(x1315)))+(((IkReal(-1.00000000000000))*(x1302)*(x1328)))+(((x1298)*(x1299))));
03482 evalcond[2]=((x1323)+(((x1320)*(x1329)))+(((x1306)*(x1338)))+(((IkReal(-0.999999680000154))*(x1290)*(x1297)))+(((IkReal(-0.999999985550000))*(x1340)))+(((x1294)*(x1307)))+(((IkReal(0.000799999744000123))*(x1289)*(x1297)))+(((x1296)*(x1307)))+(((x1304)*(x1343))));
03483 evalcond[3]=((x1312)+(((IkReal(-0.999999680000154))*(x1289)*(x1297)))+(((IkReal(-1.00000000000000))*(x1308)*(x1321)))+(((IkReal(-0.000799999744000123))*(x1290)*(x1297)))+(((IkReal(0.999999985550000))*(r00)*(x1298)))+(((IkReal(-1.00000000000000))*(x1296)*(x1303)))+(((IkReal(-1.00000000000000))*(x1294)*(x1303)))+(((x1306)*(x1343)))+(((IkReal(-1.00000000000000))*(x1304)*(x1338))));
03484 evalcond[4]=((((r00)*(x1316)))+(((IkReal(-1.00000000000000))*(cj3)*(x1289)*(x1311)))+(((r00)*(x1298)*(x1310)))+(((IkReal(-1.00000000000000))*(x1339)))+(((IkReal(-1.00000000000000))*(r02)*(x1299)*(x1308)))+(((sj1)*(x1296)*(x1322)))+(((sj1)*(x1294)*(x1322)))+(((cj0)*(x1302)*(x1326)))+(((IkReal(-1.00000000000000))*(px)*(x1298)*(x1326)))+(((IkReal(-0.999999985550000))*(x1298)*(x1317)))+(((IkReal(-1.00000000000000))*(pz)*(x1303)*(x1320)))+(((IkReal(-1.00000000000000))*(x1289)*(x1313)))+(((IkReal(-1.00000000000000))*(x1311)*(x1338))));
03485 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(x1307)*(x1317)))+(((IkReal(-1.00000000000000))*(pz)*(x1307)*(x1332)))+(((cj0)*(x1299)*(x1312)))+(((IkReal(-1.00000000000000))*(cj3)*(x1290)*(x1311)))+(((IkReal(0.105999998468300))*(x1296)))+(((IkReal(0.105999998468300))*(x1294)))+(((IkReal(-1.00000000000000))*(sj1)*(x1319)))+(((IkReal(-1.00000000000000))*(cj1)*(x1294)*(x1322)))+(((pz)*(x1307)*(x1320)))+(((x1311)*(x1343)))+(((IkReal(-1.00000000000000))*(cj1)*(x1296)*(x1322)))+(((IkReal(1.80199997396110e-5))*(x1332)))+(((IkReal(-1.80199997396110e-5))*(x1320)))+(((x1307)*(x1348)))+(((IkReal(0.999999985550000))*(x1312)*(x1331)))+(((IkReal(-1.00000000000000))*(x1290)*(x1313)))+(((r00)*(x1302))));
03486 evalcond[6]=((((x1296)*(x1334)))+(((IkReal(-1.00000000000000))*(x1335)*(x1338)))+(((IkReal(-1.00000000000000))*(x1298)*(x1301)*(x1309)))+(((IkReal(-1.00000000000000))*(x1292)*(x1296)*(x1303)))+(((r00)*(x1298)*(x1341)))+(((r00)*(x1298)*(x1345)))+(((IkReal(-1.00000000000000))*(x1296)*(x1302)*(x1309)))+(((IkReal(1.90239939123229e-5))*(x1290)*(x1297)))+(((IkReal(-1.00000000000000))*(x1291)*(x1294)*(x1303)))+(((x1301)*(x1302)*(x1325)))+(((IkReal(-1.00000000000000))*(x1312)*(x1346)))+(((x1294)*(x1334)))+(((IkReal(-0.0237439924019236))*(x1349)))+(((IkReal(-1.00000000000000))*(x1293)*(x1296)*(x1303)))+(((IkReal(-0.0237799923904037))*(x1289)*(x1297)))+(((pp)*(x1312)))+(((x1298)*(x1300)*(x1301)))+(((x1298)*(x1300)*(x1305)))+(((x1294)*(x1302)*(x1309)))+(((IkReal(-1.00000000000000))*(x1316)*(x1342)))+(((IkReal(-1.00000000000000))*(x1293)*(x1308)*(x1321)))+(((IkReal(0.212000000000000))*(x1305)))+(((IkReal(0.212000000000000))*(x1301)))+(((IkReal(-1.00000000000000))*(r00)*(x1298)*(x1347)))+(((x1300)*(x1308)*(x1319)))+(((x1301)*(x1308)*(x1314)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((IkReal(-0.0112359998376398))*(r00)*(x1298)))+(((IkReal(1.89951939215389e-5))*(x1344)))+(((IkReal(-0.0112360000000000))*(x1312)))+(((x1291)*(x1308)*(x1321)))+(((IkReal(0.0112359998376398))*(r01)*(x1308)))+(((IkReal(-1.00000000000000))*(x1327)*(x1343)))+(((IkReal(-1.00000000000000))*(x1292)*(x1294)*(x1303)))+(((x1291)*(x1296)*(x1303)))+(((IkReal(-2.00000000000000))*(x1305)*(x1330)))+(((IkReal(-1.00000000000000))*(x1292)*(x1308)*(x1321)))+(((x1293)*(x1294)*(x1303))));
03487 evalcond[7]=((((x1296)*(x1333)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1318)))+(((x1292)*(x1296)*(x1307)))+(((x1291)*(x1294)*(x1307)))+(((IkReal(-1.00000000000000))*(x1300)*(x1305)*(x1324)))+(((IkReal(-1.00000000000000))*(x1327)*(x1338)))+(((x1292)*(x1294)*(x1307)))+(((IkReal(-1.00000000000000))*(x1340)*(x1341)))+(((IkReal(-1.00000000000000))*(x1340)*(x1345)))+(((IkReal(-0.0237799923904037))*(x1290)*(x1297)))+(((x1294)*(x1333)))+(((IkReal(-0.0237439924019236))*(x1344)))+(((IkReal(0.211999996936600))*(cj0)*(x1317)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x1300)*(x1318)))+(((IkReal(-1.00000000000000))*(x1294)*(x1309)*(x1316)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1301)*(x1314)))+(((IkReal(-1.00000000000000))*(x1293)*(x1294)*(x1307)))+(((x1340)*(x1347)))+(((pp)*(x1323)))+(((IkReal(-1.90239939123229e-5))*(x1289)*(x1297)))+(((IkReal(-1.00000000000000))*(x1300)*(x1301)*(x1324)))+(((IkReal(-1.00000000000000))*(x1320)*(x1336)))+(((IkReal(-0.0112359998376398))*(x1340)))+(((IkReal(-1.00000000000000))*(x1291)*(x1296)*(x1307)))+(((IkReal(-1.00000000000000))*(x1295)*(x1296)))+(((IkReal(-1.00000000000000))*(x1291)*(x1320)*(x1329)))+(((IkReal(-1.89951939215389e-5))*(x1349)))+(((IkReal(3.60399994792220e-5))*(sj0)*(x1317)))+(((x1292)*(x1320)*(x1329)))+(((IkReal(-1.00000000000000))*(x1301)*(x1316)*(x1325)))+(((IkReal(-1.00000000000000))*(x1302)*(x1342)))+(((x1335)*(x1343)))+(((x1293)*(x1296)*(x1307)))+(((IkReal(0.0112359998376398))*(cj1)*(x1320)))+(((IkReal(-1.00000000000000))*(x1294)*(x1295)))+(((x1301)*(x1309)*(x1324)))+(((IkReal(-0.211999996936600))*(x1348)))+(((IkReal(-1.00000000000000))*(x1323)*(x1346)))+(((x1293)*(x1320)*(x1329)))+(((IkReal(-2.00000000000000))*(x1305)*(x1337)))+(((IkReal(0.0112360000000000))*(x1323)))+(((x1332)*(x1336)))+(((x1296)*(x1309)*(x1316))));
03488 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  )
03489 {
03490 continue;
03491 }
03492 }
03493 
03494 {
03495 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03496 vinfos[0].jointtype = 1;
03497 vinfos[0].foffset = j0;
03498 vinfos[0].indices[0] = _ij0[0];
03499 vinfos[0].indices[1] = _ij0[1];
03500 vinfos[0].maxsolutions = _nj0;
03501 vinfos[1].jointtype = 1;
03502 vinfos[1].foffset = j1;
03503 vinfos[1].indices[0] = _ij1[0];
03504 vinfos[1].indices[1] = _ij1[1];
03505 vinfos[1].maxsolutions = _nj1;
03506 vinfos[2].jointtype = 1;
03507 vinfos[2].foffset = j2;
03508 vinfos[2].indices[0] = _ij2[0];
03509 vinfos[2].indices[1] = _ij2[1];
03510 vinfos[2].maxsolutions = _nj2;
03511 vinfos[3].jointtype = 1;
03512 vinfos[3].foffset = j3;
03513 vinfos[3].indices[0] = _ij3[0];
03514 vinfos[3].indices[1] = _ij3[1];
03515 vinfos[3].maxsolutions = _nj3;
03516 vinfos[4].jointtype = 1;
03517 vinfos[4].foffset = j5;
03518 vinfos[4].indices[0] = _ij5[0];
03519 vinfos[4].indices[1] = _ij5[1];
03520 vinfos[4].maxsolutions = _nj5;
03521 std::vector<int> vfree(0);
03522 solutions.AddSolution(vinfos,vfree);
03523 }
03524 }
03525 }
03526 
03527 }
03528 
03529 }
03530 }
03531 }
03532 
03533 }
03534 
03535 }
03536 
03537 } else
03538 {
03539 {
03540 IkReal j3array[1], cj3array[1], sj3array[1];
03541 bool j3valid[1]={false};
03542 _nj3 = 1;
03543 IkReal x1350=((IkReal(66250.0202426838))*(sj1));
03544 IkReal x1351=((r00)*(sj0));
03545 IkReal x1352=((cj0)*(cj1));
03546 IkReal x1353=((IkReal(14078.1293015703))*(r00));
03547 IkReal x1354=((cj0)*(r01));
03548 IkReal x1355=((py)*(r01));
03549 IkReal x1356=((r01)*(sj0));
03550 IkReal x1357=((IkReal(82812525.3033548))*(sj1));
03551 IkReal x1358=((cj1)*(r02));
03552 IkReal x1359=((py)*(r02));
03553 IkReal x1360=((pz)*(r02));
03554 IkReal x1361=((px)*(r00));
03555 IkReal x1362=((IkReal(11.2625034412562))*(sj1));
03556 IkReal x1363=((r02)*(sj1));
03557 IkReal x1364=((px)*(r02));
03558 IkReal x1365=((IkReal(781250238.710894))*(pz));
03559 IkReal x1366=((IkReal(625000.190968715))*(pz));
03560 IkReal x1367=((cj0)*(pz)*(r00));
03561 if( IKabs(((gconst0)*(((((IkReal(781250249.999960))*(x1355)))+(((IkReal(-625000.190968715))*(sj0)*(x1364)))+(((IkReal(781250249.999960))*(x1360)))+(((IkReal(781250249.999960))*(x1361)))+(((IkReal(106.250032464682))*(cj0)*(x1364)))+(((IkReal(14078.1293015703))*(sj1)*(x1356)))+(((IkReal(-1.00000000000000))*(x1354)*(x1366)))+(((IkReal(-106.250032464682))*(pz)*(x1356)))+(((x1354)*(x1357)))+(((IkReal(11.2625034412562))*(cj1)*(x1356)))+(((IkReal(11.2625034412562))*(r00)*(x1352)))+(((IkReal(66250.0202426838))*(r01)*(x1352)))+(((IkReal(-106.250032464682))*(x1367)))+(((IkReal(625000.190968715))*(cj0)*(x1359)))+(((x1351)*(x1366)))+(((IkReal(-82812526.4999958))*(x1358)))+(((cj0)*(sj1)*(x1353)))+(((IkReal(106.250032464682))*(sj0)*(x1359)))+(((IkReal(-1.00000000000000))*(x1351)*(x1357)))+(((IkReal(-66250.0202426838))*(cj1)*(x1351)))+(((IkReal(66250.0211999966))*(x1363))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((x1356)*(x1362)))+(((IkReal(-1.00000000000000))*(x1352)*(x1353)))+(((IkReal(-82812525.3033548))*(r01)*(x1352)))+(((IkReal(-87500056.0000000))*(cj5)))+(((cj0)*(r00)*(x1362)))+(((IkReal(-14078.1293015703))*(cj1)*(x1356)))+(((x1354)*(x1365)))+(((IkReal(-1.00000000000000))*(x1350)*(x1351)))+(((IkReal(-132812.540580852))*(sj0)*(x1359)))+(((IkReal(-132812.540580852))*(cj0)*(x1364)))+(((IkReal(-66250.0211999966))*(x1358)))+(((IkReal(781250238.710894))*(sj0)*(x1364)))+(((x1350)*(x1354)))+(((IkReal(132812.540580852))*(pz)*(x1356)))+(((IkReal(625000.199999968))*(x1361)))+(((IkReal(625000.199999968))*(x1360)))+(((IkReal(82812525.3033548))*(cj1)*(x1351)))+(((IkReal(132812.540580852))*(x1367)))+(((IkReal(625000.199999968))*(x1355)))+(((IkReal(-82812526.4999958))*(x1363)))+(((IkReal(-781250238.710894))*(cj0)*(x1359)))+(((IkReal(-1.00000000000000))*(x1351)*(x1365))))))) < IKFAST_ATAN2_MAGTHRESH )
03562     continue;
03563 j3array[0]=IKatan2(((gconst0)*(((((IkReal(781250249.999960))*(x1355)))+(((IkReal(-625000.190968715))*(sj0)*(x1364)))+(((IkReal(781250249.999960))*(x1360)))+(((IkReal(781250249.999960))*(x1361)))+(((IkReal(106.250032464682))*(cj0)*(x1364)))+(((IkReal(14078.1293015703))*(sj1)*(x1356)))+(((IkReal(-1.00000000000000))*(x1354)*(x1366)))+(((IkReal(-106.250032464682))*(pz)*(x1356)))+(((x1354)*(x1357)))+(((IkReal(11.2625034412562))*(cj1)*(x1356)))+(((IkReal(11.2625034412562))*(r00)*(x1352)))+(((IkReal(66250.0202426838))*(r01)*(x1352)))+(((IkReal(-106.250032464682))*(x1367)))+(((IkReal(625000.190968715))*(cj0)*(x1359)))+(((x1351)*(x1366)))+(((IkReal(-82812526.4999958))*(x1358)))+(((cj0)*(sj1)*(x1353)))+(((IkReal(106.250032464682))*(sj0)*(x1359)))+(((IkReal(-1.00000000000000))*(x1351)*(x1357)))+(((IkReal(-66250.0202426838))*(cj1)*(x1351)))+(((IkReal(66250.0211999966))*(x1363)))))), ((gconst0)*(((((x1356)*(x1362)))+(((IkReal(-1.00000000000000))*(x1352)*(x1353)))+(((IkReal(-82812525.3033548))*(r01)*(x1352)))+(((IkReal(-87500056.0000000))*(cj5)))+(((cj0)*(r00)*(x1362)))+(((IkReal(-14078.1293015703))*(cj1)*(x1356)))+(((x1354)*(x1365)))+(((IkReal(-1.00000000000000))*(x1350)*(x1351)))+(((IkReal(-132812.540580852))*(sj0)*(x1359)))+(((IkReal(-132812.540580852))*(cj0)*(x1364)))+(((IkReal(-66250.0211999966))*(x1358)))+(((IkReal(781250238.710894))*(sj0)*(x1364)))+(((x1350)*(x1354)))+(((IkReal(132812.540580852))*(pz)*(x1356)))+(((IkReal(625000.199999968))*(x1361)))+(((IkReal(625000.199999968))*(x1360)))+(((IkReal(82812525.3033548))*(cj1)*(x1351)))+(((IkReal(132812.540580852))*(x1367)))+(((IkReal(625000.199999968))*(x1355)))+(((IkReal(-82812526.4999958))*(x1363)))+(((IkReal(-781250238.710894))*(cj0)*(x1359)))+(((IkReal(-1.00000000000000))*(x1351)*(x1365)))))));
03564 sj3array[0]=IKsin(j3array[0]);
03565 cj3array[0]=IKcos(j3array[0]);
03566 if( j3array[0] > IKPI )
03567 {
03568     j3array[0]-=IK2PI;
03569 }
03570 else if( j3array[0] < -IKPI )
03571 {    j3array[0]+=IK2PI;
03572 }
03573 j3valid[0] = true;
03574 for(int ij3 = 0; ij3 < 1; ++ij3)
03575 {
03576 if( !j3valid[ij3] )
03577 {
03578     continue;
03579 }
03580 _ij3[0] = ij3; _ij3[1] = -1;
03581 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
03582 {
03583 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
03584 {
03585     j3valid[iij3]=false; _ij3[1] = iij3; break; 
03586 }
03587 }
03588 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
03589 {
03590 IkReal evalcond[4];
03591 IkReal x1368=IKcos(j3);
03592 IkReal x1369=IKsin(j3);
03593 IkReal x1370=(px)*(px);
03594 IkReal x1371=(py)*(py);
03595 IkReal x1372=(pz)*(pz);
03596 IkReal x1373=((r00)*(sj0));
03597 IkReal x1374=((cj0)*(r00));
03598 IkReal x1375=((py)*(sj1));
03599 IkReal x1376=((cj1)*(pz));
03600 IkReal x1377=((cj0)*(r01));
03601 IkReal x1378=((px)*(py));
03602 IkReal x1379=((r01)*(sj0));
03603 IkReal x1380=((IkReal(1.80199997396110e-5))*(sj1));
03604 IkReal x1381=((cj0)*(r02));
03605 IkReal x1382=((IkReal(3.60399994792220e-5))*(cj1));
03606 IkReal x1383=((IkReal(0.105999966080016))*(cj5));
03607 IkReal x1384=((IkReal(0.999999985550000))*(pz));
03608 IkReal x1385=((px)*(sj1));
03609 IkReal x1386=((IkReal(0.106000000000000))*(r02));
03610 IkReal x1387=((IkReal(8.47999728640130e-5))*(cj5));
03611 IkReal x1388=((IkReal(0.000169999997543500))*(pz));
03612 IkReal x1389=((IkReal(0.211999996936600))*(cj1));
03613 IkReal x1390=((IkReal(0.000339999995087000))*(pz));
03614 IkReal x1391=((IkReal(0.105999998468300))*(cj1));
03615 IkReal x1392=((IkReal(1.80199997396110e-5))*(cj1));
03616 IkReal x1393=((IkReal(1.99999997110000))*(pz));
03617 IkReal x1394=((IkReal(0.105999998468300))*(sj1));
03618 IkReal x1395=((IkReal(0.999999985550000))*(x1371));
03619 IkReal x1396=((IkReal(0.999999985550000))*(x1372));
03620 IkReal x1397=((IkReal(0.000169999997543500))*(x1370));
03621 IkReal x1398=((IkReal(0.000169999997543500))*(x1371));
03622 IkReal x1399=((IkReal(0.000169999997543500))*(x1372));
03623 IkReal x1400=((px)*(r02)*(sj0));
03624 IkReal x1401=((IkReal(0.999999985550000))*(x1370));
03625 IkReal x1402=((py)*(r02)*(sj0));
03626 IkReal x1403=((IkReal(0.0237440000000000))*(x1368));
03627 evalcond[0]=((IkReal(0.0125440000000000))+(((IkReal(-0.211999996936600))*(cj0)*(x1375)))+(((IkReal(0.211999996936600))*(sj0)*(x1385)))+(((IkReal(-3.60399994792220e-5))*(sj0)*(x1375)))+(((IkReal(-3.60399994792220e-5))*(cj0)*(x1385)))+(((IkReal(0.212000000000000))*(x1376)))+(((IkReal(-1.00000000000000))*(pp)))+(x1403));
03628 evalcond[1]=((((IkReal(-1.00000000000000))*(px)*(r00)))+(((IkReal(-1.00000000000000))*(x1377)*(x1394)))+(((IkReal(-1.00000000000000))*(x1374)*(x1380)))+(((IkReal(8.95999713280138e-5))*(cj5)))+(((IkReal(-1.00000000000000))*(pz)*(r02)))+(((x1373)*(x1394)))+(((IkReal(-1.00000000000000))*(py)*(r01)))+(((cj1)*(x1386)))+(((x1369)*(x1383)))+(((x1368)*(x1387)))+(((IkReal(-1.00000000000000))*(x1379)*(x1380))));
03629 evalcond[2]=((((IkReal(0.000169999997543500))*(px)*(x1381)))+(((IkReal(-0.999999985550000))*(x1400)))+(((IkReal(-1.00000000000000))*(x1377)*(x1384)))+(((IkReal(-1.00000000000000))*(x1374)*(x1388)))+(((sj1)*(x1386)))+(((x1379)*(x1392)))+(((x1377)*(x1391)))+(((x1374)*(x1392)))+(((IkReal(0.000169999997543500))*(x1402)))+(((x1373)*(x1384)))+(((IkReal(-1.00000000000000))*(x1369)*(x1387)))+(((IkReal(0.111999964160017))*(cj5)))+(((x1368)*(x1383)))+(((IkReal(-1.00000000000000))*(x1379)*(x1388)))+(((IkReal(0.999999985550000))*(py)*(x1381)))+(((IkReal(-1.00000000000000))*(x1373)*(x1391))));
03630 evalcond[3]=((((IkReal(0.211999996936600))*(x1376)*(x1379)))+(((IkReal(-1.00000000000000))*(px)*(x1381)*(x1389)))+(((IkReal(-1.00000000000000))*(x1389)*(x1402)))+(((IkReal(0.212000000000000))*(r01)*(x1385)))+(((px)*(x1381)*(x1393)))+(((IkReal(-1.00000000000000))*(py)*(x1381)*(x1390)))+(((IkReal(-0.0112359998376398))*(x1374)))+(((IkReal(-0.0112359998376398))*(x1379)))+(((IkReal(3.60399994792220e-5))*(x1373)*(x1376)))+(((IkReal(0.000339999995087000))*(x1378)*(x1379)))+(((IkReal(1.99999997110000))*(x1377)*(x1378)))+(((x1393)*(x1402)))+(((IkReal(0.211999996936600))*(x1374)*(x1376)))+(((IkReal(-1.00000000000000))*(x1377)*(x1398)))+(((py)*(x1381)*(x1382)))+(((IkReal(-0.212000000000000))*(r00)*(x1375)))+(((IkReal(-1.00000000000000))*(x1382)*(x1400)))+(((IkReal(-1.00000000000000))*(x1374)*(x1396)))+(((IkReal(-1.00000000000000))*(x1374)*(x1395)))+(((IkReal(-0.0237800000000000))*(sj5)))+(((x1379)*(x1395)))+(((IkReal(-1.00000000000000))*(x1379)*(x1401)))+(((IkReal(-1.91011997239877e-6))*(x1373)))+(((x1377)*(x1397)))+(((x1377)*(x1399)))+(((IkReal(-0.000339999995087000))*(x1374)*(x1378)))+(((x1373)*(x1397)))+(((IkReal(1.99999997110000))*(x1373)*(x1378)))+(((IkReal(1.91011997239877e-6))*(x1377)))+(((IkReal(-1.00000000000000))*(sj5)*(x1403)))+(((IkReal(-3.60399994792220e-5))*(x1376)*(x1377)))+(((x1390)*(x1400)))+(((IkReal(-1.00000000000000))*(x1373)*(x1398)))+(((IkReal(-1.00000000000000))*(x1373)*(x1399)))+(((x1374)*(x1401)))+(((IkReal(-1.00000000000000))*(x1379)*(x1396))));
03631 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03632 {
03633 continue;
03634 }
03635 }
03636 
03637 {
03638 IkReal dummyeval[1];
03639 IkReal gconst1;
03640 gconst1=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
03641 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
03642 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03643 {
03644 {
03645 IkReal dummyeval[1];
03646 IkReal gconst2;
03647 IkReal x1404=((IkReal(13.9999955200021))*(cj5));
03648 gconst2=IKsign(((((IkReal(-1.00000000000000))*(x1404)*((cj3)*(cj3))))+(((IkReal(0.0105999966080016))*(cj5)*(sj3)))+(((IkReal(-1.00000000000000))*(x1404)*((sj3)*(sj3))))+(((IkReal(-13.2499957600020))*(cj3)*(cj5)))));
03649 IkReal x1405=((IkReal(1320.75471698113))*(cj5));
03650 dummyeval[0]=((((cj5)*(sj3)))+(((IkReal(-1250.00000000000))*(cj3)*(cj5)))+(((IkReal(-1.00000000000000))*(x1405)*((cj3)*(cj3))))+(((IkReal(-1.00000000000000))*(x1405)*((sj3)*(sj3)))));
03651 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03652 {
03653 {
03654 IkReal evalcond[11];
03655 IkReal x1406=(px)*(px);
03656 IkReal x1407=(py)*(py);
03657 IkReal x1408=(pz)*(pz);
03658 IkReal x1409=((IkReal(0.0237440000000000))*(cj3));
03659 IkReal x1410=((IkReal(3.60399994792220e-5))*(pz));
03660 IkReal x1411=((cj0)*(r00));
03661 IkReal x1412=((r01)*(sj0));
03662 IkReal x1413=((IkReal(0.000169999997543500))*(sj1));
03663 IkReal x1414=((IkReal(0.000339999995087000))*(py));
03664 IkReal x1415=((pz)*(sj1));
03665 IkReal x1416=((r02)*(sj0));
03666 IkReal x1417=((cj0)*(px));
03667 IkReal x1418=((cj1)*(r01));
03668 IkReal x1419=((IkReal(0.000169999997543500))*(cj0));
03669 IkReal x1420=((IkReal(3.60399994792220e-5))*(sj1));
03670 IkReal x1421=((py)*(r01));
03671 IkReal x1422=((r00)*(sj0));
03672 IkReal x1423=((IkReal(0.000169999997543500))*(pz));
03673 IkReal x1424=((IkReal(0.105999998468300))*(cj0));
03674 IkReal x1425=((px)*(r00));
03675 IkReal x1426=((IkReal(1.99999997110000))*(pz));
03676 IkReal x1427=((IkReal(1.91011997239877e-6))*(cj1));
03677 IkReal x1428=((r01)*(sj1));
03678 IkReal x1429=((cj1)*(r02));
03679 IkReal x1430=((r02)*(sj1));
03680 IkReal x1431=((IkReal(0.999999985550000))*(py));
03681 IkReal x1432=((IkReal(0.999999985550000))*(cj0));
03682 IkReal x1433=((IkReal(0.211999996936600))*(px));
03683 IkReal x1434=((IkReal(0.0112359998376398))*(cj0));
03684 IkReal x1435=((cj0)*(r02));
03685 IkReal x1436=((IkReal(1.80199997396110e-5))*(sj1));
03686 IkReal x1437=((IkReal(0.211999996936600))*(py));
03687 IkReal x1438=((cj1)*(px));
03688 IkReal x1439=((IkReal(0.000339999995087000))*(pz));
03689 IkReal x1440=((IkReal(0.999999985550000))*(cj1));
03690 IkReal x1441=((IkReal(0.000169999997543500))*(cj1));
03691 IkReal x1442=((cj0)*(py));
03692 IkReal x1443=((pz)*(r02));
03693 IkReal x1444=((IkReal(0.211999996936600))*(pz));
03694 IkReal x1445=((cj1)*(pz));
03695 IkReal x1446=((IkReal(0.999999985550000))*(sj1));
03696 IkReal x1447=((IkReal(1.80199997396110e-5))*(cj1));
03697 IkReal x1448=((cj0)*(r01));
03698 IkReal x1449=((IkReal(1.91011997239877e-6))*(sj1));
03699 IkReal x1450=((IkReal(0.999999985550000))*(x1408));
03700 IkReal x1451=((IkReal(0.000169999997543500))*(x1407));
03701 IkReal x1452=((IkReal(0.999999985550000))*(x1406));
03702 IkReal x1453=((IkReal(0.000169999997543500))*(x1408));
03703 IkReal x1454=((IkReal(1.99999997110000))*(px)*(py));
03704 IkReal x1455=((IkReal(0.000169999997543500))*(x1406));
03705 IkReal x1456=((IkReal(2.00000000000000))*(x1408));
03706 IkReal x1457=((IkReal(0.999999985550000))*(x1407));
03707 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j5)), IkReal(6.28318530717959))));
03708 evalcond[1]=((((py)*(x1419)))+(((IkReal(-1.00000000000000))*(sj0)*(x1431)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((IkReal(-0.999999985550000))*(x1417))));
03709 evalcond[2]=((IkReal(-1.00000000000000))+(((r01)*(x1419)))+(((IkReal(-0.999999985550000))*(x1412)))+(((IkReal(-0.999999985550000))*(x1411)))+(((IkReal(-0.000169999997543500))*(x1422))));
03710 evalcond[3]=((IkReal(0.0125440000000000))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x1437)))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x1420)))+(((IkReal(0.212000000000000))*(x1445)))+(((IkReal(-1.00000000000000))*(x1417)*(x1420)))+(((IkReal(-1.00000000000000))*(pp)))+(x1409)+(((sj0)*(sj1)*(x1433))));
03711 evalcond[4]=((((IkReal(0.105999998468300))*(sj1)*(x1422)))+(((IkReal(-1.00000000000000))*(x1424)*(x1428)))+(((IkReal(-1.00000000000000))*(x1443)))+(((IkReal(0.106000000000000))*(x1429)))+(((IkReal(-1.00000000000000))*(x1412)*(x1436)))+(((IkReal(-1.00000000000000))*(x1421)))+(((IkReal(-1.00000000000000))*(x1425)))+(((IkReal(-1.00000000000000))*(x1411)*(x1436))));
03712 evalcond[5]=((((x1411)*(x1441)))+(((x1418)*(x1432)))+(x1430)+(((IkReal(-1.00000000000000))*(x1422)*(x1440)))+(((x1412)*(x1441))));
03713 evalcond[6]=((((x1422)*(x1446)))+(((IkReal(-1.00000000000000))*(x1412)*(x1413)))+(((IkReal(-1.00000000000000))*(x1428)*(x1432)))+(((IkReal(-1.00000000000000))*(x1411)*(x1413)))+(x1429));
03714 evalcond[7]=((((x1411)*(x1447)))+(((IkReal(0.000169999997543500))*(r02)*(x1417)))+(((IkReal(0.000169999997543500))*(py)*(x1416)))+(((x1418)*(x1424)))+(((IkReal(-0.105999998468300))*(cj1)*(x1422)))+(((IkReal(0.999999985550000))*(pz)*(x1422)))+(((IkReal(-1.00000000000000))*(x1412)*(x1423)))+(((x1412)*(x1447)))+(((IkReal(0.106000000000000))*(x1430)))+(((x1431)*(x1435)))+(((IkReal(-1.00000000000000))*(x1411)*(x1423)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x1432)))+(((IkReal(-0.999999985550000))*(px)*(x1416))));
03715 evalcond[8]=((IkReal(-0.0237800000000000))+(((cj1)*(x1410)*(x1422)))+(((IkReal(-1.00000000000000))*(px)*(x1411)*(x1414)))+(((IkReal(-1.00000000000000))*(x1422)*(x1453)))+(((IkReal(-1.00000000000000))*(x1422)*(x1451)))+(((cj1)*(x1412)*(x1444)))+(((IkReal(3.60399994792220e-5))*(x1429)*(x1442)))+(((IkReal(-1.00000000000000))*(cj0)*(x1410)*(x1418)))+(((r01)*(x1406)*(x1419)))+(((r02)*(x1417)*(x1426)))+(((px)*(x1416)*(x1439)))+(((IkReal(-3.60399994792220e-5))*(x1416)*(x1438)))+(((IkReal(1.91011997239877e-6))*(x1448)))+(((x1412)*(x1457)))+(((IkReal(-1.00000000000000))*(cj1)*(x1416)*(x1437)))+(((IkReal(-1.00000000000000))*(x1411)*(x1457)))+(((IkReal(-1.00000000000000))*(x1411)*(x1450)))+(((IkReal(-1.00000000000000))*(x1409)))+(((IkReal(-1.00000000000000))*(r01)*(x1407)*(x1419)))+(((IkReal(-0.0112359998376398))*(x1412)))+(((IkReal(-0.0112359998376398))*(x1411)))+(((IkReal(-1.00000000000000))*(x1412)*(x1452)))+(((IkReal(-1.00000000000000))*(x1412)*(x1450)))+(((x1422)*(x1455)))+(((x1422)*(x1454)))+(((IkReal(1.99999997110000))*(x1417)*(x1421)))+(((x1411)*(x1452)))+(((IkReal(-1.00000000000000))*(pz)*(x1414)*(x1435)))+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((IkReal(0.212000000000000))*(px)*(x1428)))+(((py)*(x1416)*(x1426)))+(((r01)*(x1408)*(x1419)))+(((cj1)*(x1411)*(x1444)))+(((px)*(x1412)*(x1414)))+(((IkReal(-0.211999996936600))*(x1417)*(x1429)))+(((IkReal(-1.91011997239877e-6))*(x1422))));
03716 evalcond[9]=((((x1428)*(x1434)))+(((IkReal(0.000339999995087000))*(r02)*(x1415)*(x1417)))+(((IkReal(-1.00000000000000))*(x1406)*(x1412)*(x1413)))+(((x1411)*(x1449)))+(((IkReal(-0.0112359998376398))*(sj1)*(x1422)))+(((IkReal(-1.00000000000000))*(x1429)*(x1456)))+(((IkReal(-0.0112360000000000))*(x1429)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(x1418)))+(((x1407)*(x1428)*(x1432)))+(((pp)*(x1429)))+(((x1407)*(x1412)*(x1413)))+(((IkReal(-1.00000000000000))*(x1406)*(x1422)*(x1446)))+(((IkReal(0.212000000000000))*(x1443)))+(((IkReal(1.99999997110000))*(py)*(x1415)*(x1435)))+(((IkReal(0.212000000000000))*(x1421)))+(((IkReal(0.212000000000000))*(x1425)))+(((IkReal(-1.00000000000000))*(x1406)*(x1428)*(x1432)))+(((IkReal(-1.00000000000000))*(x1407)*(x1411)*(x1413)))+(((x1414)*(x1415)*(x1416)))+(((IkReal(-2.00000000000000))*(x1425)*(x1445)))+(((IkReal(-1.00000000000000))*(sj1)*(x1412)*(x1454)))+(((x1408)*(x1422)*(x1446)))+(((px)*(sj1)*(x1414)*(x1422)))+(((IkReal(-1.00000000000000))*(x1408)*(x1411)*(x1413)))+(((IkReal(-1.00000000000000))*(x1408)*(x1428)*(x1432)))+(((sj1)*(x1411)*(x1454)))+(((x1406)*(x1411)*(x1413)))+(((x1407)*(x1422)*(x1446)))+(((x1412)*(x1449)))+(((IkReal(-1.99999997110000))*(px)*(x1415)*(x1416)))+(((x1414)*(x1417)*(x1428)))+(((IkReal(-1.00000000000000))*(x1408)*(x1412)*(x1413))));
03717 evalcond[10]=((((IkReal(-1.00000000000000))*(x1407)*(x1412)*(x1441)))+(((x1422)*(x1444)))+(((IkReal(-1.99999997110000))*(py)*(x1411)*(x1438)))+(((x1406)*(x1418)*(x1432)))+(((IkReal(-0.0112359998376398))*(cj1)*(x1422)))+(((x1408)*(x1411)*(x1441)))+(((IkReal(0.0112360000000000))*(x1430)))+(((x1418)*(x1434)))+(((x1406)*(x1422)*(x1440)))+(((x1411)*(x1427)))+(((IkReal(-1.00000000000000))*(x1407)*(x1418)*(x1432)))+(((x1435)*(x1437)))+(((IkReal(-1.00000000000000))*(x1426)*(x1429)*(x1442)))+(((IkReal(-1.00000000000000))*(x1414)*(x1417)*(x1418)))+(((x1406)*(x1412)*(x1441)))+(((IkReal(-1.00000000000000))*(x1408)*(x1422)*(x1440)))+(((x1416)*(x1426)*(x1438)))+(((IkReal(-1.00000000000000))*(x1414)*(x1422)*(x1438)))+(((IkReal(-1.00000000000000))*(x1416)*(x1433)))+(((IkReal(-1.00000000000000))*(x1410)*(x1411)))+(((IkReal(-1.00000000000000))*(x1410)*(x1412)))+(((IkReal(-2.00000000000000))*(x1415)*(x1425)))+(((IkReal(-2.00000000000000))*(x1415)*(x1421)))+(((x1408)*(x1418)*(x1432)))+(((IkReal(-1.00000000000000))*(x1417)*(x1429)*(x1439)))+(((IkReal(1.99999997110000))*(py)*(x1412)*(x1438)))+(((IkReal(-1.00000000000000))*(x1406)*(x1411)*(x1441)))+(((pp)*(x1430)))+(((x1408)*(x1412)*(x1441)))+(((IkReal(-1.00000000000000))*(x1444)*(x1448)))+(((IkReal(-1.00000000000000))*(x1414)*(x1416)*(x1445)))+(((IkReal(-1.00000000000000))*(x1407)*(x1422)*(x1440)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1417)))+(((IkReal(3.60399994792220e-5))*(py)*(x1416)))+(((x1412)*(x1427)))+(((IkReal(-1.00000000000000))*(x1430)*(x1456)))+(((x1407)*(x1411)*(x1441))));
03718 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  )
03719 {
03720 {
03721 IkReal dummyeval[1];
03722 IkReal gconst3;
03723 gconst3=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
03724 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
03725 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03726 {
03727 {
03728 IkReal dummyeval[1];
03729 IkReal gconst4;
03730 gconst4=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
03731 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
03732 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
03733 {
03734 continue;
03735 
03736 } else
03737 {
03738 {
03739 IkReal j2array[1], cj2array[1], sj2array[1];
03740 bool j2valid[1]={false};
03741 _nj2 = 1;
03742 IkReal x1458=((py)*(r02));
03743 IkReal x1459=((IkReal(1750.00000000000))*(cj1));
03744 IkReal x1460=((px)*(sj3));
03745 IkReal x1461=((cj3)*(pz));
03746 IkReal x1462=((cj0)*(sj1));
03747 IkReal x1463=((IkReal(1749.99997471250))*(r02));
03748 IkReal x1464=((px)*(r01));
03749 IkReal x1465=((r00)*(sj3));
03750 IkReal x1466=((pz)*(sj3));
03751 IkReal x1467=((pz)*(r01));
03752 IkReal x1468=((IkReal(0.297499995701125))*(sj3));
03753 IkReal x1469=((IkReal(1656.25000000000))*(cj1));
03754 IkReal x1470=((IkReal(0.297499995701125))*(cj3));
03755 IkReal x1471=((pz)*(r00));
03756 IkReal x1472=((cj3)*(px));
03757 IkReal x1473=((cj3)*(py));
03758 IkReal x1474=((px)*(r02));
03759 IkReal x1475=((IkReal(0.297499995701125))*(r01));
03760 IkReal x1476=((sj0)*(sj1));
03761 IkReal x1477=((IkReal(0.281562495931422))*(x1462));
03762 IkReal x1478=((IkReal(1656.24997606719))*(x1476));
03763 IkReal x1479=((IkReal(1749.99997471250))*(x1476));
03764 IkReal x1480=((py)*(x1476));
03765 IkReal x1481=((IkReal(0.281562495931422))*(x1476));
03766 if( IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(r00)*(x1459)*(x1473)))+(((IkReal(-1.00000000000000))*(x1468)*(x1480)))+(((cj3)*(x1459)*(x1464)))+(((x1462)*(x1463)*(x1472)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x1462)))+(((x1460)*(x1479)))+(((IkReal(-1749.99997471250))*(r00)*(x1461)*(x1462)))+(((cj3)*(x1458)*(x1479)))+(((IkReal(-1.00000000000000))*(x1458)*(x1462)*(x1470)))+(((x1459)*(x1466)))+(((IkReal(-185.500000000000))*(sj3)))+(((x1467)*(x1477)))+(((x1464)*(x1469)))+(((x1461)*(x1462)*(x1475)))+(((IkReal(-0.297499995701125))*(x1460)*(x1462)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x1469)))+(((IkReal(-1.00000000000000))*(x1467)*(x1478)))+(((x1474)*(x1481)))+(((IkReal(-1.00000000000000))*(x1458)*(x1477)))+(((IkReal(-1656.24997606719))*(x1462)*(x1471)))+(((IkReal(-1.00000000000000))*(r01)*(x1461)*(x1479)))+(((IkReal(-1.00000000000000))*(x1471)*(x1481)))+(((x1470)*(x1474)*(x1476)))+(((IkReal(1656.24997606719))*(x1462)*(x1474)))+(((IkReal(-0.297499995701125))*(r00)*(x1461)*(x1476)))+(((x1458)*(x1478))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((IkReal(175.562500000000))+(((px)*(x1462)*(x1470)))+(((IkReal(-1.00000000000000))*(pz)*(x1469)))+(((sj3)*(x1458)*(x1479)))+(((IkReal(-1.00000000000000))*(py)*(x1459)*(x1465)))+(((x1462)*(x1466)*(x1475)))+(((r01)*(x1459)*(x1460)))+(((IkReal(-1.00000000000000))*(px)*(x1478)))+(((x1470)*(x1480)))+(((IkReal(-1.00000000000000))*(x1459)*(x1461)))+(((IkReal(0.297499995701125))*(r02)*(x1460)*(x1476)))+(((IkReal(-1749.99997471250))*(pz)*(x1462)*(x1465)))+(((IkReal(0.281562495931422))*(x1480)))+(((IkReal(-1.00000000000000))*(r01)*(x1466)*(x1479)))+(((IkReal(-1.00000000000000))*(x1458)*(x1462)*(x1468)))+(((IkReal(1656.24997606719))*(py)*(x1462)))+(((IkReal(1749.99997471250))*(x1462)*(x1473)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-0.297499995701125))*(pz)*(x1465)*(x1476)))+(((x1460)*(x1462)*(x1463)))+(((px)*(x1477)))+(((IkReal(-1.00000000000000))*(x1472)*(x1479))))))) < IKFAST_ATAN2_MAGTHRESH )
03767     continue;
03768 j2array[0]=IKatan2(((gconst4)*(((((IkReal(-1.00000000000000))*(r00)*(x1459)*(x1473)))+(((IkReal(-1.00000000000000))*(x1468)*(x1480)))+(((cj3)*(x1459)*(x1464)))+(((x1462)*(x1463)*(x1472)))+(((IkReal(-1749.99997471250))*(py)*(sj3)*(x1462)))+(((x1460)*(x1479)))+(((IkReal(-1749.99997471250))*(r00)*(x1461)*(x1462)))+(((cj3)*(x1458)*(x1479)))+(((IkReal(-1.00000000000000))*(x1458)*(x1462)*(x1470)))+(((x1459)*(x1466)))+(((IkReal(-185.500000000000))*(sj3)))+(((x1467)*(x1477)))+(((x1464)*(x1469)))+(((x1461)*(x1462)*(x1475)))+(((IkReal(-0.297499995701125))*(x1460)*(x1462)))+(((IkReal(-1.00000000000000))*(py)*(r00)*(x1469)))+(((IkReal(-1.00000000000000))*(x1467)*(x1478)))+(((x1474)*(x1481)))+(((IkReal(-1.00000000000000))*(x1458)*(x1477)))+(((IkReal(-1656.24997606719))*(x1462)*(x1471)))+(((IkReal(-1.00000000000000))*(r01)*(x1461)*(x1479)))+(((IkReal(-1.00000000000000))*(x1471)*(x1481)))+(((x1470)*(x1474)*(x1476)))+(((IkReal(1656.24997606719))*(x1462)*(x1474)))+(((IkReal(-0.297499995701125))*(r00)*(x1461)*(x1476)))+(((x1458)*(x1478)))))), ((gconst4)*(((IkReal(175.562500000000))+(((px)*(x1462)*(x1470)))+(((IkReal(-1.00000000000000))*(pz)*(x1469)))+(((sj3)*(x1458)*(x1479)))+(((IkReal(-1.00000000000000))*(py)*(x1459)*(x1465)))+(((x1462)*(x1466)*(x1475)))+(((r01)*(x1459)*(x1460)))+(((IkReal(-1.00000000000000))*(px)*(x1478)))+(((x1470)*(x1480)))+(((IkReal(-1.00000000000000))*(x1459)*(x1461)))+(((IkReal(0.297499995701125))*(r02)*(x1460)*(x1476)))+(((IkReal(-1749.99997471250))*(pz)*(x1462)*(x1465)))+(((IkReal(0.281562495931422))*(x1480)))+(((IkReal(-1.00000000000000))*(r01)*(x1466)*(x1479)))+(((IkReal(-1.00000000000000))*(x1458)*(x1462)*(x1468)))+(((IkReal(1656.24997606719))*(py)*(x1462)))+(((IkReal(1749.99997471250))*(x1462)*(x1473)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-0.297499995701125))*(pz)*(x1465)*(x1476)))+(((x1460)*(x1462)*(x1463)))+(((px)*(x1477)))+(((IkReal(-1.00000000000000))*(x1472)*(x1479)))))));
03769 sj2array[0]=IKsin(j2array[0]);
03770 cj2array[0]=IKcos(j2array[0]);
03771 if( j2array[0] > IKPI )
03772 {
03773     j2array[0]-=IK2PI;
03774 }
03775 else if( j2array[0] < -IKPI )
03776 {    j2array[0]+=IK2PI;
03777 }
03778 j2valid[0] = true;
03779 for(int ij2 = 0; ij2 < 1; ++ij2)
03780 {
03781 if( !j2valid[ij2] )
03782 {
03783     continue;
03784 }
03785 _ij2[0] = ij2; _ij2[1] = -1;
03786 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03787 {
03788 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03789 {
03790     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03791 }
03792 }
03793 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03794 {
03795 IkReal evalcond[4];
03796 IkReal x1482=IKsin(j2);
03797 IkReal x1483=IKcos(j2);
03798 IkReal x1484=((r00)*(sj0));
03799 IkReal x1485=((r01)*(sj0));
03800 IkReal x1486=((py)*(sj1));
03801 IkReal x1487=((IkReal(0.999999985550000))*(r02));
03802 IkReal x1488=((px)*(sj1));
03803 IkReal x1489=((IkReal(0.999999985550000))*(sj0));
03804 IkReal x1490=((IkReal(0.000169999997543500))*(cj0));
03805 IkReal x1491=((IkReal(0.000169999997543500))*(sj0));
03806 IkReal x1492=((cj1)*(px));
03807 IkReal x1493=((pz)*(sj1));
03808 IkReal x1494=((cj0)*(r00));
03809 IkReal x1495=((cj1)*(pz));
03810 IkReal x1496=((IkReal(1.00000000000000))*(r01));
03811 IkReal x1497=((cj1)*(py));
03812 IkReal x1498=((IkReal(0.999999985550000))*(cj0));
03813 IkReal x1499=((IkReal(0.106000000000000))*(x1482));
03814 IkReal x1500=((IkReal(0.106000000000000))*(x1483));
03815 IkReal x1501=((IkReal(0.112000000000000))*(x1483));
03816 IkReal x1502=((IkReal(0.112000000000000))*(x1482));
03817 IkReal x1503=((cj3)*(x1502));
03818 IkReal x1504=((sj3)*(x1501));
03819 IkReal x1505=((sj3)*(x1502));
03820 IkReal x1506=((cj3)*(x1501));
03821 IkReal x1507=((x1500)+(x1506));
03822 IkReal x1508=((x1503)+(x1504)+(x1499));
03823 evalcond[0]=((((x1491)*(x1497)))+(((x1497)*(x1498)))+(x1508)+(x1493)+(((x1490)*(x1492)))+(((IkReal(-1.00000000000000))*(x1489)*(x1492))));
03824 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x1507)))+(((IkReal(-1.00000000000000))*(x1486)*(x1491)))+(((IkReal(-1.00000000000000))*(x1486)*(x1498)))+(x1505)+(x1495)+(((IkReal(-1.00000000000000))*(x1488)*(x1490)))+(((x1488)*(x1489))));
03825 evalcond[2]=((((IkReal(-1.00000000000000))*(x1508)))+(((r00)*(x1497)))+(((IkReal(0.999999985550000))*(x1493)*(x1494)))+(((IkReal(-1.00000000000000))*(x1492)*(x1496)))+(((IkReal(-1.00000000000000))*(r01)*(x1490)*(x1493)))+(((IkReal(0.000169999997543500))*(x1484)*(x1493)))+(((r02)*(x1486)*(x1490)))+(((IkReal(0.999999985550000))*(x1485)*(x1493)))+(((IkReal(-1.00000000000000))*(r02)*(x1488)*(x1491)))+(((IkReal(-1.00000000000000))*(cj0)*(x1487)*(x1488)))+(((IkReal(-1.00000000000000))*(sj0)*(x1486)*(x1487))));
03826 evalcond[3]=((((cj0)*(x1487)*(x1492)))+(((IkReal(-1.00000000000000))*(x1507)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((r00)*(x1486)))+(((IkReal(-0.999999985550000))*(x1494)*(x1495)))+(((IkReal(1.80199997396110e-5))*(x1484)))+(((IkReal(0.105999998468300))*(x1494)))+(((IkReal(0.105999998468300))*(x1485)))+(x1505)+(((r01)*(x1490)*(x1495)))+(((IkReal(-0.999999985550000))*(x1485)*(x1495)))+(((IkReal(-1.00000000000000))*(r02)*(x1490)*(x1497)))+(((sj0)*(x1487)*(x1497)))+(((r02)*(x1491)*(x1492)))+(((IkReal(-1.00000000000000))*(x1488)*(x1496)))+(((IkReal(-0.000169999997543500))*(x1484)*(x1495))));
03827 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03828 {
03829 continue;
03830 }
03831 }
03832 
03833 {
03834 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03835 vinfos[0].jointtype = 1;
03836 vinfos[0].foffset = j0;
03837 vinfos[0].indices[0] = _ij0[0];
03838 vinfos[0].indices[1] = _ij0[1];
03839 vinfos[0].maxsolutions = _nj0;
03840 vinfos[1].jointtype = 1;
03841 vinfos[1].foffset = j1;
03842 vinfos[1].indices[0] = _ij1[0];
03843 vinfos[1].indices[1] = _ij1[1];
03844 vinfos[1].maxsolutions = _nj1;
03845 vinfos[2].jointtype = 1;
03846 vinfos[2].foffset = j2;
03847 vinfos[2].indices[0] = _ij2[0];
03848 vinfos[2].indices[1] = _ij2[1];
03849 vinfos[2].maxsolutions = _nj2;
03850 vinfos[3].jointtype = 1;
03851 vinfos[3].foffset = j3;
03852 vinfos[3].indices[0] = _ij3[0];
03853 vinfos[3].indices[1] = _ij3[1];
03854 vinfos[3].maxsolutions = _nj3;
03855 vinfos[4].jointtype = 1;
03856 vinfos[4].foffset = j5;
03857 vinfos[4].indices[0] = _ij5[0];
03858 vinfos[4].indices[1] = _ij5[1];
03859 vinfos[4].maxsolutions = _nj5;
03860 std::vector<int> vfree(0);
03861 solutions.AddSolution(vinfos,vfree);
03862 }
03863 }
03864 }
03865 
03866 }
03867 
03868 }
03869 
03870 } else
03871 {
03872 {
03873 IkReal j2array[1], cj2array[1], sj2array[1];
03874 bool j2valid[1]={false};
03875 _nj2 = 1;
03876 IkReal x1509=((px)*(sj1));
03877 IkReal x1510=((IkReal(0.281562495931422))*(cj0));
03878 IkReal x1511=((cj1)*(sj0));
03879 IkReal x1512=((IkReal(0.281562495931422))*(py));
03880 IkReal x1513=((IkReal(1749.99997471250))*(sj3));
03881 IkReal x1514=((IkReal(1749.99997471250))*(cj3));
03882 IkReal x1515=((cj0)*(cj1));
03883 IkReal x1516=((IkReal(0.297499995701125))*(sj3));
03884 IkReal x1517=((IkReal(0.297499995701125))*(cj3));
03885 IkReal x1518=((IkReal(1656.25000000000))*(pz));
03886 IkReal x1519=((IkReal(1750.00000000000))*(cj3)*(pz));
03887 IkReal x1520=((IkReal(1750.00000000000))*(pz)*(sj3));
03888 IkReal x1521=((IkReal(1656.24997606719))*(cj0)*(py));
03889 IkReal x1522=((py)*(sj0)*(sj1));
03890 IkReal x1523=((cj0)*(py)*(sj1));
03891 if( IKabs(((gconst3)*(((((py)*(x1511)*(x1517)))+(((cj1)*(x1520)))+(((IkReal(-185.500000000000))*(sj3)))+(((px)*(x1515)*(x1517)))+(((IkReal(-1656.24997606719))*(px)*(x1511)))+(((IkReal(-1.00000000000000))*(x1513)*(x1523)))+(((sj1)*(x1518)))+(((sj1)*(x1519)))+(((cj1)*(px)*(x1510)))+(((IkReal(1656.24997606719))*(py)*(x1515)))+(((x1511)*(x1512)))+(((IkReal(-1.00000000000000))*(x1516)*(x1522)))+(((py)*(x1514)*(x1515)))+(((sj0)*(x1509)*(x1513)))+(((IkReal(-1.00000000000000))*(px)*(x1511)*(x1514)))+(((IkReal(-1.00000000000000))*(cj0)*(x1509)*(x1516))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((IkReal(175.562500000000))+(((x1509)*(x1510)))+(((IkReal(-1656.24997606719))*(sj0)*(x1509)))+(((py)*(x1511)*(x1516)))+(((IkReal(-1.00000000000000))*(cj1)*(x1518)))+(((IkReal(-1.00000000000000))*(cj1)*(x1519)))+(((sj0)*(sj1)*(x1512)))+(((IkReal(-1.00000000000000))*(sj0)*(x1509)*(x1514)))+(((sj1)*(x1521)))+(((sj1)*(x1520)))+(((px)*(x1515)*(x1516)))+(((x1517)*(x1522)))+(((IkReal(185.500000000000))*(cj3)))+(((x1514)*(x1523)))+(((py)*(x1513)*(x1515)))+(((IkReal(-1.00000000000000))*(px)*(x1511)*(x1513)))+(((cj0)*(x1509)*(x1517))))))) < IKFAST_ATAN2_MAGTHRESH )
03892     continue;
03893 j2array[0]=IKatan2(((gconst3)*(((((py)*(x1511)*(x1517)))+(((cj1)*(x1520)))+(((IkReal(-185.500000000000))*(sj3)))+(((px)*(x1515)*(x1517)))+(((IkReal(-1656.24997606719))*(px)*(x1511)))+(((IkReal(-1.00000000000000))*(x1513)*(x1523)))+(((sj1)*(x1518)))+(((sj1)*(x1519)))+(((cj1)*(px)*(x1510)))+(((IkReal(1656.24997606719))*(py)*(x1515)))+(((x1511)*(x1512)))+(((IkReal(-1.00000000000000))*(x1516)*(x1522)))+(((py)*(x1514)*(x1515)))+(((sj0)*(x1509)*(x1513)))+(((IkReal(-1.00000000000000))*(px)*(x1511)*(x1514)))+(((IkReal(-1.00000000000000))*(cj0)*(x1509)*(x1516)))))), ((gconst3)*(((IkReal(175.562500000000))+(((x1509)*(x1510)))+(((IkReal(-1656.24997606719))*(sj0)*(x1509)))+(((py)*(x1511)*(x1516)))+(((IkReal(-1.00000000000000))*(cj1)*(x1518)))+(((IkReal(-1.00000000000000))*(cj1)*(x1519)))+(((sj0)*(sj1)*(x1512)))+(((IkReal(-1.00000000000000))*(sj0)*(x1509)*(x1514)))+(((sj1)*(x1521)))+(((sj1)*(x1520)))+(((px)*(x1515)*(x1516)))+(((x1517)*(x1522)))+(((IkReal(185.500000000000))*(cj3)))+(((x1514)*(x1523)))+(((py)*(x1513)*(x1515)))+(((IkReal(-1.00000000000000))*(px)*(x1511)*(x1513)))+(((cj0)*(x1509)*(x1517)))))));
03894 sj2array[0]=IKsin(j2array[0]);
03895 cj2array[0]=IKcos(j2array[0]);
03896 if( j2array[0] > IKPI )
03897 {
03898     j2array[0]-=IK2PI;
03899 }
03900 else if( j2array[0] < -IKPI )
03901 {    j2array[0]+=IK2PI;
03902 }
03903 j2valid[0] = true;
03904 for(int ij2 = 0; ij2 < 1; ++ij2)
03905 {
03906 if( !j2valid[ij2] )
03907 {
03908     continue;
03909 }
03910 _ij2[0] = ij2; _ij2[1] = -1;
03911 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
03912 {
03913 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
03914 {
03915     j2valid[iij2]=false; _ij2[1] = iij2; break; 
03916 }
03917 }
03918 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
03919 {
03920 IkReal evalcond[4];
03921 IkReal x1524=IKsin(j2);
03922 IkReal x1525=IKcos(j2);
03923 IkReal x1526=((r00)*(sj0));
03924 IkReal x1527=((r01)*(sj0));
03925 IkReal x1528=((py)*(sj1));
03926 IkReal x1529=((IkReal(0.999999985550000))*(r02));
03927 IkReal x1530=((px)*(sj1));
03928 IkReal x1531=((IkReal(0.999999985550000))*(sj0));
03929 IkReal x1532=((IkReal(0.000169999997543500))*(cj0));
03930 IkReal x1533=((IkReal(0.000169999997543500))*(sj0));
03931 IkReal x1534=((cj1)*(px));
03932 IkReal x1535=((pz)*(sj1));
03933 IkReal x1536=((cj0)*(r00));
03934 IkReal x1537=((cj1)*(pz));
03935 IkReal x1538=((IkReal(1.00000000000000))*(r01));
03936 IkReal x1539=((cj1)*(py));
03937 IkReal x1540=((IkReal(0.999999985550000))*(cj0));
03938 IkReal x1541=((IkReal(0.106000000000000))*(x1524));
03939 IkReal x1542=((IkReal(0.106000000000000))*(x1525));
03940 IkReal x1543=((IkReal(0.112000000000000))*(x1525));
03941 IkReal x1544=((IkReal(0.112000000000000))*(x1524));
03942 IkReal x1545=((cj3)*(x1544));
03943 IkReal x1546=((sj3)*(x1543));
03944 IkReal x1547=((sj3)*(x1544));
03945 IkReal x1548=((cj3)*(x1543));
03946 IkReal x1549=((x1542)+(x1548));
03947 IkReal x1550=((x1546)+(x1545)+(x1541));
03948 evalcond[0]=((((x1539)*(x1540)))+(((IkReal(-1.00000000000000))*(x1531)*(x1534)))+(((x1532)*(x1534)))+(x1550)+(x1535)+(((x1533)*(x1539))));
03949 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x1530)*(x1532)))+(((x1530)*(x1531)))+(x1547)+(x1537)+(((IkReal(-1.00000000000000))*(x1528)*(x1533)))+(((IkReal(-1.00000000000000))*(x1549)))+(((IkReal(-1.00000000000000))*(x1528)*(x1540))));
03950 evalcond[2]=((((IkReal(-1.00000000000000))*(r01)*(x1532)*(x1535)))+(((IkReal(-1.00000000000000))*(cj0)*(x1529)*(x1530)))+(((IkReal(0.999999985550000))*(x1535)*(x1536)))+(((r00)*(x1539)))+(((IkReal(-1.00000000000000))*(r02)*(x1530)*(x1533)))+(((IkReal(-1.00000000000000))*(sj0)*(x1528)*(x1529)))+(((r02)*(x1528)*(x1532)))+(((IkReal(-1.00000000000000))*(x1534)*(x1538)))+(((IkReal(-1.00000000000000))*(x1550)))+(((IkReal(0.999999985550000))*(x1527)*(x1535)))+(((IkReal(0.000169999997543500))*(x1526)*(x1535))));
03951 evalcond[3]=((((IkReal(0.105999998468300))*(x1536)))+(((IkReal(-0.000169999997543500))*(x1526)*(x1537)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-0.999999985550000))*(x1527)*(x1537)))+(((IkReal(-1.00000000000000))*(x1530)*(x1538)))+(((r00)*(x1528)))+(((cj0)*(x1529)*(x1534)))+(((r02)*(x1533)*(x1534)))+(x1547)+(((IkReal(-1.00000000000000))*(r02)*(x1532)*(x1539)))+(((IkReal(-0.999999985550000))*(x1536)*(x1537)))+(((IkReal(1.80199997396110e-5))*(x1526)))+(((IkReal(-1.00000000000000))*(x1549)))+(((r01)*(x1532)*(x1537)))+(((IkReal(0.105999998468300))*(x1527)))+(((sj0)*(x1529)*(x1539))));
03952 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
03953 {
03954 continue;
03955 }
03956 }
03957 
03958 {
03959 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
03960 vinfos[0].jointtype = 1;
03961 vinfos[0].foffset = j0;
03962 vinfos[0].indices[0] = _ij0[0];
03963 vinfos[0].indices[1] = _ij0[1];
03964 vinfos[0].maxsolutions = _nj0;
03965 vinfos[1].jointtype = 1;
03966 vinfos[1].foffset = j1;
03967 vinfos[1].indices[0] = _ij1[0];
03968 vinfos[1].indices[1] = _ij1[1];
03969 vinfos[1].maxsolutions = _nj1;
03970 vinfos[2].jointtype = 1;
03971 vinfos[2].foffset = j2;
03972 vinfos[2].indices[0] = _ij2[0];
03973 vinfos[2].indices[1] = _ij2[1];
03974 vinfos[2].maxsolutions = _nj2;
03975 vinfos[3].jointtype = 1;
03976 vinfos[3].foffset = j3;
03977 vinfos[3].indices[0] = _ij3[0];
03978 vinfos[3].indices[1] = _ij3[1];
03979 vinfos[3].maxsolutions = _nj3;
03980 vinfos[4].jointtype = 1;
03981 vinfos[4].foffset = j5;
03982 vinfos[4].indices[0] = _ij5[0];
03983 vinfos[4].indices[1] = _ij5[1];
03984 vinfos[4].maxsolutions = _nj5;
03985 std::vector<int> vfree(0);
03986 solutions.AddSolution(vinfos,vfree);
03987 }
03988 }
03989 }
03990 
03991 }
03992 
03993 }
03994 
03995 } else
03996 {
03997 IkReal x1551=(px)*(px);
03998 IkReal x1552=((IkReal(0.0237440000000000))*(cj3));
03999 IkReal x1553=(py)*(py);
04000 IkReal x1554=(pz)*(pz);
04001 IkReal x1555=((IkReal(3.60399994792220e-5))*(pz));
04002 IkReal x1556=((cj0)*(r00));
04003 IkReal x1557=((r01)*(sj0));
04004 IkReal x1558=((IkReal(0.000169999997543500))*(sj1));
04005 IkReal x1559=((IkReal(0.000339999995087000))*(py));
04006 IkReal x1560=((pz)*(sj1));
04007 IkReal x1561=((r02)*(sj0));
04008 IkReal x1562=((cj0)*(px));
04009 IkReal x1563=((cj1)*(r01));
04010 IkReal x1564=((IkReal(0.000169999997543500))*(cj0));
04011 IkReal x1565=((IkReal(3.60399994792220e-5))*(sj1));
04012 IkReal x1566=((py)*(r01));
04013 IkReal x1567=((r00)*(sj0));
04014 IkReal x1568=((IkReal(0.000169999997543500))*(pz));
04015 IkReal x1569=((IkReal(0.105999998468300))*(cj0));
04016 IkReal x1570=((px)*(r00));
04017 IkReal x1571=((IkReal(1.99999997110000))*(pz));
04018 IkReal x1572=((IkReal(1.91011997239877e-6))*(cj1));
04019 IkReal x1573=((r01)*(sj1));
04020 IkReal x1574=((cj1)*(r02));
04021 IkReal x1575=((r02)*(sj1));
04022 IkReal x1576=((IkReal(0.999999985550000))*(py));
04023 IkReal x1577=((IkReal(0.999999985550000))*(cj0));
04024 IkReal x1578=((IkReal(0.211999996936600))*(px));
04025 IkReal x1579=((IkReal(0.0112359998376398))*(cj0));
04026 IkReal x1580=((cj0)*(r02));
04027 IkReal x1581=((IkReal(1.80199997396110e-5))*(sj1));
04028 IkReal x1582=((IkReal(0.211999996936600))*(py));
04029 IkReal x1583=((cj1)*(px));
04030 IkReal x1584=((IkReal(0.000339999995087000))*(pz));
04031 IkReal x1585=((IkReal(0.999999985550000))*(cj1));
04032 IkReal x1586=((IkReal(0.000169999997543500))*(cj1));
04033 IkReal x1587=((cj0)*(py));
04034 IkReal x1588=((pz)*(r02));
04035 IkReal x1589=((IkReal(0.211999996936600))*(pz));
04036 IkReal x1590=((cj1)*(pz));
04037 IkReal x1591=((IkReal(0.999999985550000))*(sj1));
04038 IkReal x1592=((IkReal(1.80199997396110e-5))*(cj1));
04039 IkReal x1593=((cj0)*(r01));
04040 IkReal x1594=((IkReal(1.91011997239877e-6))*(sj1));
04041 IkReal x1595=((IkReal(0.999999985550000))*(x1554));
04042 IkReal x1596=((IkReal(0.000169999997543500))*(x1553));
04043 IkReal x1597=((IkReal(0.999999985550000))*(x1551));
04044 IkReal x1598=((IkReal(0.000169999997543500))*(x1554));
04045 IkReal x1599=((IkReal(1.99999997110000))*(px)*(py));
04046 IkReal x1600=((IkReal(0.000169999997543500))*(x1551));
04047 IkReal x1601=((IkReal(2.00000000000000))*(x1554));
04048 IkReal x1602=((IkReal(0.999999985550000))*(x1553));
04049 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j5)), IkReal(6.28318530717959))));
04050 evalcond[1]=((((IkReal(-1.00000000000000))*(sj0)*(x1576)))+(((IkReal(-0.000169999997543500))*(px)*(sj0)))+(((py)*(x1564)))+(((IkReal(-0.999999985550000))*(x1562))));
04051 evalcond[2]=((IkReal(1.00000000000000))+(((IkReal(-0.000169999997543500))*(x1567)))+(((IkReal(-0.999999985550000))*(x1556)))+(((IkReal(-0.999999985550000))*(x1557)))+(((r01)*(x1564))));
04052 evalcond[3]=((IkReal(0.0125440000000000))+(((IkReal(0.212000000000000))*(x1590)))+(((IkReal(-1.00000000000000))*(py)*(sj0)*(x1565)))+(((IkReal(-1.00000000000000))*(x1562)*(x1565)))+(((IkReal(-1.00000000000000))*(pp)))+(x1552)+(((sj0)*(sj1)*(x1578)))+(((IkReal(-1.00000000000000))*(cj0)*(sj1)*(x1582))));
04053 evalcond[4]=((((IkReal(-1.00000000000000))*(x1569)*(x1573)))+(((IkReal(-1.00000000000000))*(x1557)*(x1581)))+(((IkReal(0.105999998468300))*(sj1)*(x1567)))+(((IkReal(-1.00000000000000))*(x1556)*(x1581)))+(((IkReal(-1.00000000000000))*(x1588)))+(((IkReal(0.106000000000000))*(x1574)))+(((IkReal(-1.00000000000000))*(x1566)))+(((IkReal(-1.00000000000000))*(x1570))));
04054 evalcond[5]=((((x1556)*(x1586)))+(x1575)+(((IkReal(-1.00000000000000))*(x1567)*(x1585)))+(((x1557)*(x1586)))+(((x1563)*(x1577))));
04055 evalcond[6]=((((x1567)*(x1591)))+(((IkReal(-1.00000000000000))*(x1573)*(x1577)))+(x1574)+(((IkReal(-1.00000000000000))*(x1557)*(x1558)))+(((IkReal(-1.00000000000000))*(x1556)*(x1558))));
04056 evalcond[7]=((((IkReal(0.000169999997543500))*(r02)*(x1562)))+(((IkReal(-0.999999985550000))*(px)*(x1561)))+(((IkReal(0.000169999997543500))*(py)*(x1561)))+(((IkReal(0.999999985550000))*(pz)*(x1567)))+(((x1556)*(x1592)))+(((x1576)*(x1580)))+(((IkReal(-0.105999998468300))*(cj1)*(x1567)))+(((IkReal(-1.00000000000000))*(x1557)*(x1568)))+(((IkReal(-1.00000000000000))*(x1556)*(x1568)))+(((IkReal(-1.00000000000000))*(pz)*(r01)*(x1577)))+(((x1557)*(x1592)))+(((x1563)*(x1569)))+(((IkReal(0.106000000000000))*(x1575))));
04057 evalcond[8]=((IkReal(0.0237800000000000))+(((x1567)*(x1600)))+(((cj1)*(x1557)*(x1589)))+(((py)*(x1561)*(x1571)))+(((cj1)*(x1555)*(x1567)))+(((IkReal(-1.91011997239877e-6))*(x1567)))+(((IkReal(1.99999997110000))*(x1562)*(x1566)))+(((x1567)*(x1599)))+(((x1556)*(x1597)))+(((IkReal(3.60399994792220e-5))*(x1574)*(x1587)))+(((x1557)*(x1602)))+(((IkReal(-1.00000000000000))*(px)*(x1556)*(x1559)))+(((IkReal(-1.00000000000000))*(cj0)*(x1555)*(x1563)))+(((px)*(x1561)*(x1584)))+(((r01)*(x1551)*(x1564)))+(((IkReal(-1.00000000000000))*(x1567)*(x1598)))+(((IkReal(-1.00000000000000))*(x1567)*(x1596)))+(((IkReal(-0.0112359998376398))*(x1557)))+(((IkReal(-0.0112359998376398))*(x1556)))+(((px)*(x1557)*(x1559)))+(x1552)+(((IkReal(-1.00000000000000))*(r01)*(x1553)*(x1564)))+(((IkReal(-1.00000000000000))*(pz)*(x1559)*(x1580)))+(((r02)*(x1562)*(x1571)))+(((IkReal(-0.211999996936600))*(x1562)*(x1574)))+(((IkReal(-1.00000000000000))*(cj1)*(x1561)*(x1582)))+(((r01)*(x1554)*(x1564)))+(((IkReal(-0.212000000000000))*(py)*(r00)*(sj1)))+(((IkReal(-3.60399994792220e-5))*(x1561)*(x1583)))+(((IkReal(-1.00000000000000))*(x1557)*(x1595)))+(((IkReal(-1.00000000000000))*(x1557)*(x1597)))+(((IkReal(-1.00000000000000))*(x1556)*(x1602)))+(((IkReal(-1.00000000000000))*(x1556)*(x1595)))+(((cj1)*(x1556)*(x1589)))+(((IkReal(0.212000000000000))*(px)*(x1573)))+(((IkReal(1.91011997239877e-6))*(x1593))));
04058 evalcond[9]=((((IkReal(0.212000000000000))*(x1566)))+(((x1559)*(x1562)*(x1573)))+(((IkReal(-1.00000000000000))*(x1551)*(x1567)*(x1591)))+(((IkReal(-1.00000000000000))*(x1553)*(x1556)*(x1558)))+(((IkReal(-2.00000000000000))*(x1570)*(x1590)))+(((IkReal(0.212000000000000))*(x1588)))+(((pp)*(x1574)))+(((x1556)*(x1594)))+(((IkReal(-0.0112360000000000))*(x1574)))+(((x1559)*(x1560)*(x1561)))+(((IkReal(-1.00000000000000))*(x1551)*(x1557)*(x1558)))+(((x1573)*(x1579)))+(((IkReal(-1.00000000000000))*(x1574)*(x1601)))+(((x1553)*(x1557)*(x1558)))+(((sj1)*(x1556)*(x1599)))+(((x1553)*(x1567)*(x1591)))+(((IkReal(0.000339999995087000))*(r02)*(x1560)*(x1562)))+(((IkReal(1.99999997110000))*(py)*(x1560)*(x1580)))+(((x1554)*(x1567)*(x1591)))+(((IkReal(-1.00000000000000))*(x1554)*(x1573)*(x1577)))+(((IkReal(-1.00000000000000))*(x1554)*(x1556)*(x1558)))+(((IkReal(-1.00000000000000))*(sj1)*(x1557)*(x1599)))+(((px)*(sj1)*(x1559)*(x1567)))+(((x1557)*(x1594)))+(((x1551)*(x1556)*(x1558)))+(((IkReal(-1.00000000000000))*(x1554)*(x1557)*(x1558)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(x1563)))+(((x1553)*(x1573)*(x1577)))+(((IkReal(-0.0112359998376398))*(sj1)*(x1567)))+(((IkReal(-1.99999997110000))*(px)*(x1560)*(x1561)))+(((IkReal(0.212000000000000))*(x1570)))+(((IkReal(-1.00000000000000))*(x1551)*(x1573)*(x1577))));
04059 evalcond[10]=((((IkReal(-1.00000000000000))*(x1559)*(x1562)*(x1563)))+(((x1554)*(x1557)*(x1586)))+(((IkReal(-1.00000000000000))*(x1575)*(x1601)))+(((x1553)*(x1556)*(x1586)))+(((x1551)*(x1563)*(x1577)))+(((x1567)*(x1589)))+(((x1554)*(x1563)*(x1577)))+(((x1556)*(x1572)))+(((pp)*(x1575)))+(((IkReal(-1.00000000000000))*(x1559)*(x1561)*(x1590)))+(((IkReal(-1.00000000000000))*(x1562)*(x1574)*(x1584)))+(((IkReal(-2.00000000000000))*(x1560)*(x1566)))+(((IkReal(-2.00000000000000))*(x1560)*(x1570)))+(((IkReal(-1.00000000000000))*(x1555)*(x1557)))+(((IkReal(-1.00000000000000))*(x1555)*(x1556)))+(((IkReal(0.0112360000000000))*(x1575)))+(((x1561)*(x1571)*(x1583)))+(((IkReal(-1.00000000000000))*(x1553)*(x1567)*(x1585)))+(((IkReal(-1.99999997110000))*(py)*(x1556)*(x1583)))+(((x1557)*(x1572)))+(((IkReal(-1.00000000000000))*(x1589)*(x1593)))+(((IkReal(-1.00000000000000))*(x1559)*(x1567)*(x1583)))+(((x1580)*(x1582)))+(((x1554)*(x1556)*(x1586)))+(((IkReal(-1.00000000000000))*(x1553)*(x1563)*(x1577)))+(((x1551)*(x1567)*(x1585)))+(((IkReal(-1.00000000000000))*(x1554)*(x1567)*(x1585)))+(((x1551)*(x1557)*(x1586)))+(((IkReal(-1.00000000000000))*(x1551)*(x1556)*(x1586)))+(((x1563)*(x1579)))+(((IkReal(-1.00000000000000))*(x1571)*(x1574)*(x1587)))+(((IkReal(1.99999997110000))*(py)*(x1557)*(x1583)))+(((IkReal(-0.0112359998376398))*(cj1)*(x1567)))+(((IkReal(-1.00000000000000))*(x1553)*(x1557)*(x1586)))+(((IkReal(3.60399994792220e-5))*(py)*(x1561)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1562)))+(((IkReal(-1.00000000000000))*(x1561)*(x1578))));
04060 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  )
04061 {
04062 {
04063 IkReal dummyeval[1];
04064 IkReal gconst5;
04065 gconst5=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
04066 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
04067 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04068 {
04069 {
04070 IkReal dummyeval[1];
04071 IkReal gconst6;
04072 gconst6=IKsign(((IkReal(-175.562500000000))+(((IkReal(-196.000000000000))*((cj3)*(cj3))))+(((IkReal(-371.000000000000))*(cj3)))+(((IkReal(-196.000000000000))*((sj3)*(sj3))))));
04073 dummyeval[0]=((IkReal(-1.00000000000000))+(((IkReal(-1.11641153435386))*((cj3)*(cj3))))+(((IkReal(-1.11641153435386))*((sj3)*(sj3))))+(((IkReal(-2.11320754716981))*(cj3))));
04074 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
04075 {
04076 continue;
04077 
04078 } else
04079 {
04080 {
04081 IkReal j2array[1], cj2array[1], sj2array[1];
04082 bool j2valid[1]={false};
04083 _nj2 = 1;
04084 IkReal x1603=((cj0)*(sj1));
04085 IkReal x1604=((IkReal(1656.24997606719))*(pz));
04086 IkReal x1605=((py)*(r02));
04087 IkReal x1606=((IkReal(1750.00000000000))*(cj1));
04088 IkReal x1607=((px)*(sj3));
04089 IkReal x1608=((cj3)*(pz));
04090 IkReal x1609=((sj0)*(sj1));
04091 IkReal x1610=((IkReal(1749.99997471250))*(r02));
04092 IkReal x1611=((px)*(r01));
04093 IkReal x1612=((py)*(sj3));
04094 IkReal x1613=((pz)*(sj3));
04095 IkReal x1614=((IkReal(0.281562495931422))*(px));
04096 IkReal x1615=((IkReal(0.297499995701125))*(cj3));
04097 IkReal x1616=((IkReal(1749.99997471250))*(r01));
04098 IkReal x1617=((IkReal(1749.99997471250))*(r00));
04099 IkReal x1618=((IkReal(1656.25000000000))*(cj1));
04100 IkReal x1619=((IkReal(0.281562495931422))*(pz));
04101 IkReal x1620=((IkReal(1749.99997471250))*(cj3));
04102 IkReal x1621=((IkReal(1656.24997606719))*(px));
04103 IkReal x1622=((IkReal(0.297499995701125))*(r01));
04104 IkReal x1623=((py)*(r00));
04105 IkReal x1624=((IkReal(0.297499995701125))*(r00));
04106 if( IKabs(((gconst6)*(((((x1608)*(x1609)*(x1616)))+(((IkReal(-1.00000000000000))*(r02)*(x1609)*(x1614)))+(((IkReal(0.281562495931422))*(x1603)*(x1605)))+(((IkReal(-0.297499995701125))*(x1603)*(x1607)))+(((IkReal(-1.00000000000000))*(x1611)*(x1618)))+(((IkReal(-0.297499995701125))*(x1609)*(x1612)))+(((r01)*(x1604)*(x1609)))+(((IkReal(-1.00000000000000))*(x1605)*(x1609)*(x1620)))+(((x1603)*(x1605)*(x1615)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x1609)*(x1615)))+(((r00)*(x1609)*(x1619)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r02)*(x1603)*(x1621)))+(((cj3)*(x1606)*(x1623)))+(((IkReal(-1.00000000000000))*(cj3)*(x1606)*(x1611)))+(((IkReal(-1.00000000000000))*(r01)*(x1603)*(x1619)))+(((r00)*(x1603)*(x1604)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x1603)*(x1610)))+(((IkReal(-1749.99997471250))*(x1603)*(x1612)))+(((x1618)*(x1623)))+(((IkReal(-1656.24997606719))*(x1605)*(x1609)))+(((IkReal(-1.00000000000000))*(x1603)*(x1608)*(x1622)))+(((IkReal(1749.99997471250))*(x1607)*(x1609)))+(((x1606)*(x1613)))+(((x1603)*(x1608)*(x1617)))+(((x1608)*(x1609)*(x1624))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-0.297499995701125))*(r02)*(x1607)*(x1609)))+(((x1609)*(x1613)*(x1616)))+(((IkReal(-1.00000000000000))*(x1603)*(x1613)*(x1622)))+(((x1603)*(x1613)*(x1617)))+(((IkReal(-1.00000000000000))*(x1603)*(x1607)*(x1610)))+(((IkReal(-1749.99997471250))*(sj3)*(x1605)*(x1609)))+(((py)*(x1603)*(x1620)))+(((IkReal(-1.00000000000000))*(px)*(x1609)*(x1620)))+(((IkReal(-1.00000000000000))*(pz)*(x1618)))+(((py)*(x1609)*(x1615)))+(((IkReal(-1.00000000000000))*(x1609)*(x1621)))+(((IkReal(0.281562495931422))*(py)*(x1609)))+(((IkReal(0.297499995701125))*(sj3)*(x1603)*(x1605)))+(((r00)*(x1606)*(x1612)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1606)*(x1608)))+(((IkReal(1656.24997606719))*(py)*(x1603)))+(((px)*(x1603)*(x1615)))+(((x1603)*(x1614)))+(((IkReal(-1.00000000000000))*(r01)*(x1606)*(x1607)))+(((x1609)*(x1613)*(x1624))))))) < IKFAST_ATAN2_MAGTHRESH )
04107     continue;
04108 j2array[0]=IKatan2(((gconst6)*(((((x1608)*(x1609)*(x1616)))+(((IkReal(-1.00000000000000))*(r02)*(x1609)*(x1614)))+(((IkReal(0.281562495931422))*(x1603)*(x1605)))+(((IkReal(-0.297499995701125))*(x1603)*(x1607)))+(((IkReal(-1.00000000000000))*(x1611)*(x1618)))+(((IkReal(-0.297499995701125))*(x1609)*(x1612)))+(((r01)*(x1604)*(x1609)))+(((IkReal(-1.00000000000000))*(x1605)*(x1609)*(x1620)))+(((x1603)*(x1605)*(x1615)))+(((IkReal(-1.00000000000000))*(px)*(r02)*(x1609)*(x1615)))+(((r00)*(x1609)*(x1619)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(r02)*(x1603)*(x1621)))+(((cj3)*(x1606)*(x1623)))+(((IkReal(-1.00000000000000))*(cj3)*(x1606)*(x1611)))+(((IkReal(-1.00000000000000))*(r01)*(x1603)*(x1619)))+(((r00)*(x1603)*(x1604)))+(((IkReal(-1.00000000000000))*(cj3)*(px)*(x1603)*(x1610)))+(((IkReal(-1749.99997471250))*(x1603)*(x1612)))+(((x1618)*(x1623)))+(((IkReal(-1656.24997606719))*(x1605)*(x1609)))+(((IkReal(-1.00000000000000))*(x1603)*(x1608)*(x1622)))+(((IkReal(1749.99997471250))*(x1607)*(x1609)))+(((x1606)*(x1613)))+(((x1603)*(x1608)*(x1617)))+(((x1608)*(x1609)*(x1624)))))), ((gconst6)*(((IkReal(175.562500000000))+(((IkReal(-0.297499995701125))*(r02)*(x1607)*(x1609)))+(((x1609)*(x1613)*(x1616)))+(((IkReal(-1.00000000000000))*(x1603)*(x1613)*(x1622)))+(((x1603)*(x1613)*(x1617)))+(((IkReal(-1.00000000000000))*(x1603)*(x1607)*(x1610)))+(((IkReal(-1749.99997471250))*(sj3)*(x1605)*(x1609)))+(((py)*(x1603)*(x1620)))+(((IkReal(-1.00000000000000))*(px)*(x1609)*(x1620)))+(((IkReal(-1.00000000000000))*(pz)*(x1618)))+(((py)*(x1609)*(x1615)))+(((IkReal(-1.00000000000000))*(x1609)*(x1621)))+(((IkReal(0.281562495931422))*(py)*(x1609)))+(((IkReal(0.297499995701125))*(sj3)*(x1603)*(x1605)))+(((r00)*(x1606)*(x1612)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1606)*(x1608)))+(((IkReal(1656.24997606719))*(py)*(x1603)))+(((px)*(x1603)*(x1615)))+(((x1603)*(x1614)))+(((IkReal(-1.00000000000000))*(r01)*(x1606)*(x1607)))+(((x1609)*(x1613)*(x1624)))))));
04109 sj2array[0]=IKsin(j2array[0]);
04110 cj2array[0]=IKcos(j2array[0]);
04111 if( j2array[0] > IKPI )
04112 {
04113     j2array[0]-=IK2PI;
04114 }
04115 else if( j2array[0] < -IKPI )
04116 {    j2array[0]+=IK2PI;
04117 }
04118 j2valid[0] = true;
04119 for(int ij2 = 0; ij2 < 1; ++ij2)
04120 {
04121 if( !j2valid[ij2] )
04122 {
04123     continue;
04124 }
04125 _ij2[0] = ij2; _ij2[1] = -1;
04126 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
04127 {
04128 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
04129 {
04130     j2valid[iij2]=false; _ij2[1] = iij2; break; 
04131 }
04132 }
04133 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
04134 {
04135 IkReal evalcond[4];
04136 IkReal x1625=IKsin(j2);
04137 IkReal x1626=IKcos(j2);
04138 IkReal x1627=((r00)*(sj0));
04139 IkReal x1628=((r01)*(sj0));
04140 IkReal x1629=((py)*(sj1));
04141 IkReal x1630=((IkReal(0.999999985550000))*(r02));
04142 IkReal x1631=((px)*(sj1));
04143 IkReal x1632=((IkReal(0.999999985550000))*(sj0));
04144 IkReal x1633=((IkReal(0.000169999997543500))*(cj0));
04145 IkReal x1634=((IkReal(0.000169999997543500))*(sj0));
04146 IkReal x1635=((cj1)*(px));
04147 IkReal x1636=((pz)*(sj1));
04148 IkReal x1637=((cj0)*(r00));
04149 IkReal x1638=((cj1)*(pz));
04150 IkReal x1639=((IkReal(1.00000000000000))*(r01));
04151 IkReal x1640=((cj1)*(py));
04152 IkReal x1641=((IkReal(0.999999985550000))*(cj0));
04153 IkReal x1642=((IkReal(0.106000000000000))*(x1625));
04154 IkReal x1643=((IkReal(0.106000000000000))*(x1626));
04155 IkReal x1644=((IkReal(0.112000000000000))*(x1626));
04156 IkReal x1645=((IkReal(0.112000000000000))*(x1625));
04157 IkReal x1646=((cj3)*(x1645));
04158 IkReal x1647=((sj3)*(x1644));
04159 IkReal x1648=((cj3)*(x1644));
04160 IkReal x1649=((sj3)*(x1645));
04161 IkReal x1650=((x1643)+(x1648));
04162 IkReal x1651=((x1647)+(x1646)+(x1642));
04163 evalcond[0]=((((x1640)*(x1641)))+(x1651)+(x1636)+(((IkReal(-1.00000000000000))*(x1632)*(x1635)))+(((x1633)*(x1635)))+(((x1634)*(x1640))));
04164 evalcond[1]=((IkReal(-0.106000000000000))+(x1649)+(x1638)+(((IkReal(-1.00000000000000))*(x1650)))+(((IkReal(-1.00000000000000))*(x1629)*(x1641)))+(((IkReal(-1.00000000000000))*(x1629)*(x1634)))+(((IkReal(-1.00000000000000))*(x1631)*(x1633)))+(((x1631)*(x1632))));
04165 evalcond[2]=((((IkReal(-1.00000000000000))*(x1635)*(x1639)))+(((IkReal(-1.00000000000000))*(cj0)*(x1630)*(x1631)))+(x1651)+(((IkReal(0.000169999997543500))*(x1627)*(x1636)))+(((IkReal(-1.00000000000000))*(r02)*(x1631)*(x1634)))+(((IkReal(0.999999985550000))*(x1628)*(x1636)))+(((r00)*(x1640)))+(((r02)*(x1629)*(x1633)))+(((IkReal(-1.00000000000000))*(r01)*(x1633)*(x1636)))+(((IkReal(-1.00000000000000))*(sj0)*(x1629)*(x1630)))+(((IkReal(0.999999985550000))*(x1636)*(x1637))));
04166 evalcond[3]=((((r00)*(x1629)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((r02)*(x1634)*(x1635)))+(x1650)+(((IkReal(0.105999998468300))*(x1628)))+(((IkReal(-1.00000000000000))*(r02)*(x1633)*(x1640)))+(((IkReal(-0.000169999997543500))*(x1627)*(x1638)))+(((IkReal(-1.00000000000000))*(x1649)))+(((IkReal(-0.999999985550000))*(x1637)*(x1638)))+(((IkReal(0.105999998468300))*(x1637)))+(((r01)*(x1633)*(x1638)))+(((IkReal(-0.999999985550000))*(x1628)*(x1638)))+(((sj0)*(x1630)*(x1640)))+(((IkReal(-1.00000000000000))*(x1631)*(x1639)))+(((cj0)*(x1630)*(x1635)))+(((IkReal(1.80199997396110e-5))*(x1627))));
04167 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04168 {
04169 continue;
04170 }
04171 }
04172 
04173 {
04174 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
04175 vinfos[0].jointtype = 1;
04176 vinfos[0].foffset = j0;
04177 vinfos[0].indices[0] = _ij0[0];
04178 vinfos[0].indices[1] = _ij0[1];
04179 vinfos[0].maxsolutions = _nj0;
04180 vinfos[1].jointtype = 1;
04181 vinfos[1].foffset = j1;
04182 vinfos[1].indices[0] = _ij1[0];
04183 vinfos[1].indices[1] = _ij1[1];
04184 vinfos[1].maxsolutions = _nj1;
04185 vinfos[2].jointtype = 1;
04186 vinfos[2].foffset = j2;
04187 vinfos[2].indices[0] = _ij2[0];
04188 vinfos[2].indices[1] = _ij2[1];
04189 vinfos[2].maxsolutions = _nj2;
04190 vinfos[3].jointtype = 1;
04191 vinfos[3].foffset = j3;
04192 vinfos[3].indices[0] = _ij3[0];
04193 vinfos[3].indices[1] = _ij3[1];
04194 vinfos[3].maxsolutions = _nj3;
04195 vinfos[4].jointtype = 1;
04196 vinfos[4].foffset = j5;
04197 vinfos[4].indices[0] = _ij5[0];
04198 vinfos[4].indices[1] = _ij5[1];
04199 vinfos[4].maxsolutions = _nj5;
04200 std::vector<int> vfree(0);
04201 solutions.AddSolution(vinfos,vfree);
04202 }
04203 }
04204 }
04205 
04206 }
04207 
04208 }
04209 
04210 } else
04211 {
04212 {
04213 IkReal j2array[1], cj2array[1], sj2array[1];
04214 bool j2valid[1]={false};
04215 _nj2 = 1;
04216 IkReal x1652=((cj0)*(sj1));
04217 IkReal x1653=((IkReal(0.281562495931422))*(px));
04218 IkReal x1654=((cj1)*(sj0));
04219 IkReal x1655=((IkReal(0.281562495931422))*(py));
04220 IkReal x1656=((IkReal(1656.24997606719))*(px));
04221 IkReal x1657=((IkReal(1656.24997606719))*(py));
04222 IkReal x1658=((cj0)*(cj1));
04223 IkReal x1659=((IkReal(1749.99997471250))*(px));
04224 IkReal x1660=((IkReal(0.297499995701125))*(px));
04225 IkReal x1661=((IkReal(1749.99997471250))*(py));
04226 IkReal x1662=((IkReal(0.297499995701125))*(py));
04227 IkReal x1663=((sj0)*(sj1));
04228 IkReal x1664=((IkReal(1656.25000000000))*(pz));
04229 IkReal x1665=((IkReal(1750.00000000000))*(cj3)*(pz));
04230 IkReal x1666=((IkReal(1750.00000000000))*(pz)*(sj3));
04231 IkReal x1667=((sj3)*(x1663));
04232 IkReal x1668=((cj3)*(x1663));
04233 if( IKabs(((gconst5)*(((((sj1)*(x1664)))+(((sj1)*(x1665)))+(((x1654)*(x1655)))+(((IkReal(-1.00000000000000))*(x1662)*(x1667)))+(((cj1)*(x1666)))+(((IkReal(-1.00000000000000))*(x1654)*(x1656)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1652)*(x1661)))+(((IkReal(-1.00000000000000))*(sj3)*(x1652)*(x1660)))+(((cj3)*(x1658)*(x1660)))+(((cj3)*(x1658)*(x1661)))+(((x1659)*(x1667)))+(((x1657)*(x1658)))+(((cj3)*(x1654)*(x1662)))+(((x1653)*(x1658)))+(((IkReal(-1.00000000000000))*(cj3)*(x1654)*(x1659))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((IkReal(175.562500000000))+(((sj1)*(x1666)))+(((IkReal(-1.00000000000000))*(x1656)*(x1663)))+(((x1655)*(x1663)))+(((IkReal(-1.00000000000000))*(cj1)*(x1665)))+(((IkReal(-1.00000000000000))*(cj1)*(x1664)))+(((IkReal(-1.00000000000000))*(sj3)*(x1654)*(x1659)))+(((x1662)*(x1668)))+(((cj3)*(x1652)*(x1661)))+(((cj3)*(x1652)*(x1660)))+(((sj3)*(x1654)*(x1662)))+(((IkReal(185.500000000000))*(cj3)))+(((sj3)*(x1658)*(x1660)))+(((sj3)*(x1658)*(x1661)))+(((x1652)*(x1653)))+(((x1652)*(x1657)))+(((IkReal(-1.00000000000000))*(x1659)*(x1668))))))) < IKFAST_ATAN2_MAGTHRESH )
04234     continue;
04235 j2array[0]=IKatan2(((gconst5)*(((((sj1)*(x1664)))+(((sj1)*(x1665)))+(((x1654)*(x1655)))+(((IkReal(-1.00000000000000))*(x1662)*(x1667)))+(((cj1)*(x1666)))+(((IkReal(-1.00000000000000))*(x1654)*(x1656)))+(((IkReal(-185.500000000000))*(sj3)))+(((IkReal(-1.00000000000000))*(sj3)*(x1652)*(x1661)))+(((IkReal(-1.00000000000000))*(sj3)*(x1652)*(x1660)))+(((cj3)*(x1658)*(x1660)))+(((cj3)*(x1658)*(x1661)))+(((x1659)*(x1667)))+(((x1657)*(x1658)))+(((cj3)*(x1654)*(x1662)))+(((x1653)*(x1658)))+(((IkReal(-1.00000000000000))*(cj3)*(x1654)*(x1659)))))), ((gconst5)*(((IkReal(175.562500000000))+(((sj1)*(x1666)))+(((IkReal(-1.00000000000000))*(x1656)*(x1663)))+(((x1655)*(x1663)))+(((IkReal(-1.00000000000000))*(cj1)*(x1665)))+(((IkReal(-1.00000000000000))*(cj1)*(x1664)))+(((IkReal(-1.00000000000000))*(sj3)*(x1654)*(x1659)))+(((x1662)*(x1668)))+(((cj3)*(x1652)*(x1661)))+(((cj3)*(x1652)*(x1660)))+(((sj3)*(x1654)*(x1662)))+(((IkReal(185.500000000000))*(cj3)))+(((sj3)*(x1658)*(x1660)))+(((sj3)*(x1658)*(x1661)))+(((x1652)*(x1653)))+(((x1652)*(x1657)))+(((IkReal(-1.00000000000000))*(x1659)*(x1668)))))));
04236 sj2array[0]=IKsin(j2array[0]);
04237 cj2array[0]=IKcos(j2array[0]);
04238 if( j2array[0] > IKPI )
04239 {
04240     j2array[0]-=IK2PI;
04241 }
04242 else if( j2array[0] < -IKPI )
04243 {    j2array[0]+=IK2PI;
04244 }
04245 j2valid[0] = true;
04246 for(int ij2 = 0; ij2 < 1; ++ij2)
04247 {
04248 if( !j2valid[ij2] )
04249 {
04250     continue;
04251 }
04252 _ij2[0] = ij2; _ij2[1] = -1;
04253 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
04254 {
04255 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
04256 {
04257     j2valid[iij2]=false; _ij2[1] = iij2; break; 
04258 }
04259 }
04260 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
04261 {
04262 IkReal evalcond[4];
04263 IkReal x1669=IKsin(j2);
04264 IkReal x1670=IKcos(j2);
04265 IkReal x1671=((r00)*(sj0));
04266 IkReal x1672=((r01)*(sj0));
04267 IkReal x1673=((py)*(sj1));
04268 IkReal x1674=((IkReal(0.999999985550000))*(r02));
04269 IkReal x1675=((px)*(sj1));
04270 IkReal x1676=((IkReal(0.999999985550000))*(sj0));
04271 IkReal x1677=((IkReal(0.000169999997543500))*(cj0));
04272 IkReal x1678=((IkReal(0.000169999997543500))*(sj0));
04273 IkReal x1679=((cj1)*(px));
04274 IkReal x1680=((pz)*(sj1));
04275 IkReal x1681=((cj0)*(r00));
04276 IkReal x1682=((cj1)*(pz));
04277 IkReal x1683=((IkReal(1.00000000000000))*(r01));
04278 IkReal x1684=((cj1)*(py));
04279 IkReal x1685=((IkReal(0.999999985550000))*(cj0));
04280 IkReal x1686=((IkReal(0.106000000000000))*(x1669));
04281 IkReal x1687=((IkReal(0.106000000000000))*(x1670));
04282 IkReal x1688=((IkReal(0.112000000000000))*(x1670));
04283 IkReal x1689=((IkReal(0.112000000000000))*(x1669));
04284 IkReal x1690=((cj3)*(x1689));
04285 IkReal x1691=((sj3)*(x1688));
04286 IkReal x1692=((cj3)*(x1688));
04287 IkReal x1693=((sj3)*(x1689));
04288 IkReal x1694=((x1692)+(x1687));
04289 IkReal x1695=((x1690)+(x1691)+(x1686));
04290 evalcond[0]=((x1695)+(x1680)+(((x1684)*(x1685)))+(((IkReal(-1.00000000000000))*(x1676)*(x1679)))+(((x1678)*(x1684)))+(((x1677)*(x1679))));
04291 evalcond[1]=((IkReal(-0.106000000000000))+(((x1675)*(x1676)))+(((IkReal(-1.00000000000000))*(x1673)*(x1678)))+(((IkReal(-1.00000000000000))*(x1694)))+(x1693)+(x1682)+(((IkReal(-1.00000000000000))*(x1673)*(x1685)))+(((IkReal(-1.00000000000000))*(x1675)*(x1677))));
04292 evalcond[2]=((((IkReal(-1.00000000000000))*(r02)*(x1675)*(x1678)))+(((IkReal(0.999999985550000))*(x1680)*(x1681)))+(((IkReal(0.000169999997543500))*(x1671)*(x1680)))+(((r00)*(x1684)))+(x1695)+(((IkReal(-1.00000000000000))*(x1679)*(x1683)))+(((IkReal(-1.00000000000000))*(sj0)*(x1673)*(x1674)))+(((IkReal(-1.00000000000000))*(r01)*(x1677)*(x1680)))+(((IkReal(-1.00000000000000))*(cj0)*(x1674)*(x1675)))+(((IkReal(0.999999985550000))*(x1672)*(x1680)))+(((r02)*(x1673)*(x1677))));
04293 evalcond[3]=((((r00)*(x1673)))+(((IkReal(-1.80199997396110e-5))*(cj0)*(r01)))+(((IkReal(-1.00000000000000))*(x1693)))+(((IkReal(-1.00000000000000))*(x1675)*(x1683)))+(x1694)+(((r01)*(x1677)*(x1682)))+(((r02)*(x1678)*(x1679)))+(((IkReal(-1.00000000000000))*(r02)*(x1677)*(x1684)))+(((IkReal(1.80199997396110e-5))*(x1671)))+(((IkReal(-0.999999985550000))*(x1672)*(x1682)))+(((IkReal(-0.000169999997543500))*(x1671)*(x1682)))+(((sj0)*(x1674)*(x1684)))+(((IkReal(0.105999998468300))*(x1672)))+(((IkReal(-0.999999985550000))*(x1681)*(x1682)))+(((cj0)*(x1674)*(x1679)))+(((IkReal(0.105999998468300))*(x1681))));
04294 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
04295 {
04296 continue;
04297 }
04298 }
04299 
04300 {
04301 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
04302 vinfos[0].jointtype = 1;
04303 vinfos[0].foffset = j0;
04304 vinfos[0].indices[0] = _ij0[0];
04305 vinfos[0].indices[1] = _ij0[1];
04306 vinfos[0].maxsolutions = _nj0;
04307 vinfos[1].jointtype = 1;
04308 vinfos[1].foffset = j1;
04309 vinfos[1].indices[0] = _ij1[0];
04310 vinfos[1].indices[1] = _ij1[1];
04311 vinfos[1].maxsolutions = _nj1;
04312 vinfos[2].jointtype = 1;
04313 vinfos[2].foffset = j2;
04314 vinfos[2].indices[0] = _ij2[0];
04315 vinfos[2].indices[1] = _ij2[1];
04316 vinfos[2].maxsolutions = _nj2;
04317 vinfos[3].jointtype = 1;
04318 vinfos[3].foffset = j3;
04319 vinfos[3].indices[0] = _ij3[0];
04320 vinfos[3].indices[1] = _ij3[1];
04321 vinfos[3].maxsolutions = _nj3;
04322 vinfos[4].jointtype = 1;
04323 vinfos[4].foffset = j5;
04324 vinfos[4].indices[0] = _ij5[0];
04325 vinfos[4].indices[1] = _ij5[1];
04326 vinfos[4].maxsolutions = _nj5;
04327 std::vector<int> vfree(0);
04328 solutions.AddSolution(vinfos,vfree);
04329 }
04330 }
04331 }
04332 
04333 }
04334 
04335 }
04336 
04337 } else
04338 {
04339 if( 1 )
04340 {
04341 continue;
04342 
04343 } else
04344 {
04345 }
04346 }
04347 }
04348 }
04349 
04350 } else
04351 {
04352 {
04353 IkReal j2array[1], cj2array[1], sj2array[1];
04354 bool j2valid[1]={false};
04355 _nj2 = 1;
04356 IkReal x1696=((cj0)*(py));
04357 IkReal x1697=((r02)*(sj1));
04358 IkReal x1698=((px)*(sj0));
04359 IkReal x1699=((IkReal(13.9999997977000))*(r00));
04360 IkReal x1700=((IkReal(1.69999943143527e-5))*(cj5));
04361 IkReal x1701=((cj0)*(cj1));
04362 IkReal x1702=((IkReal(0.00237999996560900))*(r01));
04363 IkReal x1703=((cj3)*(px));
04364 IkReal x1704=((IkReal(13.9999997977000))*(r01));
04365 IkReal x1705=((cj1)*(sj0));
04366 IkReal x1706=((px)*(sj3));
04367 IkReal x1707=((IkReal(0.00237999996560900))*(r00));
04368 IkReal x1708=((IkReal(0.0212499928929409))*(cj5));
04369 IkReal x1709=((cj3)*(py));
04370 IkReal x1710=((sj3)*(x1705));
04371 IkReal x1711=((IkReal(0.0999999665550159))*(cj1)*(cj5)*(sj3));
04372 IkReal x1712=((cj5)*(pz)*(sj1)*(sj3));
04373 IkReal x1713=((IkReal(0.0999999665550159))*(cj1)*(cj3)*(cj5));
04374 IkReal x1714=((cj3)*(cj5)*(pz)*(sj1));
04375 IkReal x1715=((IkReal(124.999958193770))*(cj1)*(cj5)*(sj3));
04376 IkReal x1716=((IkReal(124.999958193770))*(cj1)*(cj3)*(cj5));
04377 if( IKabs(((gconst2)*(((((x1698)*(x1711)))+(((x1696)*(x1716)))+(((x1705)*(x1708)*(x1709)))+(((IkReal(-1.00000000000000))*(x1699)*(x1710)))+(((x1702)*(x1710)))+(((sj3)*(x1701)*(x1707)))+(((sj3)*(x1701)*(x1704)))+(((IkReal(-0.0999999680000154))*(x1712)))+(((IkReal(14.0000000000000))*(sj3)*(x1697)))+(((x1701)*(x1703)*(x1708)))+(((IkReal(-1.00000000000000))*(x1696)*(x1711)))+(((IkReal(-1.00000000000000))*(x1700)*(x1701)*(x1706)))+(((IkReal(-1.00000000000000))*(x1698)*(x1716)))+(((IkReal(124.999960000019))*(x1714)))+(((IkReal(-1.00000000000000))*(py)*(x1700)*(x1710))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((x1696)*(x1715)))+(((x1696)*(x1713)))+(((py)*(x1708)*(x1710)))+(((IkReal(-13.2500000000000))*(x1697)))+(((x1700)*(x1705)*(x1709)))+(((x1700)*(x1701)*(x1703)))+(((IkReal(-1.00000000000000))*(cj3)*(x1701)*(x1704)))+(((IkReal(-1.00000000000000))*(cj3)*(x1701)*(x1707)))+(((IkReal(-14.0000000000000))*(cj3)*(x1697)))+(((IkReal(-0.00225249996745138))*(r01)*(x1705)))+(((cj3)*(x1699)*(x1705)))+(((IkReal(-13.2499998085375))*(r01)*(x1701)))+(((IkReal(-1.00000000000000))*(cj3)*(x1702)*(x1705)))+(((IkReal(0.0999999680000154))*(x1714)))+(((x1701)*(x1706)*(x1708)))+(((IkReal(13.2499998085375))*(r00)*(x1705)))+(((IkReal(-0.00225249996745138))*(r00)*(x1701)))+(((IkReal(-1.00000000000000))*(x1698)*(x1713)))+(((IkReal(-1.00000000000000))*(x1698)*(x1715)))+(((IkReal(124.999960000019))*(x1712))))))) < IKFAST_ATAN2_MAGTHRESH )
04378     continue;
04379 j2array[0]=IKatan2(((gconst2)*(((((x1698)*(x1711)))+(((x1696)*(x1716)))+(((x1705)*(x1708)*(x1709)))+(((IkReal(-1.00000000000000))*(x1699)*(x1710)))+(((x1702)*(x1710)))+(((sj3)*(x1701)*(x1707)))+(((sj3)*(x1701)*(x1704)))+(((IkReal(-0.0999999680000154))*(x1712)))+(((IkReal(14.0000000000000))*(sj3)*(x1697)))+(((x1701)*(x1703)*(x1708)))+(((IkReal(-1.00000000000000))*(x1696)*(x1711)))+(((IkReal(-1.00000000000000))*(x1700)*(x1701)*(x1706)))+(((IkReal(-1.00000000000000))*(x1698)*(x1716)))+(((IkReal(124.999960000019))*(x1714)))+(((IkReal(-1.00000000000000))*(py)*(x1700)*(x1710)))))), ((gconst2)*(((((x1696)*(x1715)))+(((x1696)*(x1713)))+(((py)*(x1708)*(x1710)))+(((IkReal(-13.2500000000000))*(x1697)))+(((x1700)*(x1705)*(x1709)))+(((x1700)*(x1701)*(x1703)))+(((IkReal(-1.00000000000000))*(cj3)*(x1701)*(x1704)))+(((IkReal(-1.00000000000000))*(cj3)*(x1701)*(x1707)))+(((IkReal(-14.0000000000000))*(cj3)*(x1697)))+(((IkReal(-0.00225249996745138))*(r01)*(x1705)))+(((cj3)*(x1699)*(x1705)))+(((IkReal(-13.2499998085375))*(r01)*(x1701)))+(((IkReal(-1.00000000000000))*(cj3)*(x1702)*(x1705)))+(((IkReal(0.0999999680000154))*(x1714)))+(((x1701)*(x1706)*(x1708)))+(((IkReal(13.2499998085375))*(r00)*(x1705)))+(((IkReal(-0.00225249996745138))*(r00)*(x1701)))+(((IkReal(-1.00000000000000))*(x1698)*(x1713)))+(((IkReal(-1.00000000000000))*(x1698)*(x1715)))+(((IkReal(124.999960000019))*(x1712)))))));
04380 sj2array[0]=IKsin(j2array[0]);
04381 cj2array[0]=IKcos(j2array[0]);
04382 if( j2array[0] > IKPI )
04383 {
04384     j2array[0]-=IK2PI;
04385 }
04386 else if( j2array[0] < -IKPI )
04387 {    j2array[0]+=IK2PI;
04388 }
04389 j2valid[0] = true;
04390 for(int ij2 = 0; ij2 < 1; ++ij2)
04391 {
04392 if( !j2valid[ij2] )
04393 {
04394     continue;
04395 }
04396 _ij2[0] = ij2; _ij2[1] = -1;
04397 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
04398 {
04399 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
04400 {
04401     j2valid[iij2]=false; _ij2[1] = iij2; break; 
04402 }
04403 }
04404 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
04405 {
04406 IkReal evalcond[8];
04407 IkReal x1717=IKsin(j2);
04408 IkReal x1718=IKcos(j2);
04409 IkReal x1719=(py)*(py);
04410 IkReal x1720=(pz)*(pz);
04411 IkReal x1721=(px)*(px);
04412 IkReal x1722=((cj0)*(r00));
04413 IkReal x1723=((IkReal(3.60399994792220e-5))*(pz));
04414 IkReal x1724=((r01)*(sj0));
04415 IkReal x1725=((cj3)*(cj5));
04416 IkReal x1726=((sj0)*(sj1));
04417 IkReal x1727=((IkReal(0.999999985550000))*(px));
04418 IkReal x1728=((IkReal(0.000339999995087000))*(py));
04419 IkReal x1729=((pz)*(r02));
04420 IkReal x1730=((py)*(sj1));
04421 IkReal x1731=((IkReal(0.000169999997543500))*(sj1));
04422 IkReal x1732=((IkReal(0.999999680000154))*(cj5));
04423 IkReal x1733=((px)*(r00));
04424 IkReal x1734=((IkReal(0.000799999744000123))*(cj5));
04425 IkReal x1735=((IkReal(0.000169999997543500))*(cj1));
04426 IkReal x1736=((cj0)*(sj1));
04427 IkReal x1737=((IkReal(1.99999997110000))*(px));
04428 IkReal x1738=((IkReal(0.000169999997543500))*(pz));
04429 IkReal x1739=((IkReal(0.112000000000000))*(sj5));
04430 IkReal x1740=((cj1)*(r02));
04431 IkReal x1741=((IkReal(0.106000000000000))*(sj5));
04432 IkReal x1742=((IkReal(0.000339999995087000))*(px));
04433 IkReal x1743=((IkReal(0.112000000000000))*(cj3));
04434 IkReal x1744=((cj1)*(py));
04435 IkReal x1745=((py)*(r02));
04436 IkReal x1746=((cj0)*(px));
04437 IkReal x1747=((px)*(r01));
04438 IkReal x1748=((cj0)*(r01));
04439 IkReal x1749=((IkReal(0.999999985550000))*(r01));
04440 IkReal x1750=((IkReal(0.999999985550000))*(pz));
04441 IkReal x1751=((r02)*(sj1));
04442 IkReal x1752=((cj1)*(sj0));
04443 IkReal x1753=((IkReal(1.99999997110000))*(cj0));
04444 IkReal x1754=((IkReal(0.000169999997543500))*(r02));
04445 IkReal x1755=((IkReal(1.04639966515216e-6))*(cj5));
04446 IkReal x1756=((IkReal(0.999999985550000))*(cj0));
04447 IkReal x1757=((IkReal(0.999999985550000))*(cj1));
04448 IkReal x1758=((cj1)*(pz));
04449 IkReal x1759=((py)*(sj0));
04450 IkReal x1760=((r00)*(sj0));
04451 IkReal x1761=((IkReal(1.91011997239877e-6))*(cj1));
04452 IkReal x1762=((IkReal(1.91011997239877e-6))*(sj1));
04453 IkReal x1763=((IkReal(0.00130799958144020))*(cj5));
04454 IkReal x1764=((IkReal(0.211999996936600))*(pz));
04455 IkReal x1765=((pz)*(sj1));
04456 IkReal x1766=((sj3)*(x1718));
04457 IkReal x1767=((cj1)*(x1747));
04458 IkReal x1768=((r00)*(x1752));
04459 IkReal x1769=((IkReal(0.999999985550000))*(x1720));
04460 IkReal x1770=((IkReal(2.00000000000000))*(pz)*(r01));
04461 IkReal x1771=((sj3)*(x1717));
04462 IkReal x1772=((cj5)*(x1718));
04463 IkReal x1773=((IkReal(0.999999985550000))*(x1719));
04464 IkReal x1774=((IkReal(2.00000000000000))*(x1720));
04465 IkReal x1775=((IkReal(0.999999985550000))*(x1721));
04466 IkReal x1776=((px)*(r02)*(sj0));
04467 IkReal x1777=((cj5)*(x1717));
04468 evalcond[0]=((x1765)+(((x1744)*(x1756)))+(((IkReal(0.106000000000000))*(x1717)))+(((IkReal(0.112000000000000))*(x1766)))+(((IkReal(-1.00000000000000))*(x1727)*(x1752)))+(((x1735)*(x1759)))+(((x1717)*(x1743)))+(((x1735)*(x1746))));
04469 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(0.112000000000000))*(x1771)))+(x1758)+(((x1726)*(x1727)))+(((IkReal(-0.106000000000000))*(x1718)))+(((IkReal(-1.00000000000000))*(x1730)*(x1756)))+(((IkReal(-1.00000000000000))*(x1731)*(x1746)))+(((IkReal(-0.000169999997543500))*(py)*(x1726)))+(((IkReal(-1.00000000000000))*(x1718)*(x1743))));
04470 evalcond[2]=((((x1732)*(x1771)))+(((x1722)*(x1735)))+(((x1724)*(x1735)))+(x1751)+(((IkReal(0.000799999744000123))*(x1717)*(x1725)))+(((x1748)*(x1757)))+(((x1734)*(x1766)))+(((IkReal(-0.999999680000154))*(x1718)*(x1725)))+(((IkReal(-0.999999985550000))*(x1768))));
04471 evalcond[3]=((x1740)+(((IkReal(-1.00000000000000))*(x1722)*(x1731)))+(((IkReal(-1.00000000000000))*(x1736)*(x1749)))+(((IkReal(-1.00000000000000))*(x1732)*(x1766)))+(((IkReal(0.999999985550000))*(r00)*(x1726)))+(((x1734)*(x1771)))+(((IkReal(-0.000799999744000123))*(x1718)*(x1725)))+(((IkReal(-1.00000000000000))*(x1724)*(x1731)))+(((IkReal(-0.999999680000154))*(x1717)*(x1725))));
04472 evalcond[4]=((((r00)*(x1726)*(x1738)))+(((IkReal(-1.00000000000000))*(px)*(x1726)*(x1754)))+(((IkReal(-1.00000000000000))*(x1767)))+(((sj1)*(x1724)*(x1750)))+(((IkReal(-1.00000000000000))*(x1717)*(x1741)))+(((sj1)*(x1722)*(x1750)))+(((IkReal(-1.00000000000000))*(cj3)*(x1717)*(x1739)))+(((IkReal(-0.999999985550000))*(x1726)*(x1745)))+(((IkReal(-1.00000000000000))*(r02)*(x1727)*(x1736)))+(((IkReal(-1.00000000000000))*(pz)*(x1731)*(x1748)))+(((r00)*(x1744)))+(((IkReal(-1.00000000000000))*(x1739)*(x1766)))+(((cj0)*(x1730)*(x1754))));
04473 evalcond[5]=((((IkReal(-1.00000000000000))*(pz)*(x1735)*(x1760)))+(((IkReal(-1.80199997396110e-5))*(x1748)))+(((r00)*(x1730)))+(((x1735)*(x1776)))+(((IkReal(-1.00000000000000))*(cj3)*(x1718)*(x1739)))+(((IkReal(-1.00000000000000))*(cj0)*(x1735)*(x1745)))+(((cj0)*(x1727)*(x1740)))+(((pz)*(x1735)*(x1748)))+(((IkReal(-1.00000000000000))*(sj1)*(x1747)))+(((IkReal(-1.00000000000000))*(cj1)*(x1722)*(x1750)))+(((IkReal(0.999999985550000))*(x1740)*(x1759)))+(((IkReal(-1.00000000000000))*(x1718)*(x1741)))+(((IkReal(-1.00000000000000))*(cj1)*(x1724)*(x1750)))+(((x1739)*(x1771)))+(((IkReal(1.80199997396110e-5))*(x1760)))+(((IkReal(0.105999998468300))*(x1724)))+(((IkReal(0.105999998468300))*(x1722))));
04474 evalcond[6]=((((IkReal(-1.00000000000000))*(x1721)*(x1736)*(x1749)))+(((x1721)*(x1722)*(x1731)))+(((r00)*(x1726)*(x1773)))+(((IkReal(-0.0112359998376398))*(r00)*(x1726)))+(((x1722)*(x1730)*(x1737)))+(((IkReal(-1.00000000000000))*(x1724)*(x1730)*(x1737)))+(((IkReal(0.212000000000000))*(x1733)))+(((IkReal(-1.00000000000000))*(x1726)*(x1729)*(x1737)))+(((IkReal(0.212000000000000))*(x1729)))+(((x1728)*(x1736)*(x1747)))+(((IkReal(-2.00000000000000))*(x1733)*(x1758)))+(((x1722)*(x1762)))+(((IkReal(1.89951939215389e-5))*(x1772)))+(((IkReal(-1.00000000000000))*(x1763)*(x1766)))+(((x1719)*(x1736)*(x1749)))+(((IkReal(-0.0237439924019236))*(x1777)))+(((IkReal(-1.00000000000000))*(x1719)*(x1722)*(x1731)))+(((x1724)*(x1762)))+(((IkReal(-1.00000000000000))*(x1755)*(x1771)))+(((IkReal(-0.0237799923904037))*(x1717)*(x1725)))+(((x1726)*(x1728)*(x1733)))+(((IkReal(-1.00000000000000))*(x1720)*(x1736)*(x1749)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((x1726)*(x1728)*(x1729)))+(((IkReal(-1.00000000000000))*(x1744)*(x1770)))+(((IkReal(-1.00000000000000))*(x1740)*(x1774)))+(((IkReal(1.90239939123229e-5))*(x1718)*(x1725)))+(((r00)*(x1726)*(x1769)))+(((IkReal(-1.00000000000000))*(x1720)*(x1722)*(x1731)))+(((x1729)*(x1730)*(x1753)))+(((IkReal(-0.0112360000000000))*(x1740)))+(((x1729)*(x1736)*(x1742)))+(((x1719)*(x1724)*(x1731)))+(((IkReal(0.0112359998376398))*(r01)*(x1736)))+(((IkReal(-1.00000000000000))*(r00)*(x1726)*(x1775)))+(((IkReal(-1.00000000000000))*(x1720)*(x1724)*(x1731)))+(((IkReal(-1.00000000000000))*(x1721)*(x1724)*(x1731)))+(((pp)*(x1740))));
04475 evalcond[7]=((((pp)*(x1751)))+(((IkReal(-1.00000000000000))*(x1719)*(x1724)*(x1735)))+(((x1720)*(x1748)*(x1757)))+(((x1720)*(x1724)*(x1735)))+(((IkReal(-1.00000000000000))*(x1719)*(x1748)*(x1757)))+(((x1721)*(x1724)*(x1735)))+(((IkReal(-0.0237799923904037))*(x1718)*(x1725)))+(((x1763)*(x1771)))+(((IkReal(-1.00000000000000))*(x1722)*(x1737)*(x1744)))+(((x1720)*(x1722)*(x1735)))+(((IkReal(-1.00000000000000))*(x1722)*(x1723)))+(((IkReal(-1.00000000000000))*(x1755)*(x1766)))+(((x1722)*(x1761)))+(((IkReal(-0.0237439924019236))*(x1772)))+(((IkReal(-1.00000000000000))*(x1721)*(x1722)*(x1735)))+(((x1719)*(x1722)*(x1735)))+(((IkReal(-1.00000000000000))*(x1723)*(x1724)))+(((IkReal(-1.00000000000000))*(x1729)*(x1744)*(x1753)))+(((x1724)*(x1761)))+(((IkReal(3.60399994792220e-5))*(sj0)*(x1745)))+(((IkReal(-0.0112359998376398))*(x1768)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1729)*(x1742)))+(((IkReal(-1.00000000000000))*(x1748)*(x1764)))+(((IkReal(0.211999996936600))*(cj0)*(x1745)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x1728)*(x1746)))+(((IkReal(-1.89951939215389e-5))*(x1777)))+(((IkReal(-1.90239939123229e-5))*(x1717)*(x1725)))+(((IkReal(-1.00000000000000))*(x1730)*(x1770)))+(((x1724)*(x1737)*(x1744)))+(((x1721)*(x1748)*(x1757)))+(((IkReal(0.0112359998376398))*(cj1)*(x1748)))+(((IkReal(-1.00000000000000))*(x1751)*(x1774)))+(((x1729)*(x1737)*(x1752)))+(((IkReal(0.0112360000000000))*(x1751)))+(((IkReal(-2.00000000000000))*(x1733)*(x1765)))+(((IkReal(-1.00000000000000))*(x1728)*(x1733)*(x1752)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1746)))+(((IkReal(-1.00000000000000))*(x1768)*(x1773)))+(((x1768)*(x1775)))+(((IkReal(-1.00000000000000))*(x1768)*(x1769)))+(((IkReal(-1.00000000000000))*(x1728)*(x1729)*(x1752)))+(((x1760)*(x1764)))+(((IkReal(-0.211999996936600))*(x1776))));
04476 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  )
04477 {
04478 continue;
04479 }
04480 }
04481 
04482 {
04483 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
04484 vinfos[0].jointtype = 1;
04485 vinfos[0].foffset = j0;
04486 vinfos[0].indices[0] = _ij0[0];
04487 vinfos[0].indices[1] = _ij0[1];
04488 vinfos[0].maxsolutions = _nj0;
04489 vinfos[1].jointtype = 1;
04490 vinfos[1].foffset = j1;
04491 vinfos[1].indices[0] = _ij1[0];
04492 vinfos[1].indices[1] = _ij1[1];
04493 vinfos[1].maxsolutions = _nj1;
04494 vinfos[2].jointtype = 1;
04495 vinfos[2].foffset = j2;
04496 vinfos[2].indices[0] = _ij2[0];
04497 vinfos[2].indices[1] = _ij2[1];
04498 vinfos[2].maxsolutions = _nj2;
04499 vinfos[3].jointtype = 1;
04500 vinfos[3].foffset = j3;
04501 vinfos[3].indices[0] = _ij3[0];
04502 vinfos[3].indices[1] = _ij3[1];
04503 vinfos[3].maxsolutions = _nj3;
04504 vinfos[4].jointtype = 1;
04505 vinfos[4].foffset = j5;
04506 vinfos[4].indices[0] = _ij5[0];
04507 vinfos[4].indices[1] = _ij5[1];
04508 vinfos[4].maxsolutions = _nj5;
04509 std::vector<int> vfree(0);
04510 solutions.AddSolution(vinfos,vfree);
04511 }
04512 }
04513 }
04514 
04515 }
04516 
04517 }
04518 
04519 } else
04520 {
04521 {
04522 IkReal j2array[1], cj2array[1], sj2array[1];
04523 bool j2valid[1]={false};
04524 _nj2 = 1;
04525 IkReal x1778=((cj0)*(sj1));
04526 IkReal x1779=((IkReal(0.281562495931422))*(px));
04527 IkReal x1780=((IkReal(1750.00000000000))*(pz));
04528 IkReal x1781=((sj1)*(sj3));
04529 IkReal x1782=((cj1)*(cj3));
04530 IkReal x1783=((IkReal(1656.24997606719))*(cj1));
04531 IkReal x1784=((px)*(sj0));
04532 IkReal x1785=((cj3)*(sj1));
04533 IkReal x1786=((cj0)*(py));
04534 IkReal x1787=((cj1)*(sj3));
04535 IkReal x1788=((py)*(sj0));
04536 IkReal x1789=((IkReal(0.297499995701125))*(px));
04537 IkReal x1790=((IkReal(1749.99997471250))*(py));
04538 IkReal x1791=((IkReal(1656.25000000000))*(pz));
04539 if( IKabs(((gconst1)*(((((cj0)*(cj1)*(x1779)))+(((IkReal(-1.00000000000000))*(x1783)*(x1784)))+(((x1783)*(x1786)))+(((IkReal(0.281562495931422))*(cj1)*(x1788)))+(((IkReal(-1749.99997471250))*(x1782)*(x1784)))+(((sj1)*(x1791)))+(((IkReal(-0.297499995701125))*(x1781)*(x1788)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj0)*(x1782)*(x1789)))+(((IkReal(-1.00000000000000))*(sj3)*(x1778)*(x1790)))+(((IkReal(0.297499995701125))*(x1782)*(x1788)))+(((IkReal(1749.99997471250))*(x1781)*(x1784)))+(((IkReal(1749.99997471250))*(x1782)*(x1786)))+(((x1780)*(x1787)))+(((x1780)*(x1785)))+(((IkReal(-1.00000000000000))*(sj3)*(x1778)*(x1789))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((IkReal(175.562500000000))+(((IkReal(0.281562495931422))*(sj1)*(x1788)))+(((IkReal(0.297499995701125))*(x1785)*(x1788)))+(((cj0)*(x1787)*(x1789)))+(((IkReal(0.297499995701125))*(x1787)*(x1788)))+(((IkReal(-1749.99997471250))*(x1784)*(x1785)))+(((IkReal(-1749.99997471250))*(x1784)*(x1787)))+(((IkReal(1749.99997471250))*(x1786)*(x1787)))+(((IkReal(-1.00000000000000))*(cj1)*(x1791)))+(((cj3)*(x1778)*(x1789)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1780)*(x1782)))+(((cj3)*(x1778)*(x1790)))+(((x1780)*(x1781)))+(((x1778)*(x1779)))+(((IkReal(-1656.24997606719))*(sj1)*(x1784)))+(((IkReal(1656.24997606719))*(py)*(x1778))))))) < IKFAST_ATAN2_MAGTHRESH )
04540     continue;
04541 j2array[0]=IKatan2(((gconst1)*(((((cj0)*(cj1)*(x1779)))+(((IkReal(-1.00000000000000))*(x1783)*(x1784)))+(((x1783)*(x1786)))+(((IkReal(0.281562495931422))*(cj1)*(x1788)))+(((IkReal(-1749.99997471250))*(x1782)*(x1784)))+(((sj1)*(x1791)))+(((IkReal(-0.297499995701125))*(x1781)*(x1788)))+(((IkReal(-185.500000000000))*(sj3)))+(((cj0)*(x1782)*(x1789)))+(((IkReal(-1.00000000000000))*(sj3)*(x1778)*(x1790)))+(((IkReal(0.297499995701125))*(x1782)*(x1788)))+(((IkReal(1749.99997471250))*(x1781)*(x1784)))+(((IkReal(1749.99997471250))*(x1782)*(x1786)))+(((x1780)*(x1787)))+(((x1780)*(x1785)))+(((IkReal(-1.00000000000000))*(sj3)*(x1778)*(x1789)))))), ((gconst1)*(((IkReal(175.562500000000))+(((IkReal(0.281562495931422))*(sj1)*(x1788)))+(((IkReal(0.297499995701125))*(x1785)*(x1788)))+(((cj0)*(x1787)*(x1789)))+(((IkReal(0.297499995701125))*(x1787)*(x1788)))+(((IkReal(-1749.99997471250))*(x1784)*(x1785)))+(((IkReal(-1749.99997471250))*(x1784)*(x1787)))+(((IkReal(1749.99997471250))*(x1786)*(x1787)))+(((IkReal(-1.00000000000000))*(cj1)*(x1791)))+(((cj3)*(x1778)*(x1789)))+(((IkReal(185.500000000000))*(cj3)))+(((IkReal(-1.00000000000000))*(x1780)*(x1782)))+(((cj3)*(x1778)*(x1790)))+(((x1780)*(x1781)))+(((x1778)*(x1779)))+(((IkReal(-1656.24997606719))*(sj1)*(x1784)))+(((IkReal(1656.24997606719))*(py)*(x1778)))))));
04542 sj2array[0]=IKsin(j2array[0]);
04543 cj2array[0]=IKcos(j2array[0]);
04544 if( j2array[0] > IKPI )
04545 {
04546     j2array[0]-=IK2PI;
04547 }
04548 else if( j2array[0] < -IKPI )
04549 {    j2array[0]+=IK2PI;
04550 }
04551 j2valid[0] = true;
04552 for(int ij2 = 0; ij2 < 1; ++ij2)
04553 {
04554 if( !j2valid[ij2] )
04555 {
04556     continue;
04557 }
04558 _ij2[0] = ij2; _ij2[1] = -1;
04559 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
04560 {
04561 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
04562 {
04563     j2valid[iij2]=false; _ij2[1] = iij2; break; 
04564 }
04565 }
04566 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
04567 {
04568 IkReal evalcond[8];
04569 IkReal x1792=IKsin(j2);
04570 IkReal x1793=IKcos(j2);
04571 IkReal x1794=(py)*(py);
04572 IkReal x1795=(pz)*(pz);
04573 IkReal x1796=(px)*(px);
04574 IkReal x1797=((cj0)*(r00));
04575 IkReal x1798=((IkReal(3.60399994792220e-5))*(pz));
04576 IkReal x1799=((r01)*(sj0));
04577 IkReal x1800=((cj3)*(cj5));
04578 IkReal x1801=((sj0)*(sj1));
04579 IkReal x1802=((IkReal(0.999999985550000))*(px));
04580 IkReal x1803=((IkReal(0.000339999995087000))*(py));
04581 IkReal x1804=((pz)*(r02));
04582 IkReal x1805=((py)*(sj1));
04583 IkReal x1806=((IkReal(0.000169999997543500))*(sj1));
04584 IkReal x1807=((IkReal(0.999999680000154))*(cj5));
04585 IkReal x1808=((px)*(r00));
04586 IkReal x1809=((IkReal(0.000799999744000123))*(cj5));
04587 IkReal x1810=((IkReal(0.000169999997543500))*(cj1));
04588 IkReal x1811=((cj0)*(sj1));
04589 IkReal x1812=((IkReal(1.99999997110000))*(px));
04590 IkReal x1813=((IkReal(0.000169999997543500))*(pz));
04591 IkReal x1814=((IkReal(0.112000000000000))*(sj5));
04592 IkReal x1815=((cj1)*(r02));
04593 IkReal x1816=((IkReal(0.106000000000000))*(sj5));
04594 IkReal x1817=((IkReal(0.000339999995087000))*(px));
04595 IkReal x1818=((IkReal(0.112000000000000))*(cj3));
04596 IkReal x1819=((cj1)*(py));
04597 IkReal x1820=((py)*(r02));
04598 IkReal x1821=((cj0)*(px));
04599 IkReal x1822=((px)*(r01));
04600 IkReal x1823=((cj0)*(r01));
04601 IkReal x1824=((IkReal(0.999999985550000))*(r01));
04602 IkReal x1825=((IkReal(0.999999985550000))*(pz));
04603 IkReal x1826=((r02)*(sj1));
04604 IkReal x1827=((cj1)*(sj0));
04605 IkReal x1828=((IkReal(1.99999997110000))*(cj0));
04606 IkReal x1829=((IkReal(0.000169999997543500))*(r02));
04607 IkReal x1830=((IkReal(1.04639966515216e-6))*(cj5));
04608 IkReal x1831=((IkReal(0.999999985550000))*(cj0));
04609 IkReal x1832=((IkReal(0.999999985550000))*(cj1));
04610 IkReal x1833=((cj1)*(pz));
04611 IkReal x1834=((py)*(sj0));
04612 IkReal x1835=((r00)*(sj0));
04613 IkReal x1836=((IkReal(1.91011997239877e-6))*(cj1));
04614 IkReal x1837=((IkReal(1.91011997239877e-6))*(sj1));
04615 IkReal x1838=((IkReal(0.00130799958144020))*(cj5));
04616 IkReal x1839=((IkReal(0.211999996936600))*(pz));
04617 IkReal x1840=((pz)*(sj1));
04618 IkReal x1841=((sj3)*(x1793));
04619 IkReal x1842=((cj1)*(x1822));
04620 IkReal x1843=((r00)*(x1827));
04621 IkReal x1844=((IkReal(0.999999985550000))*(x1795));
04622 IkReal x1845=((IkReal(2.00000000000000))*(pz)*(r01));
04623 IkReal x1846=((sj3)*(x1792));
04624 IkReal x1847=((cj5)*(x1793));
04625 IkReal x1848=((IkReal(0.999999985550000))*(x1794));
04626 IkReal x1849=((IkReal(2.00000000000000))*(x1795));
04627 IkReal x1850=((IkReal(0.999999985550000))*(x1796));
04628 IkReal x1851=((px)*(r02)*(sj0));
04629 IkReal x1852=((cj5)*(x1792));
04630 evalcond[0]=((((IkReal(-1.00000000000000))*(x1802)*(x1827)))+(((IkReal(0.112000000000000))*(x1841)))+(x1840)+(((x1810)*(x1821)))+(((x1810)*(x1834)))+(((x1819)*(x1831)))+(((IkReal(0.106000000000000))*(x1792)))+(((x1792)*(x1818))));
04631 evalcond[1]=((IkReal(-0.106000000000000))+(((IkReal(-1.00000000000000))*(x1806)*(x1821)))+(((x1801)*(x1802)))+(((IkReal(-1.00000000000000))*(x1793)*(x1818)))+(((IkReal(-1.00000000000000))*(x1805)*(x1831)))+(((IkReal(-0.000169999997543500))*(py)*(x1801)))+(((IkReal(0.112000000000000))*(x1846)))+(((IkReal(-0.106000000000000))*(x1793)))+(x1833));
04632 evalcond[2]=((((IkReal(0.000799999744000123))*(x1792)*(x1800)))+(((IkReal(-0.999999680000154))*(x1793)*(x1800)))+(((IkReal(-0.999999985550000))*(x1843)))+(((x1799)*(x1810)))+(((x1823)*(x1832)))+(((x1809)*(x1841)))+(((x1807)*(x1846)))+(x1826)+(((x1797)*(x1810))));
04633 evalcond[3]=((((IkReal(-0.000799999744000123))*(x1793)*(x1800)))+(((IkReal(-1.00000000000000))*(x1811)*(x1824)))+(((IkReal(-1.00000000000000))*(x1807)*(x1841)))+(((IkReal(-1.00000000000000))*(x1797)*(x1806)))+(((IkReal(-1.00000000000000))*(x1799)*(x1806)))+(((IkReal(0.999999985550000))*(r00)*(x1801)))+(((IkReal(-0.999999680000154))*(x1792)*(x1800)))+(((x1809)*(x1846)))+(x1815));
04634 evalcond[4]=((((sj1)*(x1797)*(x1825)))+(((sj1)*(x1799)*(x1825)))+(((IkReal(-1.00000000000000))*(cj3)*(x1792)*(x1814)))+(((IkReal(-0.999999985550000))*(x1801)*(x1820)))+(((IkReal(-1.00000000000000))*(x1792)*(x1816)))+(((IkReal(-1.00000000000000))*(pz)*(x1806)*(x1823)))+(((IkReal(-1.00000000000000))*(x1814)*(x1841)))+(((r00)*(x1801)*(x1813)))+(((IkReal(-1.00000000000000))*(x1842)))+(((r00)*(x1819)))+(((IkReal(-1.00000000000000))*(r02)*(x1802)*(x1811)))+(((cj0)*(x1805)*(x1829)))+(((IkReal(-1.00000000000000))*(px)*(x1801)*(x1829))));
04635 evalcond[5]=((((IkReal(-1.00000000000000))*(cj0)*(x1810)*(x1820)))+(((IkReal(0.105999998468300))*(x1797)))+(((IkReal(0.105999998468300))*(x1799)))+(((IkReal(-1.00000000000000))*(x1793)*(x1816)))+(((IkReal(0.999999985550000))*(x1815)*(x1834)))+(((IkReal(-1.00000000000000))*(cj3)*(x1793)*(x1814)))+(((IkReal(-1.00000000000000))*(sj1)*(x1822)))+(((pz)*(x1810)*(x1823)))+(((IkReal(-1.80199997396110e-5))*(x1823)))+(((IkReal(-1.00000000000000))*(cj1)*(x1797)*(x1825)))+(((x1814)*(x1846)))+(((IkReal(-1.00000000000000))*(pz)*(x1810)*(x1835)))+(((x1810)*(x1851)))+(((r00)*(x1805)))+(((IkReal(-1.00000000000000))*(cj1)*(x1799)*(x1825)))+(((cj0)*(x1802)*(x1815)))+(((IkReal(1.80199997396110e-5))*(x1835))));
04636 evalcond[6]=((((IkReal(-1.00000000000000))*(x1819)*(x1845)))+(((IkReal(-1.00000000000000))*(x1794)*(x1797)*(x1806)))+(((IkReal(-1.00000000000000))*(x1830)*(x1846)))+(((IkReal(1.90239939123229e-5))*(x1793)*(x1800)))+(((IkReal(-0.0237799923904037))*(x1792)*(x1800)))+(((x1794)*(x1799)*(x1806)))+(((IkReal(-1.00000000000000))*(x1799)*(x1805)*(x1812)))+(((IkReal(-0.0112360000000000))*(x1815)))+(((IkReal(1.89951939215389e-5))*(x1847)))+(((x1796)*(x1797)*(x1806)))+(((IkReal(0.0112359998376398))*(r01)*(x1811)))+(((IkReal(-1.00000000000000))*(x1796)*(x1811)*(x1824)))+(((IkReal(-1.00000000000000))*(r00)*(x1801)*(x1850)))+(((x1797)*(x1837)))+(((x1804)*(x1811)*(x1817)))+(((IkReal(-2.00000000000000))*(x1808)*(x1833)))+(((x1794)*(x1811)*(x1824)))+(((IkReal(0.212000000000000))*(x1808)))+(((IkReal(0.212000000000000))*(x1804)))+(((IkReal(-1.00000000000000))*(x1795)*(x1799)*(x1806)))+(((x1804)*(x1805)*(x1828)))+(((IkReal(-1.00000000000000))*(x1815)*(x1849)))+(((IkReal(-1.00000000000000))*(x1796)*(x1799)*(x1806)))+(((IkReal(-0.0237439924019236))*(x1852)))+(((IkReal(0.212000000000000))*(py)*(r01)))+(((x1797)*(x1805)*(x1812)))+(((IkReal(-1.00000000000000))*(x1801)*(x1804)*(x1812)))+(((pp)*(x1815)))+(((x1801)*(x1803)*(x1808)))+(((x1801)*(x1803)*(x1804)))+(((IkReal(-1.00000000000000))*(x1838)*(x1841)))+(((IkReal(-1.00000000000000))*(x1795)*(x1811)*(x1824)))+(((IkReal(-1.00000000000000))*(x1795)*(x1797)*(x1806)))+(((r00)*(x1801)*(x1848)))+(((r00)*(x1801)*(x1844)))+(((x1799)*(x1837)))+(((x1803)*(x1811)*(x1822)))+(((IkReal(-0.0112359998376398))*(r00)*(x1801))));
04637 evalcond[7]=((((IkReal(3.60399994792220e-5))*(sj0)*(x1820)))+(((IkReal(0.0112359998376398))*(cj1)*(x1823)))+(((x1843)*(x1850)))+(((IkReal(-1.00000000000000))*(x1805)*(x1845)))+(((IkReal(-1.00000000000000))*(x1803)*(x1804)*(x1827)))+(((x1838)*(x1846)))+(((IkReal(-1.00000000000000))*(x1843)*(x1848)))+(((IkReal(-1.00000000000000))*(x1843)*(x1844)))+(((IkReal(-1.00000000000000))*(x1830)*(x1841)))+(((x1795)*(x1799)*(x1810)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(x1804)*(x1817)))+(((x1795)*(x1797)*(x1810)))+(((IkReal(0.211999996936600))*(cj0)*(x1820)))+(((IkReal(-1.90239939123229e-5))*(x1792)*(x1800)))+(((pp)*(x1826)))+(((x1835)*(x1839)))+(((IkReal(-0.0237799923904037))*(x1793)*(x1800)))+(((IkReal(-0.211999996936600))*(x1851)))+(((x1796)*(x1823)*(x1832)))+(((IkReal(-1.00000000000000))*(x1796)*(x1797)*(x1810)))+(((IkReal(-1.00000000000000))*(x1797)*(x1812)*(x1819)))+(((IkReal(-1.00000000000000))*(x1803)*(x1808)*(x1827)))+(((x1794)*(x1797)*(x1810)))+(((IkReal(-0.0237439924019236))*(x1847)))+(((x1797)*(x1836)))+(((IkReal(3.60399994792220e-5))*(r02)*(x1821)))+(((IkReal(-0.0112359998376398))*(x1843)))+(((IkReal(-1.00000000000000))*(x1794)*(x1823)*(x1832)))+(((IkReal(-1.00000000000000))*(x1804)*(x1819)*(x1828)))+(((IkReal(-1.00000000000000))*(cj1)*(r01)*(x1803)*(x1821)))+(((x1804)*(x1812)*(x1827)))+(((x1796)*(x1799)*(x1810)))+(((IkReal(-1.00000000000000))*(x1826)*(x1849)))+(((IkReal(-1.00000000000000))*(x1823)*(x1839)))+(((IkReal(-1.89951939215389e-5))*(x1852)))+(((IkReal(-1.00000000000000))*(x1794)*(x1799)*(x1810)))+(((x1795)*(x1823)*(x1832)))+(((IkReal(0.0112360000000000))*(x1826)))+(((IkReal(-1.00000000000000))*(x1797)*(x1798)))+(((IkReal(-1.00000000000000))*(x1798)*(x1799)))+(((x1799)*(x1836)))+(((x1799)*(x1812)*(x1819)))+(((IkReal(-2.00000000000000))*(x1808)*(x1840))));
04638 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  )
04639 {
04640 continue;
04641 }
04642 }
04643 
04644 {
04645 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
04646 vinfos[0].jointtype = 1;
04647 vinfos[0].foffset = j0;
04648 vinfos[0].indices[0] = _ij0[0];
04649 vinfos[0].indices[1] = _ij0[1];
04650 vinfos[0].maxsolutions = _nj0;
04651 vinfos[1].jointtype = 1;
04652 vinfos[1].foffset = j1;
04653 vinfos[1].indices[0] = _ij1[0];
04654 vinfos[1].indices[1] = _ij1[1];
04655 vinfos[1].maxsolutions = _nj1;
04656 vinfos[2].jointtype = 1;
04657 vinfos[2].foffset = j2;
04658 vinfos[2].indices[0] = _ij2[0];
04659 vinfos[2].indices[1] = _ij2[1];
04660 vinfos[2].maxsolutions = _nj2;
04661 vinfos[3].jointtype = 1;
04662 vinfos[3].foffset = j3;
04663 vinfos[3].indices[0] = _ij3[0];
04664 vinfos[3].indices[1] = _ij3[1];
04665 vinfos[3].maxsolutions = _nj3;
04666 vinfos[4].jointtype = 1;
04667 vinfos[4].foffset = j5;
04668 vinfos[4].indices[0] = _ij5[0];
04669 vinfos[4].indices[1] = _ij5[1];
04670 vinfos[4].maxsolutions = _nj5;
04671 std::vector<int> vfree(0);
04672 solutions.AddSolution(vinfos,vfree);
04673 }
04674 }
04675 }
04676 
04677 }
04678 
04679 }
04680 }
04681 }
04682 
04683 }
04684 
04685 }
04686 }
04687 }
04688     }
04689 }
04690 }
04691 }
04692 return solutions.GetNumSolutions()>0;
04693 }
04694 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
04695 {
04696     using std::complex;
04697     IKFAST_ASSERT(rawcoeffs[0] != 0);
04698     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
04699     const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
04700     complex<IkReal> coeffs[4];
04701     const int maxsteps = 110;
04702     for(int i = 0; i < 4; ++i) {
04703         coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
04704     }
04705     complex<IkReal> roots[4];
04706     IkReal err[4];
04707     roots[0] = complex<IkReal>(1,0);
04708     roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
04709     err[0] = 1.0;
04710     err[1] = 1.0;
04711     for(int i = 2; i < 4; ++i) {
04712         roots[i] = roots[i-1]*roots[1];
04713         err[i] = 1.0;
04714     }
04715     for(int step = 0; step < maxsteps; ++step) {
04716         bool changed = false;
04717         for(int i = 0; i < 4; ++i) {
04718             if ( err[i] >= tol ) {
04719                 changed = true;
04720                 // evaluate
04721                 complex<IkReal> x = roots[i] + coeffs[0];
04722                 for(int j = 1; j < 4; ++j) {
04723                     x = roots[i] * x + coeffs[j];
04724                 }
04725                 for(int j = 0; j < 4; ++j) {
04726                     if( i != j ) {
04727                         if( roots[i] != roots[j] ) {
04728                             x /= (roots[i] - roots[j]);
04729                         }
04730                     }
04731                 }
04732                 roots[i] -= x;
04733                 err[i] = abs(x);
04734             }
04735         }
04736         if( !changed ) {
04737             break;
04738         }
04739     }
04740 
04741     numroots = 0;
04742     bool visited[4] = {false};
04743     for(int i = 0; i < 4; ++i) {
04744         if( !visited[i] ) {
04745             // might be a multiple root, in which case it will have more error than the other roots
04746             // find any neighboring roots, and take the average
04747             complex<IkReal> newroot=roots[i];
04748             int n = 1;
04749             for(int j = i+1; j < 4; ++j) {
04750                 if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
04751                     newroot += roots[j];
04752                     n += 1;
04753                     visited[j] = true;
04754                 }
04755             }
04756             if( n > 1 ) {
04757                 newroot /= n;
04758             }
04759             // 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
04760             if( IKabs(imag(newroot)) < tolsqrt ) {
04761                 rawroots[numroots++] = real(newroot);
04762             }
04763         }
04764     }
04765 }
04766 };
04767 
04768 
04771 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
04772 IKSolver solver;
04773 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
04774 }
04775 
04776 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - turtlebot_arm (96af0c6bf6e2cab59052ae1e773aff48)>"; }
04777 
04778 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
04779 
04780 #ifdef IKFAST_NAMESPACE
04781 } // end namespace
04782 #endif
04783 
04784 #ifndef IKFAST_NO_MAIN
04785 #include <stdio.h>
04786 #include <stdlib.h>
04787 #ifdef IKFAST_NAMESPACE
04788 using namespace IKFAST_NAMESPACE;
04789 #endif
04790 int main(int argc, char** argv)
04791 {
04792     if( argc != 12+GetNumFreeParameters()+1 ) {
04793         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
04794                "Returns the ik solutions given the transformation of the end effector specified by\n"
04795                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
04796                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
04797         return 1;
04798     }
04799 
04800     IkSolutionList<IkReal> solutions;
04801     std::vector<IkReal> vfree(GetNumFreeParameters());
04802     IkReal eerot[9],eetrans[3];
04803     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
04804     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
04805     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
04806     for(std::size_t i = 0; i < vfree.size(); ++i)
04807         vfree[i] = atof(argv[13+i]);
04808     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
04809 
04810     if( !bSuccess ) {
04811         fprintf(stderr,"Failed to get ik solution\n");
04812         return -1;
04813     }
04814 
04815     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
04816     std::vector<IkReal> solvalues(GetNumJoints());
04817     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
04818         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
04819         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
04820         std::vector<IkReal> vsolfree(sol.GetFree().size());
04821         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
04822         for( std::size_t j = 0; j < solvalues.size(); ++j)
04823             printf("%.15f, ", solvalues[j]);
04824         printf("\n");
04825     }
04826     return 0;
04827 }
04828 
04829 #endif


turtlebot_arm_ikfast_plugin
Author(s):
autogenerated on Mon Oct 6 2014 08:08:19