katana_450_6m90a_ikfast_solver.cpp
Go to the documentation of this file.
1 #define IKFAST_HAS_LIBRARY
21 #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h
22 using namespace ikfast;
23 
24 // check if the included ikfast version matches what this file was compiled with
25 #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x]
27 
28 #include <cmath>
29 #include <vector>
30 #include <limits>
31 #include <algorithm>
32 #include <complex>
33 
34 #define IKFAST_STRINGIZE2(s) #s
35 #define IKFAST_STRINGIZE(s) IKFAST_STRINGIZE2(s)
36 
37 #ifndef IKFAST_ASSERT
38 #include <stdexcept>
39 #include <sstream>
40 #include <iostream>
41 
42 #ifdef _MSC_VER
43 #ifndef __PRETTY_FUNCTION__
44 #define __PRETTY_FUNCTION__ __FUNCDNAME__
45 #endif
46 #endif
47 
48 #ifndef __PRETTY_FUNCTION__
49 #define __PRETTY_FUNCTION__ __func__
50 #endif
51 
52 #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()); } }
53 
54 #endif
55 
56 #if defined(_MSC_VER)
57 #define IKFAST_ALIGNED16(x) __declspec(align(16)) x
58 #else
59 #define IKFAST_ALIGNED16(x) x __attribute((aligned(16)))
60 #endif
61 
62 #define IK2PI ((IkReal)6.28318530717959)
63 #define IKPI ((IkReal)3.14159265358979)
64 #define IKPI_2 ((IkReal)1.57079632679490)
65 
66 #ifdef _MSC_VER
67 #ifndef std::isnan
68 #define std::isnan _isnan
69 #endif
70 #endif // _MSC_VER
71 
72 // lapack routines
73 extern "C" {
74  void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info);
75  void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info);
76  void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info);
77  void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info);
78  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);
79  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);
80 }
81 
82 using namespace std; // necessary to get std math routines
83 
84 #ifdef IKFAST_NAMESPACE
85 namespace IKFAST_NAMESPACE {
86 #endif
87 
88 inline float IKabs(float f) { return fabsf(f); }
89 inline double IKabs(double f) { return fabs(f); }
90 
91 inline float IKsqr(float f) { return f*f; }
92 inline double IKsqr(double f) { return f*f; }
93 
94 inline float IKlog(float f) { return logf(f); }
95 inline double IKlog(double f) { return log(f); }
96 
97 // allows asin and acos to exceed 1
98 #ifndef IKFAST_SINCOS_THRESH
99 #define IKFAST_SINCOS_THRESH ((IkReal)0.000001)
100 #endif
101 
102 // used to check input to atan2 for degenerate cases
103 #ifndef IKFAST_ATAN2_MAGTHRESH
104 #define IKFAST_ATAN2_MAGTHRESH ((IkReal)2e-6)
105 #endif
106 
107 // minimum distance of separate solutions
108 #ifndef IKFAST_SOLUTION_THRESH
109 #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6)
110 #endif
111 
112 inline float IKasin(float f)
113 {
114 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
115 if( f <= -1 ) return float(-IKPI_2);
116 else if( f >= 1 ) return float(IKPI_2);
117 return asinf(f);
118 }
119 inline double IKasin(double f)
120 {
121 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
122 if( f <= -1 ) return -IKPI_2;
123 else if( f >= 1 ) return IKPI_2;
124 return asin(f);
125 }
126 
127 // return positive value in [0,y)
128 inline float IKfmod(float x, float y)
129 {
130  while(x < 0) {
131  x += y;
132  }
133  return fmodf(x,y);
134 }
135 
136 // return positive value in [0,y)
137 inline double IKfmod(double x, double y)
138 {
139  while(x < 0) {
140  x += y;
141  }
142  return fmod(x,y);
143 }
144 
145 inline float IKacos(float f)
146 {
147 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
148 if( f <= -1 ) return float(IKPI);
149 else if( f >= 1 ) return float(0);
150 return acosf(f);
151 }
152 inline double IKacos(double f)
153 {
154 IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver
155 if( f <= -1 ) return IKPI;
156 else if( f >= 1 ) return 0;
157 return acos(f);
158 }
159 inline float IKsin(float f) { return sinf(f); }
160 inline double IKsin(double f) { return sin(f); }
161 inline float IKcos(float f) { return cosf(f); }
162 inline double IKcos(double f) { return cos(f); }
163 inline float IKtan(float f) { return tanf(f); }
164 inline double IKtan(double f) { return tan(f); }
165 inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); }
166 inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); }
167 inline float IKatan2(float fy, float fx) {
168  if( std::isnan(fy) ) {
169  IKFAST_ASSERT(!std::isnan(fx)); // if both are nan, probably wrong value will be returned
170  return float(IKPI_2);
171  }
172  else if( std::isnan(fx) ) {
173  return 0;
174  }
175  return atan2f(fy,fx);
176 }
177 inline double IKatan2(double fy, double fx) {
178  if( std::isnan(fy) ) {
179  IKFAST_ASSERT(!std::isnan(fx)); // if both are nan, probably wrong value will be returned
180  return IKPI_2;
181  }
182  else if( std::isnan(fx) ) {
183  return 0;
184  }
185  return atan2(fy,fx);
186 }
187 
188 inline float IKsign(float f) {
189  if( f > 0 ) {
190  return float(1);
191  }
192  else if( f < 0 ) {
193  return float(-1);
194  }
195  return 0;
196 }
197 
198 inline double IKsign(double f) {
199  if( f > 0 ) {
200  return 1.0;
201  }
202  else if( f < 0 ) {
203  return -1.0;
204  }
205  return 0;
206 }
207 
210 IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) {
211 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;
212 x0=IKcos(j[0]);
213 x1=IKcos(j[1]);
214 x2=IKsin(j[2]);
215 x3=IKcos(j[2]);
216 x4=IKsin(j[1]);
217 x5=IKcos(j[3]);
218 x6=IKsin(j[3]);
219 x7=IKsin(j[0]);
220 x8=IKcos(j[4]);
221 x9=IKsin(j[4]);
222 x10=((IkReal(0.139000000000000))*(x0));
223 x11=((IkReal(0.110000000000000))*(x6));
224 x12=((IkReal(1.00000000000000))*(x5));
225 x13=((IkReal(0.110000000000000))*(x5));
226 x14=((IkReal(1.00000000000000))*(x6));
227 x15=((IkReal(0.147300000000000))*(x0));
228 x16=((IkReal(1.00000000000000))*(x0));
229 x17=((IkReal(0.147300000000000))*(x7));
230 x18=((x3)*(x4));
231 x19=((x2)*(x4));
232 x20=((x7)*(x9));
233 x21=((x1)*(x7));
234 x22=((x1)*(x3));
235 x23=((x0)*(x9));
236 x24=((x1)*(x2));
237 x25=((((IkReal(-1.00000000000000))*(x22)))+(x19));
238 x26=((((IkReal(-1.00000000000000))*(x24)))+(((IkReal(-1.00000000000000))*(x18))));
239 x27=((x0)*(((x18)+(x24))));
240 x28=((((x18)*(x7)))+(((x2)*(x21))));
241 x29=((x16)*(((((IkReal(-1.00000000000000))*(x22)))+(x19))));
242 x30=((((IkReal(-1.00000000000000))*(x21)*(x3)))+(((IkReal(1.00000000000000))*(x19)*(x7))));
243 IkReal x31=((IkReal(1.00000000000000))*(x19));
244 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))));
245 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))))))));
246 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))));
247 eerot[0]=((((IkReal(-1.00000000000000))*(x20)))+(((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x27)))+(((IkReal(-1.00000000000000))*(x14)*(x29))))))));
248 eerot[1]=((x23)+(((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x28)))+(((IkReal(-1.00000000000000))*(x14)*(x30))))))));
249 eerot[2]=((x8)*(((((IkReal(-1.00000000000000))*(x12)*(x25)))+(((IkReal(-1.00000000000000))*(x14)*(x26))))));
250 }
251 
252 IKFAST_API int GetNumFreeParameters() { return 0; }
253 IKFAST_API int* GetFreeParameters() { return NULL; }
254 IKFAST_API int GetNumJoints() { return 5; }
255 
256 IKFAST_API int GetIkRealSize() { return sizeof(IkReal); }
257 
258 IKFAST_API int GetIkType() { return 0x56000007; }
259 
260 class IKSolver {
261 public:
262 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;
263 unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4;
264 
265 bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
266 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;
267 for(int dummyiter = 0; dummyiter < 1; ++dummyiter) {
268  solutions.Clear();
269 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
270 
271 r00 = eerot[0];
272 r01 = eerot[1];
273 r02 = eerot[2];
274 px = eetrans[0]; py = eetrans[1]; pz = eetrans[2];
275 new_r00=r00;
276 new_px=px;
277 new_r01=r01;
278 new_py=py;
279 new_r02=r02;
280 new_pz=((IkReal(-0.201500000000000))+(pz));
281 r00 = new_r00; r01 = new_r01; r02 = new_r02; px = new_px; py = new_py; pz = new_pz;
282 
283 pp=(((px)*(px))+((py)*(py))+((pz)*(pz)));
284 {
285 IkReal j0array[2], cj0array[2], sj0array[2];
286 bool j0valid[2]={false};
287 _nj0 = 2;
288 if( IKabs(((((IkReal(-0.110000000000000))*(r01)))+(py))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((IkReal(-1.00000000000000))*(px)))+(((IkReal(0.110000000000000))*(r00))))) < IKFAST_ATAN2_MAGTHRESH )
289  continue;
290 IkReal x32=IKatan2(((((IkReal(-0.110000000000000))*(r01)))+(py)), ((((IkReal(-1.00000000000000))*(px)))+(((IkReal(0.110000000000000))*(r00)))));
291 j0array[0]=((IkReal(-1.00000000000000))*(x32));
292 sj0array[0]=IKsin(j0array[0]);
293 cj0array[0]=IKcos(j0array[0]);
294 j0array[1]=((IkReal(3.14159265358979))+(((IkReal(-1.00000000000000))*(x32))));
295 sj0array[1]=IKsin(j0array[1]);
296 cj0array[1]=IKcos(j0array[1]);
297 if( j0array[0] > IKPI )
298 {
299  j0array[0]-=IK2PI;
300 }
301 else if( j0array[0] < -IKPI )
302 { j0array[0]+=IK2PI;
303 }
304 j0valid[0] = true;
305 if( j0array[1] > IKPI )
306 {
307  j0array[1]-=IK2PI;
308 }
309 else if( j0array[1] < -IKPI )
310 { j0array[1]+=IK2PI;
311 }
312 j0valid[1] = true;
313 for(int ij0 = 0; ij0 < 2; ++ij0)
314 {
315 if( !j0valid[ij0] )
316 {
317  continue;
318 }
319 _ij0[0] = ij0; _ij0[1] = -1;
320 for(int iij0 = ij0+1; iij0 < 2; ++iij0)
321 {
322 if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH )
323 {
324  j0valid[iij0]=false; _ij0[1] = iij0; break;
325 }
326 }
327 j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0];
328 
329 {
330 IkReal dummyeval[1];
331 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))));
332 if( IKabs(dummyeval[0]) < 0.0000001000000000 )
333 {
334 continue;
335 
336 } else
337 {
338 IkReal op[4+1], zeror[4];
339 int numroots;
340 IkReal j1evalpoly[2];
341 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))));
342 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)))));
343 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)))));
344 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))));
345 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))));
346 polyroots4(op,zeror,numroots);
347 IkReal j1array[4], cj1array[4], sj1array[4], tempj1array[1];
348 int numsolutions = 0;
349 for(int ij1 = 0; ij1 < numroots; ++ij1)
350 {
351 IkReal htj1 = zeror[ij1];
352 tempj1array[0]=((IkReal(2.00000000000000))*(atan(htj1)));
353 for(int kj1 = 0; kj1 < 1; ++kj1)
354 {
355 j1array[numsolutions] = tempj1array[kj1];
356 if( j1array[numsolutions] > IKPI )
357 {
358  j1array[numsolutions]-=IK2PI;
359 }
360 else if( j1array[numsolutions] < -IKPI )
361 {
362  j1array[numsolutions]+=IK2PI;
363 }
364 sj1array[numsolutions] = IKsin(j1array[numsolutions]);
365 cj1array[numsolutions] = IKcos(j1array[numsolutions]);
366 numsolutions++;
367 }
368 }
369 bool j1valid[4]={true,true,true,true};
370 _nj1 = 4;
371 for(int ij1 = 0; ij1 < numsolutions; ++ij1)
372  {
373 if( !j1valid[ij1] )
374 {
375  continue;
376 }
377  j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1];
378 htj1 = IKtan(j1/2);
379 
380 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))));
381 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)))));
382 if( IKabs(j1evalpoly[0]) > 0.0000001000000000 || IKabs(j1evalpoly[1]) > 0.0000001000000000 )
383 {
384  continue;
385 }
386 _ij1[0] = ij1; _ij1[1] = -1;
387 for(int iij1 = ij1+1; iij1 < numsolutions; ++iij1)
388 {
389 if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH )
390 {
391  j1valid[iij1]=false; _ij1[1] = iij1; break;
392 }
393 }
394 {
395 IkReal dummyeval[1];
396 IkReal gconst0;
397 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))))));
398 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)))));
399 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
400 {
401 continue;
402 
403 } else
404 {
405 {
406 IkReal j2array[1], cj2array[1], sj2array[1];
407 bool j2valid[1]={false};
408 _nj2 = 1;
409 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 )
410  continue;
411 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)))))));
412 sj2array[0]=IKsin(j2array[0]);
413 cj2array[0]=IKcos(j2array[0]);
414 if( j2array[0] > IKPI )
415 {
416  j2array[0]-=IK2PI;
417 }
418 else if( j2array[0] < -IKPI )
419 { j2array[0]+=IK2PI;
420 }
421 j2valid[0] = true;
422 for(int ij2 = 0; ij2 < 1; ++ij2)
423 {
424 if( !j2valid[ij2] )
425 {
426  continue;
427 }
428 _ij2[0] = ij2; _ij2[1] = -1;
429 for(int iij2 = ij2+1; iij2 < 1; ++iij2)
430 {
431 if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH )
432 {
433  j2valid[iij2]=false; _ij2[1] = iij2; break;
434 }
435 }
436 j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2];
437 {
438 IkReal evalcond[4];
439 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))));
440 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))));
441 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))));
442 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))));
443 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
444 {
445 continue;
446 }
447 }
448 
449 {
450 IkReal dummyeval[1];
451 IkReal gconst1;
452 gconst1=IKsign(((((IkReal(2169729.00000000))*((sj2)*(sj2)*(sj2)*(sj2))))+(((IkReal(2169729.00000000))*((cj2)*(cj2))*((sj2)*(sj2))))));
453 dummyeval[0]=(((sj2)*(sj2)*(sj2)*(sj2))+((((cj2)*(cj2))*((sj2)*(sj2)))));
454 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
455 {
456 {
457 IkReal j4array[2], cj4array[2], sj4array[2];
458 bool j4valid[2]={false};
459 _nj4 = 2;
460 sj4array[0]=((((IkReal(-1.00000000000000))*(r00)*(sj0)))+(((cj0)*(r01))));
461 if( sj4array[0] >= -1-IKFAST_SINCOS_THRESH && sj4array[0] <= 1+IKFAST_SINCOS_THRESH )
462 {
463  j4valid[0] = j4valid[1] = true;
464  j4array[0] = IKasin(sj4array[0]);
465  cj4array[0] = IKcos(j4array[0]);
466  sj4array[1] = sj4array[0];
467  j4array[1] = j4array[0] > 0 ? (IKPI-j4array[0]) : (-IKPI-j4array[0]);
468  cj4array[1] = -cj4array[0];
469 }
470 else if( std::isnan(sj4array[0]) )
471 {
472  // probably any value will work
473  j4valid[0] = true;
474  cj4array[0] = 1; sj4array[0] = 0; j4array[0] = 0;
475 }
476 for(int ij4 = 0; ij4 < 2; ++ij4)
477 {
478 if( !j4valid[ij4] )
479 {
480  continue;
481 }
482 _ij4[0] = ij4; _ij4[1] = -1;
483 for(int iij4 = ij4+1; iij4 < 2; ++iij4)
484 {
485 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
486 {
487  j4valid[iij4]=false; _ij4[1] = iij4; break;
488 }
489 }
490 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
491 {
492 IkReal evalcond[1];
493 evalcond[0]=((((IkReal(0.110000000000000))*(IKsin(j4))))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(py))));
494 if( IKabs(evalcond[0]) > 0.000001 )
495 {
496 continue;
497 }
498 }
499 
500 {
501 IkReal dummyeval[1];
502 IkReal gconst2;
503 gconst2=IKsign(((((cj4)*((cj2)*(cj2))))+(((cj4)*((sj2)*(sj2))))));
504 dummyeval[0]=((((cj4)*((cj2)*(cj2))))+(((cj4)*((sj2)*(sj2)))));
505 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
506 {
507 {
508 IkReal dummyeval[1];
509 IkReal gconst3;
510 IkReal x33=((IkReal(0.147300000000000))*(cj4));
511 gconst3=IKsign(((((IkReal(-1.00000000000000))*(x33)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x33)*((cj2)*(cj2))))));
512 IkReal x34=((IkReal(1.00000000000000))*(cj4));
513 dummyeval[0]=((((IkReal(-1.00000000000000))*(x34)*((sj2)*(sj2))))+(((IkReal(-1.00000000000000))*(x34)*((cj2)*(cj2)))));
514 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
515 {
516 {
517 IkReal evalcond[5];
518 IkReal x35=((IkReal(1.00000000000000))*(cj0));
519 IkReal x36=((r01)*(sj0));
520 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(1.57079632679490))+(j4)), IkReal(6.28318530717959))));
521 evalcond[1]=((IkReal(1.00000000000000))+(((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x35))));
522 evalcond[2]=((IkReal(0.110000000000000))+(((IkReal(-1.00000000000000))*(py)*(x35)))+(((px)*(sj0))));
523 evalcond[3]=((((cj1)*(x36)))+(((cj0)*(cj1)*(r00)))+(((r02)*(sj1))));
524 evalcond[4]=((((IkReal(-1.00000000000000))*(r00)*(sj1)*(x35)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x36))));
525 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 )
526 {
527 {
528 IkReal dummyeval[1];
529 IkReal gconst4;
530 gconst4=IKsign(((((IkReal(1473.00000000000))*((sj2)*(sj2))))+(((IkReal(1473.00000000000))*((cj2)*(cj2))))));
531 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
532 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
533 {
534 continue;
535 
536 } else
537 {
538 {
539 IkReal j3array[1], cj3array[1], sj3array[1];
540 bool j3valid[1]={false};
541 _nj3 = 1;
542 IkReal x37=((IkReal(10000.0000000000))*(pz));
543 IkReal x38=((sj1)*(sj2));
544 IkReal x39=((cj1)*(cj2));
545 IkReal x40=((cj1)*(sj2));
546 IkReal x41=((cj2)*(sj1));
547 IkReal x42=((IkReal(10000.0000000000))*(py)*(sj0));
548 IkReal x43=((IkReal(10000.0000000000))*(cj0)*(px));
549 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 )
550  continue;
551 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))))))));
552 sj3array[0]=IKsin(j3array[0]);
553 cj3array[0]=IKcos(j3array[0]);
554 if( j3array[0] > IKPI )
555 {
556  j3array[0]-=IK2PI;
557 }
558 else if( j3array[0] < -IKPI )
559 { j3array[0]+=IK2PI;
560 }
561 j3valid[0] = true;
562 for(int ij3 = 0; ij3 < 1; ++ij3)
563 {
564 if( !j3valid[ij3] )
565 {
566  continue;
567 }
568 _ij3[0] = ij3; _ij3[1] = -1;
569 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
570 {
571 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
572 {
573  j3valid[iij3]=false; _ij3[1] = iij3; break;
574 }
575 }
576 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
577 {
578 IkReal evalcond[2];
579 IkReal x44=IKsin(j3);
580 IkReal x45=IKcos(j3);
581 IkReal x46=((py)*(sj0));
582 IkReal x47=((IkReal(1.00000000000000))*(sj1));
583 IkReal x48=((cj0)*(px));
584 IkReal x49=((IkReal(0.147300000000000))*(x45));
585 IkReal x50=((IkReal(0.147300000000000))*(x44));
586 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))));
587 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))));
588 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
589 {
590 continue;
591 }
592 }
593 
594 {
595 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
596 vinfos[0].jointtype = 1;
597 vinfos[0].foffset = j0;
598 vinfos[0].indices[0] = _ij0[0];
599 vinfos[0].indices[1] = _ij0[1];
600 vinfos[0].maxsolutions = _nj0;
601 vinfos[1].jointtype = 1;
602 vinfos[1].foffset = j1;
603 vinfos[1].indices[0] = _ij1[0];
604 vinfos[1].indices[1] = _ij1[1];
605 vinfos[1].maxsolutions = _nj1;
606 vinfos[2].jointtype = 1;
607 vinfos[2].foffset = j2;
608 vinfos[2].indices[0] = _ij2[0];
609 vinfos[2].indices[1] = _ij2[1];
610 vinfos[2].maxsolutions = _nj2;
611 vinfos[3].jointtype = 1;
612 vinfos[3].foffset = j3;
613 vinfos[3].indices[0] = _ij3[0];
614 vinfos[3].indices[1] = _ij3[1];
615 vinfos[3].maxsolutions = _nj3;
616 vinfos[4].jointtype = 1;
617 vinfos[4].foffset = j4;
618 vinfos[4].indices[0] = _ij4[0];
619 vinfos[4].indices[1] = _ij4[1];
620 vinfos[4].maxsolutions = _nj4;
621 std::vector<int> vfree(0);
622 solutions.AddSolution(vinfos,vfree);
623 }
624 }
625 }
626 
627 }
628 
629 }
630 
631 } else
632 {
633 IkReal x51=((IkReal(1.00000000000000))*(cj0));
634 IkReal x52=((r01)*(sj0));
635 evalcond[0]=((IkReal(-3.14159265358979))+(IKfmod(((IkReal(4.71238898038469))+(j4)), IkReal(6.28318530717959))));
636 evalcond[1]=((IkReal(-1.00000000000000))+(((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(r01)*(x51))));
637 evalcond[2]=((IkReal(-0.110000000000000))+(((px)*(sj0)))+(((IkReal(-1.00000000000000))*(py)*(x51))));
638 evalcond[3]=((((cj1)*(x52)))+(((cj0)*(cj1)*(r00)))+(((r02)*(sj1))));
639 evalcond[4]=((((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(sj1)*(x52)))+(((IkReal(-1.00000000000000))*(r00)*(sj1)*(x51))));
640 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 )
641 {
642 {
643 IkReal dummyeval[1];
644 IkReal gconst5;
645 gconst5=IKsign(((((IkReal(1473.00000000000))*((sj2)*(sj2))))+(((IkReal(1473.00000000000))*((cj2)*(cj2))))));
646 dummyeval[0]=(((sj2)*(sj2))+((cj2)*(cj2)));
647 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
648 {
649 continue;
650 
651 } else
652 {
653 {
654 IkReal j3array[1], cj3array[1], sj3array[1];
655 bool j3valid[1]={false};
656 _nj3 = 1;
657 IkReal x53=((IkReal(10000.0000000000))*(pz));
658 IkReal x54=((sj1)*(sj2));
659 IkReal x55=((cj1)*(cj2));
660 IkReal x56=((cj1)*(sj2));
661 IkReal x57=((cj2)*(sj1));
662 IkReal x58=((IkReal(10000.0000000000))*(py)*(sj0));
663 IkReal x59=((IkReal(10000.0000000000))*(cj0)*(px));
664 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 )
665  continue;
666 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)))))));
667 sj3array[0]=IKsin(j3array[0]);
668 cj3array[0]=IKcos(j3array[0]);
669 if( j3array[0] > IKPI )
670 {
671  j3array[0]-=IK2PI;
672 }
673 else if( j3array[0] < -IKPI )
674 { j3array[0]+=IK2PI;
675 }
676 j3valid[0] = true;
677 for(int ij3 = 0; ij3 < 1; ++ij3)
678 {
679 if( !j3valid[ij3] )
680 {
681  continue;
682 }
683 _ij3[0] = ij3; _ij3[1] = -1;
684 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
685 {
686 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
687 {
688  j3valid[iij3]=false; _ij3[1] = iij3; break;
689 }
690 }
691 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
692 {
693 IkReal evalcond[2];
694 IkReal x60=IKsin(j3);
695 IkReal x61=IKcos(j3);
696 IkReal x62=((py)*(sj0));
697 IkReal x63=((IkReal(1.00000000000000))*(sj1));
698 IkReal x64=((cj0)*(px));
699 IkReal x65=((IkReal(0.147300000000000))*(x61));
700 IkReal x66=((IkReal(0.147300000000000))*(x60));
701 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))));
702 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))));
703 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 )
704 {
705 continue;
706 }
707 }
708 
709 {
710 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
711 vinfos[0].jointtype = 1;
712 vinfos[0].foffset = j0;
713 vinfos[0].indices[0] = _ij0[0];
714 vinfos[0].indices[1] = _ij0[1];
715 vinfos[0].maxsolutions = _nj0;
716 vinfos[1].jointtype = 1;
717 vinfos[1].foffset = j1;
718 vinfos[1].indices[0] = _ij1[0];
719 vinfos[1].indices[1] = _ij1[1];
720 vinfos[1].maxsolutions = _nj1;
721 vinfos[2].jointtype = 1;
722 vinfos[2].foffset = j2;
723 vinfos[2].indices[0] = _ij2[0];
724 vinfos[2].indices[1] = _ij2[1];
725 vinfos[2].maxsolutions = _nj2;
726 vinfos[3].jointtype = 1;
727 vinfos[3].foffset = j3;
728 vinfos[3].indices[0] = _ij3[0];
729 vinfos[3].indices[1] = _ij3[1];
730 vinfos[3].maxsolutions = _nj3;
731 vinfos[4].jointtype = 1;
732 vinfos[4].foffset = j4;
733 vinfos[4].indices[0] = _ij4[0];
734 vinfos[4].indices[1] = _ij4[1];
735 vinfos[4].maxsolutions = _nj4;
736 std::vector<int> vfree(0);
737 solutions.AddSolution(vinfos,vfree);
738 }
739 }
740 }
741 
742 }
743 
744 }
745 
746 } else
747 {
748 if( 1 )
749 {
750 continue;
751 
752 } else
753 {
754 }
755 }
756 }
757 }
758 
759 } else
760 {
761 {
762 IkReal j3array[1], cj3array[1], sj3array[1];
763 bool j3valid[1]={false};
764 _nj3 = 1;
765 IkReal x67=((cj1)*(cj4));
766 IkReal x68=((IkReal(0.110000000000000))*(sj2));
767 IkReal x69=((cj0)*(r00));
768 IkReal x70=((cj2)*(sj0));
769 IkReal x71=((IkReal(1.00000000000000))*(py));
770 IkReal x72=((cj2)*(cj4));
771 IkReal x73=((r02)*(sj1));
772 IkReal x74=((IkReal(0.147300000000000))*(cj1));
773 IkReal x75=((cj4)*(sj2));
774 IkReal x76=((sj0)*(sj2));
775 IkReal x77=((IkReal(1.00000000000000))*(pz)*(sj1));
776 IkReal x78=((IkReal(1.00000000000000))*(cj0)*(px));
777 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 )
778  continue;
779 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)))))));
780 sj3array[0]=IKsin(j3array[0]);
781 cj3array[0]=IKcos(j3array[0]);
782 if( j3array[0] > IKPI )
783 {
784  j3array[0]-=IK2PI;
785 }
786 else if( j3array[0] < -IKPI )
787 { j3array[0]+=IK2PI;
788 }
789 j3valid[0] = true;
790 for(int ij3 = 0; ij3 < 1; ++ij3)
791 {
792 if( !j3valid[ij3] )
793 {
794  continue;
795 }
796 _ij3[0] = ij3; _ij3[1] = -1;
797 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
798 {
799 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
800 {
801  j3valid[iij3]=false; _ij3[1] = iij3; break;
802 }
803 }
804 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
805 {
806 IkReal evalcond[4];
807 IkReal x79=IKcos(j3);
808 IkReal x80=IKsin(j3);
809 IkReal x81=((IkReal(0.147300000000000))*(sj2));
810 IkReal x82=((r01)*(sj0));
811 IkReal x83=((IkReal(1.00000000000000))*(sj1));
812 IkReal x84=((cj0)*(cj1));
813 IkReal x85=((IkReal(0.110000000000000))*(cj4));
814 IkReal x86=((py)*(sj0));
815 IkReal x87=((IkReal(1.00000000000000))*(cj4));
816 IkReal x88=((cj2)*(x79));
817 IkReal x89=((cj2)*(x80));
818 IkReal x90=((sj2)*(x79));
819 IkReal x91=((x80)*(x85));
820 evalcond[0]=((((r00)*(x84)))+(((r02)*(sj1)))+(((IkReal(-1.00000000000000))*(x87)*(x89)))+(((cj4)*(x90)))+(((cj1)*(x82))));
821 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))));
822 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))));
823 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))));
824 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
825 {
826 continue;
827 }
828 }
829 
830 {
831 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
832 vinfos[0].jointtype = 1;
833 vinfos[0].foffset = j0;
834 vinfos[0].indices[0] = _ij0[0];
835 vinfos[0].indices[1] = _ij0[1];
836 vinfos[0].maxsolutions = _nj0;
837 vinfos[1].jointtype = 1;
838 vinfos[1].foffset = j1;
839 vinfos[1].indices[0] = _ij1[0];
840 vinfos[1].indices[1] = _ij1[1];
841 vinfos[1].maxsolutions = _nj1;
842 vinfos[2].jointtype = 1;
843 vinfos[2].foffset = j2;
844 vinfos[2].indices[0] = _ij2[0];
845 vinfos[2].indices[1] = _ij2[1];
846 vinfos[2].maxsolutions = _nj2;
847 vinfos[3].jointtype = 1;
848 vinfos[3].foffset = j3;
849 vinfos[3].indices[0] = _ij3[0];
850 vinfos[3].indices[1] = _ij3[1];
851 vinfos[3].maxsolutions = _nj3;
852 vinfos[4].jointtype = 1;
853 vinfos[4].foffset = j4;
854 vinfos[4].indices[0] = _ij4[0];
855 vinfos[4].indices[1] = _ij4[1];
856 vinfos[4].maxsolutions = _nj4;
857 std::vector<int> vfree(0);
858 solutions.AddSolution(vinfos,vfree);
859 }
860 }
861 }
862 
863 }
864 
865 }
866 
867 } else
868 {
869 {
870 IkReal j3array[1], cj3array[1], sj3array[1];
871 bool j3valid[1]={false};
872 _nj3 = 1;
873 IkReal x92=((IkReal(1.00000000000000))*(sj1));
874 IkReal x93=((r02)*(sj2));
875 IkReal x94=((r01)*(sj0));
876 IkReal x95=((IkReal(1.00000000000000))*(sj2));
877 IkReal x96=((cj0)*(r00));
878 IkReal x97=((cj2)*(r02));
879 IkReal x98=((cj1)*(x96));
880 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 )
881  continue;
882 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)))))));
883 sj3array[0]=IKsin(j3array[0]);
884 cj3array[0]=IKcos(j3array[0]);
885 if( j3array[0] > IKPI )
886 {
887  j3array[0]-=IK2PI;
888 }
889 else if( j3array[0] < -IKPI )
890 { j3array[0]+=IK2PI;
891 }
892 j3valid[0] = true;
893 for(int ij3 = 0; ij3 < 1; ++ij3)
894 {
895 if( !j3valid[ij3] )
896 {
897  continue;
898 }
899 _ij3[0] = ij3; _ij3[1] = -1;
900 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
901 {
902 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
903 {
904  j3valid[iij3]=false; _ij3[1] = iij3; break;
905 }
906 }
907 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
908 {
909 IkReal evalcond[4];
910 IkReal x99=IKcos(j3);
911 IkReal x100=IKsin(j3);
912 IkReal x101=((IkReal(0.147300000000000))*(sj2));
913 IkReal x102=((r01)*(sj0));
914 IkReal x103=((IkReal(1.00000000000000))*(sj1));
915 IkReal x104=((cj0)*(cj1));
916 IkReal x105=((IkReal(0.110000000000000))*(cj4));
917 IkReal x106=((py)*(sj0));
918 IkReal x107=((IkReal(1.00000000000000))*(cj4));
919 IkReal x108=((cj2)*(x99));
920 IkReal x109=((cj2)*(x100));
921 IkReal x110=((sj2)*(x99));
922 IkReal x111=((x100)*(x105));
923 evalcond[0]=((((cj1)*(x102)))+(((IkReal(-1.00000000000000))*(x107)*(x109)))+(((r02)*(sj1)))+(((r00)*(x104)))+(((cj4)*(x110))));
924 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))));
925 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))));
926 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))));
927 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
928 {
929 continue;
930 }
931 }
932 
933 {
934 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
935 vinfos[0].jointtype = 1;
936 vinfos[0].foffset = j0;
937 vinfos[0].indices[0] = _ij0[0];
938 vinfos[0].indices[1] = _ij0[1];
939 vinfos[0].maxsolutions = _nj0;
940 vinfos[1].jointtype = 1;
941 vinfos[1].foffset = j1;
942 vinfos[1].indices[0] = _ij1[0];
943 vinfos[1].indices[1] = _ij1[1];
944 vinfos[1].maxsolutions = _nj1;
945 vinfos[2].jointtype = 1;
946 vinfos[2].foffset = j2;
947 vinfos[2].indices[0] = _ij2[0];
948 vinfos[2].indices[1] = _ij2[1];
949 vinfos[2].maxsolutions = _nj2;
950 vinfos[3].jointtype = 1;
951 vinfos[3].foffset = j3;
952 vinfos[3].indices[0] = _ij3[0];
953 vinfos[3].indices[1] = _ij3[1];
954 vinfos[3].maxsolutions = _nj3;
955 vinfos[4].jointtype = 1;
956 vinfos[4].foffset = j4;
957 vinfos[4].indices[0] = _ij4[0];
958 vinfos[4].indices[1] = _ij4[1];
959 vinfos[4].maxsolutions = _nj4;
960 std::vector<int> vfree(0);
961 solutions.AddSolution(vinfos,vfree);
962 }
963 }
964 }
965 
966 }
967 
968 }
969 }
970 }
971 
972 } else
973 {
974 {
975 IkReal j3array[1], cj3array[1], sj3array[1];
976 bool j3valid[1]={false};
977 _nj3 = 1;
978 IkReal x112=(sj2)*(sj2);
979 IkReal x113=((IkReal(1.00000000000000))*(sj2));
980 IkReal x114=((cj0)*(px));
981 IkReal x115=((py)*(sj0));
982 IkReal x116=((cj2)*(sj2));
983 IkReal x117=((cj1)*(sj2));
984 IkReal x118=((IkReal(0.110000000000000))*(r02));
985 IkReal x119=((sj1)*(sj2));
986 IkReal x120=((IkReal(14730000.0000000))*(x112));
987 IkReal x121=((IkReal(0.110000000000000))*(cj0)*(r00));
988 IkReal x122=((IkReal(0.110000000000000))*(r01)*(sj0));
989 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))));
990 IkReal x124=((IkReal(14730000.0000000))*(x123));
991 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))));
992 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 )
993  continue;
994 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)))))))))));
995 sj3array[0]=IKsin(j3array[0]);
996 cj3array[0]=IKcos(j3array[0]);
997 if( j3array[0] > IKPI )
998 {
999  j3array[0]-=IK2PI;
1000 }
1001 else if( j3array[0] < -IKPI )
1002 { j3array[0]+=IK2PI;
1003 }
1004 j3valid[0] = true;
1005 for(int ij3 = 0; ij3 < 1; ++ij3)
1006 {
1007 if( !j3valid[ij3] )
1008 {
1009  continue;
1010 }
1011 _ij3[0] = ij3; _ij3[1] = -1;
1012 for(int iij3 = ij3+1; iij3 < 1; ++iij3)
1013 {
1014 if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH )
1015 {
1016  j3valid[iij3]=false; _ij3[1] = iij3; break;
1017 }
1018 }
1019 j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3];
1020 {
1021 IkReal evalcond[4];
1022 IkReal x126=(sj2)*(sj2);
1023 IkReal x127=IKsin(j3);
1024 IkReal x128=IKcos(j3);
1025 IkReal x129=(cj2)*(cj2);
1026 IkReal x130=((cj1)*(cj2));
1027 IkReal x131=((IkReal(0.110000000000000))*(r02));
1028 IkReal x132=((py)*(sj0));
1029 IkReal x133=((cj1)*(sj2));
1030 IkReal x134=((sj1)*(sj2));
1031 IkReal x135=((cj2)*(sj2));
1032 IkReal x136=((cj2)*(sj1));
1033 IkReal x137=((IkReal(0.139000000000000))*(x135));
1034 IkReal x138=((IkReal(0.147300000000000))*(x128));
1035 IkReal x139=((IkReal(0.110000000000000))*(cj0)*(r00));
1036 IkReal x140=((IkReal(0.110000000000000))*(r01)*(sj0));
1037 IkReal x141=((IkReal(1.00000000000000))*(cj0)*(px));
1038 IkReal x142=((IkReal(0.147300000000000))*(x127));
1039 IkReal x143=((x135)*(x142));
1040 IkReal x144=((x135)*(x138));
1041 IkReal x145=((x144)+(x137));
1042 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))));
1043 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))));
1044 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))));
1045 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))));
1046 if( IKabs(evalcond[0]) > 0.000001 || IKabs(evalcond[1]) > 0.000001 || IKabs(evalcond[2]) > 0.000001 || IKabs(evalcond[3]) > 0.000001 )
1047 {
1048 continue;
1049 }
1050 }
1051 
1052 {
1053 IkReal dummyeval[1];
1054 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))));
1055 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1056 {
1057 {
1058 IkReal dummyeval[1];
1059 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(sj3)))+(((cj3)*(sj2))));
1060 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1061 {
1062 {
1063 IkReal dummyeval[1];
1064 dummyeval[0]=((((IkReal(-1.00000000000000))*(cj2)*(cj3)))+(((IkReal(-1.00000000000000))*(sj2)*(sj3))));
1065 if( IKabs(dummyeval[0]) < 0.0000010000000000 )
1066 {
1067 continue;
1068 
1069 } else
1070 {
1071 {
1072 IkReal j4array[1], cj4array[1], sj4array[1];
1073 bool j4valid[1]={false};
1074 _nj4 = 1;
1075 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 )
1076  continue;
1077 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)))))));
1078 sj4array[0]=IKsin(j4array[0]);
1079 cj4array[0]=IKcos(j4array[0]);
1080 if( j4array[0] > IKPI )
1081 {
1082  j4array[0]-=IK2PI;
1083 }
1084 else if( j4array[0] < -IKPI )
1085 { j4array[0]+=IK2PI;
1086 }
1087 j4valid[0] = true;
1088 for(int ij4 = 0; ij4 < 1; ++ij4)
1089 {
1090 if( !j4valid[ij4] )
1091 {
1092  continue;
1093 }
1094 _ij4[0] = ij4; _ij4[1] = -1;
1095 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1096 {
1097 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1098 {
1099  j4valid[iij4]=false; _ij4[1] = iij4; break;
1100 }
1101 }
1102 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1103 {
1104 IkReal evalcond[6];
1105 IkReal x146=IKsin(j4);
1106 IkReal x147=IKcos(j4);
1107 IkReal x148=((cj2)*(sj3));
1108 IkReal x149=((IkReal(0.147300000000000))*(cj3));
1109 IkReal x150=((IkReal(1.00000000000000))*(r01));
1110 IkReal x151=((sj0)*(sj1));
1111 IkReal x152=((IkReal(1.00000000000000))*(py));
1112 IkReal x153=((cj0)*(r00));
1113 IkReal x154=((sj2)*(sj3));
1114 IkReal x155=((cj2)*(cj3));
1115 IkReal x156=((cj1)*(sj0));
1116 IkReal x157=((IkReal(1.00000000000000))*(sj1));
1117 IkReal x158=((cj0)*(px));
1118 IkReal x159=((cj3)*(sj2));
1119 IkReal x160=((IkReal(0.110000000000000))*(x147));
1120 IkReal x161=((IkReal(1.00000000000000))*(x147));
1121 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x150)))+(x146));
1122 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x152)))+(((IkReal(0.110000000000000))*(x146)))+(((px)*(sj0))));
1123 evalcond[2]=((((r01)*(x156)))+(((r02)*(sj1)))+(((IkReal(-1.00000000000000))*(x148)*(x161)))+(((x147)*(x159)))+(((cj1)*(x153))));
1124 evalcond[3]=((((IkReal(-1.00000000000000))*(x154)*(x161)))+(((IkReal(-1.00000000000000))*(x153)*(x157)))+(((IkReal(-1.00000000000000))*(x150)*(x151)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x155)*(x161))));
1125 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))));
1126 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))));
1127 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 )
1128 {
1129 continue;
1130 }
1131 }
1132 
1133 {
1134 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
1135 vinfos[0].jointtype = 1;
1136 vinfos[0].foffset = j0;
1137 vinfos[0].indices[0] = _ij0[0];
1138 vinfos[0].indices[1] = _ij0[1];
1139 vinfos[0].maxsolutions = _nj0;
1140 vinfos[1].jointtype = 1;
1141 vinfos[1].foffset = j1;
1142 vinfos[1].indices[0] = _ij1[0];
1143 vinfos[1].indices[1] = _ij1[1];
1144 vinfos[1].maxsolutions = _nj1;
1145 vinfos[2].jointtype = 1;
1146 vinfos[2].foffset = j2;
1147 vinfos[2].indices[0] = _ij2[0];
1148 vinfos[2].indices[1] = _ij2[1];
1149 vinfos[2].maxsolutions = _nj2;
1150 vinfos[3].jointtype = 1;
1151 vinfos[3].foffset = j3;
1152 vinfos[3].indices[0] = _ij3[0];
1153 vinfos[3].indices[1] = _ij3[1];
1154 vinfos[3].maxsolutions = _nj3;
1155 vinfos[4].jointtype = 1;
1156 vinfos[4].foffset = j4;
1157 vinfos[4].indices[0] = _ij4[0];
1158 vinfos[4].indices[1] = _ij4[1];
1159 vinfos[4].maxsolutions = _nj4;
1160 std::vector<int> vfree(0);
1161 solutions.AddSolution(vinfos,vfree);
1162 }
1163 }
1164 }
1165 
1166 }
1167 
1168 }
1169 
1170 } else
1171 {
1172 {
1173 IkReal j4array[1], cj4array[1], sj4array[1];
1174 bool j4valid[1]={false};
1175 _nj4 = 1;
1176 IkReal x162=((IkReal(1.00000000000000))*(cj1));
1177 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 )
1178  continue;
1179 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)))))));
1180 sj4array[0]=IKsin(j4array[0]);
1181 cj4array[0]=IKcos(j4array[0]);
1182 if( j4array[0] > IKPI )
1183 {
1184  j4array[0]-=IK2PI;
1185 }
1186 else if( j4array[0] < -IKPI )
1187 { j4array[0]+=IK2PI;
1188 }
1189 j4valid[0] = true;
1190 for(int ij4 = 0; ij4 < 1; ++ij4)
1191 {
1192 if( !j4valid[ij4] )
1193 {
1194  continue;
1195 }
1196 _ij4[0] = ij4; _ij4[1] = -1;
1197 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1198 {
1199 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1200 {
1201  j4valid[iij4]=false; _ij4[1] = iij4; break;
1202 }
1203 }
1204 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1205 {
1206 IkReal evalcond[6];
1207 IkReal x163=IKsin(j4);
1208 IkReal x164=IKcos(j4);
1209 IkReal x165=((cj2)*(sj3));
1210 IkReal x166=((IkReal(0.147300000000000))*(cj3));
1211 IkReal x167=((IkReal(1.00000000000000))*(r01));
1212 IkReal x168=((sj0)*(sj1));
1213 IkReal x169=((IkReal(1.00000000000000))*(py));
1214 IkReal x170=((cj0)*(r00));
1215 IkReal x171=((sj2)*(sj3));
1216 IkReal x172=((cj2)*(cj3));
1217 IkReal x173=((cj1)*(sj0));
1218 IkReal x174=((IkReal(1.00000000000000))*(sj1));
1219 IkReal x175=((cj0)*(px));
1220 IkReal x176=((cj3)*(sj2));
1221 IkReal x177=((IkReal(0.110000000000000))*(x164));
1222 IkReal x178=((IkReal(1.00000000000000))*(x164));
1223 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x167)))+(x163));
1224 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x169)))+(((IkReal(0.110000000000000))*(x163)))+(((px)*(sj0))));
1225 evalcond[2]=((((r01)*(x173)))+(((r02)*(sj1)))+(((x164)*(x176)))+(((cj1)*(x170)))+(((IkReal(-1.00000000000000))*(x165)*(x178))));
1226 evalcond[3]=((((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x170)*(x174)))+(((IkReal(-1.00000000000000))*(x171)*(x178)))+(((IkReal(-1.00000000000000))*(x172)*(x178)))+(((IkReal(-1.00000000000000))*(x167)*(x168))));
1227 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))));
1228 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))));
1229 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 )
1230 {
1231 continue;
1232 }
1233 }
1234 
1235 {
1236 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
1237 vinfos[0].jointtype = 1;
1238 vinfos[0].foffset = j0;
1239 vinfos[0].indices[0] = _ij0[0];
1240 vinfos[0].indices[1] = _ij0[1];
1241 vinfos[0].maxsolutions = _nj0;
1242 vinfos[1].jointtype = 1;
1243 vinfos[1].foffset = j1;
1244 vinfos[1].indices[0] = _ij1[0];
1245 vinfos[1].indices[1] = _ij1[1];
1246 vinfos[1].maxsolutions = _nj1;
1247 vinfos[2].jointtype = 1;
1248 vinfos[2].foffset = j2;
1249 vinfos[2].indices[0] = _ij2[0];
1250 vinfos[2].indices[1] = _ij2[1];
1251 vinfos[2].maxsolutions = _nj2;
1252 vinfos[3].jointtype = 1;
1253 vinfos[3].foffset = j3;
1254 vinfos[3].indices[0] = _ij3[0];
1255 vinfos[3].indices[1] = _ij3[1];
1256 vinfos[3].maxsolutions = _nj3;
1257 vinfos[4].jointtype = 1;
1258 vinfos[4].foffset = j4;
1259 vinfos[4].indices[0] = _ij4[0];
1260 vinfos[4].indices[1] = _ij4[1];
1261 vinfos[4].maxsolutions = _nj4;
1262 std::vector<int> vfree(0);
1263 solutions.AddSolution(vinfos,vfree);
1264 }
1265 }
1266 }
1267 
1268 }
1269 
1270 }
1271 
1272 } else
1273 {
1274 {
1275 IkReal j4array[1], cj4array[1], sj4array[1];
1276 bool j4valid[1]={false};
1277 _nj4 = 1;
1278 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 )
1279  continue;
1280 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)))))));
1281 sj4array[0]=IKsin(j4array[0]);
1282 cj4array[0]=IKcos(j4array[0]);
1283 if( j4array[0] > IKPI )
1284 {
1285  j4array[0]-=IK2PI;
1286 }
1287 else if( j4array[0] < -IKPI )
1288 { j4array[0]+=IK2PI;
1289 }
1290 j4valid[0] = true;
1291 for(int ij4 = 0; ij4 < 1; ++ij4)
1292 {
1293 if( !j4valid[ij4] )
1294 {
1295  continue;
1296 }
1297 _ij4[0] = ij4; _ij4[1] = -1;
1298 for(int iij4 = ij4+1; iij4 < 1; ++iij4)
1299 {
1300 if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH )
1301 {
1302  j4valid[iij4]=false; _ij4[1] = iij4; break;
1303 }
1304 }
1305 j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4];
1306 {
1307 IkReal evalcond[6];
1308 IkReal x179=IKsin(j4);
1309 IkReal x180=IKcos(j4);
1310 IkReal x181=((cj2)*(sj3));
1311 IkReal x182=((IkReal(0.147300000000000))*(cj3));
1312 IkReal x183=((IkReal(1.00000000000000))*(r01));
1313 IkReal x184=((sj0)*(sj1));
1314 IkReal x185=((IkReal(1.00000000000000))*(py));
1315 IkReal x186=((cj0)*(r00));
1316 IkReal x187=((sj2)*(sj3));
1317 IkReal x188=((cj2)*(cj3));
1318 IkReal x189=((cj1)*(sj0));
1319 IkReal x190=((IkReal(1.00000000000000))*(sj1));
1320 IkReal x191=((cj0)*(px));
1321 IkReal x192=((cj3)*(sj2));
1322 IkReal x193=((IkReal(0.110000000000000))*(x180));
1323 IkReal x194=((IkReal(1.00000000000000))*(x180));
1324 evalcond[0]=((((r00)*(sj0)))+(((IkReal(-1.00000000000000))*(cj0)*(x183)))+(x179));
1325 evalcond[1]=((((IkReal(-1.00000000000000))*(cj0)*(x185)))+(((IkReal(0.110000000000000))*(x179)))+(((px)*(sj0))));
1326 evalcond[2]=((((r01)*(x189)))+(((x180)*(x192)))+(((r02)*(sj1)))+(((cj1)*(x186)))+(((IkReal(-1.00000000000000))*(x181)*(x194))));
1327 evalcond[3]=((((IkReal(-1.00000000000000))*(x188)*(x194)))+(((IkReal(-1.00000000000000))*(x186)*(x190)))+(((cj1)*(r02)))+(((IkReal(-1.00000000000000))*(x187)*(x194)))+(((IkReal(-1.00000000000000))*(x183)*(x184))));
1328 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))));
1329 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))));
1330 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 )
1331 {
1332 continue;
1333 }
1334 }
1335 
1336 {
1337 std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(5);
1338 vinfos[0].jointtype = 1;
1339 vinfos[0].foffset = j0;
1340 vinfos[0].indices[0] = _ij0[0];
1341 vinfos[0].indices[1] = _ij0[1];
1342 vinfos[0].maxsolutions = _nj0;
1343 vinfos[1].jointtype = 1;
1344 vinfos[1].foffset = j1;
1345 vinfos[1].indices[0] = _ij1[0];
1346 vinfos[1].indices[1] = _ij1[1];
1347 vinfos[1].maxsolutions = _nj1;
1348 vinfos[2].jointtype = 1;
1349 vinfos[2].foffset = j2;
1350 vinfos[2].indices[0] = _ij2[0];
1351 vinfos[2].indices[1] = _ij2[1];
1352 vinfos[2].maxsolutions = _nj2;
1353 vinfos[3].jointtype = 1;
1354 vinfos[3].foffset = j3;
1355 vinfos[3].indices[0] = _ij3[0];
1356 vinfos[3].indices[1] = _ij3[1];
1357 vinfos[3].maxsolutions = _nj3;
1358 vinfos[4].jointtype = 1;
1359 vinfos[4].foffset = j4;
1360 vinfos[4].indices[0] = _ij4[0];
1361 vinfos[4].indices[1] = _ij4[1];
1362 vinfos[4].maxsolutions = _nj4;
1363 std::vector<int> vfree(0);
1364 solutions.AddSolution(vinfos,vfree);
1365 }
1366 }
1367 }
1368 
1369 }
1370 
1371 }
1372 }
1373 }
1374 
1375 }
1376 
1377 }
1378 }
1379 }
1380 
1381 }
1382 
1383 }
1384  }
1385 
1386 }
1387 
1388 }
1389 }
1390 }
1391 }
1392 return solutions.GetNumSolutions()>0;
1393 }
1394 static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots)
1395 {
1396  using std::complex;
1397  IKFAST_ASSERT(rawcoeffs[0] != 0);
1398  const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon();
1399  const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon());
1400  complex<IkReal> coeffs[4];
1401  const int maxsteps = 110;
1402  for(int i = 0; i < 4; ++i) {
1403  coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]);
1404  }
1405  complex<IkReal> roots[4];
1406  IkReal err[4];
1407  roots[0] = complex<IkReal>(1,0);
1408  roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works
1409  err[0] = 1.0;
1410  err[1] = 1.0;
1411  for(int i = 2; i < 4; ++i) {
1412  roots[i] = roots[i-1]*roots[1];
1413  err[i] = 1.0;
1414  }
1415  for(int step = 0; step < maxsteps; ++step) {
1416  bool changed = false;
1417  for(int i = 0; i < 4; ++i) {
1418  if ( err[i] >= tol ) {
1419  changed = true;
1420  // evaluate
1421  complex<IkReal> x = roots[i] + coeffs[0];
1422  for(int j = 1; j < 4; ++j) {
1423  x = roots[i] * x + coeffs[j];
1424  }
1425  for(int j = 0; j < 4; ++j) {
1426  if( i != j ) {
1427  if( roots[i] != roots[j] ) {
1428  x /= (roots[i] - roots[j]);
1429  }
1430  }
1431  }
1432  roots[i] -= x;
1433  err[i] = abs(x);
1434  }
1435  }
1436  if( !changed ) {
1437  break;
1438  }
1439  }
1440 
1441  numroots = 0;
1442  bool visited[4] = {false};
1443  for(int i = 0; i < 4; ++i) {
1444  if( !visited[i] ) {
1445  // might be a multiple root, in which case it will have more error than the other roots
1446  // find any neighboring roots, and take the average
1447  complex<IkReal> newroot=roots[i];
1448  int n = 1;
1449  for(int j = i+1; j < 4; ++j) {
1450  if( abs(roots[i]-roots[j]) < 8*tolsqrt ) {
1451  newroot += roots[j];
1452  n += 1;
1453  visited[j] = true;
1454  }
1455  }
1456  if( n > 1 ) {
1457  newroot /= n;
1458  }
1459  // 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
1460  if( IKabs(imag(newroot)) < tolsqrt ) {
1461  rawroots[numroots++] = real(newroot);
1462  }
1463  }
1464  }
1465 }
1466 };
1467 
1468 
1471 IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) {
1472 IKSolver solver;
1473 return solver.ComputeIk(eetrans,eerot,pfree,solutions);
1474 }
1475 
1476 IKFAST_API const char* GetKinematicsHash() { return "<robot:genericrobot - katana_450_6m90a (0ae658000dba03e5e2af5e0545d8ad48)>"; }
1477 
1478 IKFAST_API const char* GetIkFastVersion() { return IKFAST_STRINGIZE(IKFAST_VERSION); }
1479 
1480 #ifdef IKFAST_NAMESPACE
1481 } // end namespace
1482 #endif
1483 
1484 #ifndef IKFAST_NO_MAIN
1485 #include <stdio.h>
1486 #include <stdlib.h>
1487 #ifdef IKFAST_NAMESPACE
1488 using namespace IKFAST_NAMESPACE;
1489 #endif
1490 int main(int argc, char** argv)
1491 {
1492  if( argc != 12+GetNumFreeParameters()+1 ) {
1493  printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n"
1494  "Returns the ik solutions given the transformation of the end effector specified by\n"
1495  "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n"
1496  "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters());
1497  return 1;
1498  }
1499 
1500  IkSolutionList<IkReal> solutions;
1501  std::vector<IkReal> vfree(GetNumFreeParameters());
1502  IkReal eerot[9],eetrans[3];
1503  eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]);
1504  eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]);
1505  eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]);
1506  for(std::size_t i = 0; i < vfree.size(); ++i)
1507  vfree[i] = atof(argv[13+i]);
1508  bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions);
1509 
1510  if( !bSuccess ) {
1511  fprintf(stderr,"Failed to get ik solution\n");
1512  return -1;
1513  }
1514 
1515  printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions());
1516  std::vector<IkReal> solvalues(GetNumJoints());
1517  for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) {
1518  const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i);
1519  printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size());
1520  std::vector<IkReal> vsolfree(sol.GetFree().size());
1521  sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL);
1522  for( std::size_t j = 0; j < solvalues.size(); ++j)
1523  printf("%.15f, ", solvalues[j]);
1524  printf("\n");
1525  }
1526  return 0;
1527 }
1528 
1529 #endif
Definition: ikfast.h:45
virtual const IkSolutionBase< T > & GetSolution(size_t index) const
returns the solution pointer
Definition: ikfast.h:283
IKFAST_API int * GetFreeParameters()
#define IKFAST_ATAN2_MAGTHRESH
#define IKFAST_ASSERT(b)
float IKfmod(float x, float y)
float IKlog(float f)
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)
#define IKFAST_STRINGIZE(s)
float IKatan2(float fy, float fx)
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
virtual size_t GetNumSolutions() const
returns the number of solutions stored
Definition: ikfast.h:294
IKFAST_API bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
void dgesv_(const int *n, const int *nrhs, double *a, const int *lda, int *ipiv, double *b, const int *ldb, int *info)
The discrete solutions are returned in this structure.
Definition: ikfast.h:70
float IKcos(float f)
float IKtan(float f)
virtual const std::vector< int > & GetFree() const =0
Gets the indices of the configuration space that have to be preset before a full solution can be retu...
float IKsqrt(float f)
int main(int argc, char **argv)
float IKsqr(float f)
IKFAST_API const char * GetIkFastVersion()
virtual size_t AddSolution(const std::vector< IkSingleDOFSolutionBase< T > > &vinfos, const std::vector< int > &vfree)=0
add one solution and return its index for later retrieval
#define IKFAST_SOLUTION_THRESH
INLINE Rall1d< T, V, S > atan(const Rall1d< T, V, S > &x)
IKFAST_API int GetNumFreeParameters()
float IKsin(float f)
INLINE Rall1d< T, V, S > asin(const Rall1d< T, V, S > &x)
#define IKFAST_COMPILE_ASSERT(x)
void zgetrf_(const int *m, const int *n, std::complex< double > *a, const int *lda, int *ipiv, int *info)
virtual void Clear()=0
clears all current solutions, note that any memory addresses returned from GetSolution will be invali...
IKFAST_API const char * GetKinematicsHash()
IKFAST_API int GetIkType()
IKFAST_API int GetIkRealSize()
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
float IKasin(float f)
virtual void GetSolution(T *solution, const T *freevalues) const =0
gets a concrete solution
bool ComputeIk(const IkReal *eetrans, const IkReal *eerot, const IkReal *pfree, IkSolutionListBase< IkReal > &solutions)
static void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int &numroots)
unsigned int step
IKFAST_API int GetNumJoints()
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
Default implementation of IkSolutionListBase.
Definition: ikfast.h:273
void dgetrf_(const int *m, const int *n, double *a, const int *lda, int *ipiv, int *info)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define IKFAST_VERSION
Header file for all ikfast c++ files/shared objects.
Definition: ikfast.h:43
#define IKFAST_SINCOS_THRESH
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
float IKabs(float f)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
double x
float IKsign(float f)
manages all the solutions
Definition: ikfast.h:100
void dgetri_(const int *n, const double *a, const int *lda, int *ipiv, double *work, const int *lwork, int *info)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
virtual size_t GetNumSolutions() const =0
returns the number of solutions stored
float IKacos(float f)
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)
IKFAST_API void ComputeFk(const IkReal *j, IkReal *eetrans, IkReal *eerot)


katana_moveit_ikfast_plugin
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:30