katana_450_6m90a_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;
00212 x0=IKcos(j[0]);
00213 x1=IKcos(j[1]);
00214 x2=IKsin(j[2]);
00215 x3=IKcos(j[2]);
00216 x4=IKsin(j[1]);
00217 x5=IKcos(j[3]);
00218 x6=IKsin(j[3]);
00219 x7=IKsin(j[0]);
00220 x8=IKcos(j[4]);
00221 x9=IKsin(j[4]);
00222 x10=((IkReal(0.139000000000000))*(x0));
00223 x11=((IkReal(0.110000000000000))*(x6));
00224 x12=((IkReal(1.00000000000000))*(x5));
00225 x13=((IkReal(0.110000000000000))*(x5));
00226 x14=((IkReal(1.00000000000000))*(x6));
00227 x15=((IkReal(0.147300000000000))*(x0));
00228 x16=((IkReal(1.00000000000000))*(x0));
00229 x17=((IkReal(0.147300000000000))*(x7));
00230 x18=((x3)*(x4));
00231 x19=((x2)*(x4));
00232 x20=((x7)*(x9));
00233 x21=((x1)*(x7));
00234 x22=((x1)*(x3));
00235 x23=((x0)*(x9));
00236 x24=((x1)*(x2));
00237 x25=((((IkReal(-1.00000000000000))*(x22)))+(x19));
00238 x26=((((IkReal(-1.00000000000000))*(x24)))+(((IkReal(-1.00000000000000))*(x18))));
00239 x27=((x0)*(((x18)+(x24))));
00240 x28=((((x18)*(x7)))+(((x2)*(x21))));
00241 x29=((x16)*(((((IkReal(-1.00000000000000))*(x22)))+(x19))));
00242 x30=((((IkReal(-1.00000000000000))*(x21)*(x3)))+(((IkReal(1.00000000000000))*(x19)*(x7))));
00243 IkReal x31=((IkReal(1.00000000000000))*(x19));
00244 eetrans[0]=((((IkReal(0.190000000000000))*(x0)*(x1)))+(((x8)*(((((IkReal(-1.00000000000000))*(x13)*(x27)))+(((IkReal(-1.00000000000000))*(x11)*(x29)))))))+(((IkReal(-1.00000000000000))*(x10)*(x31)))+(((IkReal(-0.110000000000000))*(x20)))+(((x6)*(((((x15)*(x18)))+(((x15)*(x24)))))))+(((x5)*(((((IkReal(-1.00000000000000))*(x15)*(x31)))+(((x15)*(x22)))))))+(((x10)*(x22))));
00245 eetrans[1]=((((IkReal(0.190000000000000))*(x21)))+(((IkReal(0.110000000000000))*(x23)))+(((x5)*(((((IkReal(-1.00000000000000))*(x17)*(x19)))+(((x17)*(x22)))))))+(((IkReal(0.139000000000000))*(x21)*(x3)))+(((x6)*(((((x17)*(x18)))+(((x17)*(x24)))))))+(((IkReal(-0.139000000000000))*(x19)*(x7)))+(((x8)*(((((IkReal(-1.00000000000000))*(x13)*(x28)))+(((IkReal(-1.00000000000000))*(x11)*(x30))))))));
00246 eetrans[2]=((IkReal(0.201500000000000))+(((x6)*(((((IkReal(-0.147300000000000))*(x22)))+(((IkReal(0.147300000000000))*(x19)))))))+(((x5)*(((((IkReal(0.147300000000000))*(x24)))+(((IkReal(0.147300000000000))*(x18)))))))+(((x8)*(((((IkReal(-1.00000000000000))*(x13)*(x25)))+(((IkReal(-1.00000000000000))*(x11)*(x26)))))))+(((IkReal(0.190000000000000))*(x4)))+(((IkReal(0.139000000000000))*(x24)))+(((IkReal(0.139000000000000))*(x18))));
00247 eerot[0]=((((IkReal(-1.00000000000000))*(x20)))+(((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x27)))+(((IkReal(-1.00000000000000))*(x14)*(x29))))))));
00248 eerot[1]=((x23)+(((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x28)))+(((IkReal(-1.00000000000000))*(x14)*(x30))))))));
00249 eerot[2]=((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x25)))+(((IkReal(-1.00000000000000))*(x14)*(x26))))));
00250 }
00251 
00252 IKFAST_API int GetNumFreeParameters() { return 0; }
00253 IKFAST_API int* GetFreeParameters() { return NULL; }
00254 IKFAST_API int GetNumJoints() { return 5; }
00255 
00256 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
00257 
00258 IKFAST_API int GetIkType() { return 0x56000007; }
00259 
00260 class IKSolver {
00261 public:
00262 IkReal j0,cj0,sj0,htj0,j1,cj1,sj1,htj1,j2,cj2,sj2,htj2,j3,cj3,sj3,htj3,j4,cj4,sj4,htj4,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp;
00263 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4;
00264 
00265 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
00266 j0=numeric_limits<IkReal>::quiet_NaN(); _ij0[0] = -1; _ij0[1] = -1; _nj0 = -1; j1=numeric_limits<IkReal>::quiet_NaN(); _ij1[0] = -1; _ij1[1] = -1; _nj1 = -1; j2=numeric_limits<IkReal>::quiet_NaN(); _ij2[0] = -1; _ij2[1] = -1; _nj2 = -1; j3=numeric_limits<IkReal>::quiet_NaN(); _ij3[0] = -1; _ij3[1] = -1; _nj3 = -1; j4=numeric_limits<IkReal>::quiet_NaN(); _ij4[0] = -1; _ij4[1] = -1; _nj4 = -1;
00267 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
00268     solutions.Clear();
00269 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00270 
00271 r00 = eerot[0];
00272 r01 = eerot[1];
00273 r02 = eerot[2];
00274 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
00275 new_r00=r00;
00276 new_px=px;
00277 new_r01=r01;
00278 new_py=py;
00279 new_r02=r02;
00280 new_pz=((IkReal(-0.201500000000000))+(pz));
00281 r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz;
00282 
00283 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
00284 {
00285 IkReal j0array[2], cj0array[2], sj0array[2];
00286 bool j0valid[2]={false};
00287 _nj0 = 2;
00288 if( IKabs(((((IkReal(-0.110000000000000))*(r01)))+(py))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(px)))+(((IkReal(0.110000000000000))*(r00))))) < IKFAST_ATAN2_MAGTHRESH )
00289     continue;
00290 IkReal x32=IKatan2(((((IkReal(-0.110000000000000))*(r01)))+(py)), ((((IkReal(-1.00000000000000))*(px)))+(((IkReal(0.110000000000000))*(r00)))));
00291 j0array[0]=((IkReal(-1.00000000000000))*(x32));
00292 sj0array[0]=IKsin(j0array[0]);
00293 cj0array[0]=IKcos(j0array[0]);
00294 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x32))));
00295 sj0array[1]=IKsin(j0array[1]);
00296 cj0array[1]=IKcos(j0array[1]);
00297 if( j0array[0] > IKPI )
00298 {
00299     j0array[0]-=IK2PI;
00300 }
00301 else if( j0array[0] < -IKPI )
00302 {    j0array[0]+=IK2PI;
00303 }
00304 j0valid[0] = true;
00305 if( j0array[1] > IKPI )
00306 {
00307     j0array[1]-=IK2PI;
00308 }
00309 else if( j0array[1] < -IKPI )
00310 {    j0array[1]+=IK2PI;
00311 }
00312 j0valid[1] = true;
00313 for(int ij0 = 0; ij0 < 2; ++ij0)
00314 {
00315 if( !j0valid[ij0] )
00316 {
00317     continue;
00318 }
00319 _ij0[0] = ij0; _ij0[1] = -1;
00320 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
00321 {
00322 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
00323 {
00324     j0valid[iij0]=false; _ij0[1] = iij0; break;
00325 }
00326 }
00327 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
00328 
00329 {
00330 IkReal dummyeval[1];
00331 dummyeval[0]=((IkReal(1.00000000000000))+(((IkReal(-434.971726837756))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-12.7364114832536))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(47.8468899521531))*(pp)*(r01)*(sj0)))+(((IkReal(-2.41991818181818))*(cj0)*(r00)))+(((IkReal(165.289256198347))*(px)*(py)*(r00)*(r01)))+(((IkReal(115.785558938669))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(4578.64975618690))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(21.9992561983471))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(4578.64975618690))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(572.331219523363))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(21.9992561983471))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-503.651473180559))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(115.785558938669))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-191.387559808612))*(cj0)*(r00)*((px)*(px))))+(((IkReal(572.331219523363))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-18.1818181818182))*(py)*(r01)))+(((IkReal(-2289.32487809345))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(9157.29951237380))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-2289.32487809345))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(1739.88690735102))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(4578.64975618690))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-12.7364114832536))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(2289.32487809345))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(869.943453675511))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(47.8468899521531))*(cj0)*(pp)*(r00)))+(((IkReal(-503.651473180559))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-12.7364114832536))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-503.651473180559))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-12.7364114832536))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(-1007.30294636112))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-503.651473180559))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-869.943453675511))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(-2289.32487809345))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(572.331219523363))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-503.651473180559))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-191.387559808612))*(px)*(py)*(r00)*(sj0)))+(((IkReal(4578.64975618690))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(4578.64975618690))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-2289.32487809345))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-503.651473180559))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-95.6937799043062))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(2289.32487809345))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1007.30294636112))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(38.4125821295300))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-2.41991818181818))*(r01)*(sj0)))+(((IkReal(-57.8927794693345))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(38.9603946796090))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(251.825736590280))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(1739.88690735102))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(4578.64975618690))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-7.40247498912571))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-503.651473180559))*(py)*(r01)*((pz)*(pz))))+(((IkReal(29.4017311874728))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-191.387559808612))*(r01)*(sj0)*((py)*(py))))+(((IkReal(115.785558938669))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-2289.32487809345))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(2.92800200334711))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-95.6937799043062))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(76.8251642590600))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(1.46400100167355))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(24.7518486298391))*(pp)*((r02)*(r02))))+(((IkReal(4578.64975618690))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(869.943453675511))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(251.825736590280))*(pp)*(pz)*(r02)))+(((IkReal(-95.6937799043062))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(434.971726837756))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(115.785558938669))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(251.825736590280))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(82.6446280991736))*((px)*(px))*((r00)*(r00))))+(((IkReal(-434.971726837756))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(869.943453675511))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(869.943453675511))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(21.9992561983471))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(869.943453675511))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(869.943453675511))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(9157.29951237380))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(10.5263157894737))*(py)*(sj0)))+(((IkReal(869.943453675511))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(115.785558938669))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(38.4125821295300))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(4578.64975618690))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-1007.30294636112))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(38.9603946796090))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(33.1409308394954))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(4578.64975618690))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2289.32487809345))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(38.4125821295300))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-869.943453675511))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-191.387559808612))*(cj0)*(px)*(py)*(r01)))+(((IkReal(115.785558938669))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-2289.32487809345))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(251.825736590280))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-2289.32487809345))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(869.943453675511))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(82.6446280991736))*((py)*(py))*((r01)*(r01))))+(((IkReal(2289.32487809345))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(869.943453675511))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-95.6937799043062))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(9157.29951237380))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(4578.64975618690))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(27.7008310249307))*((pz)*(pz))))+(((IkReal(251.825736590280))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(1.46400100167355))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(38.9603946796090))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(869.943453675511))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(115.785558938669))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(115.785558938669))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-434.971726837756))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-115.785558938669))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-503.651473180559))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-503.651473180559))*(px)*(r00)*((pz)*(pz))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(27.7008310249307))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(76.8251642590600))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(2289.32487809345))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-434.971726837756))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-57.8927794693345))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.7364114832536))*(pz)*(r02)))+(((IkReal(1144.66243904673))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(2289.32487809345))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.32916346113636))*((r02)*(r02))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(38.4125821295300))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(2289.32487809345))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(4578.64975618690))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(2289.32487809345))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(115.785558938669))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(869.943453675511))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(55.4016620498615))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(-2289.32487809345))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(29.4017311874728))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(869.943453675511))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-2289.32487809345))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(38.9603946796090))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-2289.32487809345))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(869.943453675511))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(434.971726837756))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(21.9992561983471))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-7.40247498912571))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(115.785558938669))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(27.7008310249307))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(10.5263157894737))*(cj0)*(px)))+(((IkReal(869.943453675511))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4578.64975618690))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(2289.32487809345))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-18.1818181818182))*(px)*(r00))));
00332 if( IKabs(dummyeval[0]) < 0.0000001000000000  )
00333 {
00334 continue;
00335 
00336 } else
00337 {
00338 IkReal op[4+1], zeror[4];
00339 int numroots;
00340 IkReal j1evalpoly[2];
00341 op[0]=((IkReal(0.00698896000000000))+(((IkReal(1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(-0.0169127113760000))*(r01)*(sj0)))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(0.0735680000000000))*(py)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.0890142704000000))*(pz)*(r02)))+(((IkReal(16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00928947026334360))*((r02)*(r02))))+(((IkReal(16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0169127113760000))*(cj0)*(r00)))+(((IkReal(-16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.127072000000000))*(px)*(r00)))+(((IkReal(-0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.193600000000000))*((pz)*(pz))))+(((IkReal(0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(0.0735680000000000))*(cj0)*(px)))+(((IkReal(6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.127072000000000))*(py)*(r01)))+(((IkReal(6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0890142704000000))*(cj0)*(px)*(r01)*(sj0))));
00342 op[1]=((((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.668800000000000))*(pp)*(r02)))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.0338254227520000))*(r02)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(-0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-0.147136000000000))*(pz)))+(((IkReal(-2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(-0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0)))));
00343 op[2]=((IkReal(0.0139779200000000))+(((IkReal(32.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(6.23924128000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-7.04000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-14.0800000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-4.07621472000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-32.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(3.52000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0595063182893128))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(1.07385600000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.536928000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.07621472000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(pp)*(pz)*(r02)))+(((IkReal(-3.00235872000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.254144000000000))*(py)*(r01)))+(((IkReal(-32.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(3.52000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-7.04000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.536928000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(128.000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.0576215699346872))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-4.07621472000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-14.0800000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(64.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.15520000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.00235872000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(3.52000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(64.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.254144000000000))*(px)*(r00)))+(((IkReal(2.31040000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(3.52000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-7.04000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.15520000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(5.08404128000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(128.000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(64.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.330259459200000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-7.04000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.115243139869374))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-7.04000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.00235872000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.330259459200000))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(6.23924128000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.536928000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.686316540800000))*(pz)*(r02)))+(((IkReal(-14.0800000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(64.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-4.07621472000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.387200000000000))*((pz)*(pz))))+(((IkReal(1.50117936000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-3.00235872000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.536928000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.50117936000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.330259459200000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(64.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.0576215699346872))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(128.000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.96442064000000))*(pp)*((r02)*(r02))))+(((IkReal(32.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.00235872000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(64.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-7.04000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.330259459200000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(1.07385600000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-7.04000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-7.04000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.774400000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(-7.04000000000000))*(px)*(r00)*((pz)*(pz)))));
00344 op[3]=((((IkReal(-0.668800000000000))*(pp)*(r02)))+(((IkReal(-0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(0.0338254227520000))*(r02)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(-0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-0.147136000000000))*(pz)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0))));
00345 op[4]=((IkReal(0.00698896000000000))+(((IkReal(1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0735680000000000))*(cj0)*(px)))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0735680000000000))*(py)*(sj0)))+(((IkReal(0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0890142704000000))*(pz)*(r02)))+(((IkReal(16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00928947026334360))*((r02)*(r02))))+(((IkReal(16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-0.127072000000000))*(px)*(r00)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(-0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.0169127113760000))*(cj0)*(r00)))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(-12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.193600000000000))*((pz)*(pz))))+(((IkReal(0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.0169127113760000))*(r01)*(sj0)))+(((IkReal(-3.52000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.127072000000000))*(py)*(r01)))+(((IkReal(-0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0890142704000000))*(cj0)*(px)*(r01)*(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 j1evalpoly[0]=((IkReal(0.00698896000000000))+(((IkReal(1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0735680000000000))*(cj0)*(px)))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+((((htj1)*(htj1)*(htj1))*(((((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.668800000000000))*(pp)*(r02)))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.0338254227520000))*(r02)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(-0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-0.147136000000000))*(pz)))+(((IkReal(-2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(-0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0))))))))+(((IkReal(-0.0735680000000000))*(py)*(sj0)))+(((IkReal(0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0890142704000000))*(pz)*(r02)))+(((IkReal(16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+((((htj1)*(htj1)*(htj1)*(htj1))*(((IkReal(0.00698896000000000))+(((IkReal(1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(-0.0169127113760000))*(r01)*(sj0)))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(0.0735680000000000))*(py)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-0.0890142704000000))*(pz)*(r02)))+(((IkReal(16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00928947026334360))*((r02)*(r02))))+(((IkReal(16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.0169127113760000))*(cj0)*(r00)))+(((IkReal(-16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.127072000000000))*(px)*(r00)))+(((IkReal(-0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.193600000000000))*((pz)*(pz))))+(((IkReal(0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(0.0735680000000000))*(cj0)*(px)))+(((IkReal(6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-0.127072000000000))*(py)*(r01)))+(((IkReal(6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0890142704000000))*(cj0)*(px)*(r01)*(sj0)))))))+(((IkReal(-3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((htj1)*(((((IkReal(-0.668800000000000))*(pp)*(r02)))+(((IkReal(-0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(0.0338254227520000))*(r02)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(-0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-0.147136000000000))*(pz)))+(((IkReal(6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0)))))))+(((IkReal(0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.00928947026334360))*((r02)*(r02))))+((((htj1)*(htj1))*(((IkReal(0.0139779200000000))+(((IkReal(32.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(6.23924128000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-7.04000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-14.0800000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-4.07621472000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-32.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(3.52000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0595063182893128))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(1.07385600000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(0.536928000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.07621472000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(pp)*(pz)*(r02)))+(((IkReal(-3.00235872000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.254144000000000))*(py)*(r01)))+(((IkReal(-32.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(3.52000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-7.04000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.536928000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(128.000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-0.0576215699346872))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-4.07621472000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-14.0800000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(64.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.15520000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.00235872000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(3.52000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(64.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.254144000000000))*(px)*(r00)))+(((IkReal(2.31040000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(32.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(3.52000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-7.04000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.15520000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(5.08404128000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(128.000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(64.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.330259459200000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-7.04000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.115243139869374))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-7.04000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.00235872000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.330259459200000))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(6.23924128000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.536928000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.686316540800000))*(pz)*(r02)))+(((IkReal(-14.0800000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(32.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(64.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-4.07621472000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.387200000000000))*((pz)*(pz))))+(((IkReal(1.50117936000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-3.00235872000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.536928000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.50117936000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.330259459200000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(64.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.0576215699346872))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(128.000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-1.96442064000000))*(pp)*((r02)*(r02))))+(((IkReal(32.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(3.00235872000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(64.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-7.04000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.330259459200000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(64.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(64.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(1.07385600000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-7.04000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-7.04000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(0.774400000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(-7.04000000000000))*(px)*(r00)*((pz)*(pz))))))))+(((IkReal(16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(-7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-0.127072000000000))*(px)*(r00)))+(((IkReal(64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(-0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.0169127113760000))*(cj0)*(r00)))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(-12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.193600000000000))*((pz)*(pz))))+(((IkReal(0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.0169127113760000))*(r01)*(sj0)))+(((IkReal(-3.52000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.127072000000000))*(py)*(r01)))+(((IkReal(-0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0890142704000000))*(cj0)*(px)*(r01)*(sj0))));
00381 j1evalpoly[1]=((IkReal(-0.00698896000000000))+(((IkReal(0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.0890142704000000))*(pz)*(r02)))+(((IkReal(-0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+((((htj1)*(htj1))*(((IkReal(-0.0139779200000000))+(((IkReal(-64.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(-32.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.536928000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.330259459200000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(7.04000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-0.330259459200000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(7.04000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-64.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(3.00235872000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(3.00235872000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.23924128000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(7.04000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(7.04000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(3.00235872000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-64.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(32.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(14.0800000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(0.115243139869374))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(14.0800000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-1.15520000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.387200000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(4.07621472000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.0595063182893128))*((r02)*(r02))))+(((IkReal(3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(3.00235872000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.15520000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(3.00235872000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.686316540800000))*(pz)*(r02)))+(((IkReal(-1.50117936000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-64.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-64.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-3.52000000000000))*(pp)*(pz)*(r02)))+(((IkReal(-128.000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-3.52000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-128.000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(4.07621472000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-64.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-5.08404128000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.330259459200000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.536928000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(-32.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.387200000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.330259459200000))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.0576215699346872))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-64.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.387200000000000))*((pz)*(pz))))+(((IkReal(-3.00235872000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(-128.000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.50117936000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-64.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(32.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(32.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-64.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(7.04000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(4.07621472000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-32.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-1.07385600000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-32.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-64.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.536928000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(1.96442064000000))*(pp)*((r02)*(r02))))+(((IkReal(-0.536928000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(7.04000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-3.52000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(32.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(7.04000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(0.254144000000000))*(px)*(r00)))+(((IkReal(-64.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.0576215699346872))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.254144000000000))*(py)*(r01)))+(((IkReal(-32.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(14.0800000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-64.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-6.23924128000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(7.04000000000000))*(r02)*((pz)*(pz)*(pz))))+(((IkReal(4.07621472000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(3.00235872000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.774400000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(32.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(-32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-3.52000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.07385600000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(7.04000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))))))+(((IkReal(0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(-1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(-0.0169127113760000))*(r01)*(sj0)))+(((IkReal(0.0735680000000000))*(py)*(sj0)))+(((IkReal(-0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.00928947026334360))*((r02)*(r02))))+(((IkReal(16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(-1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(0.127072000000000))*(py)*(r01)))+(((IkReal(-0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+((((htj1)*(htj1)*(htj1))*(((((IkReal(1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(-0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(0.147136000000000))*(pz)))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(-2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.668800000000000))*(pp)*(r02)))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(-0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(-12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-0.0338254227520000))*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(-6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(-0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(-12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0)))))))+(((IkReal(-1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(-0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.0890142704000000))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(-16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.0169127113760000))*(cj0)*(r00)))+(((IkReal(16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.127072000000000))*(px)*(r00)))+(((IkReal(0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+((((htj1)*(htj1)*(htj1)*(htj1))*(((IkReal(-0.00698896000000000))+(((IkReal(0.404610320000000))*(pp)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.0890142704000000))*(pz)*(r02)))+(((IkReal(-0.809220640000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(-32.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-0.268464000000000))*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-0.536928000000000))*(cj0)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-0.0735680000000000))*(cj0)*(px)))+(((IkReal(-3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-1.76000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-0.577600000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-4.00000000000000))*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-0.334400000000000))*(pp)*(r01)*(sj0)))+(((IkReal(-32.0000000000000))*(px)*(pz)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.231620640000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0735680000000000))*(py)*(sj0)))+(((IkReal(16.0000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.809220640000000))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.00928947026334360))*((r02)*(r02))))+(((IkReal(16.0000000000000))*(pp)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-16.0000000000000))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-1.76000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)))+(((IkReal(-6.08000000000000))*(cj0)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(0.127072000000000))*(py)*(r01)))+(((IkReal(-0.193600000000000))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.809220640000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.0102318444406564))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-0.205487523200000))*(cj0)*(pz)*(r00)*(r02)))+(((IkReal(-0.272292640000000))*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-1.76000000000000))*(pp)*(pz)*(r02)))+(((IkReal(0.668800000000000))*(cj0)*(px)*(pz)*(r02)))+(((IkReal(-0.809220640000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(0.0890142704000000))*(cj0)*(px)*(r01)*(sj0)))+(((IkReal(7.04000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(py)*(r01)*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(px)*(r00)*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(pz)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.809220640000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)))+(((IkReal(0.0890142704000000))*(px)*(r00)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0517356016000000))*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.387200000000000))*(cj0)*(px)*(py)*(sj0)))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(0.0890142704000000))*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-64.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-1.76000000000000))*(pp)*(py)*(r01)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(7.04000000000000))*(cj0)*(py)*(r00)*(sj0)*((px)*(px))))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.193600000000000))*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.272292640000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.153751921600000))*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.0102318444406564))*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-4.00000000000000))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.268464000000000))*((cj0)*(cj0))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-6.08000000000000))*(cj0)*(r00)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(3.52000000000000))*(px)*(r00)*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))))+(((IkReal(-8.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((pp)*(pp))))+(((IkReal(-16.0000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.809220640000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.809220640000000))*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(16.0000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(7.04000000000000))*(cj0)*(px)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-16.0000000000000))*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.272292640000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.268464000000000))*((pz)*(pz))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.127072000000000))*(px)*(r00)))+(((IkReal(-0.172989680000000))*(pp)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(pz)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r00)*(r00))))+(((IkReal(0.404610320000000))*(pp)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(px)*(r00)*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(-6.08000000000000))*(r01)*(r02)*(sj0)*((pz)*(pz)*(pz))))+(((IkReal(-0.334400000000000))*(cj0)*(pp)*(r00)))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(cj0)*(py)*(sj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(3.52000000000000))*(py)*(r01)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(3.52000000000000))*(px)*(r00)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.0169127113760000))*(cj0)*(r00)))+(((IkReal(0.668800000000000))*(py)*(pz)*(r02)*(sj0)))+(((IkReal(3.04000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(-0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(-1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(0.0517356016000000))*(cj0)*(px)*((r02)*(r02))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(-0.205487523200000))*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((IkReal(3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.193600000000000))*((pz)*(pz))))+(((IkReal(-0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-12.1600000000000))*(cj0)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.33760000000000))*(cj0)*(r00)*((px)*(px))))+(((IkReal(-0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(-16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.668800000000000))*(r01)*(sj0)*((pz)*(pz))))+(((IkReal(0.0169127113760000))*(r01)*(sj0)))+(((IkReal(0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(-4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(6.08000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.153751921600000))*(cj0)*(px)*((r00)*(r00))))+(((IkReal(3.52000000000000))*(r02)*((pz)*(pz)*(pz))))))))+(((IkReal(6.08000000000000))*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(6.08000000000000))*(cj0)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.809220640000000))*(cj0)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))))+(((IkReal(6.08000000000000))*(py)*(sj0)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.15520000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(16.0000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-1.33760000000000))*(px)*(py)*(r00)*(sj0)))+(((IkReal(16.0000000000000))*(pp)*(px)*(pz)*(r00)*(r02)))+(((IkReal(-1.33760000000000))*(r01)*(sj0)*((py)*(py))))+(((IkReal(3.52000000000000))*(pz)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.193600000000000))*((pz)*(pz))))+(((IkReal(-0.268464000000000))*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-1.76000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)))+(((IkReal(-0.577600000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(pp)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.0204636888813128))*(cj0)*(r00)*(r01)*(sj0)))+(((IkReal(-0.272292640000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-32.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(3.04000000000000))*(cj0)*(pp)*(px)*((r02)*(r02))))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(6.08000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(16.0000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-32.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.809220640000000))*(px)*(py)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-64.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(3.52000000000000))*(r00)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-64.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((px)*(px))*((py)*(py))))+(((IkReal(0.0735680000000000))*(cj0)*(px)))+(((IkReal(6.08000000000000))*(cj0)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.0890142704000000))*(cj0)*(py)*(r00)*(sj0)))+(((IkReal(0.153751921600000))*(cj0)*(py)*(r00)*(r01)))+(((IkReal(-4.00000000000000))*((pp)*(pp))*((r02)*(r02))))+(((IkReal(3.52000000000000))*(r01)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.536928000000000))*(cj0)*(px)*(py)*(sj0)*((r02)*(r02))))+(((IkReal(-0.668800000000000))*(cj0)*(r00)*((pz)*(pz))))+(((IkReal(0.153751921600000))*(py)*(sj0)*((r01)*(r01))))+(((htj1)*(((((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(1.33760000000000))*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(0.103471203200000))*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(24.3200000000000))*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(1.33760000000000))*(cj0)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(-12.1600000000000))*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(24.3200000000000))*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(12.1600000000000))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(1.33760000000000))*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-1.33760000000000))*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(24.3200000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-2.67520000000000))*(py)*(pz)*(r01)))+(((IkReal(0.147136000000000))*(pz)))+(((IkReal(12.1600000000000))*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-2.67520000000000))*(px)*(pz)*(r00)))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-2.67520000000000))*(cj0)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-2.67520000000000))*(r02)*((pz)*(pz))))+(((IkReal(-12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(6.08000000000000))*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(12.1600000000000))*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.103471203200000))*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.254144000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.668800000000000))*(pp)*(r02)))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.307503843200000))*(pz)*((r02)*(r02))))+(((IkReal(-0.206942406400000))*(cj0)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-6.08000000000000))*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-2.31040000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-2.31040000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(-0.0780852588160000))*(cj0)*(r00)*(r02)))+(((IkReal(-12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(12.1600000000000))*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.103471203200000))*(cj0)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-2.31040000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(2.31040000000000))*(cj0)*(pp)*(r00)*(r02)))+(((IkReal(12.1600000000000))*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(24.3200000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-6.08000000000000))*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.307503843200000))*(py)*(r01)*(r02)))+(((IkReal(0.103471203200000))*(cj0)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.254144000000000))*(py)*(r02)*(sj0)))+(((IkReal(-2.31040000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(24.3200000000000))*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-12.1600000000000))*(cj0)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(24.3200000000000))*(cj0)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(-6.08000000000000))*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(cj0)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(12.1600000000000))*(cj0)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-2.31040000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(2.31040000000000))*(pp)*(r01)*(r02)*(sj0)))+(((IkReal(12.1600000000000))*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(0.103471203200000))*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-2.31040000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(0.254144000000000))*(pz)*(r01)*(sj0)))+(((IkReal(0.254144000000000))*(cj0)*(px)*(r02)))+(((IkReal(0.307503843200000))*(px)*(r00)*(r02)))+(((IkReal(-12.1600000000000))*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(1.33760000000000))*(cj0)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-1.33760000000000))*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-0.0780852588160000))*(r01)*(r02)*(sj0)))+(((IkReal(-0.0338254227520000))*(r02)))+(((IkReal(-6.08000000000000))*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-6.08000000000000))*(cj0)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-6.08000000000000))*(pp)*(px)*(r00)*(r02)))+(((IkReal(-12.1600000000000))*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-0.103471203200000))*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-12.1600000000000))*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))))))+(((IkReal(16.0000000000000))*(pp)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-1.33760000000000))*(cj0)*(px)*(py)*(r01)))+(((IkReal(3.52000000000000))*(r02)*((pz)*(pz)*(pz)))));
00382 if( IKabs(j1evalpoly[0]) > 0.0000001000000000  || IKabs(j1evalpoly[1]) > 0.0000001000000000  )
00383 {
00384     continue;
00385 }
00386 _ij1[0] = ij1; _ij1[1] = -1;
00387 for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1)
00388 {
00389 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
00390 {
00391     j1valid[iij1]=false; _ij1[1] = iij1; break;
00392 }
00393 }
00394 {
00395 IkReal dummyeval[1];
00396 IkReal gconst0;
00397 gconst0=IKsign(((((IkReal(0.105640000000000))*(cj1)*(pp)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0281204172400000))*(cj1)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.211280000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(-0.0232408000000000))*(cj0)*(px)*(r02)))+(((IkReal(0.0401432000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-1.11200000000000))*(cj1)*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.0232408000000000))*(cj1)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.211280000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.556000000000000))*(cj1)*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.211280000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(0.211280000000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.0232408000000000))*(pz)*(r01)*(sj0)))+(((IkReal(-0.211280000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(1.11200000000000))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.105640000000000))*(cj0)*(pp)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(0.244640000000000))*(cj0)*(cj1)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-0.122320000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(1.11200000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(0.0401432000000000))*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(1.11200000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(-2.22400000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.211280000000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(0.211280000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-1.11200000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.122320000000000))*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-1.11200000000000))*(cj1)*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.00534287927560000))*(cj1)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.556000000000000))*(cj0)*(pp)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(0.556000000000000))*(pp)*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(-0.00441575200000000))*(cj0)*(r00)*(sj1)))+(((IkReal(-0.211280000000000))*(cj1)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.122320000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(0.105640000000000))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.00534287927560000))*(cj1)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.556000000000000))*(cj1)*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.122320000000000))*(cj1)*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(-1.11200000000000))*(cj1)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-2.22400000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(1.11200000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.211280000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.211280000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(1.11200000000000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.211280000000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(0.211280000000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(0.00441575200000000))*(cj1)*(r02)))+(((IkReal(0.0401432000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(1.11200000000000))*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(0.0232408000000000))*(cj1)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.0232408000000000))*(cj0)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.11200000000000))*(cj1)*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.211280000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-1.11200000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.00534287927560000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.211280000000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(0.556000000000000))*(cj0)*(pp)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-0.211280000000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(-0.211280000000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(1.11200000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.211280000000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(0.0682636172400000))*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(0.211280000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-0.211280000000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.0232408000000000))*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.211280000000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.211280000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(1.11200000000000))*(cj0)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(0.211280000000000))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(0.122320000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0232408000000000))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(0.556000000000000))*(cj0)*(cj1)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-0.0281204172400000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-1.11200000000000))*(cj1)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0401432000000000))*(cj1)*(px)*(r00)*(r02)))+(((IkReal(-0.0106857585512000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(0.105640000000000))*(pp)*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.211280000000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-0.0401432000000000))*(cj1)*(pz)*((r02)*(r02))))+(((IkReal(0.0281204172400000))*(cj1)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-0.105640000000000))*(cj1)*(pp)*(sj1)*((r02)*(r02))))+(((IkReal(-1.11200000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0232408000000000))*(cj0)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(0.0232408000000000))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(0.211280000000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(-1.11200000000000))*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.211280000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.211280000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-0.0281204172400000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(0.211280000000000))*(cj1)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0232408000000000))*(py)*(r02)*(sj0)))+(((IkReal(0.211280000000000))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-1.11200000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.211280000000000))*(cj0)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-0.00534287927560000))*(cj0)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(1.11200000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-0.0281204172400000))*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(1.11200000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(0.00534287927560000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-0.556000000000000))*(cj1)*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.122320000000000))*(cj1)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-1.11200000000000))*(cj0)*(pz)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(-0.211280000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(-0.00441575200000000))*(r01)*(sj0)*(sj1)))+(((IkReal(0.211280000000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-0.105640000000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.211280000000000))*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(0.122320000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(0.122320000000000))*(cj1)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(1.11200000000000))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-1.11200000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(-0.211280000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.122320000000000))*(cj0)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(0.0232408000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.0232408000000000))*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0281204172400000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.211280000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.0232408000000000))*(cj1)*(pz)*(r02)*(sj1)))+(((IkReal(0.0562408344800000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-0.0281204172400000))*(cj0)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-2.22400000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(0.0682636172400000))*(cj0)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(-0.0401432000000000))*(cj1)*(py)*(r01)*(r02)))+(((IkReal(0.556000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.211280000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-1.11200000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-0.105640000000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-0.556000000000000))*(pp)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.00534287927560000))*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.0281204172400000))*(cj1)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-0.556000000000000))*(cj1)*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(0.00534287927560000))*(cj1)*(sj1)*((r02)*(r02))))+(((IkReal(-0.122320000000000))*(cj1)*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(0.0401432000000000))*(cj0)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(1.11200000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(1.11200000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))));
00398 dummyeval[0]=((((IkReal(-47.8468899521531))*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(47.8468899521531))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(-1.20995909090909))*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-125.912868295140))*(cj1)*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(5.26315789473684))*(cj0)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(-251.825736590280))*(cj1)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(23.9234449760766))*(pp)*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-27.7008310249307))*(cj0)*(cj1)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-23.9234449760766))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-23.9234449760766))*(cj1)*(pp)*(sj1)*((r02)*(r02))))+(((IkReal(-6.36820574162679))*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(-23.9234449760766))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(47.8468899521531))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-251.825736590280))*(cj1)*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-251.825736590280))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(23.9234449760766))*(cj1)*(pp)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-47.8468899521531))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-5.26315789473684))*(cj0)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(-5.26315789473684))*(py)*(r02)*(sj0)))+(((IkReal(251.825736590280))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(251.825736590280))*(cj0)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(47.8468899521531))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-47.8468899521531))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(47.8468899521531))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(1.20995909090909))*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-251.825736590280))*(cj1)*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-251.825736590280))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(47.8468899521531))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(-125.912868295140))*(cj1)*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(27.7008310249307))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(-251.825736590280))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(9.09090909090909))*(cj0)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(47.8468899521531))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(125.912868295140))*(cj0)*(cj1)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-1.20995909090909))*(cj0)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-47.8468899521531))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(251.825736590280))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(-6.36820574162679))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-125.912868295140))*(pp)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(251.825736590280))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(27.7008310249307))*(cj1)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-47.8468899521531))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(47.8468899521531))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(5.26315789473684))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(-47.8468899521531))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(125.912868295140))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-251.825736590280))*(cj1)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(1.20995909090909))*(cj1)*(sj1)*((r02)*(r02))))+(((IkReal(-251.825736590280))*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(sj1)))+(((IkReal(23.9234449760766))*(cj0)*(pp)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(5.26315789473684))*(cj0)*(pz)*(r00)))+(((IkReal(-47.8468899521531))*(cj0)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(251.825736590280))*(px)*(r00)*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-27.7008310249307))*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(6.36820574162679))*(cj1)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-251.825736590280))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(1.20995909090909))*(cj0)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(9.09090909090909))*(cj0)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(-47.8468899521531))*(cj0)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(9.09090909090909))*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(27.7008310249307))*(cj1)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-503.651473180559))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(15.4591148325359))*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(27.7008310249307))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(-503.651473180559))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(47.8468899521531))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(-27.7008310249307))*(cj1)*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(251.825736590280))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(23.9234449760766))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(-27.7008310249307))*(cj0)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(125.912868295140))*(pp)*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(47.8468899521531))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-5.26315789473684))*(cj0)*(px)*(r02)))+(((IkReal(251.825736590280))*(cj0)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(-47.8468899521531))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(-2.41991818181818))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-47.8468899521531))*(cj1)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-47.8468899521531))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(251.825736590280))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-6.36820574162679))*(cj1)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(12.7364114832536))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(47.8468899521531))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(251.825736590280))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-47.8468899521531))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(-6.36820574162679))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(5.26315789473684))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-47.8468899521531))*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(-27.7008310249307))*(cj1)*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(-47.8468899521531))*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(55.4016620498615))*(cj0)*(cj1)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-251.825736590280))*(cj0)*(pz)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(15.4591148325359))*(cj0)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(5.26315789473684))*(cj1)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(251.825736590280))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(47.8468899521531))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(251.825736590280))*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(-251.825736590280))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-47.8468899521531))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-503.651473180559))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(125.912868295140))*(cj1)*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-1.20995909090909))*(cj1)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-6.36820574162679))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(5.26315789473684))*(cj1)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(5.26315789473684))*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-9.09090909090909))*(cj1)*(pz)*((r02)*(r02))))+(((IkReal(251.825736590280))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-5.26315789473684))*(cj1)*(pz)*(r02)*(sj1)))+(((IkReal(-9.09090909090909))*(cj1)*(py)*(r01)*(r02)))+(((IkReal(125.912868295140))*(cj0)*(pp)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-1.00000000000000))*(r01)*(sj0)*(sj1)))+(((IkReal(-27.7008310249307))*(cj0)*(cj1)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-47.8468899521531))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(125.912868295140))*(cj1)*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(-47.8468899521531))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-125.912868295140))*(cj0)*(pp)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(-47.8468899521531))*(cj0)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(47.8468899521531))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-1.20995909090909))*(cj1)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(-251.825736590280))*(cj1)*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-251.825736590280))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(47.8468899521531))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-47.8468899521531))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(-9.09090909090909))*(cj1)*(px)*(r00)*(r02)))+(((IkReal(-6.36820574162679))*(cj0)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(5.26315789473684))*(pz)*(r01)*(sj0)))+(((IkReal(9.09090909090909))*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(47.8468899521531))*(cj1)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-5.26315789473684))*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(47.8468899521531))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(47.8468899521531))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(251.825736590280))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(6.36820574162679))*(cj1)*(pz)*((r01)*(r01))*((sj0)*(sj0)))));
00399 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00400 {
00401 continue;
00402 
00403 } else
00404 {
00405 {
00406 IkReal j2array[1], cj2array[1], sj2array[1];
00407 bool j2valid[1]={false};
00408 _nj2 = 1;
00409 if( IKabs(((gconst0)*(((IkReal(-0.00349448000000000))+(((IkReal(-0.193600000000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0445071352000000))*(cj0)*(px)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.668800000000000))*(cj1)*(px)*(py)*(r00)*(sj0)))+(((IkReal(0.0635360000000000))*(pz)*(r02)))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(0.0445071352000000))*(pz)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(sj0)*((cj1)*(cj1))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-8.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.0102318444406564))*(cj1)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((px)*(px))*((pz)*(pz))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(px)*(py)*(r01)))+(((IkReal(3.04000000000000))*(pz)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)))+(((IkReal(-32.0000000000000))*(cj1)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(1.76000000000000))*(r01)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.202305160000000))*(pp)*((cj1)*(cj1))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(0.0445071352000000))*(py)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(px)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-0.00511592222032820))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(-0.404610320000000))*(py)*(pz)*(r01)*(r02)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(-0.668800000000000))*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-0.404610320000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.167200000000000))*(pp)*(r02)*(sj1)))+(((IkReal(6.08000000000000))*(cj1)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.880000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(-0.00511592222032820))*((cj1)*(cj1))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(3.52000000000000))*(cj1)*(py)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(0.0445071352000000))*(cj0)*(cj1)*(pz)*(r00)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0768759608000000))*(py)*(r01)*(r02)*(sj1)))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0635360000000000))*(py)*(r01)))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(0.0367840000000000))*(cj0)*(cj1)*(px)))+(((IkReal(-0.404610320000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(1.76000000000000))*(px)*(r00)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.0445071352000000))*(cj0)*(py)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.404610320000000))*(cj1)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-16.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(0.0445071352000000))*(px)*(r00)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.0768759608000000))*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))*((py)*(py))))+(((IkReal(1.76000000000000))*(py)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.288800000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(sj0)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(py)*(r00)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(py)*(r00)*(r01)))+(((IkReal(-1.52000000000000))*(pp)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(0.0445071352000000))*(cj1)*(py)*(r02)*(sj0)*(sj1)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(pp)*(r00)))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r01)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(pz)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(sj1)*((r00)*(r00))))+(((IkReal(-0.404610320000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(0.404610320000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(py)*(pz)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.668800000000000))*(cj1)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.404610320000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(1.76000000000000))*(r00)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(3.04000000000000))*(cj1)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r02)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.0102318444406564))*(cj0)*(cj1)*(r00)*(r02)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.0102318444406564))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.577600000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r01)*(sj1)))+(((IkReal(-0.00845635568800000))*(cj1)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(pz)*(r01)*(r02)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.404610320000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-4.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(py)*(pz)*(r01)*(sj1)))+(((IkReal(1.76000000000000))*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj1)*(pz)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.880000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0445071352000000))*(cj1)*(pz)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(-0.193600000000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)))+(((IkReal(0.404610320000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)))+(((IkReal(-0.577600000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-4.00000000000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((pp)*(pp))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.0768759608000000))*(cj1)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(py)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(-32.0000000000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(-0.880000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(r00)*((px)*(px))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.404610320000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0968000000000000))*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(cj1)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00511592222032820))*((cj0)*(cj0))*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(0.0635360000000000))*(px)*(r00)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(px)*(r02)*(sj1)))+(((IkReal(-0.404610320000000))*(px)*(pz)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.668800000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.288800000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(sj0)*((cj1)*(cj1))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.0968000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj1)*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(3.52000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(6.08000000000000))*(px)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.288800000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0367840000000000))*(pz)*(sj1)))+(((IkReal(-0.880000000000000))*(pp)*(pz)*(r02)*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(6.08000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-2.00000000000000))*((cj1)*(cj1))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.577600000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(3.04000000000000))*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0445071352000000))*(cj0)*(cj1)*(px)*(r02)*(sj1)))+(((IkReal(1.76000000000000))*(px)*(r00)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(sj0)*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(3.04000000000000))*(cj1)*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.0367840000000000))*(cj1)*(py)*(sj0)))+(((IkReal(-0.0968000000000000))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(0.202305160000000))*(pp)*((cj0)*(cj0))*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(6.08000000000000))*(py)*(r01)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(0.0768759608000000))*(cj1)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.880000000000000))*(pp)*(py)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(pp)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(pp)*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r01)*(sj1)*((px)*(px))))+(((IkReal(1.76000000000000))*(pz)*(r02)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(pz)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(pz)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(cj1)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.193600000000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)))+(((IkReal(-1.52000000000000))*(pp)*(px)*(r00)*(r02)*(sj1)))+(((IkReal(-0.00845635568800000))*(cj0)*(cj1)*(r00)))+(((IkReal(-8.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-2.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-0.404610320000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(0.167200000000000))*(cj1)*(pp)*(r01)*(sj0)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.52000000000000))*(pp)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(px)*(py)*(r00)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(px)*(r00)*(r02)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-4.00000000000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((pp)*(pp))))+(((IkReal(-16.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(0.404610320000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.668800000000000))*(px)*(pz)*(r00)*(sj1)))+(((IkReal(-0.00845635568800000))*(r02)*(sj1)))+(((IkReal(-16.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj0)*(px)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(1.76000000000000))*(pz)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.404610320000000))*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(pz)*(r00)*(r02)))+(((IkReal(-0.404610320000000))*((pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(sj1)*((px)*(px))))+(((IkReal(0.202305160000000))*(pp)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(px)*((r00)*(r00))))+(((IkReal(1.76000000000000))*(py)*(r01)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj1)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-32.0000000000000))*(cj1)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py)))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst0)*(((((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0579051600000000))*(cj0)*(pp)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.0183920000000000))*(cj1)*(pz)))+(((IkReal(1.76000000000000))*(cj0)*(px)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00951443240000000))*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*(cj0)*(pz)*((px)*(px)*(px))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj0)*(px)*((cj1)*(cj1))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0222535676000000))*(cj0)*(pz)*(r00)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(0.288800000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(16.0000000000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.00218729405567180))*(cj0)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(16.0000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.00218729405567180))*(cj1)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.0317680000000000))*(cj0)*(px)*(r02)))+(((IkReal(16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(r01)*(r02)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.115810320000000))*(cj1)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.76000000000000))*(cj1)*(r01)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0384379804000000))*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(-0.202305160000000))*(cj0)*(px)*(pz)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(2.00000000000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0864948400000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.167200000000000))*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.0164340196000000))*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.760000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(0.115810320000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.0968000000000000))*(cj0)*(px)*(pz)*((sj1)*(sj1))))+(((IkReal(1.76000000000000))*(cj1)*(pz)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(px)*(r00)*(r02)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))*((py)*(py))))+(((IkReal(0.440000000000000))*(cj0)*(pp)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(r02)*((pp)*(pp))*((sj1)*(sj1))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(-0.501600000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(-0.0768759608000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(16.0000000000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))*((pz)*(pz))))+(((IkReal(-0.00218729405567180))*(cj1)*(sj1)*((r02)*(r02))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(0.0384379804000000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*(r01)*(r02)*(sj0)*((py)*(py))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.440000000000000))*(pp)*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(1.76000000000000))*(cj1)*(r00)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.288800000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(1.52000000000000))*(cj1)*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*((pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-3.04000000000000))*(cj1)*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.0864948400000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-0.00951443240000000))*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.334400000000000))*(cj1)*(py)*(pz)*(r01)))+(((IkReal(-1.76000000000000))*(px)*(py)*(pz)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-1.52000000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.0127391352000000))*(cj1)*(pz)*(r02)*(sj1)))+(((IkReal(-2.00000000000000))*(cj1)*(sj1)*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00180774215600000))*(cj0)*(r00)*(sj1)))+(((IkReal(-0.0384379804000000))*(cj1)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.76000000000000))*(py)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.288800000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-1.52000000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(4.56000000000000))*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-0.501600000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.0864948400000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.760000000000000))*(cj0)*(cj1)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.288800000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.00218729405567180))*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(1.52000000000000))*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.76000000000000))*(cj0)*(pz)*(r00)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0164340196000000))*(cj1)*(py)*(r01)*(r02)))+(((IkReal(16.0000000000000))*(cj1)*(px)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0183920000000000))*(py)*(sj0)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(sj1)*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-1.76000000000000))*(cj1)*(px)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(1.76000000000000))*(cj1)*(px)*(r00)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.52000000000000))*(cj1)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(1.76000000000000))*(py)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.0864948400000000))*(cj0)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(py)*(sj0)*((pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(0.0127391352000000))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.0579051600000000))*(cj1)*(pp)*(sj1)*((r02)*(r02))))+(((IkReal(-3.04000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.0317680000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.0127391352000000))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-1.52000000000000))*(cj0)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(0.0579051600000000))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0968000000000000))*(cj1)*(sj1)*((pz)*(pz))))+(((IkReal(-0.115810320000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(1.52000000000000))*(cj0)*(px)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.288800000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(1.76000000000000))*(px)*(py)*(pz)*(r00)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.202305160000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(0.880000000000000))*(cj1)*(pp)*(pz)*(r02)*(sj1)))+(((IkReal(0.00218729405567180))*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.167200000000000))*(cj1)*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(3.04000000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0384379804000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.288800000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((pp)*(pp))))+(((IkReal(-0.440000000000000))*(pp)*(py)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.167200000000000))*(cj1)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.0864948400000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(0.0127391352000000))*(cj1)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.288800000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(r01)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.202305160000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(-0.202305160000000))*(px)*(py)*(r00)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.0864948400000000))*(cj0)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-0.440000000000000))*(cj0)*(pp)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(-0.0968000000000000))*(cj1)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0864948400000000))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.202305160000000))*(cj0)*(px)*(py)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.440000000000000))*(cj0)*(pp)*(px)*(r02)*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(0.0384379804000000))*(cj0)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-1.76000000000000))*(cj0)*(pz)*(r00)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(8.00000000000000))*(cj0)*(pz)*((cj1)*(cj1))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(2.00000000000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(-2.00000000000000))*(r01)*(r02)*(sj0)*((pp)*(pp))*((sj1)*(sj1))))+(((IkReal(-0.334400000000000))*(cj0)*(px)*(py)*(r01)*(sj1)))+(((IkReal(0.0864948400000000))*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(-3.04000000000000))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(0.0968000000000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0222535676000000))*(py)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.76000000000000))*(cj1)*(py)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(0.288800000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(4.56000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.0579051600000000))*(cj1)*(pp)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0164340196000000))*(cj0)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(-4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(-0.760000000000000))*(pp)*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(0.00180774215600000))*(r01)*(sj0)*(sj1)))+(((IkReal(-0.288800000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(1.52000000000000))*(py)*(sj0)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.0164340196000000))*(cj1)*(pz)*((r02)*(r02))))+(((IkReal(-0.440000000000000))*(pp)*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.202305160000000))*(py)*(pz)*(sj0)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.760000000000000))*(cj1)*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.00218729405567180))*(cj1)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.202305160000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))))+(((IkReal(1.76000000000000))*(cj1)*(py)*(r01)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.00951443240000000))*(cj0)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(0.0864948400000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(-0.760000000000000))*(cj1)*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.202305160000000))*(cj0)*(r00)*(r02)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(16.0000000000000))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.0836000000000000))*(pp)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.00180774215600000))*(cj1)*(r02)))+(((IkReal(-0.334400000000000))*(px)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(0.202305160000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(-1.76000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*((cj1)*(cj1))))+(((IkReal(-0.760000000000000))*(pp)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(py)*(sj0)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.00218729405567180))*(cj0)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.334400000000000))*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(3.04000000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)*((px)*(px))))+(((IkReal(-0.115810320000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(1.76000000000000))*(pz)*(r01)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(-0.288800000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.52000000000000))*(cj0)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.0579051600000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.0127391352000000))*(cj1)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(1.76000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*((sj1)*(sj1))))+(((IkReal(0.0317680000000000))*(py)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.00951443240000000))*(cj0)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0384379804000000))*(cj1)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0222535676000000))*(cj0)*(px)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.202305160000000))*(r01)*(r02)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(-0.0164340196000000))*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(0.0968000000000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))))+(((IkReal(-0.0548720000000000))*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.288800000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.334400000000000))*(cj0)*(r00)*(sj1)*((px)*(px))))+(((IkReal(-0.167200000000000))*(cj1)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(4.56000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.334400000000000))*(cj1)*(r02)*((pz)*(pz))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(-1.76000000000000))*(cj0)*(px)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.334400000000000))*(cj1)*(px)*(pz)*(r00)))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(0.0864948400000000))*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(pz)*((py)*(py))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.0579051600000000))*(pp)*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.167200000000000))*(cj1)*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(0.115810320000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.440000000000000))*(pp)*(pz)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.0968000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(8.00000000000000))*(pz)*(sj0)*((cj1)*(cj1))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.202305160000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(-0.334400000000000))*(cj0)*(cj1)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r02)*((px)*(px))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-1.76000000000000))*(pz)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(0.440000000000000))*(cj0)*(pp)*(pz)*(r00)*((cj1)*(cj1))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.0317680000000000))*(pz)*(r01)*(sj0)))+(((IkReal(16.0000000000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))*((pz)*(pz))))+(((IkReal(-8.00000000000000))*(pz)*(sj0)*((py)*(py)*(py))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(0.0384379804000000))*(cj1)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(1.52000000000000))*(cj1)*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.202305160000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-0.288800000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0384379804000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-0.193600000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)))+(((IkReal(-0.0579051600000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.76000000000000))*(cj1)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(-0.0548720000000000))*(cj0)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.760000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.0183920000000000))*(cj0)*(px)*(sj1)))+(((IkReal(0.0164340196000000))*(cj1)*(px)*(r00)*(r02)))+(((IkReal(4.56000000000000))*(cj0)*(pz)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(0.0864948400000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(py)*(pz)*(sj0)*((px)*(px))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(0.167200000000000))*(cj0)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(0.115810320000000))*(cj1)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(1.76000000000000))*(cj1)*(pz)*(r02)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.115810320000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(8.00000000000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0836000000000000))*(cj1)*(pp)*(r02)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-0.0164340196000000))*(cj0)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(-0.0968000000000000))*(py)*(pz)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.0864948400000000))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))))+(((IkReal(0.00437458811134360))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(1.52000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.52000000000000))*(cj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0222535676000000))*(pz)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj1)*(px)*(r00)*(r01)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*(cj1)*(py)*(r01)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(8.00000000000000))*(py)*(sj0)*((cj1)*(cj1))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0836000000000000))*(cj0)*(pp)*(r00)*(sj1))))))) < IKFAST_ATAN2_MAGTHRESH )
00410     continue;
00411 j2array[0]=IKatan2(((gconst0)*(((IkReal(-0.00349448000000000))+(((IkReal(-0.193600000000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0445071352000000))*(cj0)*(px)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.668800000000000))*(cj1)*(px)*(py)*(r00)*(sj0)))+(((IkReal(0.0635360000000000))*(pz)*(r02)))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(0.0445071352000000))*(pz)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(sj0)*((cj1)*(cj1))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-8.00000000000000))*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.0102318444406564))*(cj1)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((px)*(px))*((pz)*(pz))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(px)*(py)*(r01)))+(((IkReal(3.04000000000000))*(pz)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)))+(((IkReal(-32.0000000000000))*(cj1)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(1.76000000000000))*(r01)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.202305160000000))*(pp)*((cj1)*(cj1))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(pp)*(py)*(pz)*(r01)*(r02)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(0.0445071352000000))*(py)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(6.08000000000000))*(px)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-0.00511592222032820))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(-0.404610320000000))*(py)*(pz)*(r01)*(r02)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(-0.668800000000000))*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-0.404610320000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.167200000000000))*(pp)*(r02)*(sj1)))+(((IkReal(6.08000000000000))*(cj1)*(pz)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-0.880000000000000))*(pp)*(px)*(r00)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(-0.00511592222032820))*((cj1)*(cj1))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(3.52000000000000))*(cj1)*(py)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(0.0445071352000000))*(cj0)*(cj1)*(pz)*(r00)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0768759608000000))*(py)*(r01)*(r02)*(sj1)))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0635360000000000))*(py)*(r01)))+(((IkReal(-8.00000000000000))*((py)*(py))*((pz)*(pz))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(0.0367840000000000))*(cj0)*(cj1)*(px)))+(((IkReal(-0.404610320000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(1.76000000000000))*(px)*(r00)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(px)*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-32.0000000000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.0445071352000000))*(cj0)*(py)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.404610320000000))*(cj1)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-16.0000000000000))*(py)*(r00)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(0.0445071352000000))*(px)*(r00)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*((py)*(py))*((r01)*(r01))))+(((IkReal(0.0768759608000000))*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))*((py)*(py))))+(((IkReal(1.76000000000000))*(py)*(r01)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.288800000000000))*((px)*(px))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(sj0)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(py)*(r00)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r01)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(py)*(r00)*(r01)))+(((IkReal(-1.52000000000000))*(pp)*(py)*(r01)*(r02)*(sj1)))+(((IkReal(0.0445071352000000))*(cj1)*(py)*(r02)*(sj0)*(sj1)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(pp)*(r00)))+(((IkReal(8.00000000000000))*(pp)*(px)*(py)*(r00)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(px)*(r00)*(r01)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(pz)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(sj1)*((r00)*(r00))))+(((IkReal(-0.404610320000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(0.404610320000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(py)*(pz)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.668800000000000))*(cj1)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.404610320000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(1.76000000000000))*(r00)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px)*(px))))+(((IkReal(8.00000000000000))*(pp)*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(3.04000000000000))*(cj1)*(py)*(sj0)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r02)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.0102318444406564))*(cj0)*(cj1)*(r00)*(r02)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-2.00000000000000))*((pp)*(pp))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.0102318444406564))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.577600000000000))*(py)*(pz)*(r01)*(r02)))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r01)*(sj1)))+(((IkReal(-0.00845635568800000))*(cj1)*(r01)*(sj0)))+(((IkReal(-16.0000000000000))*(pz)*(r01)*(r02)*((cj1)*(cj1))*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.404610320000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-4.00000000000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(-0.668800000000000))*(py)*(pz)*(r01)*(sj1)))+(((IkReal(1.76000000000000))*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj1)*(pz)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.880000000000000))*(cj0)*(pp)*(py)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0445071352000000))*(cj1)*(pz)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(-0.193600000000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)))+(((IkReal(0.404610320000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)))+(((IkReal(-0.577600000000000))*(px)*(pz)*(r00)*(r02)))+(((IkReal(-0.404610320000000))*(cj0)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-4.00000000000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((pp)*(pp))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(0.0768759608000000))*(cj1)*(py)*(sj0)*((r01)*(r01))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(py)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(px)*(pz)*(r00)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))))+(((IkReal(-32.0000000000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r02)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(-0.880000000000000))*(cj0)*(pp)*(px)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)*((r00)*(r00))))+(((IkReal(-0.668800000000000))*(cj0)*(cj1)*(r00)*((px)*(px))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(px)*((r00)*(r00))))+(((IkReal(-0.404610320000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0968000000000000))*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(cj1)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(-0.00511592222032820))*((cj0)*(cj0))*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(0.0635360000000000))*(px)*(r00)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(px)*(r02)*(sj1)))+(((IkReal(-0.404610320000000))*(px)*(pz)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.668800000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-0.288800000000000))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(sj0)*((cj1)*(cj1))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.0968000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj1)*(px)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(3.52000000000000))*(cj0)*(px)*(py)*(pz)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.404610320000000))*(cj0)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(6.08000000000000))*(px)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.288800000000000))*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*((cj1)*(cj1))*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0367840000000000))*(pz)*(sj1)))+(((IkReal(-0.880000000000000))*(pp)*(pz)*(r02)*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(pp)*((pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(6.08000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r02)*(sj0)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(py)*(pz)*(r00)*(r01)*(sj1)))+(((IkReal(-2.00000000000000))*((cj1)*(cj1))*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.577600000000000))*(px)*(py)*(r00)*(r01)))+(((IkReal(3.04000000000000))*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0445071352000000))*(cj0)*(cj1)*(px)*(r02)*(sj1)))+(((IkReal(1.76000000000000))*(px)*(r00)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(sj0)*(sj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(3.04000000000000))*(cj1)*(py)*(sj0)*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.0367840000000000))*(cj1)*(py)*(sj0)))+(((IkReal(-0.0968000000000000))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj0)*(cj1)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(0.202305160000000))*(pp)*((cj0)*(cj0))*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-1.52000000000000))*(cj1)*(pp)*(px)*(r00)*(r01)*(sj0)))+(((IkReal(6.08000000000000))*(py)*(r01)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(0.0768759608000000))*(cj1)*(pz)*(r01)*(r02)*(sj0)))+(((IkReal(-0.880000000000000))*(pp)*(py)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(pp)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(pp)*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r01)*(sj1)*((px)*(px))))+(((IkReal(1.76000000000000))*(pz)*(r02)*((cj1)*(cj1))*((py)*(py))*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(pz)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(pz)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(3.04000000000000))*(cj1)*(sj0)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-0.193600000000000))*(cj0)*(cj1)*(px)*(pz)*(sj1)))+(((IkReal(-1.52000000000000))*(pp)*(px)*(r00)*(r02)*(sj1)))+(((IkReal(-0.00845635568800000))*(cj0)*(cj1)*(r00)))+(((IkReal(-8.00000000000000))*((px)*(px))*((pz)*(pz))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r01)))+(((IkReal(-2.00000000000000))*((cj0)*(cj0))*((cj1)*(cj1))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-0.404610320000000))*(cj1)*(py)*(pz)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(0.167200000000000))*(cj1)*(pp)*(r01)*(sj0)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(sj0)*((cj1)*(cj1))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-1.52000000000000))*(pp)*(pz)*(sj1)*((r02)*(r02))))+(((IkReal(-0.404610320000000))*(px)*(py)*(r00)*(r01)*((cj1)*(cj1))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(px)*(r00)*(r02)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(pp)*(px)*(py)*(sj0)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-32.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r02)*(sj0)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-4.00000000000000))*(cj1)*(r01)*(r02)*(sj0)*(sj1)*((pp)*(pp))))+(((IkReal(-16.0000000000000))*(py)*(pz)*(r01)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(py)*(r00)*(r01)*((px)*(px))))+(((IkReal(0.404610320000000))*(cj0)*(pp)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.668800000000000))*(px)*(pz)*(r00)*(sj1)))+(((IkReal(-0.00845635568800000))*(r02)*(sj1)))+(((IkReal(-16.0000000000000))*(py)*(r01)*(r02)*((pz)*(pz)*(pz))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj0)*(px)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(1.76000000000000))*(pz)*(r02)*((cj0)*(cj0))*((cj1)*(cj1))*((px)*(px))))+(((IkReal(6.08000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r01)*(r02)))+(((IkReal(-0.404610320000000))*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(pz)*(r00)*(r02)))+(((IkReal(-0.404610320000000))*((pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(sj1)*((px)*(px))))+(((IkReal(0.202305160000000))*(pp)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(0.0768759608000000))*(cj0)*(cj1)*(px)*((r00)*(r00))))+(((IkReal(1.76000000000000))*(py)*(r01)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.404610320000000))*(cj1)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-32.0000000000000))*(cj1)*(px)*(pz)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))))), ((gconst0)*(((((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0579051600000000))*(cj0)*(pp)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.0183920000000000))*(cj1)*(pz)))+(((IkReal(1.76000000000000))*(cj0)*(px)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00951443240000000))*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*(cj0)*(pz)*((px)*(px)*(px))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj0)*(px)*((cj1)*(cj1))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0222535676000000))*(cj0)*(pz)*(r00)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r00)*(r00))))+(((IkReal(0.288800000000000))*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(16.0000000000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((sj0)*(sj0))))+(((IkReal(-0.00218729405567180))*(cj0)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))))+(((IkReal(16.0000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.00218729405567180))*(cj1)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(py)*(r01)*(r02)))+(((IkReal(0.0317680000000000))*(cj0)*(px)*(r02)))+(((IkReal(16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(r01)*(r02)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.115810320000000))*(cj1)*(sj1)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(1.76000000000000))*(cj1)*(r01)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0384379804000000))*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(-0.202305160000000))*(cj0)*(px)*(pz)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(2.00000000000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((px)*(px))))+(((IkReal(-0.0864948400000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(0.167200000000000))*(r01)*(sj0)*(sj1)*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(r00)*(r02)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((px)*(px))*((py)*(py))*((r00)*(r00))*((sj0)*(sj0))))+(((IkReal(-0.0164340196000000))*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.760000000000000))*(pp)*(px)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-16.0000000000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(0.115810320000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.0968000000000000))*(cj0)*(px)*(pz)*((sj1)*(sj1))))+(((IkReal(1.76000000000000))*(cj1)*(pz)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(px)*(r00)*(r02)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))*((py)*(py))))+(((IkReal(0.440000000000000))*(cj0)*(pp)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((py)*(py))*((r01)*(r01))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(r02)*((pp)*(pp))*((sj1)*(sj1))))+(((IkReal(4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r00)*(r00))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(-0.501600000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(-0.0768759608000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(sj0)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))*((sj0)*(sj0))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((py)*(py))*((pz)*(pz))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(16.0000000000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))*((pz)*(pz))))+(((IkReal(-0.00218729405567180))*(cj1)*(sj1)*((r02)*(r02))))+(((IkReal(-0.880000000000000))*(cj1)*(pp)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(0.0384379804000000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-16.0000000000000))*(r01)*(r02)*(sj0)*((py)*(py))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.440000000000000))*(pp)*(py)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(1.76000000000000))*(cj1)*(r00)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(0.288800000000000))*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(1.52000000000000))*(cj1)*(py)*(r01)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*((pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-3.04000000000000))*(cj1)*(px)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-0.0864948400000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-0.00951443240000000))*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.334400000000000))*(cj1)*(py)*(pz)*(r01)))+(((IkReal(-1.76000000000000))*(px)*(py)*(pz)*(r00)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj1)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(-1.52000000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.0127391352000000))*(cj1)*(pz)*(r02)*(sj1)))+(((IkReal(-2.00000000000000))*(cj1)*(sj1)*((pp)*(pp))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.00180774215600000))*(cj0)*(r00)*(sj1)))+(((IkReal(-0.0384379804000000))*(cj1)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.76000000000000))*(py)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.288800000000000))*(cj0)*(px)*(pz)*((r00)*(r00))))+(((IkReal(-1.52000000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(4.56000000000000))*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-0.501600000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(-0.0864948400000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.760000000000000))*(cj0)*(cj1)*(pp)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(0.288800000000000))*(px)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((py)*(py))*((pz)*(pz))*((r01)*(r01))))+(((IkReal(-0.00218729405567180))*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(1.52000000000000))*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(1.76000000000000))*(cj0)*(pz)*(r00)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(0.0164340196000000))*(cj1)*(py)*(r01)*(r02)))+(((IkReal(16.0000000000000))*(cj1)*(px)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.0183920000000000))*(py)*(sj0)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(sj1)*((pp)*(pp))*((r02)*(r02))))+(((IkReal(-1.76000000000000))*(cj1)*(px)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(1.76000000000000))*(cj1)*(px)*(r00)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(1.52000000000000))*(cj1)*(r01)*(r02)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(1.76000000000000))*(py)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.0864948400000000))*(cj0)*(r00)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-8.00000000000000))*(py)*(sj0)*((pz)*(pz)*(pz))*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((pz)*(pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(0.0127391352000000))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.0579051600000000))*(cj1)*(pp)*(sj1)*((r02)*(r02))))+(((IkReal(-3.04000000000000))*(cj1)*(px)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.0317680000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.0127391352000000))*(cj0)*(cj1)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-1.52000000000000))*(cj0)*(r00)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(0.0579051600000000))*(cj1)*(pp)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0968000000000000))*(cj1)*(sj1)*((pz)*(pz))))+(((IkReal(-0.115810320000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)*((px)*(px))))+(((IkReal(1.52000000000000))*(cj0)*(px)*(sj1)*((py)*(py))*((r01)*(r01))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(-0.288800000000000))*(cj0)*(px)*(py)*(r01)*(r02)))+(((IkReal(-0.880000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(1.76000000000000))*(px)*(py)*(pz)*(r00)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.202305160000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(py)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(0.880000000000000))*(cj1)*(pp)*(pz)*(r02)*(sj1)))+(((IkReal(0.00218729405567180))*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.167200000000000))*(cj1)*(px)*(pz)*(r00)*((cj0)*(cj0))))+(((IkReal(3.04000000000000))*(cj0)*(px)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(py)*(sj0)*(sj1)*((r00)*(r00))))+(((IkReal(4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-8.00000000000000))*(cj1)*(pp)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0384379804000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.288800000000000))*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-4.00000000000000))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)*((pp)*(pp))))+(((IkReal(-0.440000000000000))*(pp)*(py)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.167200000000000))*(cj1)*(r02)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(-0.0864948400000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(0.0127391352000000))*(cj1)*(px)*(r00)*(sj1)*((cj0)*(cj0))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.288800000000000))*(cj0)*(px)*(pz)*((r02)*(r02))))+(((IkReal(-16.0000000000000))*(cj0)*(px)*(py)*(r01)*(r02)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.202305160000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-0.760000000000000))*(cj0)*(pp)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(-0.202305160000000))*(px)*(py)*(r00)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.0864948400000000))*(cj0)*(px)*(pz)*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(-0.440000000000000))*(cj0)*(pp)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(-0.0968000000000000))*(cj1)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-0.0864948400000000))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.202305160000000))*(cj0)*(px)*(py)*(r01)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.440000000000000))*(cj0)*(pp)*(px)*(r02)*((sj1)*(sj1))))+(((IkReal(-4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(0.0384379804000000))*(cj0)*(px)*(sj1)*((r02)*(r02))))+(((IkReal(-1.76000000000000))*(cj0)*(pz)*(r00)*((cj1)*(cj1))*((px)*(px))))+(((IkReal(8.00000000000000))*(cj0)*(pz)*((cj1)*(cj1))*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(2.00000000000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((pp)*(pp))))+(((IkReal(-2.00000000000000))*(r01)*(r02)*(sj0)*((pp)*(pp))*((sj1)*(sj1))))+(((IkReal(-0.334400000000000))*(cj0)*(px)*(py)*(r01)*(sj1)))+(((IkReal(0.0864948400000000))*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(-3.04000000000000))*(cj1)*(py)*(r01)*(r02)*((pz)*(pz))))+(((IkReal(0.0968000000000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))))+(((IkReal(0.0222535676000000))*(py)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(-1.76000000000000))*(cj1)*(py)*(r01)*(sj1)*((pz)*(pz))))+(((IkReal(0.288800000000000))*(cj0)*(r00)*(r02)*((pz)*(pz))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(4.00000000000000))*(pp)*(px)*(py)*(r00)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(4.56000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.0579051600000000))*(cj1)*(pp)*(sj1)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-0.0164340196000000))*(cj0)*(px)*(sj1)*((r00)*(r00))))+(((IkReal(-4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(-0.760000000000000))*(pp)*(py)*(sj0)*(sj1)*((r02)*(r02))))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(0.00180774215600000))*(r01)*(sj0)*(sj1)))+(((IkReal(-0.288800000000000))*(px)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(1.52000000000000))*(py)*(sj0)*(sj1)*((px)*(px))*((r00)*(r00))))+(((IkReal(8.00000000000000))*(cj1)*(sj1)*((px)*(px))*((pz)*(pz))*((r00)*(r00))))+(((IkReal(0.0164340196000000))*(cj1)*(pz)*((r02)*(r02))))+(((IkReal(-0.440000000000000))*(pp)*(pz)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.202305160000000))*(py)*(pz)*(sj0)*((r02)*(r02))*((sj1)*(sj1))))+(((IkReal(-0.760000000000000))*(cj1)*(pp)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(0.00218729405567180))*(cj1)*(sj1)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.202305160000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))))+(((IkReal(1.76000000000000))*(cj1)*(py)*(r01)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(0.00951443240000000))*(cj0)*(px)*(r02)*((cj1)*(cj1))))+(((IkReal(0.0864948400000000))*(cj0)*(py)*(pz)*(r00)*(r01)*((sj1)*(sj1))))+(((IkReal(-0.760000000000000))*(cj1)*(pp)*(px)*(r00)*(r02)*((cj0)*(cj0))))+(((IkReal(-0.202305160000000))*(cj0)*(r00)*(r02)*((px)*(px))*((sj1)*(sj1))))+(((IkReal(16.0000000000000))*(px)*(py)*(r00)*(r02)*(sj0)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(1.52000000000000))*(cj1)*(pz)*((py)*(py))*((r02)*(r02))*((sj0)*(sj0))))+(((IkReal(0.0836000000000000))*(pp)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.00180774215600000))*(cj1)*(r02)))+(((IkReal(-0.334400000000000))*(px)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(0.202305160000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((r01)*(r01))))+(((IkReal(-1.76000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*((cj1)*(cj1))))+(((IkReal(-0.760000000000000))*(pp)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(py)*(sj0)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(0.00218729405567180))*(cj0)*(r00)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.334400000000000))*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(3.04000000000000))*(cj0)*(py)*(r00)*(r01)*(sj1)*((px)*(px))))+(((IkReal(-0.115810320000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))*((r00)*(r00))))+(((IkReal(1.76000000000000))*(pz)*(r01)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(-0.288800000000000))*(py)*(pz)*(sj0)*((r02)*(r02))))+(((IkReal(1.52000000000000))*(cj0)*(sj1)*((px)*(px)*(px))*((r00)*(r00))))+(((IkReal(-0.0579051600000000))*(pp)*(r01)*(r02)*(sj0)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(cj1)*(px)*(r00)*(r02)*((cj0)*(cj0))*((pz)*(pz))))+(((IkReal(0.0127391352000000))*(cj1)*(py)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(1.76000000000000))*(cj0)*(px)*(py)*(pz)*(r01)*((sj1)*(sj1))))+(((IkReal(0.0317680000000000))*(py)*(r02)*(sj0)))+(((IkReal(-8.00000000000000))*(cj1)*(sj1)*((py)*(py)*(py)*(py))*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(-1.52000000000000))*(cj1)*(pz)*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.00951443240000000))*(cj0)*(pz)*(r00)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(py)*(sj0)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0384379804000000))*(cj1)*(pz)*((cj0)*(cj0))*((r00)*(r00))))+(((IkReal(0.0222535676000000))*(cj0)*(px)*(r02)*((sj1)*(sj1))))+(((IkReal(-0.202305160000000))*(r01)*(r02)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(-0.0164340196000000))*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(0.0968000000000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))))+(((IkReal(-0.0548720000000000))*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(0.288800000000000))*(cj0)*(py)*(pz)*(r00)*(r01)))+(((IkReal(-0.334400000000000))*(cj0)*(r00)*(sj1)*((px)*(px))))+(((IkReal(-0.167200000000000))*(cj1)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(-16.0000000000000))*(cj0)*(cj1)*(px)*(sj0)*(sj1)*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(cj1)*(pz)*(r00)*(r02)*(sj1)*((cj0)*(cj0))*((px)*(px)*(px))))+(((IkReal(4.00000000000000))*(pp)*(py)*(pz)*(sj0)*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(-32.0000000000000))*(cj0)*(cj1)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(4.56000000000000))*(px)*(py)*(pz)*(r00)*(r02)*(sj0)*(sj1)))+(((IkReal(0.334400000000000))*(cj1)*(r02)*((pz)*(pz))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(-1.76000000000000))*(cj0)*(px)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(8.00000000000000))*(cj1)*(pp)*(py)*(pz)*(r01)*(r02)*(sj1)*((sj0)*(sj0))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((sj0)*(sj0))))+(((IkReal(0.760000000000000))*(cj1)*(pp)*(pz)*((r01)*(r01))*((sj0)*(sj0))))+(((IkReal(0.334400000000000))*(cj1)*(px)*(pz)*(r00)))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(0.0864948400000000))*(r01)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-8.00000000000000))*(cj0)*(px)*(pz)*((py)*(py))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((py)*(py))))+(((IkReal(0.0579051600000000))*(pp)*(r01)*(r02)*(sj0)*((sj1)*(sj1))))+(((IkReal(0.167200000000000))*(cj1)*(py)*(pz)*(r01)*((sj0)*(sj0))))+(((IkReal(0.115810320000000))*(cj1)*(py)*(pz)*(r01)*(r02)*(sj1)))+(((IkReal(0.440000000000000))*(pp)*(pz)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-0.115810320000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)*((r01)*(r01))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(r01)*(r02)*(sj0)*((pz)*(pz))))+(((IkReal(-0.0968000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((px)*(px))))+(((IkReal(8.00000000000000))*(pz)*(sj0)*((cj1)*(cj1))*((py)*(py)*(py))*((r01)*(r01))))+(((IkReal(0.202305160000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-1.52000000000000))*(r01)*(r02)*(sj0)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(-0.334400000000000))*(cj0)*(cj1)*(px)*(py)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*(cj1)*(sj1)*((cj0)*(cj0))*((pp)*(pp))*((r00)*(r00))))+(((IkReal(-16.0000000000000))*(cj0)*(r00)*(r02)*((px)*(px))*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(-1.76000000000000))*(pz)*(r01)*(sj0)*((cj1)*(cj1))*((py)*(py))))+(((IkReal(4.00000000000000))*(pp)*(r01)*(r02)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(0.440000000000000))*(cj0)*(pp)*(pz)*(r00)*((cj1)*(cj1))))+(((IkReal(-0.115810320000000))*(cj1)*(px)*(py)*(r00)*(r01)*(sj1)*((cj0)*(cj0))))+(((IkReal(-0.0317680000000000))*(pz)*(r01)*(sj0)))+(((IkReal(16.0000000000000))*(r01)*(r02)*(sj0)*((cj1)*(cj1))*((py)*(py))*((pz)*(pz))))+(((IkReal(-8.00000000000000))*(pz)*(sj0)*((py)*(py)*(py))*((r01)*(r01))*((sj1)*(sj1))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(r01)*(sj0)*(sj1)*((px)*(px))))+(((IkReal(0.0384379804000000))*(cj1)*(py)*(r01)*(r02)*((sj0)*(sj0))))+(((IkReal(8.00000000000000))*(cj0)*(cj1)*(pp)*(px)*(pz)*(r01)*(r02)*(sj0)*(sj1)))+(((IkReal(1.52000000000000))*(cj1)*(px)*(r00)*(r02)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.202305160000000))*(cj0)*(r00)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-0.288800000000000))*(cj0)*(r00)*(r02)*((px)*(px))))+(((IkReal(0.0384379804000000))*(cj0)*(cj1)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(-0.193600000000000))*(cj0)*(cj1)*(px)*(py)*(sj0)*(sj1)))+(((IkReal(-0.0579051600000000))*(cj0)*(pp)*(r00)*(r02)*((cj1)*(cj1))))+(((IkReal(-1.76000000000000))*(cj1)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(-0.0548720000000000))*(cj0)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(px)*(py)*(pz)*(sj0)*((r01)*(r01))))+(((IkReal(-0.760000000000000))*(cj0)*(cj1)*(pp)*(py)*(r00)*(r02)*(sj0)))+(((IkReal(0.0183920000000000))*(cj0)*(px)*(sj1)))+(((IkReal(0.0164340196000000))*(cj1)*(px)*(r00)*(r02)))+(((IkReal(4.56000000000000))*(cj0)*(pz)*(r00)*(r02)*(sj1)*((px)*(px))))+(((IkReal(0.0864948400000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((sj1)*(sj1))))+(((IkReal(3.04000000000000))*(px)*(r00)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((cj1)*(cj1))*((r00)*(r00))))+(((IkReal(-8.00000000000000))*(py)*(pz)*(sj0)*((px)*(px))*((r00)*(r00))*((sj1)*(sj1))))+(((IkReal(0.167200000000000))*(cj0)*(r00)*(sj1)*((pz)*(pz))))+(((IkReal(0.115810320000000))*(cj1)*(sj1)*((pz)*(pz))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(pp)*(px)*(pz)*(r00)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(px)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))*((sj1)*(sj1))))+(((IkReal(1.76000000000000))*(cj1)*(pz)*(r02)*(sj1)*((py)*(py))*((sj0)*(sj0))))+(((IkReal(0.115810320000000))*(cj1)*(px)*(pz)*(r00)*(r02)*(sj1)))+(((IkReal(3.52000000000000))*(cj0)*(cj1)*(px)*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(8.00000000000000))*(py)*(pz)*(sj0)*((cj1)*(cj1))*((px)*(px))*((r00)*(r00))))+(((IkReal(-0.0836000000000000))*(cj1)*(pp)*(r02)))+(((IkReal(0.167200000000000))*(cj0)*(cj1)*(px)*(pz)*(r01)*(sj0)))+(((IkReal(-0.0164340196000000))*(cj0)*(py)*(r00)*(r01)*(sj1)))+(((IkReal(-0.0968000000000000))*(py)*(pz)*(sj0)*((sj1)*(sj1))))+(((IkReal(-0.0864948400000000))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(px)*(pz)*((cj1)*(cj1))*((r02)*(r02))))+(((IkReal(-4.00000000000000))*(cj0)*(pp)*(py)*(pz)*(r00)*(r01)*((cj1)*(cj1))))+(((IkReal(0.00437458811134360))*(cj0)*(cj1)*(r00)*(r01)*(sj0)*(sj1)))+(((IkReal(8.00000000000000))*(cj0)*(px)*(pz)*((cj1)*(cj1))*((py)*(py))*((r01)*(r01))))+(((IkReal(-16.0000000000000))*(px)*(py)*(r00)*(r02)*(sj0)*((pz)*(pz))*((sj1)*(sj1))))+(((IkReal(1.52000000000000))*(cj0)*(cj1)*(pp)*(pz)*(r00)*(r01)*(sj0)))+(((IkReal(-1.52000000000000))*(cj1)*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(-0.0222535676000000))*(pz)*(r01)*(sj0)*((cj1)*(cj1))))+(((IkReal(-16.0000000000000))*(cj1)*(px)*(r00)*(r01)*(sj1)*((py)*(py)*(py))*((sj0)*(sj0))))+(((IkReal(16.0000000000000))*(cj0)*(px)*(py)*(r01)*(r02)*((cj1)*(cj1))*((pz)*(pz))))+(((IkReal(-1.52000000000000))*(cj0)*(cj1)*(pz)*(r00)*(r01)*(sj0)*((py)*(py))))+(((IkReal(16.0000000000000))*(cj1)*(py)*(r01)*(r02)*(sj1)*((pz)*(pz)*(pz))))+(((IkReal(8.00000000000000))*(py)*(sj0)*((cj1)*(cj1))*((pz)*(pz)*(pz))*((r02)*(r02))))+(((IkReal(0.0836000000000000))*(cj0)*(pp)*(r00)*(sj1)))))));
00412 sj2array[0]=IKsin(j2array[0]);
00413 cj2array[0]=IKcos(j2array[0]);
00414 if( j2array[0] > IKPI )
00415 {
00416     j2array[0]-=IK2PI;
00417 }
00418 else if( j2array[0] < -IKPI )
00419 {    j2array[0]+=IK2PI;
00420 }
00421 j2valid[0] = true;
00422 for(int ij2 = 0; ij2 < 1; ++ij2)
00423 {
00424 if( !j2valid[ij2] )
00425 {
00426     continue;
00427 }
00428 _ij2[0] = ij2; _ij2[1] = -1;
00429 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
00430 {
00431 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
00432 {
00433     j2valid[iij2]=false; _ij2[1] = iij2; break;
00434 }
00435 }
00436 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
00437 {
00438 IkReal evalcond[4];
00439 evalcond[0]=((IkReal(-0.0418000000000000))+(((IkReal(-0.658000000000000))*(pz)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(-0.380000000000000))*(py)*(r01)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(0.658000000000000))*(cj0)*(px)*(r02)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r01)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r01)*(sj0)*(IKcos(j2))))+(((cj0)*(pp)*(r00)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(IKcos(j2))))+(((IkReal(-0.380000000000000))*(px)*(r00)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj1)*(r01)*(sj0)*(IKcos(j2))))+(((IkReal(0.0505762900000000))*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(pz)*(sj1)))+(((IkReal(0.0744437100000000))*(r01)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(0.220000000000000))*(cj1)*(py)*(sj0)))+(((IkReal(-0.0505762900000000))*(cj1)*(r01)*(sj0)))+(((IkReal(-0.0505762900000000))*(r02)*(sj1)))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(IKcos(j2))))+(((cj1)*(pp)*(r01)*(sj0)))+(((IkReal(0.0744437100000000))*(cj0)*(r00)*(sj1)*(IKsin(j2))))+(((pp)*(r02)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)*(IKcos(j2))))+(((IkReal(-0.220000000000000))*(pz)*(sj1)*(IKcos(j2))))+(((pp)*(r01)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj0)*(cj1)*(r00)*(IKcos(j2))))+(((IkReal(-0.0505762900000000))*(cj0)*(cj1)*(r00)))+(((IkReal(-2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj0)*(cj1)*(px)*(IKcos(j2))))+(((IkReal(-0.380000000000000))*(pz)*(r02)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(px)*(pz)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(0.658000000000000))*(py)*(r02)*(sj0)*(IKsin(j2))))+(((IkReal(0.380000000000000))*(px)*(r00)))+(((IkReal(-0.220000000000000))*(cj1)*(py)*(sj0)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))*(IKcos(j2))))+(((cj0)*(cj1)*(pp)*(r00)))+(((IkReal(2.00000000000000))*(py)*(pz)*(r01)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(py)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r02)*((pz)*(pz))*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(px)*(pz)*(r00)*(sj1)))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r01)*(sj1)))+(((IkReal(2.00000000000000))*(r02)*(sj1)*((pz)*(pz))*(IKcos(j2))))+(((IkReal(0.220000000000000))*(cj0)*(px)*(sj1)*(IKsin(j2))))+(((IkReal(0.220000000000000))*(cj0)*(cj1)*(px)))+(((IkReal(-0.220000000000000))*(cj1)*(pz)*(IKsin(j2))))+(((IkReal(-0.658000000000000))*(cj0)*(pz)*(r00)*(IKsin(j2))))+(((IkReal(0.0418000000000000))*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))*(IKcos(j2))))+(((IkReal(0.380000000000000))*(py)*(r01)))+(((IkReal(-0.0744437100000000))*(cj1)*(r02)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))))+(((IkReal(2.00000000000000))*(cj1)*(px)*(pz)*(r00)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r02)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))*(IKsin(j2))))+(((IkReal(0.380000000000000))*(pz)*(r02))));
00440 evalcond[1]=((IkReal(0.0418000000000000))+(((IkReal(-0.380000000000000))*(py)*(r01)*(IKcos(j2))))+(((IkReal(0.0505762900000000))*(cj1)*(r01)*(sj0)))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj0)*(cj1)*(r00)))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r01)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r01)*(sj0)*(IKcos(j2))))+(((cj0)*(pp)*(r00)*(sj1)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(IKcos(j2))))+(((IkReal(-0.0311962900000000))*(cj0)*(r00)*(sj1)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(r02)*(sj1)*((pz)*(pz))))+(((IkReal(-0.380000000000000))*(px)*(r00)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj1)*(r01)*(sj0)*(IKcos(j2))))+(((IkReal(0.0311962900000000))*(cj1)*(r02)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)*(IKcos(j2))))+(((IkReal(-0.220000000000000))*(pz)*(sj1)*(IKcos(j2))))+(((IkReal(-0.380000000000000))*(py)*(r01)))+(((pp)*(r01)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(0.102000000000000))*(cj0)*(px)*(r02)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj0)*(cj1)*(r00)*(IKcos(j2))))+(((IkReal(0.0505762900000000))*(r02)*(sj1)))+(((IkReal(-2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj0)*(cj1)*(px)*(IKcos(j2))))+(((IkReal(-0.380000000000000))*(pz)*(r02)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(px)*(pz)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(py)*(sj0)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))*(IKcos(j2))))+(((IkReal(2.00000000000000))*(py)*(pz)*(r01)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(py)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(-0.380000000000000))*(pz)*(r02)))+(((IkReal(2.00000000000000))*(py)*(pz)*(r01)*(sj1)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)))+(((IkReal(-2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj0)*(cj1)*(px)))+(((IkReal(-0.220000000000000))*(pz)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(r02)*((pz)*(pz))*(IKsin(j2))))+(((IkReal(2.00000000000000))*(r02)*(sj1)*((pz)*(pz))*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))))+(((IkReal(-0.102000000000000))*(cj0)*(pz)*(r00)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(pp)*(r00)))+(((IkReal(0.220000000000000))*(cj0)*(px)*(sj1)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(pz)*(IKsin(j2))))+(((IkReal(-0.102000000000000))*(pz)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(sj1)))+(((IkReal(0.102000000000000))*(py)*(r02)*(sj0)*(IKsin(j2))))+(((IkReal(0.0418000000000000))*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)))+(((IkReal(2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)*(IKcos(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(py)*(sj0)))+(((IkReal(-0.0311962900000000))*(r01)*(sj0)*(sj1)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))*(IKcos(j2))))+(((IkReal(2.00000000000000))*(px)*(pz)*(r00)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(px)*(pz)*(r00)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r02)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))*(IKsin(j2))))+(((IkReal(-0.380000000000000))*(px)*(r00)))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r01)*(sj0))));
00441 evalcond[2]=((((IkReal(-2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)))+(((IkReal(0.0744437100000000))*(r01)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(-0.0744437100000000))*(cj1)*(r02)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r01)))+(((IkReal(0.0744437100000000))*(cj0)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(0.658000000000000))*(cj0)*(px)*(r02)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(py)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(cj1)*(py)*(sj0)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(cj0)*(px)*(sj1)*(IKcos(j2))))+(((IkReal(0.380000000000000))*(pz)*(r02)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(-2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)*(IKsin(j2))))+(((pp)*(r02)*(sj1)*(IKsin(j2))))+(((cj0)*(pp)*(r00)*(sj1)))+(((IkReal(0.0744437100000000))*(r01)*(sj0)*(sj1)))+(((IkReal(-0.658000000000000))*(cj0)*(pz)*(r00)))+(((IkReal(-2.00000000000000))*(r02)*(sj1)*((pz)*(pz))*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))))+(((IkReal(-0.0505762900000000))*(cj1)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(0.658000000000000))*(py)*(r02)*(sj0)))+(((IkReal(2.00000000000000))*(cj1)*(r02)*((pz)*(pz))*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(0.220000000000000))*(py)*(sj0)*(sj1)))+(((pp)*(r01)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(pz)*(sj1)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r02)*(IKcos(j2))))+(((IkReal(0.0744437100000000))*(cj0)*(r00)*(sj1)))+(((cj0)*(pp)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(0.658000000000000))*(cj0)*(px)*(r02)))+(((IkReal(-0.220000000000000))*(cj1)*(pz)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)*(IKsin(j2))))+(((IkReal(-0.0505762900000000))*(cj0)*(cj1)*(r00)*(IKsin(j2))))+(((pp)*(r01)*(sj0)*(sj1)))+(((cj1)*(pp)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r01)*(sj1)*(IKsin(j2))))+(((cj0)*(cj1)*(pp)*(r00)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(IKsin(j2))))+(((IkReal(-0.0744437100000000))*(cj1)*(r02)))+(((IkReal(-0.0418000000000000))*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(pz)))+(((IkReal(-2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(px)*(pz)*(r00)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(px)*(pz)*(r00)*(sj1)*(IKsin(j2))))+(((IkReal(0.380000000000000))*(py)*(r01)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)*(IKsin(j2))))+(((IkReal(-0.0505762900000000))*(r02)*(sj1)*(IKsin(j2))))+(((IkReal(-0.658000000000000))*(cj0)*(pz)*(r00)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r01)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r02)))+(((IkReal(2.00000000000000))*(cj1)*(px)*(pz)*(r00)))+(((IkReal(0.658000000000000))*(py)*(r02)*(sj0)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))*(IKsin(j2))))+(((IkReal(-0.658000000000000))*(pz)*(r01)*(sj0)))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r02)*((pz)*(pz))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(-2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))*(IKcos(j2))))+(((IkReal(-0.658000000000000))*(pz)*(r01)*(sj0)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(cj0)*(cj1)*(px)*(IKsin(j2))))+(((IkReal(0.380000000000000))*(px)*(r00)*(IKsin(j2))))+(((IkReal(0.220000000000000))*(cj0)*(px)*(sj1))));
00442 evalcond[3]=((((IkReal(2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))*(IKcos(j2))))+(((IkReal(0.0505762900000000))*(r02)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)))+(((IkReal(0.0418000000000000))*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(py)*(pz)*(r01)*(IKcos(j2))))+(((IkReal(0.102000000000000))*(pz)*(r01)*(sj0)*(IKcos(j2))))+(((cj1)*(pp)*(r02)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r01)))+(((IkReal(2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(cj0)*(pp)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(r02)*(sj1)*((pz)*(pz))*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(r01)*(sj0)*(sj1)*((py)*(py))))+(((IkReal(0.102000000000000))*(cj0)*(px)*(r02)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(r00)*((px)*(px))*(IKsin(j2))))+(((cj0)*(pp)*(r00)*(sj1)))+(((IkReal(2.00000000000000))*(cj0)*(px)*(py)*(r01)*(sj1)*(IKcos(j2))))+(((IkReal(-0.102000000000000))*(pz)*(r01)*(sj0)))+(((IkReal(-2.00000000000000))*(cj1)*(r02)*((pz)*(pz))*(IKcos(j2))))+(((IkReal(-0.380000000000000))*(pz)*(r02)*(IKsin(j2))))+(((IkReal(-0.102000000000000))*(py)*(r02)*(sj0)*(IKcos(j2))))+(((IkReal(0.0311962900000000))*(cj0)*(r00)*(sj1)*(IKcos(j2))))+(((IkReal(-2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))))+(((IkReal(2.00000000000000))*(px)*(pz)*(r00)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)))+(((IkReal(0.220000000000000))*(py)*(sj0)*(sj1)))+(((IkReal(0.0505762900000000))*(cj0)*(cj1)*(r00)*(IKsin(j2))))+(((IkReal(0.0505762900000000))*(cj1)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(py)*(sj0)*(IKsin(j2))))+(((IkReal(-0.102000000000000))*(cj0)*(pz)*(r00)))+(((IkReal(0.220000000000000))*(cj1)*(pz)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(px)*(py)*(r00)*(sj0)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(cj1)*(py)*(pz)*(r02)*(sj0)*(IKsin(j2))))+(((pp)*(r01)*(sj0)*(sj1)))+(((IkReal(-0.380000000000000))*(py)*(r01)*(IKsin(j2))))+(((IkReal(0.102000000000000))*(cj0)*(pz)*(r00)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(pz)*(r02)*(IKsin(j2))))+(((IkReal(0.0311962900000000))*(cj1)*(r02)))+(((IkReal(-0.102000000000000))*(cj0)*(px)*(r02)*(IKcos(j2))))+(((IkReal(-0.220000000000000))*(cj1)*(pz)))+(((IkReal(-2.00000000000000))*(px)*(py)*(r00)*(sj0)*(sj1)))+(((IkReal(-0.0311962900000000))*(cj0)*(r00)*(sj1)))+(((IkReal(-0.220000000000000))*(cj0)*(px)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r01)*(sj0)*((py)*(py))*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(pp)*(r01)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r01)*(sj0)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(cj0)*(cj1)*(pp)*(r00)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(cj0)*(cj1)*(px)*(IKsin(j2))))+(((IkReal(-1.00000000000000))*(pp)*(r02)*(sj1)*(IKsin(j2))))+(((IkReal(2.00000000000000))*(py)*(pz)*(r02)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(0.102000000000000))*(py)*(r02)*(sj0)))+(((IkReal(2.00000000000000))*(cj0)*(r00)*(sj1)*((px)*(px))*(IKcos(j2))))+(((IkReal(-1.00000000000000))*(cj1)*(pp)*(r02)))+(((IkReal(-0.0311962900000000))*(r01)*(sj0)*(sj1)))+(((IkReal(2.00000000000000))*(cj1)*(px)*(pz)*(r00)))+(((IkReal(2.00000000000000))*(cj0)*(cj1)*(px)*(py)*(r01)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(py)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(-0.0311962900000000))*(cj1)*(r02)*(IKcos(j2))))+(((IkReal(0.0311962900000000))*(r01)*(sj0)*(sj1)*(IKcos(j2))))+(((IkReal(2.00000000000000))*(cj1)*(r02)*((pz)*(pz))))+(((IkReal(-2.00000000000000))*(cj0)*(px)*(pz)*(r02)*(sj1)))+(((IkReal(2.00000000000000))*(py)*(pz)*(r01)*(sj1)*(IKsin(j2))))+(((IkReal(-0.380000000000000))*(px)*(r00)*(IKsin(j2))))+(((IkReal(-0.220000000000000))*(pz)*(sj1)*(IKsin(j2))))+(((IkReal(-2.00000000000000))*(cj1)*(px)*(pz)*(r00)*(IKcos(j2))))+(((IkReal(0.220000000000000))*(cj0)*(px)*(sj1))));
00443 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00444 {
00445 continue;
00446 }
00447 }
00448 
00449 {
00450 IkReal dummyeval[1];
00451 IkReal gconst1;
00452 gconst1=IKsign(((((IkReal(2169729.00000000))*((sj2)*(sj2)*(sj2)*(sj2))))+(((IkReal(2169729.00000000))*((cj2)*(cj2))*((sj2)*(sj2))))));
00453 dummyeval[0]=(((sj2)*(sj2)*(sj2)*(sj2))+((((cj2)*(cj2))*((sj2)*(sj2)))));
00454 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00455 {
00456 {
00457 IkReal j4array[2], cj4array[2], sj4array[2];
00458 bool j4valid[2]={false};
00459 _nj4 = 2;
00460 sj4array[0]=((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
00461 if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH )
00462 {
00463     j4valid[0] = j4valid[1] = true;
00464     j4array[0] = IKasin(sj4array[0]);
00465     cj4array[0] = IKcos(j4array[0]);
00466     sj4array[1] = sj4array[0];
00467     j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]);
00468     cj4array[1] = -cj4array[0];
00469 }
00470 else if( isnan(sj4array[0]) )
00471 {
00472     // probably any value will work
00473     j4valid[0] = true;
00474     cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0;
00475 }
00476 for(int ij4 = 0; ij4 < 2; ++ij4)
00477 {
00478 if( !j4valid[ij4] )
00479 {
00480     continue;
00481 }
00482 _ij4[0] = ij4; _ij4[1] = -1;
00483 for(int iij4 = ij4+1; iij4 < 2; ++iij4)
00484 {
00485 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
00486 {
00487     j4valid[iij4]=false; _ij4[1] = iij4; break;
00488 }
00489 }
00490 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
00491 {
00492 IkReal evalcond[1];
00493 evalcond[0]=((((IkReal(0.110000000000000))*(IKsin(j4))))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(py))));
00494 if( IKabs(evalcond[0]) > 0.000001  )
00495 {
00496 continue;
00497 }
00498 }
00499 
00500 {
00501 IkReal dummyeval[1];
00502 IkReal gconst2;
00503 gconst2=IKsign(((((cj4)*((cj2)*(cj2))))+(((cj4)*((sj2)*(sj2))))));
00504 dummyeval[0]=((((cj4)*((cj2)*(cj2))))+(((cj4)*((sj2)*(sj2)))));
00505 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00506 {
00507 {
00508 IkReal dummyeval[1];
00509 IkReal gconst3;
00510 IkReal x33=((IkReal(0.147300000000000))*(cj4));
00511 gconst3=IKsign(((((IkReal(-1.00000000000000))*(x33)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x33)*((cj2)*(cj2))))));
00512 IkReal x34=((IkReal(1.00000000000000))*(cj4));
00513 dummyeval[0]=((((IkReal(-1.00000000000000))*(x34)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x34)*((cj2)*(cj2)))));
00514 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00515 {
00516 {
00517 IkReal evalcond[5];
00518 IkReal x35=((IkReal(1.00000000000000))*(cj0));
00519 IkReal x36=((r01)*(sj0));
00520 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
00521 evalcond[1]=((IkReal(1.00000000000000))+(((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x35))));
00522 evalcond[2]=((IkReal(0.110000000000000))+(((IkReal(-1.00000000000000))*(py)*(x35)))+(((px)*(sj0))));
00523 evalcond[3]=((((cj1)*(x36)))+(((cj0)*(cj1)*(r00)))+(((r02)*(sj1))));
00524 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(sj1)*(x35)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x36))));
00525 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  )
00526 {
00527 {
00528 IkReal dummyeval[1];
00529 IkReal gconst4;
00530 gconst4=IKsign(((((IkReal(1473.00000000000))*((sj2)*(sj2))))+(((IkReal(1473.00000000000))*((cj2)*(cj2))))));
00531 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
00532 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00533 {
00534 continue;
00535 
00536 } else
00537 {
00538 {
00539 IkReal j3array[1], cj3array[1], sj3array[1];
00540 bool j3valid[1]={false};
00541 _nj3 = 1;
00542 IkReal x37=((IkReal(10000.0000000000))*(pz));
00543 IkReal x38=((sj1)*(sj2));
00544 IkReal x39=((cj1)*(cj2));
00545 IkReal x40=((cj1)*(sj2));
00546 IkReal x41=((cj2)*(sj1));
00547 IkReal x42=((IkReal(10000.0000000000))*(py)*(sj0));
00548 IkReal x43=((IkReal(10000.0000000000))*(cj0)*(px));
00549 if( IKabs(((gconst4)*(((((IkReal(-1.00000000000000))*(x37)*(x39)))+(((x41)*(x42)))+(((x41)*(x43)))+(((x37)*(x38)))+(((x40)*(x42)))+(((x40)*(x43)))+(((IkReal(-1900.00000000000))*(sj2))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst4)*(((((IkReal(-1390.00000000000))*((cj2)*(cj2))))+(((IkReal(-1900.00000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(x38)*(x42)))+(((IkReal(-1.00000000000000))*(x38)*(x43)))+(((x37)*(x40)))+(((x37)*(x41)))+(((x39)*(x42)))+(((x39)*(x43)))+(((IkReal(-1390.00000000000))*((sj2)*(sj2)))))))) < IKFAST_ATAN2_MAGTHRESH )
00550     continue;
00551 j3array[0]=IKatan2(((gconst4)*(((((IkReal(-1.00000000000000))*(x37)*(x39)))+(((x41)*(x42)))+(((x41)*(x43)))+(((x37)*(x38)))+(((x40)*(x42)))+(((x40)*(x43)))+(((IkReal(-1900.00000000000))*(sj2)))))), ((gconst4)*(((((IkReal(-1390.00000000000))*((cj2)*(cj2))))+(((IkReal(-1900.00000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(x38)*(x42)))+(((IkReal(-1.00000000000000))*(x38)*(x43)))+(((x37)*(x40)))+(((x37)*(x41)))+(((x39)*(x42)))+(((x39)*(x43)))+(((IkReal(-1390.00000000000))*((sj2)*(sj2))))))));
00552 sj3array[0]=IKsin(j3array[0]);
00553 cj3array[0]=IKcos(j3array[0]);
00554 if( j3array[0] > IKPI )
00555 {
00556     j3array[0]-=IK2PI;
00557 }
00558 else if( j3array[0] < -IKPI )
00559 {    j3array[0]+=IK2PI;
00560 }
00561 j3valid[0] = true;
00562 for(int ij3 = 0; ij3 < 1; ++ij3)
00563 {
00564 if( !j3valid[ij3] )
00565 {
00566     continue;
00567 }
00568 _ij3[0] = ij3; _ij3[1] = -1;
00569 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00570 {
00571 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00572 {
00573     j3valid[iij3]=false; _ij3[1] = iij3; break;
00574 }
00575 }
00576 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00577 {
00578 IkReal evalcond[2];
00579 IkReal x44=IKsin(j3);
00580 IkReal x45=IKcos(j3);
00581 IkReal x46=((py)*(sj0));
00582 IkReal x47=((IkReal(1.00000000000000))*(sj1));
00583 IkReal x48=((cj0)*(px));
00584 IkReal x49=((IkReal(0.147300000000000))*(x45));
00585 IkReal x50=((IkReal(0.147300000000000))*(x44));
00586 evalcond[0]=((IkReal(-0.190000000000000))+(((cj1)*(x48)))+(((cj1)*(x46)))+(((IkReal(-1.00000000000000))*(cj2)*(x49)))+(((IkReal(-1.00000000000000))*(sj2)*(x50)))+(((pz)*(sj1)))+(((IkReal(-0.139000000000000))*(cj2))));
00587 evalcond[1]=((((cj2)*(x50)))+(((cj1)*(pz)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(sj2)*(x49)))+(((IkReal(-1.00000000000000))*(x47)*(x48)))+(((IkReal(-1.00000000000000))*(x46)*(x47))));
00588 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00589 {
00590 continue;
00591 }
00592 }
00593 
00594 {
00595 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00596 vinfos[0].jointtype = 1;
00597 vinfos[0].foffset = j0;
00598 vinfos[0].indices[0] = _ij0[0];
00599 vinfos[0].indices[1] = _ij0[1];
00600 vinfos[0].maxsolutions = _nj0;
00601 vinfos[1].jointtype = 1;
00602 vinfos[1].foffset = j1;
00603 vinfos[1].indices[0] = _ij1[0];
00604 vinfos[1].indices[1] = _ij1[1];
00605 vinfos[1].maxsolutions = _nj1;
00606 vinfos[2].jointtype = 1;
00607 vinfos[2].foffset = j2;
00608 vinfos[2].indices[0] = _ij2[0];
00609 vinfos[2].indices[1] = _ij2[1];
00610 vinfos[2].maxsolutions = _nj2;
00611 vinfos[3].jointtype = 1;
00612 vinfos[3].foffset = j3;
00613 vinfos[3].indices[0] = _ij3[0];
00614 vinfos[3].indices[1] = _ij3[1];
00615 vinfos[3].maxsolutions = _nj3;
00616 vinfos[4].jointtype = 1;
00617 vinfos[4].foffset = j4;
00618 vinfos[4].indices[0] = _ij4[0];
00619 vinfos[4].indices[1] = _ij4[1];
00620 vinfos[4].maxsolutions = _nj4;
00621 std::vector<int> vfree(0);
00622 solutions.AddSolution(vinfos,vfree);
00623 }
00624 }
00625 }
00626 
00627 }
00628 
00629 }
00630 
00631 } else
00632 {
00633 IkReal x51=((IkReal(1.00000000000000))*(cj0));
00634 IkReal x52=((r01)*(sj0));
00635 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
00636 evalcond[1]=((IkReal(-1.00000000000000))+(((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x51))));
00637 evalcond[2]=((IkReal(-0.110000000000000))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x51))));
00638 evalcond[3]=((((cj1)*(x52)))+(((cj0)*(cj1)*(r00)))+(((r02)*(sj1))));
00639 evalcond[4]=((((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x52)))+(((IkReal(-1.00000000000000))*(r00)*(sj1)*(x51))));
00640 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  )
00641 {
00642 {
00643 IkReal dummyeval[1];
00644 IkReal gconst5;
00645 gconst5=IKsign(((((IkReal(1473.00000000000))*((sj2)*(sj2))))+(((IkReal(1473.00000000000))*((cj2)*(cj2))))));
00646 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
00647 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
00648 {
00649 continue;
00650 
00651 } else
00652 {
00653 {
00654 IkReal j3array[1], cj3array[1], sj3array[1];
00655 bool j3valid[1]={false};
00656 _nj3 = 1;
00657 IkReal x53=((IkReal(10000.0000000000))*(pz));
00658 IkReal x54=((sj1)*(sj2));
00659 IkReal x55=((cj1)*(cj2));
00660 IkReal x56=((cj1)*(sj2));
00661 IkReal x57=((cj2)*(sj1));
00662 IkReal x58=((IkReal(10000.0000000000))*(py)*(sj0));
00663 IkReal x59=((IkReal(10000.0000000000))*(cj0)*(px));
00664 if( IKabs(((gconst5)*(((((IkReal(-1.00000000000000))*(x53)*(x55)))+(((x57)*(x58)))+(((x57)*(x59)))+(((x53)*(x54)))+(((x56)*(x58)))+(((x56)*(x59)))+(((IkReal(-1900.00000000000))*(sj2))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst5)*(((((IkReal(-1390.00000000000))*((cj2)*(cj2))))+(((IkReal(-1900.00000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(x54)*(x59)))+(((IkReal(-1.00000000000000))*(x54)*(x58)))+(((IkReal(-1390.00000000000))*((sj2)*(sj2))))+(((x53)*(x56)))+(((x53)*(x57)))+(((x55)*(x58)))+(((x55)*(x59))))))) < IKFAST_ATAN2_MAGTHRESH )
00665     continue;
00666 j3array[0]=IKatan2(((gconst5)*(((((IkReal(-1.00000000000000))*(x53)*(x55)))+(((x57)*(x58)))+(((x57)*(x59)))+(((x53)*(x54)))+(((x56)*(x58)))+(((x56)*(x59)))+(((IkReal(-1900.00000000000))*(sj2)))))), ((gconst5)*(((((IkReal(-1390.00000000000))*((cj2)*(cj2))))+(((IkReal(-1900.00000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(x54)*(x59)))+(((IkReal(-1.00000000000000))*(x54)*(x58)))+(((IkReal(-1390.00000000000))*((sj2)*(sj2))))+(((x53)*(x56)))+(((x53)*(x57)))+(((x55)*(x58)))+(((x55)*(x59)))))));
00667 sj3array[0]=IKsin(j3array[0]);
00668 cj3array[0]=IKcos(j3array[0]);
00669 if( j3array[0] > IKPI )
00670 {
00671     j3array[0]-=IK2PI;
00672 }
00673 else if( j3array[0] < -IKPI )
00674 {    j3array[0]+=IK2PI;
00675 }
00676 j3valid[0] = true;
00677 for(int ij3 = 0; ij3 < 1; ++ij3)
00678 {
00679 if( !j3valid[ij3] )
00680 {
00681     continue;
00682 }
00683 _ij3[0] = ij3; _ij3[1] = -1;
00684 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00685 {
00686 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00687 {
00688     j3valid[iij3]=false; _ij3[1] = iij3; break;
00689 }
00690 }
00691 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00692 {
00693 IkReal evalcond[2];
00694 IkReal x60=IKsin(j3);
00695 IkReal x61=IKcos(j3);
00696 IkReal x62=((py)*(sj0));
00697 IkReal x63=((IkReal(1.00000000000000))*(sj1));
00698 IkReal x64=((cj0)*(px));
00699 IkReal x65=((IkReal(0.147300000000000))*(x61));
00700 IkReal x66=((IkReal(0.147300000000000))*(x60));
00701 evalcond[0]=((IkReal(-0.190000000000000))+(((cj1)*(x62)))+(((cj1)*(x64)))+(((IkReal(-1.00000000000000))*(sj2)*(x66)))+(((pz)*(sj1)))+(((IkReal(-1.00000000000000))*(cj2)*(x65)))+(((IkReal(-0.139000000000000))*(cj2))));
00702 evalcond[1]=((((cj1)*(pz)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(sj2)*(x65)))+(((IkReal(-1.00000000000000))*(x63)*(x64)))+(((cj2)*(x66)))+(((IkReal(-1.00000000000000))*(x62)*(x63))));
00703 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  )
00704 {
00705 continue;
00706 }
00707 }
00708 
00709 {
00710 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00711 vinfos[0].jointtype = 1;
00712 vinfos[0].foffset = j0;
00713 vinfos[0].indices[0] = _ij0[0];
00714 vinfos[0].indices[1] = _ij0[1];
00715 vinfos[0].maxsolutions = _nj0;
00716 vinfos[1].jointtype = 1;
00717 vinfos[1].foffset = j1;
00718 vinfos[1].indices[0] = _ij1[0];
00719 vinfos[1].indices[1] = _ij1[1];
00720 vinfos[1].maxsolutions = _nj1;
00721 vinfos[2].jointtype = 1;
00722 vinfos[2].foffset = j2;
00723 vinfos[2].indices[0] = _ij2[0];
00724 vinfos[2].indices[1] = _ij2[1];
00725 vinfos[2].maxsolutions = _nj2;
00726 vinfos[3].jointtype = 1;
00727 vinfos[3].foffset = j3;
00728 vinfos[3].indices[0] = _ij3[0];
00729 vinfos[3].indices[1] = _ij3[1];
00730 vinfos[3].maxsolutions = _nj3;
00731 vinfos[4].jointtype = 1;
00732 vinfos[4].foffset = j4;
00733 vinfos[4].indices[0] = _ij4[0];
00734 vinfos[4].indices[1] = _ij4[1];
00735 vinfos[4].maxsolutions = _nj4;
00736 std::vector<int> vfree(0);
00737 solutions.AddSolution(vinfos,vfree);
00738 }
00739 }
00740 }
00741 
00742 }
00743 
00744 }
00745 
00746 } else
00747 {
00748 if( 1 )
00749 {
00750 continue;
00751 
00752 } else
00753 {
00754 }
00755 }
00756 }
00757 }
00758 
00759 } else
00760 {
00761 {
00762 IkReal j3array[1], cj3array[1], sj3array[1];
00763 bool j3valid[1]={false};
00764 _nj3 = 1;
00765 IkReal x67=((cj1)*(cj4));
00766 IkReal x68=((IkReal(0.110000000000000))*(sj2));
00767 IkReal x69=((cj0)*(r00));
00768 IkReal x70=((cj2)*(sj0));
00769 IkReal x71=((IkReal(1.00000000000000))*(py));
00770 IkReal x72=((cj2)*(cj4));
00771 IkReal x73=((r02)*(sj1));
00772 IkReal x74=((IkReal(0.147300000000000))*(cj1));
00773 IkReal x75=((cj4)*(sj2));
00774 IkReal x76=((sj0)*(sj2));
00775 IkReal x77=((IkReal(1.00000000000000))*(pz)*(sj1));
00776 IkReal x78=((IkReal(1.00000000000000))*(cj0)*(px));
00777 if( IKabs(((gconst3)*(((((IkReal(-1.00000000000000))*(sj2)*(x67)*(x78)))+(((r01)*(sj0)*(x67)*(x68)))+(((IkReal(-0.147300000000000))*(cj2)*(x73)))+(((IkReal(-1.00000000000000))*(r01)*(x70)*(x74)))+(((cj4)*(x68)*(x73)))+(((IkReal(0.139000000000000))*(sj2)*(x72)))+(((IkReal(-1.00000000000000))*(x67)*(x71)*(x76)))+(((IkReal(0.190000000000000))*(x75)))+(((IkReal(-1.00000000000000))*(cj2)*(x69)*(x74)))+(((x67)*(x68)*(x69)))+(((IkReal(-1.00000000000000))*(x75)*(x77))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst3)*(((((sj2)*(x69)*(x74)))+(((IkReal(0.110000000000000))*(x72)*(x73)))+(((r01)*(x74)*(x76)))+(((IkReal(0.110000000000000))*(r01)*(x67)*(x70)))+(((IkReal(0.139000000000000))*(cj2)*(x72)))+(((IkReal(-1.00000000000000))*(x67)*(x70)*(x71)))+(((IkReal(0.110000000000000))*(cj2)*(x67)*(x69)))+(((IkReal(-1.00000000000000))*(cj2)*(x67)*(x78)))+(((IkReal(0.147300000000000))*(sj2)*(x73)))+(((IkReal(-1.00000000000000))*(x72)*(x77)))+(((IkReal(0.190000000000000))*(x72))))))) < IKFAST_ATAN2_MAGTHRESH )
00778     continue;
00779 j3array[0]=IKatan2(((gconst3)*(((((IkReal(-1.00000000000000))*(sj2)*(x67)*(x78)))+(((r01)*(sj0)*(x67)*(x68)))+(((IkReal(-0.147300000000000))*(cj2)*(x73)))+(((IkReal(-1.00000000000000))*(r01)*(x70)*(x74)))+(((cj4)*(x68)*(x73)))+(((IkReal(0.139000000000000))*(sj2)*(x72)))+(((IkReal(-1.00000000000000))*(x67)*(x71)*(x76)))+(((IkReal(0.190000000000000))*(x75)))+(((IkReal(-1.00000000000000))*(cj2)*(x69)*(x74)))+(((x67)*(x68)*(x69)))+(((IkReal(-1.00000000000000))*(x75)*(x77)))))), ((gconst3)*(((((sj2)*(x69)*(x74)))+(((IkReal(0.110000000000000))*(x72)*(x73)))+(((r01)*(x74)*(x76)))+(((IkReal(0.110000000000000))*(r01)*(x67)*(x70)))+(((IkReal(0.139000000000000))*(cj2)*(x72)))+(((IkReal(-1.00000000000000))*(x67)*(x70)*(x71)))+(((IkReal(0.110000000000000))*(cj2)*(x67)*(x69)))+(((IkReal(-1.00000000000000))*(cj2)*(x67)*(x78)))+(((IkReal(0.147300000000000))*(sj2)*(x73)))+(((IkReal(-1.00000000000000))*(x72)*(x77)))+(((IkReal(0.190000000000000))*(x72)))))));
00780 sj3array[0]=IKsin(j3array[0]);
00781 cj3array[0]=IKcos(j3array[0]);
00782 if( j3array[0] > IKPI )
00783 {
00784     j3array[0]-=IK2PI;
00785 }
00786 else if( j3array[0] < -IKPI )
00787 {    j3array[0]+=IK2PI;
00788 }
00789 j3valid[0] = true;
00790 for(int ij3 = 0; ij3 < 1; ++ij3)
00791 {
00792 if( !j3valid[ij3] )
00793 {
00794     continue;
00795 }
00796 _ij3[0] = ij3; _ij3[1] = -1;
00797 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00798 {
00799 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00800 {
00801     j3valid[iij3]=false; _ij3[1] = iij3; break;
00802 }
00803 }
00804 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00805 {
00806 IkReal evalcond[4];
00807 IkReal x79=IKcos(j3);
00808 IkReal x80=IKsin(j3);
00809 IkReal x81=((IkReal(0.147300000000000))*(sj2));
00810 IkReal x82=((r01)*(sj0));
00811 IkReal x83=((IkReal(1.00000000000000))*(sj1));
00812 IkReal x84=((cj0)*(cj1));
00813 IkReal x85=((IkReal(0.110000000000000))*(cj4));
00814 IkReal x86=((py)*(sj0));
00815 IkReal x87=((IkReal(1.00000000000000))*(cj4));
00816 IkReal x88=((cj2)*(x79));
00817 IkReal x89=((cj2)*(x80));
00818 IkReal x90=((sj2)*(x79));
00819 IkReal x91=((x80)*(x85));
00820 evalcond[0]=((((r00)*(x84)))+(((r02)*(sj1)))+(((IkReal(-1.00000000000000))*(x87)*(x89)))+(((cj4)*(x90)))+(((cj1)*(x82))));
00821 evalcond[1]=((((IkReal(-1.00000000000000))*(x82)*(x83)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(sj2)*(x80)*(x87)))+(((IkReal(-1.00000000000000))*(x87)*(x88)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x83))));
00822 evalcond[2]=((IkReal(-0.190000000000000))+(((IkReal(-1.00000000000000))*(x80)*(x81)))+(((x85)*(x90)))+(((px)*(x84)))+(((IkReal(-0.147300000000000))*(x88)))+(((pz)*(sj1)))+(((cj1)*(x86)))+(((IkReal(-1.00000000000000))*(x85)*(x89)))+(((IkReal(-0.139000000000000))*(cj2))));
00823 evalcond[3]=((((IkReal(-1.00000000000000))*(sj2)*(x91)))+(((IkReal(-1.00000000000000))*(cj0)*(px)*(x83)))+(((IkReal(-1.00000000000000))*(x83)*(x86)))+(((cj1)*(pz)))+(((IkReal(-1.00000000000000))*(x79)*(x81)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x85)*(x88)))+(((IkReal(0.147300000000000))*(x89))));
00824 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00825 {
00826 continue;
00827 }
00828 }
00829 
00830 {
00831 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00832 vinfos[0].jointtype = 1;
00833 vinfos[0].foffset = j0;
00834 vinfos[0].indices[0] = _ij0[0];
00835 vinfos[0].indices[1] = _ij0[1];
00836 vinfos[0].maxsolutions = _nj0;
00837 vinfos[1].jointtype = 1;
00838 vinfos[1].foffset = j1;
00839 vinfos[1].indices[0] = _ij1[0];
00840 vinfos[1].indices[1] = _ij1[1];
00841 vinfos[1].maxsolutions = _nj1;
00842 vinfos[2].jointtype = 1;
00843 vinfos[2].foffset = j2;
00844 vinfos[2].indices[0] = _ij2[0];
00845 vinfos[2].indices[1] = _ij2[1];
00846 vinfos[2].maxsolutions = _nj2;
00847 vinfos[3].jointtype = 1;
00848 vinfos[3].foffset = j3;
00849 vinfos[3].indices[0] = _ij3[0];
00850 vinfos[3].indices[1] = _ij3[1];
00851 vinfos[3].maxsolutions = _nj3;
00852 vinfos[4].jointtype = 1;
00853 vinfos[4].foffset = j4;
00854 vinfos[4].indices[0] = _ij4[0];
00855 vinfos[4].indices[1] = _ij4[1];
00856 vinfos[4].maxsolutions = _nj4;
00857 std::vector<int> vfree(0);
00858 solutions.AddSolution(vinfos,vfree);
00859 }
00860 }
00861 }
00862 
00863 }
00864 
00865 }
00866 
00867 } else
00868 {
00869 {
00870 IkReal j3array[1], cj3array[1], sj3array[1];
00871 bool j3valid[1]={false};
00872 _nj3 = 1;
00873 IkReal x92=((IkReal(1.00000000000000))*(sj1));
00874 IkReal x93=((r02)*(sj2));
00875 IkReal x94=((r01)*(sj0));
00876 IkReal x95=((IkReal(1.00000000000000))*(sj2));
00877 IkReal x96=((cj0)*(r00));
00878 IkReal x97=((cj2)*(r02));
00879 IkReal x98=((cj1)*(x96));
00880 if( IKabs(((gconst2)*(((((cj2)*(x98)))+(((sj1)*(x97)))+(((IkReal(-1.00000000000000))*(sj2)*(x92)*(x94)))+(((IkReal(-1.00000000000000))*(sj2)*(x92)*(x96)))+(((cj1)*(x93)))+(((cj1)*(cj2)*(x94))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst2)*(((((IkReal(-1.00000000000000))*(x95)*(x98)))+(((IkReal(-1.00000000000000))*(cj2)*(x92)*(x96)))+(((IkReal(-1.00000000000000))*(cj2)*(x92)*(x94)))+(((IkReal(-1.00000000000000))*(cj1)*(x94)*(x95)))+(((IkReal(-1.00000000000000))*(x92)*(x93)))+(((cj1)*(x97))))))) < IKFAST_ATAN2_MAGTHRESH )
00881     continue;
00882 j3array[0]=IKatan2(((gconst2)*(((((cj2)*(x98)))+(((sj1)*(x97)))+(((IkReal(-1.00000000000000))*(sj2)*(x92)*(x94)))+(((IkReal(-1.00000000000000))*(sj2)*(x92)*(x96)))+(((cj1)*(x93)))+(((cj1)*(cj2)*(x94)))))), ((gconst2)*(((((IkReal(-1.00000000000000))*(x95)*(x98)))+(((IkReal(-1.00000000000000))*(cj2)*(x92)*(x96)))+(((IkReal(-1.00000000000000))*(cj2)*(x92)*(x94)))+(((IkReal(-1.00000000000000))*(cj1)*(x94)*(x95)))+(((IkReal(-1.00000000000000))*(x92)*(x93)))+(((cj1)*(x97)))))));
00883 sj3array[0]=IKsin(j3array[0]);
00884 cj3array[0]=IKcos(j3array[0]);
00885 if( j3array[0] > IKPI )
00886 {
00887     j3array[0]-=IK2PI;
00888 }
00889 else if( j3array[0] < -IKPI )
00890 {    j3array[0]+=IK2PI;
00891 }
00892 j3valid[0] = true;
00893 for(int ij3 = 0; ij3 < 1; ++ij3)
00894 {
00895 if( !j3valid[ij3] )
00896 {
00897     continue;
00898 }
00899 _ij3[0] = ij3; _ij3[1] = -1;
00900 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
00901 {
00902 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
00903 {
00904     j3valid[iij3]=false; _ij3[1] = iij3; break;
00905 }
00906 }
00907 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
00908 {
00909 IkReal evalcond[4];
00910 IkReal x99=IKcos(j3);
00911 IkReal x100=IKsin(j3);
00912 IkReal x101=((IkReal(0.147300000000000))*(sj2));
00913 IkReal x102=((r01)*(sj0));
00914 IkReal x103=((IkReal(1.00000000000000))*(sj1));
00915 IkReal x104=((cj0)*(cj1));
00916 IkReal x105=((IkReal(0.110000000000000))*(cj4));
00917 IkReal x106=((py)*(sj0));
00918 IkReal x107=((IkReal(1.00000000000000))*(cj4));
00919 IkReal x108=((cj2)*(x99));
00920 IkReal x109=((cj2)*(x100));
00921 IkReal x110=((sj2)*(x99));
00922 IkReal x111=((x100)*(x105));
00923 evalcond[0]=((((cj1)*(x102)))+(((IkReal(-1.00000000000000))*(x107)*(x109)))+(((r02)*(sj1)))+(((r00)*(x104)))+(((cj4)*(x110))));
00924 evalcond[1]=((((IkReal(-1.00000000000000))*(x107)*(x108)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x103)))+(((IkReal(-1.00000000000000))*(x102)*(x103)))+(((IkReal(-1.00000000000000))*(sj2)*(x100)*(x107))));
00925 evalcond[2]=((IkReal(-0.190000000000000))+(((cj1)*(x106)))+(((IkReal(-1.00000000000000))*(x100)*(x101)))+(((px)*(x104)))+(((IkReal(-0.147300000000000))*(x108)))+(((pz)*(sj1)))+(((x105)*(x110)))+(((IkReal(-1.00000000000000))*(x105)*(x109)))+(((IkReal(-0.139000000000000))*(cj2))));
00926 evalcond[3]=((((IkReal(-1.00000000000000))*(cj0)*(px)*(x103)))+(((IkReal(0.147300000000000))*(x109)))+(((cj1)*(pz)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x101)*(x99)))+(((IkReal(-1.00000000000000))*(x103)*(x106)))+(((IkReal(-1.00000000000000))*(x105)*(x108)))+(((IkReal(-1.00000000000000))*(sj2)*(x111))));
00927 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
00928 {
00929 continue;
00930 }
00931 }
00932 
00933 {
00934 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
00935 vinfos[0].jointtype = 1;
00936 vinfos[0].foffset = j0;
00937 vinfos[0].indices[0] = _ij0[0];
00938 vinfos[0].indices[1] = _ij0[1];
00939 vinfos[0].maxsolutions = _nj0;
00940 vinfos[1].jointtype = 1;
00941 vinfos[1].foffset = j1;
00942 vinfos[1].indices[0] = _ij1[0];
00943 vinfos[1].indices[1] = _ij1[1];
00944 vinfos[1].maxsolutions = _nj1;
00945 vinfos[2].jointtype = 1;
00946 vinfos[2].foffset = j2;
00947 vinfos[2].indices[0] = _ij2[0];
00948 vinfos[2].indices[1] = _ij2[1];
00949 vinfos[2].maxsolutions = _nj2;
00950 vinfos[3].jointtype = 1;
00951 vinfos[3].foffset = j3;
00952 vinfos[3].indices[0] = _ij3[0];
00953 vinfos[3].indices[1] = _ij3[1];
00954 vinfos[3].maxsolutions = _nj3;
00955 vinfos[4].jointtype = 1;
00956 vinfos[4].foffset = j4;
00957 vinfos[4].indices[0] = _ij4[0];
00958 vinfos[4].indices[1] = _ij4[1];
00959 vinfos[4].maxsolutions = _nj4;
00960 std::vector<int> vfree(0);
00961 solutions.AddSolution(vinfos,vfree);
00962 }
00963 }
00964 }
00965 
00966 }
00967 
00968 }
00969 }
00970 }
00971 
00972 } else
00973 {
00974 {
00975 IkReal j3array[1], cj3array[1], sj3array[1];
00976 bool j3valid[1]={false};
00977 _nj3 = 1;
00978 IkReal x112=(sj2)*(sj2);
00979 IkReal x113=((IkReal(1.00000000000000))*(sj2));
00980 IkReal x114=((cj0)*(px));
00981 IkReal x115=((py)*(sj0));
00982 IkReal x116=((cj2)*(sj2));
00983 IkReal x117=((cj1)*(sj2));
00984 IkReal x118=((IkReal(0.110000000000000))*(r02));
00985 IkReal x119=((sj1)*(sj2));
00986 IkReal x120=((IkReal(14730000.0000000))*(x112));
00987 IkReal x121=((IkReal(0.110000000000000))*(cj0)*(r00));
00988 IkReal x122=((IkReal(0.110000000000000))*(r01)*(sj0));
00989 IkReal x123=((((IkReal(-1.00000000000000))*(x117)*(x118)))+(((pz)*(x117)))+(((IkReal(-0.139000000000000))*(x112)))+(((IkReal(-1.00000000000000))*(sj1)*(x113)*(x115)))+(((IkReal(-1.00000000000000))*(sj1)*(x113)*(x114)))+(((x119)*(x121)))+(((x119)*(x122))));
00990 IkReal x124=((IkReal(14730000.0000000))*(x123));
00991 IkReal x125=((((x117)*(x122)))+(((x117)*(x121)))+(((IkReal(0.139000000000000))*(x116)))+(((IkReal(-1.00000000000000))*(pz)*(sj1)*(x113)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x115)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x114)))+(((IkReal(0.190000000000000))*(sj2)))+(((x118)*(x119))));
00992 if( IKabs(((gconst1)*(((((IkReal(-1.00000000000000))*(x120)*(x125)))+(((IkReal(-1.00000000000000))*(x116)*(x124))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((gconst1)*(((((x120)*(x123)))+(((IkReal(-14730000.0000000))*(x116)*(((((x117)*(x122)))+(((x117)*(x121)))+(((IkReal(-1.00000000000000))*(pz)*(sj1)*(x113)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x115)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x114)))+(((IkReal(0.190000000000000))*(sj2)))+(((IkReal(0.139000000000000))*(cj2)*(sj2)))+(((x118)*(x119))))))))))) < IKFAST_ATAN2_MAGTHRESH )
00993     continue;
00994 j3array[0]=IKatan2(((gconst1)*(((((IkReal(-1.00000000000000))*(x120)*(x125)))+(((IkReal(-1.00000000000000))*(x116)*(x124)))))), ((gconst1)*(((((x120)*(x123)))+(((IkReal(-14730000.0000000))*(x116)*(((((x117)*(x122)))+(((x117)*(x121)))+(((IkReal(-1.00000000000000))*(pz)*(sj1)*(x113)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x115)))+(((IkReal(-1.00000000000000))*(cj1)*(x113)*(x114)))+(((IkReal(0.190000000000000))*(sj2)))+(((IkReal(0.139000000000000))*(cj2)*(sj2)))+(((x118)*(x119)))))))))));
00995 sj3array[0]=IKsin(j3array[0]);
00996 cj3array[0]=IKcos(j3array[0]);
00997 if( j3array[0] > IKPI )
00998 {
00999     j3array[0]-=IK2PI;
01000 }
01001 else if( j3array[0] < -IKPI )
01002 {    j3array[0]+=IK2PI;
01003 }
01004 j3valid[0] = true;
01005 for(int ij3 = 0; ij3 < 1; ++ij3)
01006 {
01007 if( !j3valid[ij3] )
01008 {
01009     continue;
01010 }
01011 _ij3[0] = ij3; _ij3[1] = -1;
01012 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
01013 {
01014 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
01015 {
01016     j3valid[iij3]=false; _ij3[1] = iij3; break;
01017 }
01018 }
01019 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
01020 {
01021 IkReal evalcond[4];
01022 IkReal x126=(sj2)*(sj2);
01023 IkReal x127=IKsin(j3);
01024 IkReal x128=IKcos(j3);
01025 IkReal x129=(cj2)*(cj2);
01026 IkReal x130=((cj1)*(cj2));
01027 IkReal x131=((IkReal(0.110000000000000))*(r02));
01028 IkReal x132=((py)*(sj0));
01029 IkReal x133=((cj1)*(sj2));
01030 IkReal x134=((sj1)*(sj2));
01031 IkReal x135=((cj2)*(sj2));
01032 IkReal x136=((cj2)*(sj1));
01033 IkReal x137=((IkReal(0.139000000000000))*(x135));
01034 IkReal x138=((IkReal(0.147300000000000))*(x128));
01035 IkReal x139=((IkReal(0.110000000000000))*(cj0)*(r00));
01036 IkReal x140=((IkReal(0.110000000000000))*(r01)*(sj0));
01037 IkReal x141=((IkReal(1.00000000000000))*(cj0)*(px));
01038 IkReal x142=((IkReal(0.147300000000000))*(x127));
01039 IkReal x143=((x135)*(x142));
01040 IkReal x144=((x135)*(x138));
01041 IkReal x145=((x144)+(x137));
01042 evalcond[0]=((((IkReal(-0.139000000000000))*(x126)))+(((IkReal(-1.00000000000000))*(x134)*(x141)))+(((pz)*(x133)))+(((IkReal(-1.00000000000000))*(x126)*(x138)))+(x143)+(((x134)*(x139)))+(((IkReal(-1.00000000000000))*(x132)*(x134)))+(((x134)*(x140)))+(((IkReal(-1.00000000000000))*(x131)*(x133))));
01043 evalcond[1]=((((IkReal(-1.00000000000000))*(x145)))+(((x136)*(x140)))+(((pz)*(x130)))+(((x136)*(x139)))+(((x129)*(x142)))+(((IkReal(-1.00000000000000))*(x132)*(x136)))+(((IkReal(-1.00000000000000))*(x130)*(x131)))+(((IkReal(-1.00000000000000))*(x136)*(x141))));
01044 evalcond[2]=((((IkReal(-1.00000000000000))*(x143)))+(((IkReal(-0.139000000000000))*(x129)))+(((IkReal(-0.190000000000000))*(cj2)))+(((pz)*(x136)))+(((x130)*(x132)))+(((IkReal(-1.00000000000000))*(x129)*(x138)))+(((cj0)*(px)*(x130)))+(((IkReal(-1.00000000000000))*(x131)*(x136)))+(((IkReal(-1.00000000000000))*(x130)*(x139)))+(((IkReal(-1.00000000000000))*(x130)*(x140))));
01045 evalcond[3]=((((x126)*(x142)))+(((IkReal(0.190000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(x133)*(x141)))+(x145)+(((x131)*(x134)))+(((IkReal(-1.00000000000000))*(pz)*(x134)))+(((IkReal(-1.00000000000000))*(x132)*(x133)))+(((x133)*(x139)))+(((x133)*(x140))));
01046 if( IKabs(evalcond[0]) > 0.000001  || IKabs(evalcond[1]) > 0.000001  || IKabs(evalcond[2]) > 0.000001  || IKabs(evalcond[3]) > 0.000001  )
01047 {
01048 continue;
01049 }
01050 }
01051 
01052 {
01053 IkReal dummyeval[1];
01054 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))));
01055 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01056 {
01057 {
01058 IkReal dummyeval[1];
01059 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2))));
01060 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01061 {
01062 {
01063 IkReal dummyeval[1];
01064 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))));
01065 if( IKabs(dummyeval[0]) < 0.0000010000000000  )
01066 {
01067 continue;
01068 
01069 } else
01070 {
01071 {
01072 IkReal j4array[1], cj4array[1], sj4array[1];
01073 bool j4valid[1]={false};
01074 _nj4 = 1;
01075 if( IKabs(((((IkReal(-9.09090909090909))*(px)*(sj0)))+(((IkReal(9.09090909090909))*(cj0)*(py))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-9.09090909090909))*(px)*(sj0)))+(((IkReal(9.09090909090909))*(cj0)*(py)))))+IKsqr(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02)))))))-1) <= IKFAST_SINCOS_THRESH )
01076     continue;
01077 j4array[0]=IKatan2(((((IkReal(-9.09090909090909))*(px)*(sj0)))+(((IkReal(9.09090909090909))*(cj0)*(py)))), ((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02)))))));
01078 sj4array[0]=IKsin(j4array[0]);
01079 cj4array[0]=IKcos(j4array[0]);
01080 if( j4array[0] > IKPI )
01081 {
01082     j4array[0]-=IK2PI;
01083 }
01084 else if( j4array[0] < -IKPI )
01085 {    j4array[0]+=IK2PI;
01086 }
01087 j4valid[0] = true;
01088 for(int ij4 = 0; ij4 < 1; ++ij4)
01089 {
01090 if( !j4valid[ij4] )
01091 {
01092     continue;
01093 }
01094 _ij4[0] = ij4; _ij4[1] = -1;
01095 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01096 {
01097 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01098 {
01099     j4valid[iij4]=false; _ij4[1] = iij4; break;
01100 }
01101 }
01102 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01103 {
01104 IkReal evalcond[6];
01105 IkReal x146=IKsin(j4);
01106 IkReal x147=IKcos(j4);
01107 IkReal x148=((cj2)*(sj3));
01108 IkReal x149=((IkReal(0.147300000000000))*(cj3));
01109 IkReal x150=((IkReal(1.00000000000000))*(r01));
01110 IkReal x151=((sj0)*(sj1));
01111 IkReal x152=((IkReal(1.00000000000000))*(py));
01112 IkReal x153=((cj0)*(r00));
01113 IkReal x154=((sj2)*(sj3));
01114 IkReal x155=((cj2)*(cj3));
01115 IkReal x156=((cj1)*(sj0));
01116 IkReal x157=((IkReal(1.00000000000000))*(sj1));
01117 IkReal x158=((cj0)*(px));
01118 IkReal x159=((cj3)*(sj2));
01119 IkReal x160=((IkReal(0.110000000000000))*(x147));
01120 IkReal x161=((IkReal(1.00000000000000))*(x147));
01121 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x150)))+(x146));
01122 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x152)))+(((IkReal(0.110000000000000))*(x146)))+(((px)*(sj0))));
01123 evalcond[2]=((((r01)*(x156)))+(((r02)*(sj1)))+(((IkReal(-1.00000000000000))*(x148)*(x161)))+(((x147)*(x159)))+(((cj1)*(x153))));
01124 evalcond[3]=((((IkReal(-1.00000000000000))*(x154)*(x161)))+(((IkReal(-1.00000000000000))*(x153)*(x157)))+(((IkReal(-1.00000000000000))*(x150)*(x151)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x155)*(x161))));
01125 evalcond[4]=((IkReal(-0.190000000000000))+(((IkReal(-0.147300000000000))*(x154)))+(((IkReal(-1.00000000000000))*(cj2)*(x149)))+(((IkReal(-1.00000000000000))*(x148)*(x160)))+(((pz)*(sj1)))+(((cj1)*(x158)))+(((x159)*(x160)))+(((IkReal(-0.139000000000000))*(cj2)))+(((py)*(x156))));
01126 evalcond[5]=((((IkReal(-1.00000000000000))*(x154)*(x160)))+(((IkReal(-1.00000000000000))*(x157)*(x158)))+(((IkReal(-1.00000000000000))*(x151)*(x152)))+(((cj1)*(pz)))+(((IkReal(0.147300000000000))*(x148)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(sj2)*(x149)))+(((IkReal(-1.00000000000000))*(x155)*(x160))));
01127 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  )
01128 {
01129 continue;
01130 }
01131 }
01132 
01133 {
01134 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01135 vinfos[0].jointtype = 1;
01136 vinfos[0].foffset = j0;
01137 vinfos[0].indices[0] = _ij0[0];
01138 vinfos[0].indices[1] = _ij0[1];
01139 vinfos[0].maxsolutions = _nj0;
01140 vinfos[1].jointtype = 1;
01141 vinfos[1].foffset = j1;
01142 vinfos[1].indices[0] = _ij1[0];
01143 vinfos[1].indices[1] = _ij1[1];
01144 vinfos[1].maxsolutions = _nj1;
01145 vinfos[2].jointtype = 1;
01146 vinfos[2].foffset = j2;
01147 vinfos[2].indices[0] = _ij2[0];
01148 vinfos[2].indices[1] = _ij2[1];
01149 vinfos[2].maxsolutions = _nj2;
01150 vinfos[3].jointtype = 1;
01151 vinfos[3].foffset = j3;
01152 vinfos[3].indices[0] = _ij3[0];
01153 vinfos[3].indices[1] = _ij3[1];
01154 vinfos[3].maxsolutions = _nj3;
01155 vinfos[4].jointtype = 1;
01156 vinfos[4].foffset = j4;
01157 vinfos[4].indices[0] = _ij4[0];
01158 vinfos[4].indices[1] = _ij4[1];
01159 vinfos[4].maxsolutions = _nj4;
01160 std::vector<int> vfree(0);
01161 solutions.AddSolution(vinfos,vfree);
01162 }
01163 }
01164 }
01165 
01166 }
01167 
01168 }
01169 
01170 } else
01171 {
01172 {
01173 IkReal j4array[1], cj4array[1], sj4array[1];
01174 bool j4valid[1]={false};
01175 _nj4 = 1;
01176 IkReal x162=((IkReal(1.00000000000000))*(cj1));
01177 if( IKabs(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x162)))+(((IkReal(-1.00000000000000))*(r02)*(sj1)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x162))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01)))))+IKsqr(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x162)))+(((IkReal(-1.00000000000000))*(r02)*(sj1)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x162)))))))-1) <= IKFAST_SINCOS_THRESH )
01178     continue;
01179 j4array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01)))), ((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2)))))):(IkReal)1.0e30))*(((((IkReal(-1.00000000000000))*(r01)*(sj0)*(x162)))+(((IkReal(-1.00000000000000))*(r02)*(sj1)))+(((IkReal(-1.00000000000000))*(cj0)*(r00)*(x162)))))));
01180 sj4array[0]=IKsin(j4array[0]);
01181 cj4array[0]=IKcos(j4array[0]);
01182 if( j4array[0] > IKPI )
01183 {
01184     j4array[0]-=IK2PI;
01185 }
01186 else if( j4array[0] < -IKPI )
01187 {    j4array[0]+=IK2PI;
01188 }
01189 j4valid[0] = true;
01190 for(int ij4 = 0; ij4 < 1; ++ij4)
01191 {
01192 if( !j4valid[ij4] )
01193 {
01194     continue;
01195 }
01196 _ij4[0] = ij4; _ij4[1] = -1;
01197 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01198 {
01199 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01200 {
01201     j4valid[iij4]=false; _ij4[1] = iij4; break;
01202 }
01203 }
01204 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01205 {
01206 IkReal evalcond[6];
01207 IkReal x163=IKsin(j4);
01208 IkReal x164=IKcos(j4);
01209 IkReal x165=((cj2)*(sj3));
01210 IkReal x166=((IkReal(0.147300000000000))*(cj3));
01211 IkReal x167=((IkReal(1.00000000000000))*(r01));
01212 IkReal x168=((sj0)*(sj1));
01213 IkReal x169=((IkReal(1.00000000000000))*(py));
01214 IkReal x170=((cj0)*(r00));
01215 IkReal x171=((sj2)*(sj3));
01216 IkReal x172=((cj2)*(cj3));
01217 IkReal x173=((cj1)*(sj0));
01218 IkReal x174=((IkReal(1.00000000000000))*(sj1));
01219 IkReal x175=((cj0)*(px));
01220 IkReal x176=((cj3)*(sj2));
01221 IkReal x177=((IkReal(0.110000000000000))*(x164));
01222 IkReal x178=((IkReal(1.00000000000000))*(x164));
01223 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x167)))+(x163));
01224 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x169)))+(((IkReal(0.110000000000000))*(x163)))+(((px)*(sj0))));
01225 evalcond[2]=((((r01)*(x173)))+(((r02)*(sj1)))+(((x164)*(x176)))+(((cj1)*(x170)))+(((IkReal(-1.00000000000000))*(x165)*(x178))));
01226 evalcond[3]=((((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x170)*(x174)))+(((IkReal(-1.00000000000000))*(x171)*(x178)))+(((IkReal(-1.00000000000000))*(x172)*(x178)))+(((IkReal(-1.00000000000000))*(x167)*(x168))));
01227 evalcond[4]=((IkReal(-0.190000000000000))+(((py)*(x173)))+(((x176)*(x177)))+(((IkReal(-0.147300000000000))*(x171)))+(((IkReal(-1.00000000000000))*(cj2)*(x166)))+(((cj1)*(x175)))+(((pz)*(sj1)))+(((IkReal(-0.139000000000000))*(cj2)))+(((IkReal(-1.00000000000000))*(x165)*(x177))));
01228 evalcond[5]=((((IkReal(-1.00000000000000))*(x174)*(x175)))+(((cj1)*(pz)))+(((IkReal(-1.00000000000000))*(x168)*(x169)))+(((IkReal(-1.00000000000000))*(x171)*(x177)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(0.147300000000000))*(x165)))+(((IkReal(-1.00000000000000))*(sj2)*(x166)))+(((IkReal(-1.00000000000000))*(x172)*(x177))));
01229 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  )
01230 {
01231 continue;
01232 }
01233 }
01234 
01235 {
01236 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01237 vinfos[0].jointtype = 1;
01238 vinfos[0].foffset = j0;
01239 vinfos[0].indices[0] = _ij0[0];
01240 vinfos[0].indices[1] = _ij0[1];
01241 vinfos[0].maxsolutions = _nj0;
01242 vinfos[1].jointtype = 1;
01243 vinfos[1].foffset = j1;
01244 vinfos[1].indices[0] = _ij1[0];
01245 vinfos[1].indices[1] = _ij1[1];
01246 vinfos[1].maxsolutions = _nj1;
01247 vinfos[2].jointtype = 1;
01248 vinfos[2].foffset = j2;
01249 vinfos[2].indices[0] = _ij2[0];
01250 vinfos[2].indices[1] = _ij2[1];
01251 vinfos[2].maxsolutions = _nj2;
01252 vinfos[3].jointtype = 1;
01253 vinfos[3].foffset = j3;
01254 vinfos[3].indices[0] = _ij3[0];
01255 vinfos[3].indices[1] = _ij3[1];
01256 vinfos[3].maxsolutions = _nj3;
01257 vinfos[4].jointtype = 1;
01258 vinfos[4].foffset = j4;
01259 vinfos[4].indices[0] = _ij4[0];
01260 vinfos[4].indices[1] = _ij4[1];
01261 vinfos[4].maxsolutions = _nj4;
01262 std::vector<int> vfree(0);
01263 solutions.AddSolution(vinfos,vfree);
01264 }
01265 }
01266 }
01267 
01268 }
01269 
01270 }
01271 
01272 } else
01273 {
01274 {
01275 IkReal j4array[1], cj4array[1], sj4array[1];
01276 bool j4valid[1]={false};
01277 _nj4 = 1;
01278 if( IKabs(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02))))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01)))))+IKsqr(((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02)))))))-1) <= IKFAST_SINCOS_THRESH )
01279     continue;
01280 j4array[0]=IKatan2(((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01)))), ((((IKabs(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))))) != 0)?((IkReal)1/(((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3)))))):(IkReal)1.0e30))*(((((cj0)*(r00)*(sj1)))+(((r01)*(sj0)*(sj1)))+(((IkReal(-1.00000000000000))*(cj1)*(r02)))))));
01281 sj4array[0]=IKsin(j4array[0]);
01282 cj4array[0]=IKcos(j4array[0]);
01283 if( j4array[0] > IKPI )
01284 {
01285     j4array[0]-=IK2PI;
01286 }
01287 else if( j4array[0] < -IKPI )
01288 {    j4array[0]+=IK2PI;
01289 }
01290 j4valid[0] = true;
01291 for(int ij4 = 0; ij4 < 1; ++ij4)
01292 {
01293 if( !j4valid[ij4] )
01294 {
01295     continue;
01296 }
01297 _ij4[0] = ij4; _ij4[1] = -1;
01298 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
01299 {
01300 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
01301 {
01302     j4valid[iij4]=false; _ij4[1] = iij4; break;
01303 }
01304 }
01305 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
01306 {
01307 IkReal evalcond[6];
01308 IkReal x179=IKsin(j4);
01309 IkReal x180=IKcos(j4);
01310 IkReal x181=((cj2)*(sj3));
01311 IkReal x182=((IkReal(0.147300000000000))*(cj3));
01312 IkReal x183=((IkReal(1.00000000000000))*(r01));
01313 IkReal x184=((sj0)*(sj1));
01314 IkReal x185=((IkReal(1.00000000000000))*(py));
01315 IkReal x186=((cj0)*(r00));
01316 IkReal x187=((sj2)*(sj3));
01317 IkReal x188=((cj2)*(cj3));
01318 IkReal x189=((cj1)*(sj0));
01319 IkReal x190=((IkReal(1.00000000000000))*(sj1));
01320 IkReal x191=((cj0)*(px));
01321 IkReal x192=((cj3)*(sj2));
01322 IkReal x193=((IkReal(0.110000000000000))*(x180));
01323 IkReal x194=((IkReal(1.00000000000000))*(x180));
01324 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x183)))+(x179));
01325 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x185)))+(((IkReal(0.110000000000000))*(x179)))+(((px)*(sj0))));
01326 evalcond[2]=((((r01)*(x189)))+(((x180)*(x192)))+(((r02)*(sj1)))+(((cj1)*(x186)))+(((IkReal(-1.00000000000000))*(x181)*(x194))));
01327 evalcond[3]=((((IkReal(-1.00000000000000))*(x188)*(x194)))+(((IkReal(-1.00000000000000))*(x186)*(x190)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x187)*(x194)))+(((IkReal(-1.00000000000000))*(x183)*(x184))));
01328 evalcond[4]=((IkReal(-0.190000000000000))+(((IkReal(-0.147300000000000))*(x187)))+(((x192)*(x193)))+(((cj1)*(x191)))+(((pz)*(sj1)))+(((IkReal(-1.00000000000000))*(cj2)*(x182)))+(((IkReal(-1.00000000000000))*(x181)*(x193)))+(((py)*(x189)))+(((IkReal(-0.139000000000000))*(cj2))));
01329 evalcond[5]=((((IkReal(-1.00000000000000))*(x188)*(x193)))+(((IkReal(-1.00000000000000))*(x190)*(x191)))+(((IkReal(-1.00000000000000))*(x187)*(x193)))+(((cj1)*(pz)))+(((IkReal(-1.00000000000000))*(x184)*(x185)))+(((IkReal(0.147300000000000))*(x181)))+(((IkReal(-0.139000000000000))*(sj2)))+(((IkReal(-1.00000000000000))*(sj2)*(x182))));
01330 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  )
01331 {
01332 continue;
01333 }
01334 }
01335 
01336 {
01337 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
01338 vinfos[0].jointtype = 1;
01339 vinfos[0].foffset = j0;
01340 vinfos[0].indices[0] = _ij0[0];
01341 vinfos[0].indices[1] = _ij0[1];
01342 vinfos[0].maxsolutions = _nj0;
01343 vinfos[1].jointtype = 1;
01344 vinfos[1].foffset = j1;
01345 vinfos[1].indices[0] = _ij1[0];
01346 vinfos[1].indices[1] = _ij1[1];
01347 vinfos[1].maxsolutions = _nj1;
01348 vinfos[2].jointtype = 1;
01349 vinfos[2].foffset = j2;
01350 vinfos[2].indices[0] = _ij2[0];
01351 vinfos[2].indices[1] = _ij2[1];
01352 vinfos[2].maxsolutions = _nj2;
01353 vinfos[3].jointtype = 1;
01354 vinfos[3].foffset = j3;
01355 vinfos[3].indices[0] = _ij3[0];
01356 vinfos[3].indices[1] = _ij3[1];
01357 vinfos[3].maxsolutions = _nj3;
01358 vinfos[4].jointtype = 1;
01359 vinfos[4].foffset = j4;
01360 vinfos[4].indices[0] = _ij4[0];
01361 vinfos[4].indices[1] = _ij4[1];
01362 vinfos[4].maxsolutions = _nj4;
01363 std::vector<int> vfree(0);
01364 solutions.AddSolution(vinfos,vfree);
01365 }
01366 }
01367 }
01368 
01369 }
01370 
01371 }
01372 }
01373 }
01374 
01375 }
01376 
01377 }
01378 }
01379 }
01380 
01381 }
01382 
01383 }
01384     }
01385 
01386 }
01387 
01388 }
01389 }
01390 }
01391 }
01392 return solutions.GetNumSolutions()>0;
01393 }
01394 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
01395 {
01396     using std::complex;
01397     IKFAST_ASSERT(rawcoeffs[0] != 0);
01398     const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
01399     const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
01400     complex<IkReal> coeffs[4];
01401     const int maxsteps = 110;
01402     for(int i = 0; i < 4; ++i) {
01403         coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
01404     }
01405     complex<IkReal> roots[4];
01406     IkReal err[4];
01407     roots[0] = complex<IkReal>(1,0);
01408     roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
01409     err[0] = 1.0;
01410     err[1] = 1.0;
01411     for(int i = 2; i < 4; ++i) {
01412         roots[i] = roots[i-1]*roots[1];
01413         err[i] = 1.0;
01414     }
01415     for(int step = 0; step < maxsteps; ++step) {
01416         bool changed = false;
01417         for(int i = 0; i < 4; ++i) {
01418             if ( err[i] >= tol ) {
01419                 changed = true;
01420                 // evaluate
01421                 complex<IkReal> x = roots[i] + coeffs[0];
01422                 for(int j = 1; j < 4; ++j) {
01423                     x = roots[i] * x + coeffs[j];
01424                 }
01425                 for(int j = 0; j < 4; ++j) {
01426                     if( i != j ) {
01427                         if( roots[i] != roots[j] ) {
01428                             x /= (roots[i] - roots[j]);
01429                         }
01430                     }
01431                 }
01432                 roots[i] -= x;
01433                 err[i] = abs(x);
01434             }
01435         }
01436         if( !changed ) {
01437             break;
01438         }
01439     }
01440 
01441     numroots = 0;
01442     bool visited[4] = {false};
01443     for(int i = 0; i < 4; ++i) {
01444         if( !visited[i] ) {
01445             // might be a multiple root, in which case it will have more error than the other roots
01446             // find any neighboring roots, and take the average
01447             complex<IkReal> newroot=roots[i];
01448             int n = 1;
01449             for(int j = i+1; j < 4; ++j) {
01450                 if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
01451                     newroot += roots[j];
01452                     n += 1;
01453                     visited[j] = true;
01454                 }
01455             }
01456             if( n > 1 ) {
01457                 newroot /= n;
01458             }
01459             // 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
01460             if( IKabs(imag(newroot)) < tolsqrt ) {
01461                 rawroots[numroots++] = real(newroot);
01462             }
01463         }
01464     }
01465 }
01466 };
01467 
01468 
01471 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
01472 IKSolver solver;
01473 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
01474 }
01475 
01476 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - katana_450_6m90a (0ae658000dba03e5e2af5e0545d8ad48)>"; }
01477 
01478 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
01479 
01480 #ifdef IKFAST_NAMESPACE
01481 } // end namespace
01482 #endif
01483 
01484 #ifndef IKFAST_NO_MAIN
01485 #include <stdio.h>
01486 #include <stdlib.h>
01487 #ifdef IKFAST_NAMESPACE
01488 using namespace IKFAST_NAMESPACE;
01489 #endif
01490 int main(int argc, char** argv)
01491 {
01492     if( argc != 12+GetNumFreeParameters()+1 ) {
01493         printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
01494                "Returns the ik solutions given the transformation of the end effector specified by\n"
01495                "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
01496                "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
01497         return 1;
01498     }
01499 
01500     IkSolutionList<IkReal> solutions;
01501     std::vector<IkReal> vfree(GetNumFreeParameters());
01502     IkReal eerot[9],eetrans[3];
01503     eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
01504     eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
01505     eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
01506     for(std::size_t i = 0; i < vfree.size(); ++i)
01507         vfree[i] = atof(argv[13+i]);
01508     bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
01509 
01510     if( !bSuccess ) {
01511         fprintf(stderr,"Failed to get ik solution\n");
01512         return -1;
01513     }
01514 
01515     printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
01516     std::vector<IkReal> solvalues(GetNumJoints());
01517     for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
01518         const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
01519         printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
01520         std::vector<IkReal> vsolfree(sol.GetFree().size());
01521         sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
01522         for( std::size_t j = 0; j < solvalues.size(); ++j)
01523             printf("%.15f, ", solvalues[j]);
01524         printf("\n");
01525     }
01526     return 0;
01527 }
01528 
01529 #endif


katana_moveit_ikfast_plugin
Author(s): Martin Günther
autogenerated on Thu Aug 27 2015 13:40:30