Austin Schuh | 7400da0 | 2018-01-28 19:54:58 -0800 | [diff] [blame^] | 1 | /// autogenerated analytical inverse kinematics code from ikfast program part of OpenRAVE |
| 2 | /// \author Rosen Diankov |
| 3 | /// |
| 4 | /// Licensed under the Apache License, Version 2.0 (the "License"); |
| 5 | /// you may not use this file except in compliance with the License. |
| 6 | /// You may obtain a copy of the License at |
| 7 | /// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | /// |
| 9 | /// Unless required by applicable law or agreed to in writing, software |
| 10 | /// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | /// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | /// See the License for the specific language governing permissions and |
| 13 | /// limitations under the License. |
| 14 | /// |
| 15 | /// ikfast version 0x1000004a generated on 2018-01-21 23:37:30.503597 |
| 16 | /// Generated using solver transform6d |
| 17 | /// To compile with gcc: |
| 18 | /// gcc -lstdc++ ik.cpp |
| 19 | /// To compile without any main function as a shared object (might need -llapack): |
| 20 | /// gcc -fPIC -lstdc++ -DIKFAST_NO_MAIN -DIKFAST_CLIBRARY -shared -Wl,-soname,libik.so -o libik.so ik.cpp |
| 21 | #define IKFAST_HAS_LIBRARY |
| 22 | #include "ikfast.h" // found inside share/openrave-X.Y/python/ikfast.h |
| 23 | using namespace ikfast; |
| 24 | |
| 25 | // check if the included ikfast version matches what this file was compiled with |
| 26 | #define IKFAST_COMPILE_ASSERT(x) extern int __dummy[(int)x] |
| 27 | IKFAST_COMPILE_ASSERT(IKFAST_VERSION==0x1000004a); |
| 28 | |
| 29 | #include <cmath> |
| 30 | #include <vector> |
| 31 | #include <limits> |
| 32 | #include <algorithm> |
| 33 | #include <complex> |
| 34 | |
| 35 | #ifndef IKFAST_ASSERT |
| 36 | #include <stdexcept> |
| 37 | #include <sstream> |
| 38 | #include <iostream> |
| 39 | |
| 40 | #ifdef _MSC_VER |
| 41 | #ifndef __PRETTY_FUNCTION__ |
| 42 | #define __PRETTY_FUNCTION__ __FUNCDNAME__ |
| 43 | #endif |
| 44 | #endif |
| 45 | |
| 46 | #ifndef __PRETTY_FUNCTION__ |
| 47 | #define __PRETTY_FUNCTION__ __func__ |
| 48 | #endif |
| 49 | |
| 50 | #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()); } } |
| 51 | |
| 52 | #endif |
| 53 | |
| 54 | #if defined(_MSC_VER) |
| 55 | #define IKFAST_ALIGNED16(x) __declspec(align(16)) x |
| 56 | #else |
| 57 | #define IKFAST_ALIGNED16(x) x __attribute((aligned(16))) |
| 58 | #endif |
| 59 | |
| 60 | #define IK2PI ((IkReal)6.28318530717959) |
| 61 | #define IKPI ((IkReal)3.14159265358979) |
| 62 | #define IKPI_2 ((IkReal)1.57079632679490) |
| 63 | |
| 64 | #ifdef _MSC_VER |
| 65 | #ifndef isnan |
| 66 | #define isnan _isnan |
| 67 | #endif |
| 68 | #ifndef isinf |
| 69 | #define isinf _isinf |
| 70 | #endif |
| 71 | //#ifndef isfinite |
| 72 | //#define isfinite _isfinite |
| 73 | //#endif |
| 74 | #endif // _MSC_VER |
| 75 | |
| 76 | // lapack routines |
| 77 | extern "C" { |
| 78 | void dgetrf_ (const int* m, const int* n, double* a, const int* lda, int* ipiv, int* info); |
| 79 | void zgetrf_ (const int* m, const int* n, std::complex<double>* a, const int* lda, int* ipiv, int* info); |
| 80 | void dgetri_(const int* n, const double* a, const int* lda, int* ipiv, double* work, const int* lwork, int* info); |
| 81 | void dgesv_ (const int* n, const int* nrhs, double* a, const int* lda, int* ipiv, double* b, const int* ldb, int* info); |
| 82 | 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); |
| 83 | 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); |
| 84 | } |
| 85 | |
| 86 | using namespace std; // necessary to get std math routines |
| 87 | |
| 88 | #ifdef IKFAST_NAMESPACE |
| 89 | namespace IKFAST_NAMESPACE { |
| 90 | #endif |
| 91 | |
| 92 | inline float IKabs(float f) { return fabsf(f); } |
| 93 | inline double IKabs(double f) { return fabs(f); } |
| 94 | |
| 95 | inline float IKsqr(float f) { return f*f; } |
| 96 | inline double IKsqr(double f) { return f*f; } |
| 97 | |
| 98 | inline float IKlog(float f) { return logf(f); } |
| 99 | inline double IKlog(double f) { return log(f); } |
| 100 | |
| 101 | // allows asin and acos to exceed 1. has to be smaller than thresholds used for branch conds and evaluation |
| 102 | #ifndef IKFAST_SINCOS_THRESH |
| 103 | #define IKFAST_SINCOS_THRESH ((IkReal)1e-7) |
| 104 | #endif |
| 105 | |
| 106 | // used to check input to atan2 for degenerate cases. has to be smaller than thresholds used for branch conds and evaluation |
| 107 | #ifndef IKFAST_ATAN2_MAGTHRESH |
| 108 | #define IKFAST_ATAN2_MAGTHRESH ((IkReal)1e-7) |
| 109 | #endif |
| 110 | |
| 111 | // minimum distance of separate solutions |
| 112 | #ifndef IKFAST_SOLUTION_THRESH |
| 113 | #define IKFAST_SOLUTION_THRESH ((IkReal)1e-6) |
| 114 | #endif |
| 115 | |
| 116 | // there are checkpoints in ikfast that are evaluated to make sure they are 0. This threshold speicfies by how much they can deviate |
| 117 | #ifndef IKFAST_EVALCOND_THRESH |
| 118 | #define IKFAST_EVALCOND_THRESH ((IkReal)0.00001) |
| 119 | #endif |
| 120 | |
| 121 | |
| 122 | inline float IKasin(float f) |
| 123 | { |
| 124 | IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| 125 | if( f <= -1 ) return float(-IKPI_2); |
| 126 | else if( f >= 1 ) return float(IKPI_2); |
| 127 | return asinf(f); |
| 128 | } |
| 129 | inline double IKasin(double f) |
| 130 | { |
| 131 | IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| 132 | if( f <= -1 ) return -IKPI_2; |
| 133 | else if( f >= 1 ) return IKPI_2; |
| 134 | return asin(f); |
| 135 | } |
| 136 | |
| 137 | // return positive value in [0,y) |
| 138 | inline float IKfmod(float x, float y) |
| 139 | { |
| 140 | while(x < 0) { |
| 141 | x += y; |
| 142 | } |
| 143 | return fmodf(x,y); |
| 144 | } |
| 145 | |
| 146 | // return positive value in [0,y) |
| 147 | inline double IKfmod(double x, double y) |
| 148 | { |
| 149 | while(x < 0) { |
| 150 | x += y; |
| 151 | } |
| 152 | return fmod(x,y); |
| 153 | } |
| 154 | |
| 155 | inline float IKacos(float f) |
| 156 | { |
| 157 | IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| 158 | if( f <= -1 ) return float(IKPI); |
| 159 | else if( f >= 1 ) return float(0); |
| 160 | return acosf(f); |
| 161 | } |
| 162 | inline double IKacos(double f) |
| 163 | { |
| 164 | IKFAST_ASSERT( f > -1-IKFAST_SINCOS_THRESH && f < 1+IKFAST_SINCOS_THRESH ); // any more error implies something is wrong with the solver |
| 165 | if( f <= -1 ) return IKPI; |
| 166 | else if( f >= 1 ) return 0; |
| 167 | return acos(f); |
| 168 | } |
| 169 | inline float IKsin(float f) { return sinf(f); } |
| 170 | inline double IKsin(double f) { return sin(f); } |
| 171 | inline float IKcos(float f) { return cosf(f); } |
| 172 | inline double IKcos(double f) { return cos(f); } |
| 173 | inline float IKtan(float f) { return tanf(f); } |
| 174 | inline double IKtan(double f) { return tan(f); } |
| 175 | inline float IKsqrt(float f) { if( f <= 0.0f ) return 0.0f; return sqrtf(f); } |
| 176 | inline double IKsqrt(double f) { if( f <= 0.0 ) return 0.0; return sqrt(f); } |
| 177 | inline float IKatan2Simple(float fy, float fx) { |
| 178 | return atan2f(fy,fx); |
| 179 | } |
| 180 | inline float IKatan2(float fy, float fx) { |
| 181 | if( isnan(fy) ) { |
| 182 | IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned |
| 183 | return float(IKPI_2); |
| 184 | } |
| 185 | else if( isnan(fx) ) { |
| 186 | return 0; |
| 187 | } |
| 188 | return atan2f(fy,fx); |
| 189 | } |
| 190 | inline double IKatan2Simple(double fy, double fx) { |
| 191 | return atan2(fy,fx); |
| 192 | } |
| 193 | inline double IKatan2(double fy, double fx) { |
| 194 | if( isnan(fy) ) { |
| 195 | IKFAST_ASSERT(!isnan(fx)); // if both are nan, probably wrong value will be returned |
| 196 | return IKPI_2; |
| 197 | } |
| 198 | else if( isnan(fx) ) { |
| 199 | return 0; |
| 200 | } |
| 201 | return atan2(fy,fx); |
| 202 | } |
| 203 | |
| 204 | template <typename T> |
| 205 | struct CheckValue |
| 206 | { |
| 207 | T value; |
| 208 | bool valid; |
| 209 | }; |
| 210 | |
| 211 | template <typename T> |
| 212 | inline CheckValue<T> IKatan2WithCheck(T fy, T fx, T epsilon) |
| 213 | { |
| 214 | CheckValue<T> ret; |
| 215 | ret.valid = false; |
| 216 | ret.value = 0; |
| 217 | if( !isnan(fy) && !isnan(fx) ) { |
| 218 | if( IKabs(fy) >= IKFAST_ATAN2_MAGTHRESH || IKabs(fx) > IKFAST_ATAN2_MAGTHRESH ) { |
| 219 | ret.value = IKatan2Simple(fy,fx); |
| 220 | ret.valid = true; |
| 221 | } |
| 222 | } |
| 223 | return ret; |
| 224 | } |
| 225 | |
| 226 | inline float IKsign(float f) { |
| 227 | if( f > 0 ) { |
| 228 | return float(1); |
| 229 | } |
| 230 | else if( f < 0 ) { |
| 231 | return float(-1); |
| 232 | } |
| 233 | return 0; |
| 234 | } |
| 235 | |
| 236 | inline double IKsign(double f) { |
| 237 | if( f > 0 ) { |
| 238 | return 1.0; |
| 239 | } |
| 240 | else if( f < 0 ) { |
| 241 | return -1.0; |
| 242 | } |
| 243 | return 0; |
| 244 | } |
| 245 | |
| 246 | template <typename T> |
| 247 | inline CheckValue<T> IKPowWithIntegerCheck(T f, int n) |
| 248 | { |
| 249 | CheckValue<T> ret; |
| 250 | ret.valid = true; |
| 251 | if( n == 0 ) { |
| 252 | ret.value = 1.0; |
| 253 | return ret; |
| 254 | } |
| 255 | else if( n == 1 ) |
| 256 | { |
| 257 | ret.value = f; |
| 258 | return ret; |
| 259 | } |
| 260 | else if( n < 0 ) |
| 261 | { |
| 262 | if( f == 0 ) |
| 263 | { |
| 264 | ret.valid = false; |
| 265 | ret.value = (T)1.0e30; |
| 266 | return ret; |
| 267 | } |
| 268 | if( n == -1 ) { |
| 269 | ret.value = T(1.0)/f; |
| 270 | return ret; |
| 271 | } |
| 272 | } |
| 273 | |
| 274 | int num = n > 0 ? n : -n; |
| 275 | if( num == 2 ) { |
| 276 | ret.value = f*f; |
| 277 | } |
| 278 | else if( num == 3 ) { |
| 279 | ret.value = f*f*f; |
| 280 | } |
| 281 | else { |
| 282 | ret.value = 1.0; |
| 283 | while(num>0) { |
| 284 | if( num & 1 ) { |
| 285 | ret.value *= f; |
| 286 | } |
| 287 | num >>= 1; |
| 288 | f *= f; |
| 289 | } |
| 290 | } |
| 291 | |
| 292 | if( n < 0 ) { |
| 293 | ret.value = T(1.0)/ret.value; |
| 294 | } |
| 295 | return ret; |
| 296 | } |
| 297 | |
| 298 | /// solves the forward kinematics equations. |
| 299 | /// \param pfree is an array specifying the free joints of the chain. |
| 300 | IKFAST_API void ComputeFk(const IkReal* j, IkReal* eetrans, IkReal* eerot) { |
| 301 | IkReal x0,x1,x2,x3,x4,x5,x6,x7,x8,x9,x10,x11,x12,x13,x14,x15,x16,x17,x18,x19,x20,x21,x22,x23,x24,x25,x26,x27,x28,x29,x30,x31,x32,x33,x34,x35,x36,x37,x38,x39,x40,x41,x42,x43,x44,x45,x46,x47,x48,x49,x50,x51,x52,x53,x54,x55; |
| 302 | x0=IKcos(j[0]); |
| 303 | x1=IKcos(j[2]); |
| 304 | x2=IKsin(j[0]); |
| 305 | x3=IKsin(j[1]); |
| 306 | x4=IKsin(j[2]); |
| 307 | x5=IKcos(j[3]); |
| 308 | x6=IKcos(j[1]); |
| 309 | x7=IKsin(j[3]); |
| 310 | x8=IKcos(j[5]); |
| 311 | x9=IKsin(j[5]); |
| 312 | x10=IKcos(j[4]); |
| 313 | x11=IKsin(j[4]); |
| 314 | x12=((0.02075)*x3); |
| 315 | x13=((0.03)*x5); |
| 316 | x14=((1.0)*x2); |
| 317 | x15=((1.0)*x6); |
| 318 | x16=((0.296)*x5); |
| 319 | x17=((0.03)*x11); |
| 320 | x18=((0.03)*x7); |
| 321 | x19=((1.0)*x3); |
| 322 | x20=((0.02075)*x5); |
| 323 | x21=((1.0)*x7); |
| 324 | x22=((0.03)*x10); |
| 325 | x23=(x0*x4); |
| 326 | x24=(x0*x6); |
| 327 | x25=(x2*x4); |
| 328 | x26=(x6*x7); |
| 329 | x27=(x2*x6); |
| 330 | x28=(x0*x1); |
| 331 | x29=(x1*x3); |
| 332 | x30=(x1*x5*x6); |
| 333 | x31=(x10*x4*x6); |
| 334 | x32=(x19*x28); |
| 335 | x33=(x0*x15*x5); |
| 336 | x34=(x14*x5*x6); |
| 337 | x35=(x14*x3*x4); |
| 338 | x36=((((-1.0)*x32))+x25); |
| 339 | x37=((((-1.0)*x35))+x28); |
| 340 | x38=((((-1.0)*x19*x7))+x30); |
| 341 | x39=((((-1.0)*x14*x4))+x32); |
| 342 | x40=(((x19*x23))+((x1*x14))); |
| 343 | x41=((-1.0)*x40); |
| 344 | x42=(((x14*x29))+(((1.0)*x23))); |
| 345 | x43=((-1.0)*x42); |
| 346 | x44=(((x1*x15*x7))+((x19*x5))); |
| 347 | x45=(x10*x37); |
| 348 | x46=(x11*x38); |
| 349 | x47=(x36*x5); |
| 350 | x48=(x39*x7); |
| 351 | x49=(x42*x7); |
| 352 | x50=(x10*x41); |
| 353 | x51=(x47+(((-1.0)*x0*x15*x7))); |
| 354 | x52=(x31+x46); |
| 355 | x53=((((-1.0)*x14*x26))+((x43*x5))); |
| 356 | x54=(((x11*x51))+x50); |
| 357 | x55=(((x11*x53))+x45); |
| 358 | eerot[0]=(((x8*((x33+(((-1.0)*x21*x39))))))+((x54*x9))); |
| 359 | eerot[1]=(((x54*x8))+((x9*(((((-1.0)*x33))+x48))))); |
| 360 | eerot[2]=(((x11*x40))+((x10*x51))); |
| 361 | eetrans[0]=(((x7*(((((-0.296)*x28*x3))+(((0.296)*x25))))))+((x9*((((x17*x51))+((x22*x41))))))+((x8*(((((-1.0)*x18*x39))+((x13*x24))))))+((x11*((((x20*x36))+(((-0.02075)*x24*x7))))))+(((0.416)*x24))+((x16*x24))+((x10*(((((-0.02075)*x1*x2))+(((-1.0)*x12*x23))))))); |
| 362 | eerot[3]=(((x55*x9))+((x8*((x34+(((-1.0)*x21*x42))))))); |
| 363 | eerot[4]=(((x9*(((((-1.0)*x34))+x49))))+((x55*x8))); |
| 364 | eerot[5]=(((x11*(((((-1.0)*x28))+x35))))+((x10*x53))); |
| 365 | eetrans[1]=(((x10*(((((-1.0)*x12*x25))+(((0.02075)*x28))))))+((x8*(((((-1.0)*x18*x42))+((x13*x27))))))+((x9*((((x17*x53))+((x22*x37))))))+((x7*(((((-0.296)*x23))+(((-0.296)*x2*x29))))))+((x11*((((x20*x43))+(((-0.02075)*x2*x26))))))+(((0.416)*x27))+((x16*x27))); |
| 366 | eerot[6]=(((x44*x8))+((x52*x9))); |
| 367 | eerot[7]=((((-1.0)*x44*x9))+((x52*x8))); |
| 368 | eerot[8]=(((x10*x38))+(((-1.0)*x11*x15*x4))); |
| 369 | IkReal x56=(x1*x6); |
| 370 | eetrans[2]=((0.178)+(((0.02075)*x31))+((x11*(((((-1.0)*x12*x7))+((x20*x56))))))+(((0.416)*x3))+(((0.296)*x1*x26))+((x8*((((x18*x56))+((x13*x3))))))+((x16*x3))+((x9*((((x22*x4*x6))+((x17*x38))))))); |
| 371 | } |
| 372 | |
| 373 | IKFAST_API int GetNumFreeParameters() { return 0; } |
| 374 | IKFAST_API int* GetFreeParameters() { return NULL; } |
| 375 | IKFAST_API int GetNumJoints() { return 6; } |
| 376 | |
| 377 | IKFAST_API int GetIkRealSize() { return sizeof(IkReal); } |
| 378 | |
| 379 | IKFAST_API int GetIkType() { return 0x67000001; } |
| 380 | |
| 381 | class IKSolver { |
| 382 | public: |
| 383 | IkReal j0,cj0,sj0,htj0,j0mul,j1,cj1,sj1,htj1,j1mul,j2,cj2,sj2,htj2,j2mul,j3,cj3,sj3,htj3,j3mul,j4,cj4,sj4,htj4,j4mul,j5,cj5,sj5,htj5,j5mul,new_r00,r00,rxp0_0,new_r01,r01,rxp0_1,new_r02,r02,rxp0_2,new_r10,r10,rxp1_0,new_r11,r11,rxp1_1,new_r12,r12,rxp1_2,new_r20,r20,rxp2_0,new_r21,r21,rxp2_1,new_r22,r22,rxp2_2,new_px,px,npx,new_py,py,npy,new_pz,pz,npz,pp; |
| 384 | unsigned char _ij0[2], _nj0,_ij1[2], _nj1,_ij2[2], _nj2,_ij3[2], _nj3,_ij4[2], _nj4,_ij5[2], _nj5; |
| 385 | |
| 386 | IkReal j100, cj100, sj100; |
| 387 | unsigned char _ij100[2], _nj100; |
| 388 | bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) { |
| 389 | 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; j5=numeric_limits<IkReal>::quiet_NaN(); _ij5[0] = -1; _ij5[1] = -1; _nj5 = -1; |
| 390 | for(int dummyiter = 0; dummyiter < 1; ++dummyiter) { |
| 391 | solutions.Clear(); |
| 392 | r00 = eerot[0*3+0]; |
| 393 | r01 = eerot[0*3+1]; |
| 394 | r02 = eerot[0*3+2]; |
| 395 | r10 = eerot[1*3+0]; |
| 396 | r11 = eerot[1*3+1]; |
| 397 | r12 = eerot[1*3+2]; |
| 398 | r20 = eerot[2*3+0]; |
| 399 | r21 = eerot[2*3+1]; |
| 400 | r22 = eerot[2*3+2]; |
| 401 | px = eetrans[0]; py = eetrans[1]; pz = eetrans[2]; |
| 402 | |
| 403 | new_r00=r01; |
| 404 | new_r01=((-1.0)*r00); |
| 405 | new_r02=r02; |
| 406 | new_px=(px+(((-0.03)*r00))); |
| 407 | new_r10=r11; |
| 408 | new_r11=((-1.0)*r10); |
| 409 | new_r12=r12; |
| 410 | new_py=(py+(((-0.03)*r10))); |
| 411 | new_r20=r21; |
| 412 | new_r21=((-1.0)*r20); |
| 413 | new_r22=r22; |
| 414 | new_pz=((-0.178)+(((-0.03)*r20))+pz); |
| 415 | r00 = new_r00; r01 = new_r01; r02 = new_r02; r10 = new_r10; r11 = new_r11; r12 = new_r12; r20 = new_r20; r21 = new_r21; r22 = new_r22; px = new_px; py = new_py; pz = new_pz; |
| 416 | IkReal x57=((1.0)*px); |
| 417 | IkReal x58=((1.0)*pz); |
| 418 | IkReal x59=((1.0)*py); |
| 419 | pp=((px*px)+(py*py)+(pz*pz)); |
| 420 | npx=(((px*r00))+((py*r10))+((pz*r20))); |
| 421 | npy=(((px*r01))+((py*r11))+((pz*r21))); |
| 422 | npz=(((px*r02))+((py*r12))+((pz*r22))); |
| 423 | rxp0_0=((((-1.0)*r20*x59))+((pz*r10))); |
| 424 | rxp0_1=(((px*r20))+(((-1.0)*r00*x58))); |
| 425 | rxp0_2=((((-1.0)*r10*x57))+((py*r00))); |
| 426 | rxp1_0=((((-1.0)*r21*x59))+((pz*r11))); |
| 427 | rxp1_1=(((px*r21))+(((-1.0)*r01*x58))); |
| 428 | rxp1_2=((((-1.0)*r11*x57))+((py*r01))); |
| 429 | rxp2_0=(((pz*r12))+(((-1.0)*r22*x59))); |
| 430 | rxp2_1=(((px*r22))+(((-1.0)*r02*x58))); |
| 431 | rxp2_2=((((-1.0)*r12*x57))+((py*r02))); |
| 432 | { |
| 433 | IkReal j4eval[1]; |
| 434 | IkReal x60=pp*pp; |
| 435 | IkReal x61=npz*npz; |
| 436 | IkReal x62=((0.030003082397184)*npz); |
| 437 | IkReal x63=((0.114909184)*npz*pp); |
| 438 | j4eval[0]=((((2.0)*(IKabs((x63+(((-1.0)*x62)))))))+(((1.95033419776)*(IKabs(x61))))+(IKabs(((-0.00520874343240181)+(((-0.242599591936)*x61))+(((0.361482920448)*pp))+(((-0.692224)*x60)))))+(IKabs(((0.0104174868648036)+(((-1.465135013888)*x61))+(((1.384448)*x60))+(((-0.722965840896)*pp)))))+(((2.0)*(IKabs((x62+(((-1.0)*x63)))))))); |
| 439 | if( IKabs(j4eval[0]) < 0.0000000100000000 ) |
| 440 | { |
| 441 | continue; // no branches [j3, j4, j5] |
| 442 | |
| 443 | } else |
| 444 | { |
| 445 | IkReal op[8+1], zeror[8]; |
| 446 | int numroots; |
| 447 | IkReal x64=npz*npz; |
| 448 | IkReal x65=pp*pp; |
| 449 | IkReal x66=((0.030003082397184)*npz); |
| 450 | IkReal x67=((0.114909184)*npz*pp); |
| 451 | IkReal x68=(x66+(((-1.0)*x67))); |
| 452 | IkReal x69=((-0.97516709888)*x64); |
| 453 | IkReal x70=(x67+(((-1.0)*x66))); |
| 454 | IkReal x71=((-0.00520874343240181)+(((-0.242599591936)*x64))+(((0.361482920448)*pp))+(((-0.692224)*x65))); |
| 455 | op[0]=x71; |
| 456 | op[1]=x68; |
| 457 | op[2]=x69; |
| 458 | op[3]=x68; |
| 459 | op[4]=((0.0104174868648036)+(((-1.465135013888)*x64))+(((1.384448)*x65))+(((-0.722965840896)*pp))); |
| 460 | op[5]=x70; |
| 461 | op[6]=x69; |
| 462 | op[7]=x70; |
| 463 | op[8]=x71; |
| 464 | polyroots8(op,zeror,numroots); |
| 465 | IkReal j4array[8], cj4array[8], sj4array[8], tempj4array[1]; |
| 466 | int numsolutions = 0; |
| 467 | for(int ij4 = 0; ij4 < numroots; ++ij4) |
| 468 | { |
| 469 | IkReal htj4 = zeror[ij4]; |
| 470 | tempj4array[0]=((2.0)*(atan(htj4))); |
| 471 | for(int kj4 = 0; kj4 < 1; ++kj4) |
| 472 | { |
| 473 | j4array[numsolutions] = tempj4array[kj4]; |
| 474 | if( j4array[numsolutions] > IKPI ) |
| 475 | { |
| 476 | j4array[numsolutions]-=IK2PI; |
| 477 | } |
| 478 | else if( j4array[numsolutions] < -IKPI ) |
| 479 | { |
| 480 | j4array[numsolutions]+=IK2PI; |
| 481 | } |
| 482 | sj4array[numsolutions] = IKsin(j4array[numsolutions]); |
| 483 | cj4array[numsolutions] = IKcos(j4array[numsolutions]); |
| 484 | numsolutions++; |
| 485 | } |
| 486 | } |
| 487 | bool j4valid[8]={true,true,true,true,true,true,true,true}; |
| 488 | _nj4 = 8; |
| 489 | for(int ij4 = 0; ij4 < numsolutions; ++ij4) |
| 490 | { |
| 491 | if( !j4valid[ij4] ) |
| 492 | { |
| 493 | continue; |
| 494 | } |
| 495 | j4 = j4array[ij4]; cj4 = cj4array[ij4]; sj4 = sj4array[ij4]; |
| 496 | htj4 = IKtan(j4/2); |
| 497 | |
| 498 | _ij4[0] = ij4; _ij4[1] = -1; |
| 499 | for(int iij4 = ij4+1; iij4 < numsolutions; ++iij4) |
| 500 | { |
| 501 | if( j4valid[iij4] && IKabs(cj4array[ij4]-cj4array[iij4]) < IKFAST_SOLUTION_THRESH && IKabs(sj4array[ij4]-sj4array[iij4]) < IKFAST_SOLUTION_THRESH ) |
| 502 | { |
| 503 | j4valid[iij4]=false; _ij4[1] = iij4; break; |
| 504 | } |
| 505 | } |
| 506 | { |
| 507 | IkReal j3eval[1]; |
| 508 | j3eval[0]=cj4; |
| 509 | if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| 510 | { |
| 511 | { |
| 512 | IkReal j5eval[2]; |
| 513 | IkReal x72=cj4*cj4; |
| 514 | j5eval[0]=(((x72*(npx*npx)))+((x72*(npy*npy)))); |
| 515 | j5eval[1]=((IKabs((cj4*npy)))+(IKabs((cj4*npx)))); |
| 516 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 ) |
| 517 | { |
| 518 | { |
| 519 | IkReal evalcond[2]; |
| 520 | bool bgotonextstatement = true; |
| 521 | do |
| 522 | { |
| 523 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| 524 | evalcond[1]=npz; |
| 525 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 526 | { |
| 527 | bgotonextstatement=false; |
| 528 | { |
| 529 | IkReal j3array[2], cj3array[2], sj3array[2]; |
| 530 | bool j3valid[2]={false}; |
| 531 | _nj3 = 2; |
| 532 | if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH ) |
| 533 | continue; |
| 534 | IkReal x73=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp)))); |
| 535 | j3array[0]=((1.50080946872133)+(((-1.0)*x73))); |
| 536 | sj3array[0]=IKsin(j3array[0]); |
| 537 | cj3array[0]=IKcos(j3array[0]); |
| 538 | j3array[1]=((4.64240212231113)+x73); |
| 539 | sj3array[1]=IKsin(j3array[1]); |
| 540 | cj3array[1]=IKcos(j3array[1]); |
| 541 | if( j3array[0] > IKPI ) |
| 542 | { |
| 543 | j3array[0]-=IK2PI; |
| 544 | } |
| 545 | else if( j3array[0] < -IKPI ) |
| 546 | { j3array[0]+=IK2PI; |
| 547 | } |
| 548 | j3valid[0] = true; |
| 549 | if( j3array[1] > IKPI ) |
| 550 | { |
| 551 | j3array[1]-=IK2PI; |
| 552 | } |
| 553 | else if( j3array[1] < -IKPI ) |
| 554 | { j3array[1]+=IK2PI; |
| 555 | } |
| 556 | j3valid[1] = true; |
| 557 | for(int ij3 = 0; ij3 < 2; ++ij3) |
| 558 | { |
| 559 | if( !j3valid[ij3] ) |
| 560 | { |
| 561 | continue; |
| 562 | } |
| 563 | _ij3[0] = ij3; _ij3[1] = -1; |
| 564 | for(int iij3 = ij3+1; iij3 < 2; ++iij3) |
| 565 | { |
| 566 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 567 | { |
| 568 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 569 | } |
| 570 | } |
| 571 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 572 | |
| 573 | { |
| 574 | IkReal j5eval[3]; |
| 575 | sj4=1.0; |
| 576 | cj4=0; |
| 577 | j4=1.5707963267949; |
| 578 | IkReal x74=((0.416)*cj3); |
| 579 | IkReal x75=((0.416)*sj3); |
| 580 | IkReal x76=((npx*npx)+(npy*npy)); |
| 581 | j5eval[0]=x76; |
| 582 | j5eval[1]=((IKabs(((((-1.0)*npy*x74))+(((-1.0)*npx*x75))+(((0.02075)*npx))+(((-0.296)*npy)))))+(IKabs(((((-1.0)*npx*x74))+(((-0.02075)*npy))+((npy*x75))+(((-0.296)*npx)))))); |
| 583 | j5eval[2]=IKsign(x76); |
| 584 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 585 | { |
| 586 | { |
| 587 | IkReal j5eval[3]; |
| 588 | sj4=1.0; |
| 589 | cj4=0; |
| 590 | j4=1.5707963267949; |
| 591 | IkReal x77=npx*npx; |
| 592 | IkReal x78=npy*npy; |
| 593 | IkReal x79=(cj3*npy); |
| 594 | IkReal x80=(cj3*npx); |
| 595 | IkReal x81=((2000.0)*pp); |
| 596 | j5eval[0]=(x77+x78); |
| 597 | j5eval[1]=IKsign(((((83.0)*x77))+(((83.0)*x78)))); |
| 598 | j5eval[2]=((IKabs(((((492.544)*x79))+(((-24.568)*npx))+(((-34.528)*x80))+(((-1.0)*npy*x81))+(((520.482875)*npy)))))+(IKabs(((((-520.482875)*npx))+(((-492.544)*x80))+(((-24.568)*npy))+(((-34.528)*x79))+((npx*x81)))))); |
| 599 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 600 | { |
| 601 | continue; // no branches [j5] |
| 602 | |
| 603 | } else |
| 604 | { |
| 605 | { |
| 606 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 607 | bool j5valid[1]={false}; |
| 608 | _nj5 = 1; |
| 609 | IkReal x82=(cj3*npy); |
| 610 | IkReal x83=(cj3*npx); |
| 611 | IkReal x84=((2000.0)*pp); |
| 612 | CheckValue<IkReal> x85 = IKatan2WithCheck(IkReal(((((-24.568)*npx))+(((-34.528)*x83))+(((-1.0)*npy*x84))+(((492.544)*x82))+(((520.482875)*npy)))),IkReal(((((-520.482875)*npx))+(((-492.544)*x83))+(((-24.568)*npy))+(((-34.528)*x82))+((npx*x84)))),IKFAST_ATAN2_MAGTHRESH); |
| 613 | if(!x85.valid){ |
| 614 | continue; |
| 615 | } |
| 616 | CheckValue<IkReal> x86=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| 617 | if(!x86.valid){ |
| 618 | continue; |
| 619 | } |
| 620 | j5array[0]=((-1.5707963267949)+(x85.value)+(((1.5707963267949)*(x86.value)))); |
| 621 | sj5array[0]=IKsin(j5array[0]); |
| 622 | cj5array[0]=IKcos(j5array[0]); |
| 623 | if( j5array[0] > IKPI ) |
| 624 | { |
| 625 | j5array[0]-=IK2PI; |
| 626 | } |
| 627 | else if( j5array[0] < -IKPI ) |
| 628 | { j5array[0]+=IK2PI; |
| 629 | } |
| 630 | j5valid[0] = true; |
| 631 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 632 | { |
| 633 | if( !j5valid[ij5] ) |
| 634 | { |
| 635 | continue; |
| 636 | } |
| 637 | _ij5[0] = ij5; _ij5[1] = -1; |
| 638 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 639 | { |
| 640 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 641 | { |
| 642 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 643 | } |
| 644 | } |
| 645 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 646 | { |
| 647 | IkReal evalcond[3]; |
| 648 | IkReal x87=IKcos(j5); |
| 649 | IkReal x88=IKsin(j5); |
| 650 | IkReal x89=((1.0)*x87); |
| 651 | IkReal x90=(npy*x88); |
| 652 | evalcond[0]=((0.02075)+(((-0.416)*sj3))+x90+(((-1.0)*npx*x89))); |
| 653 | evalcond[1]=((-0.296)+(((-1.0)*npx*x88))+(((-0.416)*cj3))+(((-1.0)*npy*x89))); |
| 654 | evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x87))+(((-0.246272)*cj3))+pp+(((0.0415)*x90))); |
| 655 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 656 | { |
| 657 | continue; |
| 658 | } |
| 659 | } |
| 660 | |
| 661 | rotationfunction0(solutions); |
| 662 | } |
| 663 | } |
| 664 | |
| 665 | } |
| 666 | |
| 667 | } |
| 668 | |
| 669 | } else |
| 670 | { |
| 671 | { |
| 672 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 673 | bool j5valid[1]={false}; |
| 674 | _nj5 = 1; |
| 675 | IkReal x1857=((0.416)*cj3); |
| 676 | IkReal x1858=((0.416)*sj3); |
| 677 | CheckValue<IkReal> x1859 = IKatan2WithCheck(IkReal(((((-1.0)*npx*x1857))+(((-0.02075)*npy))+((npy*x1858))+(((-0.296)*npx)))),IkReal(((((-1.0)*npy*x1857))+(((-1.0)*npx*x1858))+(((0.02075)*npx))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH); |
| 678 | if(!x1859.valid){ |
| 679 | continue; |
| 680 | } |
| 681 | CheckValue<IkReal> x1860=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| 682 | if(!x1860.valid){ |
| 683 | continue; |
| 684 | } |
| 685 | j5array[0]=((-1.5707963267949)+(x1859.value)+(((1.5707963267949)*(x1860.value)))); |
| 686 | sj5array[0]=IKsin(j5array[0]); |
| 687 | cj5array[0]=IKcos(j5array[0]); |
| 688 | if( j5array[0] > IKPI ) |
| 689 | { |
| 690 | j5array[0]-=IK2PI; |
| 691 | } |
| 692 | else if( j5array[0] < -IKPI ) |
| 693 | { j5array[0]+=IK2PI; |
| 694 | } |
| 695 | j5valid[0] = true; |
| 696 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 697 | { |
| 698 | if( !j5valid[ij5] ) |
| 699 | { |
| 700 | continue; |
| 701 | } |
| 702 | _ij5[0] = ij5; _ij5[1] = -1; |
| 703 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 704 | { |
| 705 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 706 | { |
| 707 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 708 | } |
| 709 | } |
| 710 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 711 | { |
| 712 | IkReal evalcond[3]; |
| 713 | IkReal x1861=IKcos(j5); |
| 714 | IkReal x1862=IKsin(j5); |
| 715 | IkReal x1863=((1.0)*x1861); |
| 716 | IkReal x1864=(npy*x1862); |
| 717 | evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1863))+x1864); |
| 718 | evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x1862))+(((-1.0)*npy*x1863))); |
| 719 | evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((0.0415)*x1864))+(((-0.0415)*npx*x1861))); |
| 720 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 721 | { |
| 722 | continue; |
| 723 | } |
| 724 | } |
| 725 | |
| 726 | rotationfunction0(solutions); |
| 727 | } |
| 728 | } |
| 729 | |
| 730 | } |
| 731 | |
| 732 | } |
| 733 | } |
| 734 | } |
| 735 | |
| 736 | } |
| 737 | } while(0); |
| 738 | if( bgotonextstatement ) |
| 739 | { |
| 740 | bool bgotonextstatement = true; |
| 741 | do |
| 742 | { |
| 743 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| 744 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 745 | { |
| 746 | bgotonextstatement=false; |
| 747 | { |
| 748 | IkReal j3array[2], cj3array[2], sj3array[2]; |
| 749 | bool j3valid[2]={false}; |
| 750 | _nj3 = 2; |
| 751 | if( (((-1.05762474974545)+(((4.05061037938089)*pp)))) < -1-IKFAST_SINCOS_THRESH || (((-1.05762474974545)+(((4.05061037938089)*pp)))) > 1+IKFAST_SINCOS_THRESH ) |
| 752 | continue; |
| 753 | IkReal x1865=IKasin(((-1.05762474974545)+(((4.05061037938089)*pp)))); |
| 754 | j3array[0]=((1.64078318486846)+(((-1.0)*x1865))); |
| 755 | sj3array[0]=IKsin(j3array[0]); |
| 756 | cj3array[0]=IKcos(j3array[0]); |
| 757 | j3array[1]=((4.78237583845825)+x1865); |
| 758 | sj3array[1]=IKsin(j3array[1]); |
| 759 | cj3array[1]=IKcos(j3array[1]); |
| 760 | if( j3array[0] > IKPI ) |
| 761 | { |
| 762 | j3array[0]-=IK2PI; |
| 763 | } |
| 764 | else if( j3array[0] < -IKPI ) |
| 765 | { j3array[0]+=IK2PI; |
| 766 | } |
| 767 | j3valid[0] = true; |
| 768 | if( j3array[1] > IKPI ) |
| 769 | { |
| 770 | j3array[1]-=IK2PI; |
| 771 | } |
| 772 | else if( j3array[1] < -IKPI ) |
| 773 | { j3array[1]+=IK2PI; |
| 774 | } |
| 775 | j3valid[1] = true; |
| 776 | for(int ij3 = 0; ij3 < 2; ++ij3) |
| 777 | { |
| 778 | if( !j3valid[ij3] ) |
| 779 | { |
| 780 | continue; |
| 781 | } |
| 782 | _ij3[0] = ij3; _ij3[1] = -1; |
| 783 | for(int iij3 = ij3+1; iij3 < 2; ++iij3) |
| 784 | { |
| 785 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 786 | { |
| 787 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 788 | } |
| 789 | } |
| 790 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 791 | |
| 792 | { |
| 793 | IkReal j5eval[3]; |
| 794 | sj4=-1.0; |
| 795 | cj4=0; |
| 796 | j4=-1.5707963267949; |
| 797 | IkReal x1866=((0.416)*cj3); |
| 798 | IkReal x1867=((0.416)*sj3); |
| 799 | IkReal x1868=((npx*npx)+(npy*npy)); |
| 800 | j5eval[0]=x1868; |
| 801 | j5eval[1]=IKsign(x1868); |
| 802 | j5eval[2]=((IKabs(((((-0.02075)*npy))+(((-1.0)*npy*x1867))+(((-1.0)*npx*x1866))+(((-0.296)*npx)))))+(IKabs(((((-1.0)*npy*x1866))+(((0.02075)*npx))+((npx*x1867))+(((-0.296)*npy)))))); |
| 803 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 804 | { |
| 805 | { |
| 806 | IkReal j5eval[3]; |
| 807 | sj4=-1.0; |
| 808 | cj4=0; |
| 809 | j4=-1.5707963267949; |
| 810 | IkReal x1869=npx*npx; |
| 811 | IkReal x1870=npy*npy; |
| 812 | IkReal x1871=(cj3*npy); |
| 813 | IkReal x1872=(cj3*npx); |
| 814 | IkReal x1873=((2000.0)*pp); |
| 815 | j5eval[0]=(x1869+x1870); |
| 816 | j5eval[1]=IKsign(((((83.0)*x1869))+(((83.0)*x1870)))); |
| 817 | j5eval[2]=((IKabs(((((-1.0)*npy*x1873))+(((-24.568)*npx))+(((-34.528)*x1872))+(((520.482875)*npy))+(((492.544)*x1871)))))+(IKabs((((npx*x1873))+(((-520.482875)*npx))+(((-492.544)*x1872))+(((-24.568)*npy))+(((-34.528)*x1871)))))); |
| 818 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 819 | { |
| 820 | continue; // no branches [j5] |
| 821 | |
| 822 | } else |
| 823 | { |
| 824 | { |
| 825 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 826 | bool j5valid[1]={false}; |
| 827 | _nj5 = 1; |
| 828 | IkReal x1874=(cj3*npy); |
| 829 | IkReal x1875=(cj3*npx); |
| 830 | IkReal x1876=((2000.0)*pp); |
| 831 | CheckValue<IkReal> x1877 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1876))+(((-24.568)*npx))+(((-34.528)*x1875))+(((520.482875)*npy))+(((492.544)*x1874)))),IkReal((((npx*x1876))+(((-520.482875)*npx))+(((-492.544)*x1875))+(((-24.568)*npy))+(((-34.528)*x1874)))),IKFAST_ATAN2_MAGTHRESH); |
| 832 | if(!x1877.valid){ |
| 833 | continue; |
| 834 | } |
| 835 | CheckValue<IkReal> x1878=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| 836 | if(!x1878.valid){ |
| 837 | continue; |
| 838 | } |
| 839 | j5array[0]=((-1.5707963267949)+(x1877.value)+(((1.5707963267949)*(x1878.value)))); |
| 840 | sj5array[0]=IKsin(j5array[0]); |
| 841 | cj5array[0]=IKcos(j5array[0]); |
| 842 | if( j5array[0] > IKPI ) |
| 843 | { |
| 844 | j5array[0]-=IK2PI; |
| 845 | } |
| 846 | else if( j5array[0] < -IKPI ) |
| 847 | { j5array[0]+=IK2PI; |
| 848 | } |
| 849 | j5valid[0] = true; |
| 850 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 851 | { |
| 852 | if( !j5valid[ij5] ) |
| 853 | { |
| 854 | continue; |
| 855 | } |
| 856 | _ij5[0] = ij5; _ij5[1] = -1; |
| 857 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 858 | { |
| 859 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 860 | { |
| 861 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 862 | } |
| 863 | } |
| 864 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 865 | { |
| 866 | IkReal evalcond[3]; |
| 867 | IkReal x1879=IKcos(j5); |
| 868 | IkReal x1880=IKsin(j5); |
| 869 | IkReal x1881=((1.0)*x1879); |
| 870 | IkReal x1882=(npy*x1880); |
| 871 | evalcond[0]=((0.02075)+(((-1.0)*npx*x1881))+x1882+(((0.416)*sj3))); |
| 872 | evalcond[1]=((-0.296)+(((-1.0)*npx*x1880))+(((-0.416)*cj3))+(((-1.0)*npy*x1881))); |
| 873 | evalcond[2]=((-0.2602414375)+(((0.0415)*x1882))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1879))); |
| 874 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 875 | { |
| 876 | continue; |
| 877 | } |
| 878 | } |
| 879 | |
| 880 | rotationfunction0(solutions); |
| 881 | } |
| 882 | } |
| 883 | |
| 884 | } |
| 885 | |
| 886 | } |
| 887 | |
| 888 | } else |
| 889 | { |
| 890 | { |
| 891 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 892 | bool j5valid[1]={false}; |
| 893 | _nj5 = 1; |
| 894 | IkReal x1883=((0.416)*cj3); |
| 895 | IkReal x1884=((0.416)*sj3); |
| 896 | CheckValue<IkReal> x1885 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npx*x1883))+(((-0.296)*npx))+(((-1.0)*npy*x1884)))),IkReal(((((0.02075)*npx))+(((-0.296)*npy))+(((-1.0)*npy*x1883))+((npx*x1884)))),IKFAST_ATAN2_MAGTHRESH); |
| 897 | if(!x1885.valid){ |
| 898 | continue; |
| 899 | } |
| 900 | CheckValue<IkReal> x1886=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| 901 | if(!x1886.valid){ |
| 902 | continue; |
| 903 | } |
| 904 | j5array[0]=((-1.5707963267949)+(x1885.value)+(((1.5707963267949)*(x1886.value)))); |
| 905 | sj5array[0]=IKsin(j5array[0]); |
| 906 | cj5array[0]=IKcos(j5array[0]); |
| 907 | if( j5array[0] > IKPI ) |
| 908 | { |
| 909 | j5array[0]-=IK2PI; |
| 910 | } |
| 911 | else if( j5array[0] < -IKPI ) |
| 912 | { j5array[0]+=IK2PI; |
| 913 | } |
| 914 | j5valid[0] = true; |
| 915 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 916 | { |
| 917 | if( !j5valid[ij5] ) |
| 918 | { |
| 919 | continue; |
| 920 | } |
| 921 | _ij5[0] = ij5; _ij5[1] = -1; |
| 922 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 923 | { |
| 924 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 925 | { |
| 926 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 927 | } |
| 928 | } |
| 929 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 930 | { |
| 931 | IkReal evalcond[3]; |
| 932 | IkReal x1887=IKcos(j5); |
| 933 | IkReal x1888=IKsin(j5); |
| 934 | IkReal x1889=((1.0)*x1887); |
| 935 | IkReal x1890=(npy*x1888); |
| 936 | evalcond[0]=((0.02075)+(((-1.0)*npx*x1889))+x1890+(((0.416)*sj3))); |
| 937 | evalcond[1]=((-0.296)+(((-1.0)*npx*x1888))+(((-0.416)*cj3))+(((-1.0)*npy*x1889))); |
| 938 | evalcond[2]=((-0.2602414375)+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1887))+(((0.0415)*x1890))); |
| 939 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 940 | { |
| 941 | continue; |
| 942 | } |
| 943 | } |
| 944 | |
| 945 | rotationfunction0(solutions); |
| 946 | } |
| 947 | } |
| 948 | |
| 949 | } |
| 950 | |
| 951 | } |
| 952 | } |
| 953 | } |
| 954 | |
| 955 | } |
| 956 | } while(0); |
| 957 | if( bgotonextstatement ) |
| 958 | { |
| 959 | bool bgotonextstatement = true; |
| 960 | do |
| 961 | { |
| 962 | if( 1 ) |
| 963 | { |
| 964 | bgotonextstatement=false; |
| 965 | continue; // branch miss [j3, j5] |
| 966 | |
| 967 | } |
| 968 | } while(0); |
| 969 | if( bgotonextstatement ) |
| 970 | { |
| 971 | } |
| 972 | } |
| 973 | } |
| 974 | } |
| 975 | |
| 976 | } else |
| 977 | { |
| 978 | { |
| 979 | IkReal j5array[2], cj5array[2], sj5array[2]; |
| 980 | bool j5valid[2]={false}; |
| 981 | _nj5 = 2; |
| 982 | IkReal x1891=cj4*cj4; |
| 983 | CheckValue<IkReal> x1894 = IKatan2WithCheck(IkReal(((-1.0)*cj4*npx)),IkReal((cj4*npy)),IKFAST_ATAN2_MAGTHRESH); |
| 984 | if(!x1894.valid){ |
| 985 | continue; |
| 986 | } |
| 987 | IkReal x1892=((1.0)*(x1894.value)); |
| 988 | if(((((x1891*(npy*npy)))+((x1891*(npx*npx))))) < -0.00001) |
| 989 | continue; |
| 990 | CheckValue<IkReal> x1895=IKPowWithIntegerCheck(IKabs(IKsqrt((((x1891*(npy*npy)))+((x1891*(npx*npx)))))),-1); |
| 991 | if(!x1895.valid){ |
| 992 | continue; |
| 993 | } |
| 994 | if( (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) < -1-IKFAST_SINCOS_THRESH || (((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))) > 1+IKFAST_SINCOS_THRESH ) |
| 995 | continue; |
| 996 | IkReal x1893=IKasin(((x1895.value)*(((((0.02075)*cj4))+((npz*sj4)))))); |
| 997 | j5array[0]=((((-1.0)*x1893))+(((-1.0)*x1892))); |
| 998 | sj5array[0]=IKsin(j5array[0]); |
| 999 | cj5array[0]=IKcos(j5array[0]); |
| 1000 | j5array[1]=((3.14159265358979)+x1893+(((-1.0)*x1892))); |
| 1001 | sj5array[1]=IKsin(j5array[1]); |
| 1002 | cj5array[1]=IKcos(j5array[1]); |
| 1003 | if( j5array[0] > IKPI ) |
| 1004 | { |
| 1005 | j5array[0]-=IK2PI; |
| 1006 | } |
| 1007 | else if( j5array[0] < -IKPI ) |
| 1008 | { j5array[0]+=IK2PI; |
| 1009 | } |
| 1010 | j5valid[0] = true; |
| 1011 | if( j5array[1] > IKPI ) |
| 1012 | { |
| 1013 | j5array[1]-=IK2PI; |
| 1014 | } |
| 1015 | else if( j5array[1] < -IKPI ) |
| 1016 | { j5array[1]+=IK2PI; |
| 1017 | } |
| 1018 | j5valid[1] = true; |
| 1019 | for(int ij5 = 0; ij5 < 2; ++ij5) |
| 1020 | { |
| 1021 | if( !j5valid[ij5] ) |
| 1022 | { |
| 1023 | continue; |
| 1024 | } |
| 1025 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1026 | for(int iij5 = ij5+1; iij5 < 2; ++iij5) |
| 1027 | { |
| 1028 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1029 | { |
| 1030 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1031 | } |
| 1032 | } |
| 1033 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1034 | |
| 1035 | { |
| 1036 | IkReal j3eval[1]; |
| 1037 | j3eval[0]=cj4; |
| 1038 | if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| 1039 | { |
| 1040 | { |
| 1041 | IkReal j3eval[1]; |
| 1042 | j3eval[0]=sj4; |
| 1043 | if( IKabs(j3eval[0]) < 0.0000010000000000 ) |
| 1044 | { |
| 1045 | { |
| 1046 | IkReal evalcond[2]; |
| 1047 | bool bgotonextstatement = true; |
| 1048 | do |
| 1049 | { |
| 1050 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j4))), 6.28318530717959))); |
| 1051 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 1052 | { |
| 1053 | bgotonextstatement=false; |
| 1054 | { |
| 1055 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1056 | bool j3valid[1]={false}; |
| 1057 | _nj3 = 1; |
| 1058 | if( IKabs(((-2.40384615384615)*npz)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.06022025443412)+(((4.06055093555094)*pp)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz))+IKsqr(((-1.06022025443412)+(((4.06055093555094)*pp))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1059 | continue; |
| 1060 | j3array[0]=IKatan2(((-2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp)))); |
| 1061 | sj3array[0]=IKsin(j3array[0]); |
| 1062 | cj3array[0]=IKcos(j3array[0]); |
| 1063 | if( j3array[0] > IKPI ) |
| 1064 | { |
| 1065 | j3array[0]-=IK2PI; |
| 1066 | } |
| 1067 | else if( j3array[0] < -IKPI ) |
| 1068 | { j3array[0]+=IK2PI; |
| 1069 | } |
| 1070 | j3valid[0] = true; |
| 1071 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1072 | { |
| 1073 | if( !j3valid[ij3] ) |
| 1074 | { |
| 1075 | continue; |
| 1076 | } |
| 1077 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1078 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1079 | { |
| 1080 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1081 | { |
| 1082 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1083 | } |
| 1084 | } |
| 1085 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1086 | { |
| 1087 | IkReal evalcond[3]; |
| 1088 | IkReal x1896=IKcos(j3); |
| 1089 | evalcond[0]=((-0.2611025625)+(((-0.246272)*x1896))+pp); |
| 1090 | evalcond[1]=((((-1.0)*npz))+(((-0.416)*(IKsin(j3))))); |
| 1091 | evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1896))); |
| 1092 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1093 | { |
| 1094 | continue; |
| 1095 | } |
| 1096 | } |
| 1097 | |
| 1098 | rotationfunction0(solutions); |
| 1099 | } |
| 1100 | } |
| 1101 | |
| 1102 | } |
| 1103 | } while(0); |
| 1104 | if( bgotonextstatement ) |
| 1105 | { |
| 1106 | bool bgotonextstatement = true; |
| 1107 | do |
| 1108 | { |
| 1109 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j4)))), 6.28318530717959))); |
| 1110 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 1111 | { |
| 1112 | bgotonextstatement=false; |
| 1113 | { |
| 1114 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1115 | bool j3valid[1]={false}; |
| 1116 | _nj3 = 1; |
| 1117 | if( IKabs(((2.40384615384615)*npz)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.06022025443412)+(((4.06055093555094)*pp)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((2.40384615384615)*npz))+IKsqr(((-1.06022025443412)+(((4.06055093555094)*pp))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1118 | continue; |
| 1119 | j3array[0]=IKatan2(((2.40384615384615)*npz), ((-1.06022025443412)+(((4.06055093555094)*pp)))); |
| 1120 | sj3array[0]=IKsin(j3array[0]); |
| 1121 | cj3array[0]=IKcos(j3array[0]); |
| 1122 | if( j3array[0] > IKPI ) |
| 1123 | { |
| 1124 | j3array[0]-=IK2PI; |
| 1125 | } |
| 1126 | else if( j3array[0] < -IKPI ) |
| 1127 | { j3array[0]+=IK2PI; |
| 1128 | } |
| 1129 | j3valid[0] = true; |
| 1130 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1131 | { |
| 1132 | if( !j3valid[ij3] ) |
| 1133 | { |
| 1134 | continue; |
| 1135 | } |
| 1136 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1137 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1138 | { |
| 1139 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1140 | { |
| 1141 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1142 | } |
| 1143 | } |
| 1144 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1145 | { |
| 1146 | IkReal evalcond[3]; |
| 1147 | IkReal x1897=IKcos(j3); |
| 1148 | evalcond[0]=((-0.2611025625)+(((-0.246272)*x1897))+pp); |
| 1149 | evalcond[1]=((((-1.0)*npz))+(((0.416)*(IKsin(j3))))); |
| 1150 | evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1897))); |
| 1151 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1152 | { |
| 1153 | continue; |
| 1154 | } |
| 1155 | } |
| 1156 | |
| 1157 | rotationfunction0(solutions); |
| 1158 | } |
| 1159 | } |
| 1160 | |
| 1161 | } |
| 1162 | } while(0); |
| 1163 | if( bgotonextstatement ) |
| 1164 | { |
| 1165 | bool bgotonextstatement = true; |
| 1166 | do |
| 1167 | { |
| 1168 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| 1169 | evalcond[1]=npz; |
| 1170 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 1171 | { |
| 1172 | bgotonextstatement=false; |
| 1173 | { |
| 1174 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1175 | bool j3valid[1]={false}; |
| 1176 | _nj3 = 1; |
| 1177 | IkReal x1898=(cj5*npx); |
| 1178 | IkReal x1899=(npy*sj5); |
| 1179 | if( IKabs(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899))))+IKsqr(((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1180 | continue; |
| 1181 | j3array[0]=IKatan2(((0.0498798076923077)+(((-2.40384615384615)*x1898))+(((2.40384615384615)*x1899))), ((-1.05672361250975)+(((-0.168512863825364)*x1898))+(((4.06055093555094)*pp))+(((0.168512863825364)*x1899)))); |
| 1182 | sj3array[0]=IKsin(j3array[0]); |
| 1183 | cj3array[0]=IKcos(j3array[0]); |
| 1184 | if( j3array[0] > IKPI ) |
| 1185 | { |
| 1186 | j3array[0]-=IK2PI; |
| 1187 | } |
| 1188 | else if( j3array[0] < -IKPI ) |
| 1189 | { j3array[0]+=IK2PI; |
| 1190 | } |
| 1191 | j3valid[0] = true; |
| 1192 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1193 | { |
| 1194 | if( !j3valid[ij3] ) |
| 1195 | { |
| 1196 | continue; |
| 1197 | } |
| 1198 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1199 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1200 | { |
| 1201 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1202 | { |
| 1203 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1204 | } |
| 1205 | } |
| 1206 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1207 | { |
| 1208 | IkReal evalcond[4]; |
| 1209 | IkReal x1900=IKsin(j3); |
| 1210 | IkReal x1901=IKcos(j3); |
| 1211 | IkReal x1902=(cj5*npx); |
| 1212 | IkReal x1903=(npy*sj5); |
| 1213 | IkReal x1904=((0.246272)*x1901); |
| 1214 | evalcond[0]=((-0.2611025625)+(((0.017264)*x1900))+pp+(((-1.0)*x1904))); |
| 1215 | evalcond[1]=((0.02075)+(((-0.416)*x1900))+(((-1.0)*x1902))+x1903); |
| 1216 | evalcond[2]=((-0.296)+(((-0.416)*x1901))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| 1217 | evalcond[3]=((-0.2602414375)+(((0.0415)*x1903))+(((-0.0415)*x1902))+pp+(((-1.0)*x1904))); |
| 1218 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 1219 | { |
| 1220 | continue; |
| 1221 | } |
| 1222 | } |
| 1223 | |
| 1224 | rotationfunction0(solutions); |
| 1225 | } |
| 1226 | } |
| 1227 | |
| 1228 | } |
| 1229 | } while(0); |
| 1230 | if( bgotonextstatement ) |
| 1231 | { |
| 1232 | bool bgotonextstatement = true; |
| 1233 | do |
| 1234 | { |
| 1235 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| 1236 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 1237 | { |
| 1238 | bgotonextstatement=false; |
| 1239 | { |
| 1240 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1241 | bool j3valid[1]={false}; |
| 1242 | _nj3 = 1; |
| 1243 | IkReal x1905=(cj5*npx); |
| 1244 | IkReal x1906=(npy*sj5); |
| 1245 | if( IKabs(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906))))+IKsqr(((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1246 | continue; |
| 1247 | j3array[0]=IKatan2(((-0.0498798076923077)+(((2.40384615384615)*x1905))+(((-2.40384615384615)*x1906))), ((-1.05672361250975)+(((4.06055093555094)*pp))+(((-0.168512863825364)*x1905))+(((0.168512863825364)*x1906)))); |
| 1248 | sj3array[0]=IKsin(j3array[0]); |
| 1249 | cj3array[0]=IKcos(j3array[0]); |
| 1250 | if( j3array[0] > IKPI ) |
| 1251 | { |
| 1252 | j3array[0]-=IK2PI; |
| 1253 | } |
| 1254 | else if( j3array[0] < -IKPI ) |
| 1255 | { j3array[0]+=IK2PI; |
| 1256 | } |
| 1257 | j3valid[0] = true; |
| 1258 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1259 | { |
| 1260 | if( !j3valid[ij3] ) |
| 1261 | { |
| 1262 | continue; |
| 1263 | } |
| 1264 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1265 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1266 | { |
| 1267 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1268 | { |
| 1269 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1270 | } |
| 1271 | } |
| 1272 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1273 | { |
| 1274 | IkReal evalcond[4]; |
| 1275 | IkReal x1907=IKsin(j3); |
| 1276 | IkReal x1908=IKcos(j3); |
| 1277 | IkReal x1909=(cj5*npx); |
| 1278 | IkReal x1910=(npy*sj5); |
| 1279 | IkReal x1911=((0.246272)*x1908); |
| 1280 | evalcond[0]=((-0.2611025625)+(((-0.017264)*x1907))+pp+(((-1.0)*x1911))); |
| 1281 | evalcond[1]=((0.02075)+(((0.416)*x1907))+(((-1.0)*x1909))+x1910); |
| 1282 | evalcond[2]=((-0.296)+(((-0.416)*x1908))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| 1283 | evalcond[3]=((-0.2602414375)+(((-0.0415)*x1909))+pp+(((0.0415)*x1910))+(((-1.0)*x1911))); |
| 1284 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 1285 | { |
| 1286 | continue; |
| 1287 | } |
| 1288 | } |
| 1289 | |
| 1290 | rotationfunction0(solutions); |
| 1291 | } |
| 1292 | } |
| 1293 | |
| 1294 | } |
| 1295 | } while(0); |
| 1296 | if( bgotonextstatement ) |
| 1297 | { |
| 1298 | bool bgotonextstatement = true; |
| 1299 | do |
| 1300 | { |
| 1301 | if( 1 ) |
| 1302 | { |
| 1303 | bgotonextstatement=false; |
| 1304 | continue; // branch miss [j3] |
| 1305 | |
| 1306 | } |
| 1307 | } while(0); |
| 1308 | if( bgotonextstatement ) |
| 1309 | { |
| 1310 | } |
| 1311 | } |
| 1312 | } |
| 1313 | } |
| 1314 | } |
| 1315 | } |
| 1316 | |
| 1317 | } else |
| 1318 | { |
| 1319 | { |
| 1320 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1321 | bool j3valid[1]={false}; |
| 1322 | _nj3 = 1; |
| 1323 | IkReal x1912=(npx*sj5); |
| 1324 | IkReal x1913=(cj5*npy); |
| 1325 | CheckValue<IkReal> x1914=IKPowWithIntegerCheck(sj4,-1); |
| 1326 | if(!x1914.valid){ |
| 1327 | continue; |
| 1328 | } |
| 1329 | if( IKabs(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp))))))+IKsqr(((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1330 | continue; |
| 1331 | j3array[0]=IKatan2(((0.00092678405931418)*(x1914.value)*(((5366.91015625)+(((-37000.0)*x1912))+(((-37000.0)*x1913))+(((-62500.0)*pp))))), ((-0.711538461538462)+(((-2.40384615384615)*x1912))+(((-2.40384615384615)*x1913)))); |
| 1332 | sj3array[0]=IKsin(j3array[0]); |
| 1333 | cj3array[0]=IKcos(j3array[0]); |
| 1334 | if( j3array[0] > IKPI ) |
| 1335 | { |
| 1336 | j3array[0]-=IK2PI; |
| 1337 | } |
| 1338 | else if( j3array[0] < -IKPI ) |
| 1339 | { j3array[0]+=IK2PI; |
| 1340 | } |
| 1341 | j3valid[0] = true; |
| 1342 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1343 | { |
| 1344 | if( !j3valid[ij3] ) |
| 1345 | { |
| 1346 | continue; |
| 1347 | } |
| 1348 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1349 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1350 | { |
| 1351 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1352 | { |
| 1353 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1354 | } |
| 1355 | } |
| 1356 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1357 | { |
| 1358 | IkReal evalcond[6]; |
| 1359 | IkReal x1915=IKsin(j3); |
| 1360 | IkReal x1916=IKcos(j3); |
| 1361 | IkReal x1917=(cj5*npx); |
| 1362 | IkReal x1918=((1.0)*npz); |
| 1363 | IkReal x1919=(npy*sj5); |
| 1364 | IkReal x1920=((0.246272)*x1916); |
| 1365 | IkReal x1921=((0.416)*x1915); |
| 1366 | evalcond[0]=((((-1.0)*cj4*x1921))+(((-1.0)*x1918))); |
| 1367 | evalcond[1]=((-0.2611025625)+(((-1.0)*x1920))+pp+(((0.017264)*sj4*x1915))); |
| 1368 | evalcond[2]=((-0.296)+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))+(((-0.416)*x1916))); |
| 1369 | evalcond[3]=((0.02075)+(((-1.0)*sj4*x1921))+(((-1.0)*x1917))+x1919); |
| 1370 | evalcond[4]=((-0.2602414375)+(((-1.0)*x1920))+pp+(((-0.0415)*x1917))+(((0.0415)*x1919))); |
| 1371 | evalcond[5]=((((-1.0)*cj4*x1918))+((sj4*x1919))+(((-1.0)*x1921))+(((-1.0)*sj4*x1917))+(((0.02075)*sj4))); |
| 1372 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 1373 | { |
| 1374 | continue; |
| 1375 | } |
| 1376 | } |
| 1377 | |
| 1378 | rotationfunction0(solutions); |
| 1379 | } |
| 1380 | } |
| 1381 | |
| 1382 | } |
| 1383 | |
| 1384 | } |
| 1385 | |
| 1386 | } else |
| 1387 | { |
| 1388 | { |
| 1389 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1390 | bool j3valid[1]={false}; |
| 1391 | _nj3 = 1; |
| 1392 | CheckValue<IkReal> x1922=IKPowWithIntegerCheck(cj4,-1); |
| 1393 | if(!x1922.valid){ |
| 1394 | continue; |
| 1395 | } |
| 1396 | if( IKabs(((-2.40384615384615)*npz*(x1922.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz*(x1922.value)))+IKsqr(((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1397 | continue; |
| 1398 | j3array[0]=IKatan2(((-2.40384615384615)*npz*(x1922.value)), ((-0.711538461538462)+(((-2.40384615384615)*cj5*npy))+(((-2.40384615384615)*npx*sj5)))); |
| 1399 | sj3array[0]=IKsin(j3array[0]); |
| 1400 | cj3array[0]=IKcos(j3array[0]); |
| 1401 | if( j3array[0] > IKPI ) |
| 1402 | { |
| 1403 | j3array[0]-=IK2PI; |
| 1404 | } |
| 1405 | else if( j3array[0] < -IKPI ) |
| 1406 | { j3array[0]+=IK2PI; |
| 1407 | } |
| 1408 | j3valid[0] = true; |
| 1409 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1410 | { |
| 1411 | if( !j3valid[ij3] ) |
| 1412 | { |
| 1413 | continue; |
| 1414 | } |
| 1415 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1416 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1417 | { |
| 1418 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1419 | { |
| 1420 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1421 | } |
| 1422 | } |
| 1423 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1424 | { |
| 1425 | IkReal evalcond[6]; |
| 1426 | IkReal x1923=IKsin(j3); |
| 1427 | IkReal x1924=IKcos(j3); |
| 1428 | IkReal x1925=(cj5*npx); |
| 1429 | IkReal x1926=((1.0)*npz); |
| 1430 | IkReal x1927=(npy*sj5); |
| 1431 | IkReal x1928=((0.246272)*x1924); |
| 1432 | IkReal x1929=((0.416)*x1923); |
| 1433 | evalcond[0]=((((-1.0)*cj4*x1929))+(((-1.0)*x1926))); |
| 1434 | evalcond[1]=((-0.2611025625)+(((-1.0)*x1928))+pp+(((0.017264)*sj4*x1923))); |
| 1435 | evalcond[2]=((-0.296)+(((-0.416)*x1924))+(((-1.0)*cj5*npy))+(((-1.0)*npx*sj5))); |
| 1436 | evalcond[3]=((0.02075)+(((-1.0)*x1925))+(((-1.0)*sj4*x1929))+x1927); |
| 1437 | evalcond[4]=((-0.2602414375)+(((-0.0415)*x1925))+(((-1.0)*x1928))+pp+(((0.0415)*x1927))); |
| 1438 | evalcond[5]=(((sj4*x1927))+(((-1.0)*sj4*x1925))+(((-1.0)*cj4*x1926))+(((-1.0)*x1929))+(((0.02075)*sj4))); |
| 1439 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 1440 | { |
| 1441 | continue; |
| 1442 | } |
| 1443 | } |
| 1444 | |
| 1445 | rotationfunction0(solutions); |
| 1446 | } |
| 1447 | } |
| 1448 | |
| 1449 | } |
| 1450 | |
| 1451 | } |
| 1452 | } |
| 1453 | } |
| 1454 | |
| 1455 | } |
| 1456 | |
| 1457 | } |
| 1458 | |
| 1459 | } else |
| 1460 | { |
| 1461 | { |
| 1462 | IkReal j3array[1], cj3array[1], sj3array[1]; |
| 1463 | bool j3valid[1]={false}; |
| 1464 | _nj3 = 1; |
| 1465 | CheckValue<IkReal> x1931=IKPowWithIntegerCheck(cj4,-1); |
| 1466 | if(!x1931.valid){ |
| 1467 | continue; |
| 1468 | } |
| 1469 | IkReal x1930=x1931.value; |
| 1470 | if( IKabs(((-2.40384615384615)*npz*x1930)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-2.40384615384615)*npz*x1930))+IKsqr(((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 1471 | continue; |
| 1472 | j3array[0]=IKatan2(((-2.40384615384615)*npz*x1930), ((1.62422037422037e-5)*x1930*(((((-10375.0)*npz*sj4))+(((-65275.640625)*cj4))+(((250000.0)*cj4*pp)))))); |
| 1473 | sj3array[0]=IKsin(j3array[0]); |
| 1474 | cj3array[0]=IKcos(j3array[0]); |
| 1475 | if( j3array[0] > IKPI ) |
| 1476 | { |
| 1477 | j3array[0]-=IK2PI; |
| 1478 | } |
| 1479 | else if( j3array[0] < -IKPI ) |
| 1480 | { j3array[0]+=IK2PI; |
| 1481 | } |
| 1482 | j3valid[0] = true; |
| 1483 | for(int ij3 = 0; ij3 < 1; ++ij3) |
| 1484 | { |
| 1485 | if( !j3valid[ij3] ) |
| 1486 | { |
| 1487 | continue; |
| 1488 | } |
| 1489 | _ij3[0] = ij3; _ij3[1] = -1; |
| 1490 | for(int iij3 = ij3+1; iij3 < 1; ++iij3) |
| 1491 | { |
| 1492 | if( j3valid[iij3] && IKabs(cj3array[ij3]-cj3array[iij3]) < IKFAST_SOLUTION_THRESH && IKabs(sj3array[ij3]-sj3array[iij3]) < IKFAST_SOLUTION_THRESH ) |
| 1493 | { |
| 1494 | j3valid[iij3]=false; _ij3[1] = iij3; break; |
| 1495 | } |
| 1496 | } |
| 1497 | j3 = j3array[ij3]; cj3 = cj3array[ij3]; sj3 = sj3array[ij3]; |
| 1498 | { |
| 1499 | IkReal evalcond[2]; |
| 1500 | IkReal x1932=IKsin(j3); |
| 1501 | evalcond[0]=((((-0.416)*cj4*x1932))+(((-1.0)*npz))); |
| 1502 | evalcond[1]=((-0.2611025625)+pp+(((-0.246272)*(IKcos(j3))))+(((0.017264)*sj4*x1932))); |
| 1503 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH ) |
| 1504 | { |
| 1505 | continue; |
| 1506 | } |
| 1507 | } |
| 1508 | |
| 1509 | { |
| 1510 | IkReal j5eval[3]; |
| 1511 | IkReal x1933=((0.416)*cj3); |
| 1512 | IkReal x1934=((0.416)*sj3*sj4); |
| 1513 | IkReal x1935=((npx*npx)+(npy*npy)); |
| 1514 | j5eval[0]=x1935; |
| 1515 | j5eval[1]=((IKabs(((((-0.02075)*npy))+(((-1.0)*npx*x1933))+(((-0.296)*npx))+((npy*x1934)))))+(IKabs(((((0.02075)*npx))+(((-1.0)*npx*x1934))+(((-0.296)*npy))+(((-1.0)*npy*x1933)))))); |
| 1516 | j5eval[2]=IKsign(x1935); |
| 1517 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1518 | { |
| 1519 | { |
| 1520 | IkReal j5eval[3]; |
| 1521 | IkReal x1936=(npz*sj4); |
| 1522 | IkReal x1937=(cj4*npy); |
| 1523 | IkReal x1938=((0.416)*cj3); |
| 1524 | IkReal x1939=(cj4*npx); |
| 1525 | IkReal x1940=(((npx*x1939))+((npy*x1937))); |
| 1526 | j5eval[0]=x1940; |
| 1527 | j5eval[1]=((IKabs(((((-1.0)*x1937*x1938))+(((0.02075)*x1939))+((npx*x1936))+(((-0.296)*x1937)))))+(IKabs(((((-0.02075)*x1937))+(((-1.0)*npy*x1936))+(((-0.296)*x1939))+(((-1.0)*x1938*x1939)))))); |
| 1528 | j5eval[2]=IKsign(x1940); |
| 1529 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1530 | { |
| 1531 | { |
| 1532 | IkReal j5eval[3]; |
| 1533 | IkReal x1941=npx*npx; |
| 1534 | IkReal x1942=npy*npy; |
| 1535 | IkReal x1943=(cj3*npy); |
| 1536 | IkReal x1944=(cj3*npx); |
| 1537 | IkReal x1945=((2000.0)*pp); |
| 1538 | j5eval[0]=(x1942+x1941); |
| 1539 | j5eval[1]=IKsign(((((83.0)*x1942))+(((83.0)*x1941)))); |
| 1540 | j5eval[2]=((IKabs(((((-1.0)*npy*x1945))+(((-24.568)*npx))+(((492.544)*x1943))+(((520.482875)*npy))+(((-34.528)*x1944)))))+(IKabs(((((-520.482875)*npx))+((npx*x1945))+(((-492.544)*x1944))+(((-24.568)*npy))+(((-34.528)*x1943)))))); |
| 1541 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1542 | { |
| 1543 | { |
| 1544 | IkReal evalcond[2]; |
| 1545 | bool bgotonextstatement = true; |
| 1546 | do |
| 1547 | { |
| 1548 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j4)))), 6.28318530717959))); |
| 1549 | evalcond[1]=npz; |
| 1550 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 1551 | { |
| 1552 | bgotonextstatement=false; |
| 1553 | { |
| 1554 | IkReal j5eval[3]; |
| 1555 | sj4=1.0; |
| 1556 | cj4=0; |
| 1557 | j4=1.5707963267949; |
| 1558 | IkReal x1946=((0.416)*cj3); |
| 1559 | IkReal x1947=((0.416)*sj3); |
| 1560 | IkReal x1948=((npx*npx)+(npy*npy)); |
| 1561 | j5eval[0]=x1948; |
| 1562 | j5eval[1]=((IKabs(((((-1.0)*npx*x1947))+(((-1.0)*npy*x1946))+(((0.02075)*npx))+(((-0.296)*npy)))))+(IKabs(((((-1.0)*npx*x1946))+(((-0.02075)*npy))+((npy*x1947))+(((-0.296)*npx)))))); |
| 1563 | j5eval[2]=IKsign(x1948); |
| 1564 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1565 | { |
| 1566 | { |
| 1567 | IkReal j5eval[3]; |
| 1568 | sj4=1.0; |
| 1569 | cj4=0; |
| 1570 | j4=1.5707963267949; |
| 1571 | IkReal x1949=npx*npx; |
| 1572 | IkReal x1950=npy*npy; |
| 1573 | IkReal x1951=(cj3*npy); |
| 1574 | IkReal x1952=(cj3*npx); |
| 1575 | IkReal x1953=((2000.0)*pp); |
| 1576 | j5eval[0]=(x1949+x1950); |
| 1577 | j5eval[1]=IKsign(((((83.0)*x1950))+(((83.0)*x1949)))); |
| 1578 | j5eval[2]=((IKabs(((((-1.0)*npy*x1953))+(((492.544)*x1951))+(((-24.568)*npx))+(((520.482875)*npy))+(((-34.528)*x1952)))))+(IKabs((((npx*x1953))+(((-520.482875)*npx))+(((-492.544)*x1952))+(((-24.568)*npy))+(((-34.528)*x1951)))))); |
| 1579 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1580 | { |
| 1581 | continue; // no branches [j5] |
| 1582 | |
| 1583 | } else |
| 1584 | { |
| 1585 | { |
| 1586 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1587 | bool j5valid[1]={false}; |
| 1588 | _nj5 = 1; |
| 1589 | IkReal x1954=(cj3*npy); |
| 1590 | IkReal x1955=(cj3*npx); |
| 1591 | IkReal x1956=((2000.0)*pp); |
| 1592 | CheckValue<IkReal> x1957=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| 1593 | if(!x1957.valid){ |
| 1594 | continue; |
| 1595 | } |
| 1596 | CheckValue<IkReal> x1958 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1956))+(((492.544)*x1954))+(((-24.568)*npx))+(((520.482875)*npy))+(((-34.528)*x1955)))),IkReal((((npx*x1956))+(((-520.482875)*npx))+(((-492.544)*x1955))+(((-24.568)*npy))+(((-34.528)*x1954)))),IKFAST_ATAN2_MAGTHRESH); |
| 1597 | if(!x1958.valid){ |
| 1598 | continue; |
| 1599 | } |
| 1600 | j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1957.value)))+(x1958.value)); |
| 1601 | sj5array[0]=IKsin(j5array[0]); |
| 1602 | cj5array[0]=IKcos(j5array[0]); |
| 1603 | if( j5array[0] > IKPI ) |
| 1604 | { |
| 1605 | j5array[0]-=IK2PI; |
| 1606 | } |
| 1607 | else if( j5array[0] < -IKPI ) |
| 1608 | { j5array[0]+=IK2PI; |
| 1609 | } |
| 1610 | j5valid[0] = true; |
| 1611 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 1612 | { |
| 1613 | if( !j5valid[ij5] ) |
| 1614 | { |
| 1615 | continue; |
| 1616 | } |
| 1617 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1618 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 1619 | { |
| 1620 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1621 | { |
| 1622 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1623 | } |
| 1624 | } |
| 1625 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1626 | { |
| 1627 | IkReal evalcond[3]; |
| 1628 | IkReal x1959=IKcos(j5); |
| 1629 | IkReal x1960=IKsin(j5); |
| 1630 | IkReal x1961=((1.0)*x1959); |
| 1631 | IkReal x1962=(npy*x1960); |
| 1632 | evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1961))+x1962); |
| 1633 | evalcond[1]=((-0.296)+(((-1.0)*npx*x1960))+(((-1.0)*npy*x1961))+(((-0.416)*cj3))); |
| 1634 | evalcond[2]=((-0.2602414375)+(((0.0415)*x1962))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1959))); |
| 1635 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1636 | { |
| 1637 | continue; |
| 1638 | } |
| 1639 | } |
| 1640 | |
| 1641 | rotationfunction0(solutions); |
| 1642 | } |
| 1643 | } |
| 1644 | |
| 1645 | } |
| 1646 | |
| 1647 | } |
| 1648 | |
| 1649 | } else |
| 1650 | { |
| 1651 | { |
| 1652 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1653 | bool j5valid[1]={false}; |
| 1654 | _nj5 = 1; |
| 1655 | IkReal x1963=((0.416)*cj3); |
| 1656 | IkReal x1964=((0.416)*sj3); |
| 1657 | CheckValue<IkReal> x1965 = IKatan2WithCheck(IkReal(((((-1.0)*npx*x1963))+(((-0.02075)*npy))+((npy*x1964))+(((-0.296)*npx)))),IkReal(((((-1.0)*npx*x1964))+(((-1.0)*npy*x1963))+(((0.02075)*npx))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH); |
| 1658 | if(!x1965.valid){ |
| 1659 | continue; |
| 1660 | } |
| 1661 | CheckValue<IkReal> x1966=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| 1662 | if(!x1966.valid){ |
| 1663 | continue; |
| 1664 | } |
| 1665 | j5array[0]=((-1.5707963267949)+(x1965.value)+(((1.5707963267949)*(x1966.value)))); |
| 1666 | sj5array[0]=IKsin(j5array[0]); |
| 1667 | cj5array[0]=IKcos(j5array[0]); |
| 1668 | if( j5array[0] > IKPI ) |
| 1669 | { |
| 1670 | j5array[0]-=IK2PI; |
| 1671 | } |
| 1672 | else if( j5array[0] < -IKPI ) |
| 1673 | { j5array[0]+=IK2PI; |
| 1674 | } |
| 1675 | j5valid[0] = true; |
| 1676 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 1677 | { |
| 1678 | if( !j5valid[ij5] ) |
| 1679 | { |
| 1680 | continue; |
| 1681 | } |
| 1682 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1683 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 1684 | { |
| 1685 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1686 | { |
| 1687 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1688 | } |
| 1689 | } |
| 1690 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1691 | { |
| 1692 | IkReal evalcond[3]; |
| 1693 | IkReal x1967=IKcos(j5); |
| 1694 | IkReal x1968=IKsin(j5); |
| 1695 | IkReal x1969=((1.0)*x1967); |
| 1696 | IkReal x1970=(npy*x1968); |
| 1697 | evalcond[0]=((0.02075)+(((-0.416)*sj3))+(((-1.0)*npx*x1969))+x1970); |
| 1698 | evalcond[1]=((-0.296)+(((-1.0)*npx*x1968))+(((-1.0)*npy*x1969))+(((-0.416)*cj3))); |
| 1699 | evalcond[2]=((-0.2602414375)+(((0.0415)*x1970))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1967))); |
| 1700 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1701 | { |
| 1702 | continue; |
| 1703 | } |
| 1704 | } |
| 1705 | |
| 1706 | rotationfunction0(solutions); |
| 1707 | } |
| 1708 | } |
| 1709 | |
| 1710 | } |
| 1711 | |
| 1712 | } |
| 1713 | |
| 1714 | } |
| 1715 | } while(0); |
| 1716 | if( bgotonextstatement ) |
| 1717 | { |
| 1718 | bool bgotonextstatement = true; |
| 1719 | do |
| 1720 | { |
| 1721 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j4)))), 6.28318530717959))); |
| 1722 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 1723 | { |
| 1724 | bgotonextstatement=false; |
| 1725 | { |
| 1726 | IkReal j5eval[3]; |
| 1727 | sj4=-1.0; |
| 1728 | cj4=0; |
| 1729 | j4=-1.5707963267949; |
| 1730 | IkReal x1971=((0.416)*cj3); |
| 1731 | IkReal x1972=((0.416)*sj3); |
| 1732 | IkReal x1973=((npx*npx)+(npy*npy)); |
| 1733 | j5eval[0]=x1973; |
| 1734 | j5eval[1]=IKsign(x1973); |
| 1735 | j5eval[2]=((IKabs(((((-1.0)*npx*x1971))+(((-1.0)*npy*x1972))+(((-0.02075)*npy))+(((-0.296)*npx)))))+(IKabs(((((-1.0)*npy*x1971))+((npx*x1972))+(((0.02075)*npx))+(((-0.296)*npy)))))); |
| 1736 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1737 | { |
| 1738 | { |
| 1739 | IkReal j5eval[3]; |
| 1740 | sj4=-1.0; |
| 1741 | cj4=0; |
| 1742 | j4=-1.5707963267949; |
| 1743 | IkReal x1974=npx*npx; |
| 1744 | IkReal x1975=npy*npy; |
| 1745 | IkReal x1976=(cj3*npy); |
| 1746 | IkReal x1977=(cj3*npx); |
| 1747 | IkReal x1978=((2000.0)*pp); |
| 1748 | j5eval[0]=(x1975+x1974); |
| 1749 | j5eval[1]=IKsign(((((83.0)*x1974))+(((83.0)*x1975)))); |
| 1750 | j5eval[2]=((IKabs(((((-34.528)*x1976))+(((-520.482875)*npx))+((npx*x1978))+(((-492.544)*x1977))+(((-24.568)*npy)))))+(IKabs(((((-34.528)*x1977))+(((-1.0)*npy*x1978))+(((492.544)*x1976))+(((-24.568)*npx))+(((520.482875)*npy)))))); |
| 1751 | if( IKabs(j5eval[0]) < 0.0000010000000000 || IKabs(j5eval[1]) < 0.0000010000000000 || IKabs(j5eval[2]) < 0.0000010000000000 ) |
| 1752 | { |
| 1753 | continue; // no branches [j5] |
| 1754 | |
| 1755 | } else |
| 1756 | { |
| 1757 | { |
| 1758 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1759 | bool j5valid[1]={false}; |
| 1760 | _nj5 = 1; |
| 1761 | IkReal x1979=(cj3*npy); |
| 1762 | IkReal x1980=(cj3*npx); |
| 1763 | IkReal x1981=((2000.0)*pp); |
| 1764 | CheckValue<IkReal> x1982 = IKatan2WithCheck(IkReal(((((492.544)*x1979))+(((-1.0)*npy*x1981))+(((-24.568)*npx))+(((-34.528)*x1980))+(((520.482875)*npy)))),IkReal(((((-34.528)*x1979))+(((-520.482875)*npx))+((npx*x1981))+(((-492.544)*x1980))+(((-24.568)*npy)))),IKFAST_ATAN2_MAGTHRESH); |
| 1765 | if(!x1982.valid){ |
| 1766 | continue; |
| 1767 | } |
| 1768 | CheckValue<IkReal> x1983=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| 1769 | if(!x1983.valid){ |
| 1770 | continue; |
| 1771 | } |
| 1772 | j5array[0]=((-1.5707963267949)+(x1982.value)+(((1.5707963267949)*(x1983.value)))); |
| 1773 | sj5array[0]=IKsin(j5array[0]); |
| 1774 | cj5array[0]=IKcos(j5array[0]); |
| 1775 | if( j5array[0] > IKPI ) |
| 1776 | { |
| 1777 | j5array[0]-=IK2PI; |
| 1778 | } |
| 1779 | else if( j5array[0] < -IKPI ) |
| 1780 | { j5array[0]+=IK2PI; |
| 1781 | } |
| 1782 | j5valid[0] = true; |
| 1783 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 1784 | { |
| 1785 | if( !j5valid[ij5] ) |
| 1786 | { |
| 1787 | continue; |
| 1788 | } |
| 1789 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1790 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 1791 | { |
| 1792 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1793 | { |
| 1794 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1795 | } |
| 1796 | } |
| 1797 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1798 | { |
| 1799 | IkReal evalcond[3]; |
| 1800 | IkReal x1984=IKcos(j5); |
| 1801 | IkReal x1985=IKsin(j5); |
| 1802 | IkReal x1986=((1.0)*x1984); |
| 1803 | IkReal x1987=(npy*x1985); |
| 1804 | evalcond[0]=((0.02075)+x1987+(((-1.0)*npx*x1986))+(((0.416)*sj3))); |
| 1805 | evalcond[1]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npy*x1986))+(((-1.0)*npx*x1985))); |
| 1806 | evalcond[2]=((-0.2602414375)+(((0.0415)*x1987))+(((-0.0415)*npx*x1984))+(((-0.246272)*cj3))+pp); |
| 1807 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1808 | { |
| 1809 | continue; |
| 1810 | } |
| 1811 | } |
| 1812 | |
| 1813 | rotationfunction0(solutions); |
| 1814 | } |
| 1815 | } |
| 1816 | |
| 1817 | } |
| 1818 | |
| 1819 | } |
| 1820 | |
| 1821 | } else |
| 1822 | { |
| 1823 | { |
| 1824 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1825 | bool j5valid[1]={false}; |
| 1826 | _nj5 = 1; |
| 1827 | IkReal x1988=((0.416)*cj3); |
| 1828 | IkReal x1989=((0.416)*sj3); |
| 1829 | CheckValue<IkReal> x1990 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npy*x1989))+(((-1.0)*npx*x1988))+(((-0.296)*npx)))),IkReal((((npx*x1989))+(((0.02075)*npx))+(((-1.0)*npy*x1988))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH); |
| 1830 | if(!x1990.valid){ |
| 1831 | continue; |
| 1832 | } |
| 1833 | CheckValue<IkReal> x1991=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| 1834 | if(!x1991.valid){ |
| 1835 | continue; |
| 1836 | } |
| 1837 | j5array[0]=((-1.5707963267949)+(x1990.value)+(((1.5707963267949)*(x1991.value)))); |
| 1838 | sj5array[0]=IKsin(j5array[0]); |
| 1839 | cj5array[0]=IKcos(j5array[0]); |
| 1840 | if( j5array[0] > IKPI ) |
| 1841 | { |
| 1842 | j5array[0]-=IK2PI; |
| 1843 | } |
| 1844 | else if( j5array[0] < -IKPI ) |
| 1845 | { j5array[0]+=IK2PI; |
| 1846 | } |
| 1847 | j5valid[0] = true; |
| 1848 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 1849 | { |
| 1850 | if( !j5valid[ij5] ) |
| 1851 | { |
| 1852 | continue; |
| 1853 | } |
| 1854 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1855 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 1856 | { |
| 1857 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1858 | { |
| 1859 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1860 | } |
| 1861 | } |
| 1862 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1863 | { |
| 1864 | IkReal evalcond[3]; |
| 1865 | IkReal x1992=IKcos(j5); |
| 1866 | IkReal x1993=IKsin(j5); |
| 1867 | IkReal x1994=((1.0)*x1992); |
| 1868 | IkReal x1995=(npy*x1993); |
| 1869 | evalcond[0]=((0.02075)+(((-1.0)*npx*x1994))+x1995+(((0.416)*sj3))); |
| 1870 | evalcond[1]=((-0.296)+(((-1.0)*npy*x1994))+(((-1.0)*npx*x1993))+(((-0.416)*cj3))); |
| 1871 | evalcond[2]=((-0.2602414375)+(((0.0415)*x1995))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x1992))); |
| 1872 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH ) |
| 1873 | { |
| 1874 | continue; |
| 1875 | } |
| 1876 | } |
| 1877 | |
| 1878 | rotationfunction0(solutions); |
| 1879 | } |
| 1880 | } |
| 1881 | |
| 1882 | } |
| 1883 | |
| 1884 | } |
| 1885 | |
| 1886 | } |
| 1887 | } while(0); |
| 1888 | if( bgotonextstatement ) |
| 1889 | { |
| 1890 | bool bgotonextstatement = true; |
| 1891 | do |
| 1892 | { |
| 1893 | if( 1 ) |
| 1894 | { |
| 1895 | bgotonextstatement=false; |
| 1896 | continue; // branch miss [j5] |
| 1897 | |
| 1898 | } |
| 1899 | } while(0); |
| 1900 | if( bgotonextstatement ) |
| 1901 | { |
| 1902 | } |
| 1903 | } |
| 1904 | } |
| 1905 | } |
| 1906 | |
| 1907 | } else |
| 1908 | { |
| 1909 | { |
| 1910 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1911 | bool j5valid[1]={false}; |
| 1912 | _nj5 = 1; |
| 1913 | IkReal x1996=(cj3*npy); |
| 1914 | IkReal x1997=(cj3*npx); |
| 1915 | IkReal x1998=((2000.0)*pp); |
| 1916 | CheckValue<IkReal> x1999 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x1998))+(((-24.568)*npx))+(((-34.528)*x1997))+(((520.482875)*npy))+(((492.544)*x1996)))),IkReal(((((-520.482875)*npx))+(((-24.568)*npy))+(((-492.544)*x1997))+(((-34.528)*x1996))+((npx*x1998)))),IKFAST_ATAN2_MAGTHRESH); |
| 1917 | if(!x1999.valid){ |
| 1918 | continue; |
| 1919 | } |
| 1920 | CheckValue<IkReal> x2000=IKPowWithIntegerCheck(IKsign(((((83.0)*(npx*npx)))+(((83.0)*(npy*npy))))),-1); |
| 1921 | if(!x2000.valid){ |
| 1922 | continue; |
| 1923 | } |
| 1924 | j5array[0]=((-1.5707963267949)+(x1999.value)+(((1.5707963267949)*(x2000.value)))); |
| 1925 | sj5array[0]=IKsin(j5array[0]); |
| 1926 | cj5array[0]=IKcos(j5array[0]); |
| 1927 | if( j5array[0] > IKPI ) |
| 1928 | { |
| 1929 | j5array[0]-=IK2PI; |
| 1930 | } |
| 1931 | else if( j5array[0] < -IKPI ) |
| 1932 | { j5array[0]+=IK2PI; |
| 1933 | } |
| 1934 | j5valid[0] = true; |
| 1935 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 1936 | { |
| 1937 | if( !j5valid[ij5] ) |
| 1938 | { |
| 1939 | continue; |
| 1940 | } |
| 1941 | _ij5[0] = ij5; _ij5[1] = -1; |
| 1942 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 1943 | { |
| 1944 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 1945 | { |
| 1946 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 1947 | } |
| 1948 | } |
| 1949 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 1950 | { |
| 1951 | IkReal evalcond[5]; |
| 1952 | IkReal x2001=IKsin(j5); |
| 1953 | IkReal x2002=IKcos(j5); |
| 1954 | IkReal x2003=((0.416)*sj3); |
| 1955 | IkReal x2004=(npy*x2001); |
| 1956 | IkReal x2005=((1.0)*x2002); |
| 1957 | evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2001))+(((-1.0)*npy*x2005))); |
| 1958 | evalcond[1]=((0.02075)+(((-1.0)*npx*x2005))+x2004+(((-1.0)*sj4*x2003))); |
| 1959 | evalcond[2]=((-0.2602414375)+(((0.0415)*x2004))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2002))); |
| 1960 | evalcond[3]=(((cj4*x2004))+(((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2005))); |
| 1961 | evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*x2003))+(((-1.0)*npx*sj4*x2005))+((sj4*x2004))+(((0.02075)*sj4))); |
| 1962 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 1963 | { |
| 1964 | continue; |
| 1965 | } |
| 1966 | } |
| 1967 | |
| 1968 | rotationfunction0(solutions); |
| 1969 | } |
| 1970 | } |
| 1971 | |
| 1972 | } |
| 1973 | |
| 1974 | } |
| 1975 | |
| 1976 | } else |
| 1977 | { |
| 1978 | { |
| 1979 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 1980 | bool j5valid[1]={false}; |
| 1981 | _nj5 = 1; |
| 1982 | IkReal x2006=(npz*sj4); |
| 1983 | IkReal x2007=(cj4*npy); |
| 1984 | IkReal x2008=((0.416)*cj3); |
| 1985 | IkReal x2009=(cj4*npx); |
| 1986 | CheckValue<IkReal> x2010=IKPowWithIntegerCheck(IKsign((((npy*x2007))+((npx*x2009)))),-1); |
| 1987 | if(!x2010.valid){ |
| 1988 | continue; |
| 1989 | } |
| 1990 | CheckValue<IkReal> x2011 = IKatan2WithCheck(IkReal(((((-1.0)*npy*x2006))+(((-1.0)*x2008*x2009))+(((-0.296)*x2009))+(((-0.02075)*x2007)))),IkReal(((((-1.0)*x2007*x2008))+(((-0.296)*x2007))+(((0.02075)*x2009))+((npx*x2006)))),IKFAST_ATAN2_MAGTHRESH); |
| 1991 | if(!x2011.valid){ |
| 1992 | continue; |
| 1993 | } |
| 1994 | j5array[0]=((-1.5707963267949)+(((1.5707963267949)*(x2010.value)))+(x2011.value)); |
| 1995 | sj5array[0]=IKsin(j5array[0]); |
| 1996 | cj5array[0]=IKcos(j5array[0]); |
| 1997 | if( j5array[0] > IKPI ) |
| 1998 | { |
| 1999 | j5array[0]-=IK2PI; |
| 2000 | } |
| 2001 | else if( j5array[0] < -IKPI ) |
| 2002 | { j5array[0]+=IK2PI; |
| 2003 | } |
| 2004 | j5valid[0] = true; |
| 2005 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 2006 | { |
| 2007 | if( !j5valid[ij5] ) |
| 2008 | { |
| 2009 | continue; |
| 2010 | } |
| 2011 | _ij5[0] = ij5; _ij5[1] = -1; |
| 2012 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 2013 | { |
| 2014 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 2015 | { |
| 2016 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 2017 | } |
| 2018 | } |
| 2019 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 2020 | { |
| 2021 | IkReal evalcond[5]; |
| 2022 | IkReal x2012=IKsin(j5); |
| 2023 | IkReal x2013=IKcos(j5); |
| 2024 | IkReal x2014=((0.416)*sj3); |
| 2025 | IkReal x2015=(npy*x2012); |
| 2026 | IkReal x2016=((1.0)*x2013); |
| 2027 | evalcond[0]=((-0.296)+(((-0.416)*cj3))+(((-1.0)*npx*x2012))+(((-1.0)*npy*x2016))); |
| 2028 | evalcond[1]=((0.02075)+x2015+(((-1.0)*npx*x2016))+(((-1.0)*sj4*x2014))); |
| 2029 | evalcond[2]=((-0.2602414375)+(((-0.0415)*npx*x2013))+(((0.0415)*x2015))+(((-0.246272)*cj3))+pp); |
| 2030 | evalcond[3]=((((0.02075)*cj4))+((npz*sj4))+(((-1.0)*cj4*npx*x2016))+((cj4*x2015))); |
| 2031 | evalcond[4]=((((-1.0)*x2014))+((sj4*x2015))+(((-1.0)*cj4*npz))+(((0.02075)*sj4))+(((-1.0)*npx*sj4*x2016))); |
| 2032 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 2033 | { |
| 2034 | continue; |
| 2035 | } |
| 2036 | } |
| 2037 | |
| 2038 | rotationfunction0(solutions); |
| 2039 | } |
| 2040 | } |
| 2041 | |
| 2042 | } |
| 2043 | |
| 2044 | } |
| 2045 | |
| 2046 | } else |
| 2047 | { |
| 2048 | { |
| 2049 | IkReal j5array[1], cj5array[1], sj5array[1]; |
| 2050 | bool j5valid[1]={false}; |
| 2051 | _nj5 = 1; |
| 2052 | IkReal x2017=((0.416)*cj3); |
| 2053 | IkReal x2018=((0.416)*sj3*sj4); |
| 2054 | CheckValue<IkReal> x2019 = IKatan2WithCheck(IkReal(((((-0.02075)*npy))+(((-1.0)*npx*x2017))+(((-0.296)*npx))+((npy*x2018)))),IkReal(((((0.02075)*npx))+(((-1.0)*npx*x2018))+(((-1.0)*npy*x2017))+(((-0.296)*npy)))),IKFAST_ATAN2_MAGTHRESH); |
| 2055 | if(!x2019.valid){ |
| 2056 | continue; |
| 2057 | } |
| 2058 | CheckValue<IkReal> x2020=IKPowWithIntegerCheck(IKsign(((npx*npx)+(npy*npy))),-1); |
| 2059 | if(!x2020.valid){ |
| 2060 | continue; |
| 2061 | } |
| 2062 | j5array[0]=((-1.5707963267949)+(x2019.value)+(((1.5707963267949)*(x2020.value)))); |
| 2063 | sj5array[0]=IKsin(j5array[0]); |
| 2064 | cj5array[0]=IKcos(j5array[0]); |
| 2065 | if( j5array[0] > IKPI ) |
| 2066 | { |
| 2067 | j5array[0]-=IK2PI; |
| 2068 | } |
| 2069 | else if( j5array[0] < -IKPI ) |
| 2070 | { j5array[0]+=IK2PI; |
| 2071 | } |
| 2072 | j5valid[0] = true; |
| 2073 | for(int ij5 = 0; ij5 < 1; ++ij5) |
| 2074 | { |
| 2075 | if( !j5valid[ij5] ) |
| 2076 | { |
| 2077 | continue; |
| 2078 | } |
| 2079 | _ij5[0] = ij5; _ij5[1] = -1; |
| 2080 | for(int iij5 = ij5+1; iij5 < 1; ++iij5) |
| 2081 | { |
| 2082 | if( j5valid[iij5] && IKabs(cj5array[ij5]-cj5array[iij5]) < IKFAST_SOLUTION_THRESH && IKabs(sj5array[ij5]-sj5array[iij5]) < IKFAST_SOLUTION_THRESH ) |
| 2083 | { |
| 2084 | j5valid[iij5]=false; _ij5[1] = iij5; break; |
| 2085 | } |
| 2086 | } |
| 2087 | j5 = j5array[ij5]; cj5 = cj5array[ij5]; sj5 = sj5array[ij5]; |
| 2088 | { |
| 2089 | IkReal evalcond[5]; |
| 2090 | IkReal x2021=IKsin(j5); |
| 2091 | IkReal x2022=IKcos(j5); |
| 2092 | IkReal x2023=((0.416)*sj3); |
| 2093 | IkReal x2024=(npy*x2021); |
| 2094 | IkReal x2025=((1.0)*x2022); |
| 2095 | evalcond[0]=((-0.296)+(((-1.0)*npx*x2021))+(((-0.416)*cj3))+(((-1.0)*npy*x2025))); |
| 2096 | evalcond[1]=((0.02075)+x2024+(((-1.0)*sj4*x2023))+(((-1.0)*npx*x2025))); |
| 2097 | evalcond[2]=((-0.2602414375)+(((0.0415)*x2024))+(((-0.246272)*cj3))+pp+(((-0.0415)*npx*x2022))); |
| 2098 | evalcond[3]=((((-1.0)*cj4*npx*x2025))+((cj4*x2024))+(((0.02075)*cj4))+((npz*sj4))); |
| 2099 | evalcond[4]=((((-1.0)*cj4*npz))+(((-1.0)*npx*sj4*x2025))+(((-1.0)*x2023))+(((0.02075)*sj4))+((sj4*x2024))); |
| 2100 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 2101 | { |
| 2102 | continue; |
| 2103 | } |
| 2104 | } |
| 2105 | |
| 2106 | rotationfunction0(solutions); |
| 2107 | } |
| 2108 | } |
| 2109 | |
| 2110 | } |
| 2111 | |
| 2112 | } |
| 2113 | } |
| 2114 | } |
| 2115 | |
| 2116 | } |
| 2117 | |
| 2118 | } |
| 2119 | } |
| 2120 | |
| 2121 | } |
| 2122 | |
| 2123 | } |
| 2124 | } |
| 2125 | return solutions.GetNumSolutions()>0; |
| 2126 | } |
| 2127 | inline void rotationfunction0(IkSolutionListBase<IkReal>& solutions) { |
| 2128 | for(int rotationiter = 0; rotationiter < 1; ++rotationiter) { |
| 2129 | IkReal x91=((1.0)*sj3); |
| 2130 | IkReal x92=((1.0)*sj5); |
| 2131 | IkReal x93=((1.0)*cj5); |
| 2132 | IkReal x94=((1.0)*sj4); |
| 2133 | IkReal x95=((((-1.0)*r01*x92))+((cj5*r00))); |
| 2134 | IkReal x96=(((cj5*r10))+(((-1.0)*r11*x92))); |
| 2135 | IkReal x97=(((cj5*r20))+(((-1.0)*r21*x92))); |
| 2136 | IkReal x98=((((-1.0)*r01*x93))+(((-1.0)*r00*x92))); |
| 2137 | IkReal x99=((((-1.0)*r11*x93))+(((-1.0)*r10*x92))); |
| 2138 | IkReal x100=((((-1.0)*r21*x93))+(((-1.0)*r20*x92))); |
| 2139 | IkReal x101=(((sj4*x95))+((cj4*r02))); |
| 2140 | IkReal x102=(((sj4*x96))+((cj4*r12))); |
| 2141 | IkReal x103=(((cj4*r22))+((sj4*x97))); |
| 2142 | new_r00=(((cj4*x95))+(((-1.0)*r02*x94))); |
| 2143 | new_r01=(((sj3*x98))+((cj3*x101))); |
| 2144 | new_r02=(((cj3*x98))+(((-1.0)*x101*x91))); |
| 2145 | new_r10=((((-1.0)*r12*x94))+((cj4*x96))); |
| 2146 | new_r11=(((sj3*x99))+((cj3*x102))); |
| 2147 | new_r12=((((-1.0)*x102*x91))+((cj3*x99))); |
| 2148 | new_r20=((((-1.0)*r22*x94))+((cj4*x97))); |
| 2149 | new_r21=(((cj3*x103))+((sj3*x100))); |
| 2150 | new_r22=((((-1.0)*x103*x91))+((cj3*x100))); |
| 2151 | { |
| 2152 | IkReal j1array[2], cj1array[2], sj1array[2]; |
| 2153 | bool j1valid[2]={false}; |
| 2154 | _nj1 = 2; |
| 2155 | sj1array[0]=new_r22; |
| 2156 | if( sj1array[0] >= -1-IKFAST_SINCOS_THRESH && sj1array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 2157 | { |
| 2158 | j1valid[0] = j1valid[1] = true; |
| 2159 | j1array[0] = IKasin(sj1array[0]); |
| 2160 | cj1array[0] = IKcos(j1array[0]); |
| 2161 | sj1array[1] = sj1array[0]; |
| 2162 | j1array[1] = j1array[0] > 0 ? (IKPI-j1array[0]) : (-IKPI-j1array[0]); |
| 2163 | cj1array[1] = -cj1array[0]; |
| 2164 | } |
| 2165 | else if( isnan(sj1array[0]) ) |
| 2166 | { |
| 2167 | // probably any value will work |
| 2168 | j1valid[0] = true; |
| 2169 | cj1array[0] = 1; sj1array[0] = 0; j1array[0] = 0; |
| 2170 | } |
| 2171 | for(int ij1 = 0; ij1 < 2; ++ij1) |
| 2172 | { |
| 2173 | if( !j1valid[ij1] ) |
| 2174 | { |
| 2175 | continue; |
| 2176 | } |
| 2177 | _ij1[0] = ij1; _ij1[1] = -1; |
| 2178 | for(int iij1 = ij1+1; iij1 < 2; ++iij1) |
| 2179 | { |
| 2180 | if( j1valid[iij1] && IKabs(cj1array[ij1]-cj1array[iij1]) < IKFAST_SOLUTION_THRESH && IKabs(sj1array[ij1]-sj1array[iij1]) < IKFAST_SOLUTION_THRESH ) |
| 2181 | { |
| 2182 | j1valid[iij1]=false; _ij1[1] = iij1; break; |
| 2183 | } |
| 2184 | } |
| 2185 | j1 = j1array[ij1]; cj1 = cj1array[ij1]; sj1 = sj1array[ij1]; |
| 2186 | |
| 2187 | { |
| 2188 | IkReal j0eval[3]; |
| 2189 | j0eval[0]=cj1; |
| 2190 | j0eval[1]=IKsign(cj1); |
| 2191 | j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); |
| 2192 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 2193 | { |
| 2194 | { |
| 2195 | IkReal j2eval[3]; |
| 2196 | j2eval[0]=cj1; |
| 2197 | j2eval[1]=IKsign(cj1); |
| 2198 | j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| 2199 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 2200 | { |
| 2201 | { |
| 2202 | IkReal j0eval[2]; |
| 2203 | j0eval[0]=cj1; |
| 2204 | j0eval[1]=new_r12; |
| 2205 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 2206 | { |
| 2207 | { |
| 2208 | IkReal evalcond[5]; |
| 2209 | bool bgotonextstatement = true; |
| 2210 | do |
| 2211 | { |
| 2212 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| 2213 | evalcond[1]=new_r02; |
| 2214 | evalcond[2]=new_r12; |
| 2215 | evalcond[3]=new_r20; |
| 2216 | evalcond[4]=new_r21; |
| 2217 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 2218 | { |
| 2219 | bgotonextstatement=false; |
| 2220 | IkReal j2mul = 1; |
| 2221 | j2=0; |
| 2222 | j0mul=-1.0; |
| 2223 | if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH ) |
| 2224 | continue; |
| 2225 | j0=IKatan2(((-1.0)*new_r00), ((-1.0)*new_r01)); |
| 2226 | { |
| 2227 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2228 | vinfos[0].jointtype = 1; |
| 2229 | vinfos[0].foffset = j0; |
| 2230 | vinfos[0].fmul = j0mul; |
| 2231 | vinfos[0].freeind = 0; |
| 2232 | vinfos[0].maxsolutions = 0; |
| 2233 | vinfos[1].jointtype = 1; |
| 2234 | vinfos[1].foffset = j1; |
| 2235 | vinfos[1].indices[0] = _ij1[0]; |
| 2236 | vinfos[1].indices[1] = _ij1[1]; |
| 2237 | vinfos[1].maxsolutions = _nj1; |
| 2238 | vinfos[2].jointtype = 1; |
| 2239 | vinfos[2].foffset = j2; |
| 2240 | vinfos[2].fmul = j2mul; |
| 2241 | vinfos[2].freeind = 0; |
| 2242 | vinfos[2].maxsolutions = 0; |
| 2243 | vinfos[3].jointtype = 1; |
| 2244 | vinfos[3].foffset = j3; |
| 2245 | vinfos[3].indices[0] = _ij3[0]; |
| 2246 | vinfos[3].indices[1] = _ij3[1]; |
| 2247 | vinfos[3].maxsolutions = _nj3; |
| 2248 | vinfos[4].jointtype = 1; |
| 2249 | vinfos[4].foffset = j4; |
| 2250 | vinfos[4].indices[0] = _ij4[0]; |
| 2251 | vinfos[4].indices[1] = _ij4[1]; |
| 2252 | vinfos[4].maxsolutions = _nj4; |
| 2253 | vinfos[5].jointtype = 1; |
| 2254 | vinfos[5].foffset = j5; |
| 2255 | vinfos[5].indices[0] = _ij5[0]; |
| 2256 | vinfos[5].indices[1] = _ij5[1]; |
| 2257 | vinfos[5].maxsolutions = _nj5; |
| 2258 | std::vector<int> vfree(1); |
| 2259 | vfree[0] = 2; |
| 2260 | solutions.AddSolution(vinfos,vfree); |
| 2261 | } |
| 2262 | |
| 2263 | } |
| 2264 | } while(0); |
| 2265 | if( bgotonextstatement ) |
| 2266 | { |
| 2267 | bool bgotonextstatement = true; |
| 2268 | do |
| 2269 | { |
| 2270 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| 2271 | evalcond[1]=new_r02; |
| 2272 | evalcond[2]=new_r12; |
| 2273 | evalcond[3]=new_r20; |
| 2274 | evalcond[4]=new_r21; |
| 2275 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 2276 | { |
| 2277 | bgotonextstatement=false; |
| 2278 | IkReal j2mul = 1; |
| 2279 | j2=0; |
| 2280 | j0mul=1.0; |
| 2281 | if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH ) |
| 2282 | continue; |
| 2283 | j0=IKatan2(((-1.0)*new_r00), new_r01); |
| 2284 | { |
| 2285 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2286 | vinfos[0].jointtype = 1; |
| 2287 | vinfos[0].foffset = j0; |
| 2288 | vinfos[0].fmul = j0mul; |
| 2289 | vinfos[0].freeind = 0; |
| 2290 | vinfos[0].maxsolutions = 0; |
| 2291 | vinfos[1].jointtype = 1; |
| 2292 | vinfos[1].foffset = j1; |
| 2293 | vinfos[1].indices[0] = _ij1[0]; |
| 2294 | vinfos[1].indices[1] = _ij1[1]; |
| 2295 | vinfos[1].maxsolutions = _nj1; |
| 2296 | vinfos[2].jointtype = 1; |
| 2297 | vinfos[2].foffset = j2; |
| 2298 | vinfos[2].fmul = j2mul; |
| 2299 | vinfos[2].freeind = 0; |
| 2300 | vinfos[2].maxsolutions = 0; |
| 2301 | vinfos[3].jointtype = 1; |
| 2302 | vinfos[3].foffset = j3; |
| 2303 | vinfos[3].indices[0] = _ij3[0]; |
| 2304 | vinfos[3].indices[1] = _ij3[1]; |
| 2305 | vinfos[3].maxsolutions = _nj3; |
| 2306 | vinfos[4].jointtype = 1; |
| 2307 | vinfos[4].foffset = j4; |
| 2308 | vinfos[4].indices[0] = _ij4[0]; |
| 2309 | vinfos[4].indices[1] = _ij4[1]; |
| 2310 | vinfos[4].maxsolutions = _nj4; |
| 2311 | vinfos[5].jointtype = 1; |
| 2312 | vinfos[5].foffset = j5; |
| 2313 | vinfos[5].indices[0] = _ij5[0]; |
| 2314 | vinfos[5].indices[1] = _ij5[1]; |
| 2315 | vinfos[5].maxsolutions = _nj5; |
| 2316 | std::vector<int> vfree(1); |
| 2317 | vfree[0] = 2; |
| 2318 | solutions.AddSolution(vinfos,vfree); |
| 2319 | } |
| 2320 | |
| 2321 | } |
| 2322 | } while(0); |
| 2323 | if( bgotonextstatement ) |
| 2324 | { |
| 2325 | bool bgotonextstatement = true; |
| 2326 | do |
| 2327 | { |
| 2328 | evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02))); |
| 2329 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2330 | { |
| 2331 | bgotonextstatement=false; |
| 2332 | { |
| 2333 | IkReal j0eval[1]; |
| 2334 | new_r02=0; |
| 2335 | new_r12=0; |
| 2336 | new_r20=0; |
| 2337 | new_r21=0; |
| 2338 | IkReal x104=new_r22*new_r22; |
| 2339 | IkReal x105=((16.0)*new_r11); |
| 2340 | IkReal x106=((16.0)*new_r00); |
| 2341 | IkReal x107=((16.0)*new_r01); |
| 2342 | IkReal x108=(new_r10*new_r22); |
| 2343 | IkReal x109=((8.0)*new_r01); |
| 2344 | IkReal x110=((16.0)*x104); |
| 2345 | IkReal x111=(x104*x105); |
| 2346 | IkReal x112=(x104*x106); |
| 2347 | j0eval[0]=((IKabs(((((-1.0)*x106))+x112)))+(IKabs(((((32.0)*new_r10))+(((-1.0)*new_r10*x110))+((new_r22*x107)))))+(IKabs((((new_r22*x109))+(((8.0)*new_r10*x104)))))+(IKabs((x109+(((8.0)*x108)))))+(IKabs(((((-1.0)*x105))+x111)))+(IKabs(((((-1.0)*x112))+x106)))+(IKabs(((((32.0)*new_r01*x104))+(((16.0)*x108))+(((-1.0)*x107)))))+(IKabs(((((-1.0)*x111))+x105)))); |
| 2348 | if( IKabs(j0eval[0]) < 0.0000000100000000 ) |
| 2349 | { |
| 2350 | continue; // no branches [j0, j2] |
| 2351 | |
| 2352 | } else |
| 2353 | { |
| 2354 | IkReal op[4+1], zeror[4]; |
| 2355 | int numroots; |
| 2356 | IkReal j0evalpoly[1]; |
| 2357 | IkReal x113=new_r22*new_r22; |
| 2358 | IkReal x114=((16.0)*new_r11); |
| 2359 | IkReal x115=(new_r10*new_r22); |
| 2360 | IkReal x116=(x113*x114); |
| 2361 | IkReal x117=((((8.0)*x115))+(((8.0)*new_r01))); |
| 2362 | op[0]=x117; |
| 2363 | op[1]=((((-1.0)*x114))+x116); |
| 2364 | op[2]=((((16.0)*x115))+(((-16.0)*new_r01))+(((32.0)*new_r01*x113))); |
| 2365 | op[3]=((((-1.0)*x116))+x114); |
| 2366 | op[4]=x117; |
| 2367 | polyroots4(op,zeror,numroots); |
| 2368 | IkReal j0array[4], cj0array[4], sj0array[4], tempj0array[1]; |
| 2369 | int numsolutions = 0; |
| 2370 | for(int ij0 = 0; ij0 < numroots; ++ij0) |
| 2371 | { |
| 2372 | IkReal htj0 = zeror[ij0]; |
| 2373 | tempj0array[0]=((2.0)*(atan(htj0))); |
| 2374 | for(int kj0 = 0; kj0 < 1; ++kj0) |
| 2375 | { |
| 2376 | j0array[numsolutions] = tempj0array[kj0]; |
| 2377 | if( j0array[numsolutions] > IKPI ) |
| 2378 | { |
| 2379 | j0array[numsolutions]-=IK2PI; |
| 2380 | } |
| 2381 | else if( j0array[numsolutions] < -IKPI ) |
| 2382 | { |
| 2383 | j0array[numsolutions]+=IK2PI; |
| 2384 | } |
| 2385 | sj0array[numsolutions] = IKsin(j0array[numsolutions]); |
| 2386 | cj0array[numsolutions] = IKcos(j0array[numsolutions]); |
| 2387 | numsolutions++; |
| 2388 | } |
| 2389 | } |
| 2390 | bool j0valid[4]={true,true,true,true}; |
| 2391 | _nj0 = 4; |
| 2392 | for(int ij0 = 0; ij0 < numsolutions; ++ij0) |
| 2393 | { |
| 2394 | if( !j0valid[ij0] ) |
| 2395 | { |
| 2396 | continue; |
| 2397 | } |
| 2398 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 2399 | htj0 = IKtan(j0/2); |
| 2400 | |
| 2401 | IkReal x118=new_r22*new_r22; |
| 2402 | IkReal x119=((16.0)*new_r00); |
| 2403 | IkReal x120=(new_r01*new_r22); |
| 2404 | IkReal x121=((8.0)*x120); |
| 2405 | IkReal x122=((16.0)*x118); |
| 2406 | IkReal x123=(x118*x119); |
| 2407 | IkReal x124=((8.0)*new_r10*x118); |
| 2408 | IkReal x125=(x124+x121); |
| 2409 | j0evalpoly[0]=((((htj0*htj0)*(((((16.0)*x120))+(((32.0)*new_r10))+(((-1.0)*new_r10*x122))))))+((x125*(htj0*htj0*htj0*htj0)))+x125+(((htj0*htj0*htj0)*(((((-1.0)*x119))+x123))))+((htj0*(((((-1.0)*x123))+x119))))); |
| 2410 | if( IKabs(j0evalpoly[0]) > 0.0000001000000000 ) |
| 2411 | { |
| 2412 | continue; |
| 2413 | } |
| 2414 | _ij0[0] = ij0; _ij0[1] = -1; |
| 2415 | for(int iij0 = ij0+1; iij0 < numsolutions; ++iij0) |
| 2416 | { |
| 2417 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 2418 | { |
| 2419 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 2420 | } |
| 2421 | } |
| 2422 | { |
| 2423 | IkReal j2eval[3]; |
| 2424 | new_r02=0; |
| 2425 | new_r12=0; |
| 2426 | new_r20=0; |
| 2427 | new_r21=0; |
| 2428 | IkReal x126=cj0*cj0; |
| 2429 | IkReal x127=((1.0)*new_r00); |
| 2430 | IkReal x128=(cj0*new_r22); |
| 2431 | IkReal x129=((1.0)+((x126*(new_r22*new_r22)))+(((-1.0)*x126))); |
| 2432 | j2eval[0]=x129; |
| 2433 | j2eval[1]=((IKabs((((new_r01*sj0))+(((-1.0)*x127*x128)))))+(IKabs(((((-1.0)*new_r01*x128))+(((-1.0)*sj0*x127)))))); |
| 2434 | j2eval[2]=IKsign(x129); |
| 2435 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 2436 | { |
| 2437 | { |
| 2438 | IkReal j2eval[1]; |
| 2439 | new_r02=0; |
| 2440 | new_r12=0; |
| 2441 | new_r20=0; |
| 2442 | new_r21=0; |
| 2443 | j2eval[0]=new_r22; |
| 2444 | if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| 2445 | { |
| 2446 | { |
| 2447 | IkReal j2eval[2]; |
| 2448 | new_r02=0; |
| 2449 | new_r12=0; |
| 2450 | new_r20=0; |
| 2451 | new_r21=0; |
| 2452 | IkReal x130=new_r22*new_r22; |
| 2453 | j2eval[0]=(((cj0*x130))+(((-1.0)*cj0))); |
| 2454 | j2eval[1]=((((-1.0)*sj0))+((sj0*x130))); |
| 2455 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| 2456 | { |
| 2457 | { |
| 2458 | IkReal evalcond[1]; |
| 2459 | bool bgotonextstatement = true; |
| 2460 | do |
| 2461 | { |
| 2462 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j0)))), 6.28318530717959))); |
| 2463 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2464 | { |
| 2465 | bgotonextstatement=false; |
| 2466 | { |
| 2467 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2468 | bool j2valid[1]={false}; |
| 2469 | _nj2 = 1; |
| 2470 | if( IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r01)+IKsqr(((-1.0)*new_r00))-1) <= IKFAST_SINCOS_THRESH ) |
| 2471 | continue; |
| 2472 | j2array[0]=IKatan2(new_r01, ((-1.0)*new_r00)); |
| 2473 | sj2array[0]=IKsin(j2array[0]); |
| 2474 | cj2array[0]=IKcos(j2array[0]); |
| 2475 | if( j2array[0] > IKPI ) |
| 2476 | { |
| 2477 | j2array[0]-=IK2PI; |
| 2478 | } |
| 2479 | else if( j2array[0] < -IKPI ) |
| 2480 | { j2array[0]+=IK2PI; |
| 2481 | } |
| 2482 | j2valid[0] = true; |
| 2483 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 2484 | { |
| 2485 | if( !j2valid[ij2] ) |
| 2486 | { |
| 2487 | continue; |
| 2488 | } |
| 2489 | _ij2[0] = ij2; _ij2[1] = -1; |
| 2490 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 2491 | { |
| 2492 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 2493 | { |
| 2494 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 2495 | } |
| 2496 | } |
| 2497 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 2498 | { |
| 2499 | IkReal evalcond[4]; |
| 2500 | IkReal x131=IKcos(j2); |
| 2501 | IkReal x132=IKsin(j2); |
| 2502 | evalcond[0]=(x131+new_r00); |
| 2503 | evalcond[1]=((-1.0)*x132); |
| 2504 | evalcond[2]=((-1.0)*x131); |
| 2505 | evalcond[3]=(x132+(((-1.0)*new_r01))); |
| 2506 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 2507 | { |
| 2508 | continue; |
| 2509 | } |
| 2510 | } |
| 2511 | |
| 2512 | { |
| 2513 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2514 | vinfos[0].jointtype = 1; |
| 2515 | vinfos[0].foffset = j0; |
| 2516 | vinfos[0].indices[0] = _ij0[0]; |
| 2517 | vinfos[0].indices[1] = _ij0[1]; |
| 2518 | vinfos[0].maxsolutions = _nj0; |
| 2519 | vinfos[1].jointtype = 1; |
| 2520 | vinfos[1].foffset = j1; |
| 2521 | vinfos[1].indices[0] = _ij1[0]; |
| 2522 | vinfos[1].indices[1] = _ij1[1]; |
| 2523 | vinfos[1].maxsolutions = _nj1; |
| 2524 | vinfos[2].jointtype = 1; |
| 2525 | vinfos[2].foffset = j2; |
| 2526 | vinfos[2].indices[0] = _ij2[0]; |
| 2527 | vinfos[2].indices[1] = _ij2[1]; |
| 2528 | vinfos[2].maxsolutions = _nj2; |
| 2529 | vinfos[3].jointtype = 1; |
| 2530 | vinfos[3].foffset = j3; |
| 2531 | vinfos[3].indices[0] = _ij3[0]; |
| 2532 | vinfos[3].indices[1] = _ij3[1]; |
| 2533 | vinfos[3].maxsolutions = _nj3; |
| 2534 | vinfos[4].jointtype = 1; |
| 2535 | vinfos[4].foffset = j4; |
| 2536 | vinfos[4].indices[0] = _ij4[0]; |
| 2537 | vinfos[4].indices[1] = _ij4[1]; |
| 2538 | vinfos[4].maxsolutions = _nj4; |
| 2539 | vinfos[5].jointtype = 1; |
| 2540 | vinfos[5].foffset = j5; |
| 2541 | vinfos[5].indices[0] = _ij5[0]; |
| 2542 | vinfos[5].indices[1] = _ij5[1]; |
| 2543 | vinfos[5].maxsolutions = _nj5; |
| 2544 | std::vector<int> vfree(0); |
| 2545 | solutions.AddSolution(vinfos,vfree); |
| 2546 | } |
| 2547 | } |
| 2548 | } |
| 2549 | |
| 2550 | } |
| 2551 | } while(0); |
| 2552 | if( bgotonextstatement ) |
| 2553 | { |
| 2554 | bool bgotonextstatement = true; |
| 2555 | do |
| 2556 | { |
| 2557 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j0)))), 6.28318530717959))); |
| 2558 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2559 | { |
| 2560 | bgotonextstatement=false; |
| 2561 | { |
| 2562 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2563 | bool j2valid[1]={false}; |
| 2564 | _nj2 = 1; |
| 2565 | if( IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r01))+IKsqr(new_r00)-1) <= IKFAST_SINCOS_THRESH ) |
| 2566 | continue; |
| 2567 | j2array[0]=IKatan2(((-1.0)*new_r01), new_r00); |
| 2568 | sj2array[0]=IKsin(j2array[0]); |
| 2569 | cj2array[0]=IKcos(j2array[0]); |
| 2570 | if( j2array[0] > IKPI ) |
| 2571 | { |
| 2572 | j2array[0]-=IK2PI; |
| 2573 | } |
| 2574 | else if( j2array[0] < -IKPI ) |
| 2575 | { j2array[0]+=IK2PI; |
| 2576 | } |
| 2577 | j2valid[0] = true; |
| 2578 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 2579 | { |
| 2580 | if( !j2valid[ij2] ) |
| 2581 | { |
| 2582 | continue; |
| 2583 | } |
| 2584 | _ij2[0] = ij2; _ij2[1] = -1; |
| 2585 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 2586 | { |
| 2587 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 2588 | { |
| 2589 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 2590 | } |
| 2591 | } |
| 2592 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 2593 | { |
| 2594 | IkReal evalcond[4]; |
| 2595 | IkReal x133=IKsin(j2); |
| 2596 | IkReal x134=IKcos(j2); |
| 2597 | evalcond[0]=(x133+new_r01); |
| 2598 | evalcond[1]=((-1.0)*x133); |
| 2599 | evalcond[2]=((-1.0)*x134); |
| 2600 | evalcond[3]=(x134+(((-1.0)*new_r00))); |
| 2601 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 2602 | { |
| 2603 | continue; |
| 2604 | } |
| 2605 | } |
| 2606 | |
| 2607 | { |
| 2608 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2609 | vinfos[0].jointtype = 1; |
| 2610 | vinfos[0].foffset = j0; |
| 2611 | vinfos[0].indices[0] = _ij0[0]; |
| 2612 | vinfos[0].indices[1] = _ij0[1]; |
| 2613 | vinfos[0].maxsolutions = _nj0; |
| 2614 | vinfos[1].jointtype = 1; |
| 2615 | vinfos[1].foffset = j1; |
| 2616 | vinfos[1].indices[0] = _ij1[0]; |
| 2617 | vinfos[1].indices[1] = _ij1[1]; |
| 2618 | vinfos[1].maxsolutions = _nj1; |
| 2619 | vinfos[2].jointtype = 1; |
| 2620 | vinfos[2].foffset = j2; |
| 2621 | vinfos[2].indices[0] = _ij2[0]; |
| 2622 | vinfos[2].indices[1] = _ij2[1]; |
| 2623 | vinfos[2].maxsolutions = _nj2; |
| 2624 | vinfos[3].jointtype = 1; |
| 2625 | vinfos[3].foffset = j3; |
| 2626 | vinfos[3].indices[0] = _ij3[0]; |
| 2627 | vinfos[3].indices[1] = _ij3[1]; |
| 2628 | vinfos[3].maxsolutions = _nj3; |
| 2629 | vinfos[4].jointtype = 1; |
| 2630 | vinfos[4].foffset = j4; |
| 2631 | vinfos[4].indices[0] = _ij4[0]; |
| 2632 | vinfos[4].indices[1] = _ij4[1]; |
| 2633 | vinfos[4].maxsolutions = _nj4; |
| 2634 | vinfos[5].jointtype = 1; |
| 2635 | vinfos[5].foffset = j5; |
| 2636 | vinfos[5].indices[0] = _ij5[0]; |
| 2637 | vinfos[5].indices[1] = _ij5[1]; |
| 2638 | vinfos[5].maxsolutions = _nj5; |
| 2639 | std::vector<int> vfree(0); |
| 2640 | solutions.AddSolution(vinfos,vfree); |
| 2641 | } |
| 2642 | } |
| 2643 | } |
| 2644 | |
| 2645 | } |
| 2646 | } while(0); |
| 2647 | if( bgotonextstatement ) |
| 2648 | { |
| 2649 | bool bgotonextstatement = true; |
| 2650 | do |
| 2651 | { |
| 2652 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| 2653 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2654 | { |
| 2655 | bgotonextstatement=false; |
| 2656 | { |
| 2657 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2658 | bool j2valid[1]={false}; |
| 2659 | _nj2 = 1; |
| 2660 | if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) |
| 2661 | continue; |
| 2662 | j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| 2663 | sj2array[0]=IKsin(j2array[0]); |
| 2664 | cj2array[0]=IKcos(j2array[0]); |
| 2665 | if( j2array[0] > IKPI ) |
| 2666 | { |
| 2667 | j2array[0]-=IK2PI; |
| 2668 | } |
| 2669 | else if( j2array[0] < -IKPI ) |
| 2670 | { j2array[0]+=IK2PI; |
| 2671 | } |
| 2672 | j2valid[0] = true; |
| 2673 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 2674 | { |
| 2675 | if( !j2valid[ij2] ) |
| 2676 | { |
| 2677 | continue; |
| 2678 | } |
| 2679 | _ij2[0] = ij2; _ij2[1] = -1; |
| 2680 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 2681 | { |
| 2682 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 2683 | { |
| 2684 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 2685 | } |
| 2686 | } |
| 2687 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 2688 | { |
| 2689 | IkReal evalcond[4]; |
| 2690 | IkReal x135=IKsin(j2); |
| 2691 | IkReal x136=IKcos(j2); |
| 2692 | evalcond[0]=(x135+new_r11); |
| 2693 | evalcond[1]=((-1.0)*x135); |
| 2694 | evalcond[2]=((-1.0)*x136); |
| 2695 | evalcond[3]=(x136+(((-1.0)*new_r10))); |
| 2696 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 2697 | { |
| 2698 | continue; |
| 2699 | } |
| 2700 | } |
| 2701 | |
| 2702 | { |
| 2703 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2704 | vinfos[0].jointtype = 1; |
| 2705 | vinfos[0].foffset = j0; |
| 2706 | vinfos[0].indices[0] = _ij0[0]; |
| 2707 | vinfos[0].indices[1] = _ij0[1]; |
| 2708 | vinfos[0].maxsolutions = _nj0; |
| 2709 | vinfos[1].jointtype = 1; |
| 2710 | vinfos[1].foffset = j1; |
| 2711 | vinfos[1].indices[0] = _ij1[0]; |
| 2712 | vinfos[1].indices[1] = _ij1[1]; |
| 2713 | vinfos[1].maxsolutions = _nj1; |
| 2714 | vinfos[2].jointtype = 1; |
| 2715 | vinfos[2].foffset = j2; |
| 2716 | vinfos[2].indices[0] = _ij2[0]; |
| 2717 | vinfos[2].indices[1] = _ij2[1]; |
| 2718 | vinfos[2].maxsolutions = _nj2; |
| 2719 | vinfos[3].jointtype = 1; |
| 2720 | vinfos[3].foffset = j3; |
| 2721 | vinfos[3].indices[0] = _ij3[0]; |
| 2722 | vinfos[3].indices[1] = _ij3[1]; |
| 2723 | vinfos[3].maxsolutions = _nj3; |
| 2724 | vinfos[4].jointtype = 1; |
| 2725 | vinfos[4].foffset = j4; |
| 2726 | vinfos[4].indices[0] = _ij4[0]; |
| 2727 | vinfos[4].indices[1] = _ij4[1]; |
| 2728 | vinfos[4].maxsolutions = _nj4; |
| 2729 | vinfos[5].jointtype = 1; |
| 2730 | vinfos[5].foffset = j5; |
| 2731 | vinfos[5].indices[0] = _ij5[0]; |
| 2732 | vinfos[5].indices[1] = _ij5[1]; |
| 2733 | vinfos[5].maxsolutions = _nj5; |
| 2734 | std::vector<int> vfree(0); |
| 2735 | solutions.AddSolution(vinfos,vfree); |
| 2736 | } |
| 2737 | } |
| 2738 | } |
| 2739 | |
| 2740 | } |
| 2741 | } while(0); |
| 2742 | if( bgotonextstatement ) |
| 2743 | { |
| 2744 | bool bgotonextstatement = true; |
| 2745 | do |
| 2746 | { |
| 2747 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| 2748 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2749 | { |
| 2750 | bgotonextstatement=false; |
| 2751 | { |
| 2752 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2753 | bool j2valid[1]={false}; |
| 2754 | _nj2 = 1; |
| 2755 | if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) |
| 2756 | continue; |
| 2757 | j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| 2758 | sj2array[0]=IKsin(j2array[0]); |
| 2759 | cj2array[0]=IKcos(j2array[0]); |
| 2760 | if( j2array[0] > IKPI ) |
| 2761 | { |
| 2762 | j2array[0]-=IK2PI; |
| 2763 | } |
| 2764 | else if( j2array[0] < -IKPI ) |
| 2765 | { j2array[0]+=IK2PI; |
| 2766 | } |
| 2767 | j2valid[0] = true; |
| 2768 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 2769 | { |
| 2770 | if( !j2valid[ij2] ) |
| 2771 | { |
| 2772 | continue; |
| 2773 | } |
| 2774 | _ij2[0] = ij2; _ij2[1] = -1; |
| 2775 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 2776 | { |
| 2777 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 2778 | { |
| 2779 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 2780 | } |
| 2781 | } |
| 2782 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 2783 | { |
| 2784 | IkReal evalcond[4]; |
| 2785 | IkReal x137=IKcos(j2); |
| 2786 | IkReal x138=IKsin(j2); |
| 2787 | evalcond[0]=(x137+new_r10); |
| 2788 | evalcond[1]=((-1.0)*x138); |
| 2789 | evalcond[2]=((-1.0)*x137); |
| 2790 | evalcond[3]=(x138+(((-1.0)*new_r11))); |
| 2791 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH ) |
| 2792 | { |
| 2793 | continue; |
| 2794 | } |
| 2795 | } |
| 2796 | |
| 2797 | { |
| 2798 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2799 | vinfos[0].jointtype = 1; |
| 2800 | vinfos[0].foffset = j0; |
| 2801 | vinfos[0].indices[0] = _ij0[0]; |
| 2802 | vinfos[0].indices[1] = _ij0[1]; |
| 2803 | vinfos[0].maxsolutions = _nj0; |
| 2804 | vinfos[1].jointtype = 1; |
| 2805 | vinfos[1].foffset = j1; |
| 2806 | vinfos[1].indices[0] = _ij1[0]; |
| 2807 | vinfos[1].indices[1] = _ij1[1]; |
| 2808 | vinfos[1].maxsolutions = _nj1; |
| 2809 | vinfos[2].jointtype = 1; |
| 2810 | vinfos[2].foffset = j2; |
| 2811 | vinfos[2].indices[0] = _ij2[0]; |
| 2812 | vinfos[2].indices[1] = _ij2[1]; |
| 2813 | vinfos[2].maxsolutions = _nj2; |
| 2814 | vinfos[3].jointtype = 1; |
| 2815 | vinfos[3].foffset = j3; |
| 2816 | vinfos[3].indices[0] = _ij3[0]; |
| 2817 | vinfos[3].indices[1] = _ij3[1]; |
| 2818 | vinfos[3].maxsolutions = _nj3; |
| 2819 | vinfos[4].jointtype = 1; |
| 2820 | vinfos[4].foffset = j4; |
| 2821 | vinfos[4].indices[0] = _ij4[0]; |
| 2822 | vinfos[4].indices[1] = _ij4[1]; |
| 2823 | vinfos[4].maxsolutions = _nj4; |
| 2824 | vinfos[5].jointtype = 1; |
| 2825 | vinfos[5].foffset = j5; |
| 2826 | vinfos[5].indices[0] = _ij5[0]; |
| 2827 | vinfos[5].indices[1] = _ij5[1]; |
| 2828 | vinfos[5].maxsolutions = _nj5; |
| 2829 | std::vector<int> vfree(0); |
| 2830 | solutions.AddSolution(vinfos,vfree); |
| 2831 | } |
| 2832 | } |
| 2833 | } |
| 2834 | |
| 2835 | } |
| 2836 | } while(0); |
| 2837 | if( bgotonextstatement ) |
| 2838 | { |
| 2839 | bool bgotonextstatement = true; |
| 2840 | do |
| 2841 | { |
| 2842 | CheckValue<IkReal> x139=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 2843 | if(!x139.valid){ |
| 2844 | continue; |
| 2845 | } |
| 2846 | if((((-1.0)*(x139.value))) < -0.00001) |
| 2847 | continue; |
| 2848 | IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x139.value))))); |
| 2849 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((((-1.0)*gconst40))+cj0)))+(IKabs(((-1.0)+(IKsign(sj0)))))), 6.28318530717959))); |
| 2850 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 2851 | { |
| 2852 | bgotonextstatement=false; |
| 2853 | { |
| 2854 | IkReal j2eval[1]; |
| 2855 | new_r02=0; |
| 2856 | new_r12=0; |
| 2857 | new_r20=0; |
| 2858 | new_r21=0; |
| 2859 | if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| 2860 | continue; |
| 2861 | sj0=IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))); |
| 2862 | cj0=gconst40; |
| 2863 | if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH ) |
| 2864 | continue; |
| 2865 | j0=IKacos(gconst40); |
| 2866 | CheckValue<IkReal> x140=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 2867 | if(!x140.valid){ |
| 2868 | continue; |
| 2869 | } |
| 2870 | if((((-1.0)*(x140.value))) < -0.00001) |
| 2871 | continue; |
| 2872 | IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x140.value))))); |
| 2873 | j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 2874 | if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| 2875 | { |
| 2876 | { |
| 2877 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2878 | bool j2valid[1]={false}; |
| 2879 | _nj2 = 1; |
| 2880 | CheckValue<IkReal> x141=IKPowWithIntegerCheck(gconst40,-1); |
| 2881 | if(!x141.valid){ |
| 2882 | continue; |
| 2883 | } |
| 2884 | if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| 2885 | continue; |
| 2886 | if( IKabs(((-1.0)*new_r11*(x141.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x141.value)))+IKsqr(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10))))-1) <= IKFAST_SINCOS_THRESH ) |
| 2887 | continue; |
| 2888 | j2array[0]=IKatan2(((-1.0)*new_r11*(x141.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+((gconst40*new_r10)))); |
| 2889 | sj2array[0]=IKsin(j2array[0]); |
| 2890 | cj2array[0]=IKcos(j2array[0]); |
| 2891 | if( j2array[0] > IKPI ) |
| 2892 | { |
| 2893 | j2array[0]-=IK2PI; |
| 2894 | } |
| 2895 | else if( j2array[0] < -IKPI ) |
| 2896 | { j2array[0]+=IK2PI; |
| 2897 | } |
| 2898 | j2valid[0] = true; |
| 2899 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 2900 | { |
| 2901 | if( !j2valid[ij2] ) |
| 2902 | { |
| 2903 | continue; |
| 2904 | } |
| 2905 | _ij2[0] = ij2; _ij2[1] = -1; |
| 2906 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 2907 | { |
| 2908 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 2909 | { |
| 2910 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 2911 | } |
| 2912 | } |
| 2913 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 2914 | { |
| 2915 | IkReal evalcond[8]; |
| 2916 | IkReal x142=IKsin(j2); |
| 2917 | IkReal x143=IKcos(j2); |
| 2918 | IkReal x144=((1.0)*gconst40); |
| 2919 | if((((1.0)+(((-1.0)*gconst40*x144)))) < -0.00001) |
| 2920 | continue; |
| 2921 | IkReal x145=IKsqrt(((1.0)+(((-1.0)*gconst40*x144)))); |
| 2922 | IkReal x146=((1.0)*x145); |
| 2923 | evalcond[0]=((-1.0)*x142); |
| 2924 | evalcond[1]=((-1.0)*x143); |
| 2925 | evalcond[2]=(((gconst40*x142))+new_r11); |
| 2926 | evalcond[3]=((((-1.0)*x143*x144))+new_r10); |
| 2927 | evalcond[4]=(new_r00+((x143*x145))); |
| 2928 | evalcond[5]=((((-1.0)*x142*x146))+new_r01); |
| 2929 | evalcond[6]=((((-1.0)*new_r01*x146))+((gconst40*new_r11))+x142); |
| 2930 | evalcond[7]=(((new_r00*x145))+x143+(((-1.0)*new_r10*x144))); |
| 2931 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 2932 | { |
| 2933 | continue; |
| 2934 | } |
| 2935 | } |
| 2936 | |
| 2937 | { |
| 2938 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 2939 | vinfos[0].jointtype = 1; |
| 2940 | vinfos[0].foffset = j0; |
| 2941 | vinfos[0].indices[0] = _ij0[0]; |
| 2942 | vinfos[0].indices[1] = _ij0[1]; |
| 2943 | vinfos[0].maxsolutions = _nj0; |
| 2944 | vinfos[1].jointtype = 1; |
| 2945 | vinfos[1].foffset = j1; |
| 2946 | vinfos[1].indices[0] = _ij1[0]; |
| 2947 | vinfos[1].indices[1] = _ij1[1]; |
| 2948 | vinfos[1].maxsolutions = _nj1; |
| 2949 | vinfos[2].jointtype = 1; |
| 2950 | vinfos[2].foffset = j2; |
| 2951 | vinfos[2].indices[0] = _ij2[0]; |
| 2952 | vinfos[2].indices[1] = _ij2[1]; |
| 2953 | vinfos[2].maxsolutions = _nj2; |
| 2954 | vinfos[3].jointtype = 1; |
| 2955 | vinfos[3].foffset = j3; |
| 2956 | vinfos[3].indices[0] = _ij3[0]; |
| 2957 | vinfos[3].indices[1] = _ij3[1]; |
| 2958 | vinfos[3].maxsolutions = _nj3; |
| 2959 | vinfos[4].jointtype = 1; |
| 2960 | vinfos[4].foffset = j4; |
| 2961 | vinfos[4].indices[0] = _ij4[0]; |
| 2962 | vinfos[4].indices[1] = _ij4[1]; |
| 2963 | vinfos[4].maxsolutions = _nj4; |
| 2964 | vinfos[5].jointtype = 1; |
| 2965 | vinfos[5].foffset = j5; |
| 2966 | vinfos[5].indices[0] = _ij5[0]; |
| 2967 | vinfos[5].indices[1] = _ij5[1]; |
| 2968 | vinfos[5].maxsolutions = _nj5; |
| 2969 | std::vector<int> vfree(0); |
| 2970 | solutions.AddSolution(vinfos,vfree); |
| 2971 | } |
| 2972 | } |
| 2973 | } |
| 2974 | |
| 2975 | } else |
| 2976 | { |
| 2977 | { |
| 2978 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 2979 | bool j2valid[1]={false}; |
| 2980 | _nj2 = 1; |
| 2981 | CheckValue<IkReal> x147=IKPowWithIntegerCheck(IKsign(gconst40),-1); |
| 2982 | if(!x147.valid){ |
| 2983 | continue; |
| 2984 | } |
| 2985 | CheckValue<IkReal> x148 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 2986 | if(!x148.valid){ |
| 2987 | continue; |
| 2988 | } |
| 2989 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x147.value)))+(x148.value)); |
| 2990 | sj2array[0]=IKsin(j2array[0]); |
| 2991 | cj2array[0]=IKcos(j2array[0]); |
| 2992 | if( j2array[0] > IKPI ) |
| 2993 | { |
| 2994 | j2array[0]-=IK2PI; |
| 2995 | } |
| 2996 | else if( j2array[0] < -IKPI ) |
| 2997 | { j2array[0]+=IK2PI; |
| 2998 | } |
| 2999 | j2valid[0] = true; |
| 3000 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3001 | { |
| 3002 | if( !j2valid[ij2] ) |
| 3003 | { |
| 3004 | continue; |
| 3005 | } |
| 3006 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3007 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3008 | { |
| 3009 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3010 | { |
| 3011 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3012 | } |
| 3013 | } |
| 3014 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3015 | { |
| 3016 | IkReal evalcond[8]; |
| 3017 | IkReal x149=IKsin(j2); |
| 3018 | IkReal x150=IKcos(j2); |
| 3019 | IkReal x151=((1.0)*gconst40); |
| 3020 | if((((1.0)+(((-1.0)*gconst40*x151)))) < -0.00001) |
| 3021 | continue; |
| 3022 | IkReal x152=IKsqrt(((1.0)+(((-1.0)*gconst40*x151)))); |
| 3023 | IkReal x153=((1.0)*x152); |
| 3024 | evalcond[0]=((-1.0)*x149); |
| 3025 | evalcond[1]=((-1.0)*x150); |
| 3026 | evalcond[2]=(((gconst40*x149))+new_r11); |
| 3027 | evalcond[3]=((((-1.0)*x150*x151))+new_r10); |
| 3028 | evalcond[4]=(((x150*x152))+new_r00); |
| 3029 | evalcond[5]=(new_r01+(((-1.0)*x149*x153))); |
| 3030 | evalcond[6]=(((gconst40*new_r11))+x149+(((-1.0)*new_r01*x153))); |
| 3031 | evalcond[7]=(((new_r00*x152))+x150+(((-1.0)*new_r10*x151))); |
| 3032 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3033 | { |
| 3034 | continue; |
| 3035 | } |
| 3036 | } |
| 3037 | |
| 3038 | { |
| 3039 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3040 | vinfos[0].jointtype = 1; |
| 3041 | vinfos[0].foffset = j0; |
| 3042 | vinfos[0].indices[0] = _ij0[0]; |
| 3043 | vinfos[0].indices[1] = _ij0[1]; |
| 3044 | vinfos[0].maxsolutions = _nj0; |
| 3045 | vinfos[1].jointtype = 1; |
| 3046 | vinfos[1].foffset = j1; |
| 3047 | vinfos[1].indices[0] = _ij1[0]; |
| 3048 | vinfos[1].indices[1] = _ij1[1]; |
| 3049 | vinfos[1].maxsolutions = _nj1; |
| 3050 | vinfos[2].jointtype = 1; |
| 3051 | vinfos[2].foffset = j2; |
| 3052 | vinfos[2].indices[0] = _ij2[0]; |
| 3053 | vinfos[2].indices[1] = _ij2[1]; |
| 3054 | vinfos[2].maxsolutions = _nj2; |
| 3055 | vinfos[3].jointtype = 1; |
| 3056 | vinfos[3].foffset = j3; |
| 3057 | vinfos[3].indices[0] = _ij3[0]; |
| 3058 | vinfos[3].indices[1] = _ij3[1]; |
| 3059 | vinfos[3].maxsolutions = _nj3; |
| 3060 | vinfos[4].jointtype = 1; |
| 3061 | vinfos[4].foffset = j4; |
| 3062 | vinfos[4].indices[0] = _ij4[0]; |
| 3063 | vinfos[4].indices[1] = _ij4[1]; |
| 3064 | vinfos[4].maxsolutions = _nj4; |
| 3065 | vinfos[5].jointtype = 1; |
| 3066 | vinfos[5].foffset = j5; |
| 3067 | vinfos[5].indices[0] = _ij5[0]; |
| 3068 | vinfos[5].indices[1] = _ij5[1]; |
| 3069 | vinfos[5].maxsolutions = _nj5; |
| 3070 | std::vector<int> vfree(0); |
| 3071 | solutions.AddSolution(vinfos,vfree); |
| 3072 | } |
| 3073 | } |
| 3074 | } |
| 3075 | |
| 3076 | } |
| 3077 | |
| 3078 | } |
| 3079 | |
| 3080 | } |
| 3081 | } while(0); |
| 3082 | if( bgotonextstatement ) |
| 3083 | { |
| 3084 | bool bgotonextstatement = true; |
| 3085 | do |
| 3086 | { |
| 3087 | CheckValue<IkReal> x154=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3088 | if(!x154.valid){ |
| 3089 | continue; |
| 3090 | } |
| 3091 | if((((-1.0)*(x154.value))) < -0.00001) |
| 3092 | continue; |
| 3093 | IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x154.value))))); |
| 3094 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst40))+cj0)))), 6.28318530717959))); |
| 3095 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 3096 | { |
| 3097 | bgotonextstatement=false; |
| 3098 | { |
| 3099 | IkReal j2eval[1]; |
| 3100 | new_r02=0; |
| 3101 | new_r12=0; |
| 3102 | new_r20=0; |
| 3103 | new_r21=0; |
| 3104 | if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| 3105 | continue; |
| 3106 | sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))); |
| 3107 | cj0=gconst40; |
| 3108 | if( (gconst40) < -1-IKFAST_SINCOS_THRESH || (gconst40) > 1+IKFAST_SINCOS_THRESH ) |
| 3109 | continue; |
| 3110 | j0=((-1.0)*(IKacos(gconst40))); |
| 3111 | CheckValue<IkReal> x155=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3112 | if(!x155.valid){ |
| 3113 | continue; |
| 3114 | } |
| 3115 | if((((-1.0)*(x155.value))) < -0.00001) |
| 3116 | continue; |
| 3117 | IkReal gconst40=((-1.0)*(IKsqrt(((-1.0)*(x155.value))))); |
| 3118 | j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 3119 | if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| 3120 | { |
| 3121 | { |
| 3122 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3123 | bool j2valid[1]={false}; |
| 3124 | _nj2 = 1; |
| 3125 | if((((1.0)+(((-1.0)*(gconst40*gconst40))))) < -0.00001) |
| 3126 | continue; |
| 3127 | CheckValue<IkReal> x156=IKPowWithIntegerCheck(gconst40,-1); |
| 3128 | if(!x156.valid){ |
| 3129 | continue; |
| 3130 | } |
| 3131 | if( IKabs(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x156.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11))))+IKsqr((new_r10*(x156.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 3132 | continue; |
| 3133 | j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst40*gconst40))))))))+(((-1.0)*gconst40*new_r11))), (new_r10*(x156.value))); |
| 3134 | sj2array[0]=IKsin(j2array[0]); |
| 3135 | cj2array[0]=IKcos(j2array[0]); |
| 3136 | if( j2array[0] > IKPI ) |
| 3137 | { |
| 3138 | j2array[0]-=IK2PI; |
| 3139 | } |
| 3140 | else if( j2array[0] < -IKPI ) |
| 3141 | { j2array[0]+=IK2PI; |
| 3142 | } |
| 3143 | j2valid[0] = true; |
| 3144 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3145 | { |
| 3146 | if( !j2valid[ij2] ) |
| 3147 | { |
| 3148 | continue; |
| 3149 | } |
| 3150 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3151 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3152 | { |
| 3153 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3154 | { |
| 3155 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3156 | } |
| 3157 | } |
| 3158 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3159 | { |
| 3160 | IkReal evalcond[8]; |
| 3161 | IkReal x157=IKsin(j2); |
| 3162 | IkReal x158=IKcos(j2); |
| 3163 | IkReal x159=((1.0)*gconst40); |
| 3164 | if((((1.0)+(((-1.0)*gconst40*x159)))) < -0.00001) |
| 3165 | continue; |
| 3166 | IkReal x160=IKsqrt(((1.0)+(((-1.0)*gconst40*x159)))); |
| 3167 | IkReal x161=((1.0)*x160); |
| 3168 | evalcond[0]=((-1.0)*x157); |
| 3169 | evalcond[1]=((-1.0)*x158); |
| 3170 | evalcond[2]=(((gconst40*x157))+new_r11); |
| 3171 | evalcond[3]=((((-1.0)*x158*x159))+new_r10); |
| 3172 | evalcond[4]=(((x157*x160))+new_r01); |
| 3173 | evalcond[5]=((((-1.0)*x158*x161))+new_r00); |
| 3174 | evalcond[6]=(((new_r01*x160))+((gconst40*new_r11))+x157); |
| 3175 | evalcond[7]=((((-1.0)*new_r00*x161))+x158+(((-1.0)*new_r10*x159))); |
| 3176 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3177 | { |
| 3178 | continue; |
| 3179 | } |
| 3180 | } |
| 3181 | |
| 3182 | { |
| 3183 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3184 | vinfos[0].jointtype = 1; |
| 3185 | vinfos[0].foffset = j0; |
| 3186 | vinfos[0].indices[0] = _ij0[0]; |
| 3187 | vinfos[0].indices[1] = _ij0[1]; |
| 3188 | vinfos[0].maxsolutions = _nj0; |
| 3189 | vinfos[1].jointtype = 1; |
| 3190 | vinfos[1].foffset = j1; |
| 3191 | vinfos[1].indices[0] = _ij1[0]; |
| 3192 | vinfos[1].indices[1] = _ij1[1]; |
| 3193 | vinfos[1].maxsolutions = _nj1; |
| 3194 | vinfos[2].jointtype = 1; |
| 3195 | vinfos[2].foffset = j2; |
| 3196 | vinfos[2].indices[0] = _ij2[0]; |
| 3197 | vinfos[2].indices[1] = _ij2[1]; |
| 3198 | vinfos[2].maxsolutions = _nj2; |
| 3199 | vinfos[3].jointtype = 1; |
| 3200 | vinfos[3].foffset = j3; |
| 3201 | vinfos[3].indices[0] = _ij3[0]; |
| 3202 | vinfos[3].indices[1] = _ij3[1]; |
| 3203 | vinfos[3].maxsolutions = _nj3; |
| 3204 | vinfos[4].jointtype = 1; |
| 3205 | vinfos[4].foffset = j4; |
| 3206 | vinfos[4].indices[0] = _ij4[0]; |
| 3207 | vinfos[4].indices[1] = _ij4[1]; |
| 3208 | vinfos[4].maxsolutions = _nj4; |
| 3209 | vinfos[5].jointtype = 1; |
| 3210 | vinfos[5].foffset = j5; |
| 3211 | vinfos[5].indices[0] = _ij5[0]; |
| 3212 | vinfos[5].indices[1] = _ij5[1]; |
| 3213 | vinfos[5].maxsolutions = _nj5; |
| 3214 | std::vector<int> vfree(0); |
| 3215 | solutions.AddSolution(vinfos,vfree); |
| 3216 | } |
| 3217 | } |
| 3218 | } |
| 3219 | |
| 3220 | } else |
| 3221 | { |
| 3222 | { |
| 3223 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3224 | bool j2valid[1]={false}; |
| 3225 | _nj2 = 1; |
| 3226 | CheckValue<IkReal> x162=IKPowWithIntegerCheck(IKsign(gconst40),-1); |
| 3227 | if(!x162.valid){ |
| 3228 | continue; |
| 3229 | } |
| 3230 | CheckValue<IkReal> x163 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 3231 | if(!x163.valid){ |
| 3232 | continue; |
| 3233 | } |
| 3234 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x162.value)))+(x163.value)); |
| 3235 | sj2array[0]=IKsin(j2array[0]); |
| 3236 | cj2array[0]=IKcos(j2array[0]); |
| 3237 | if( j2array[0] > IKPI ) |
| 3238 | { |
| 3239 | j2array[0]-=IK2PI; |
| 3240 | } |
| 3241 | else if( j2array[0] < -IKPI ) |
| 3242 | { j2array[0]+=IK2PI; |
| 3243 | } |
| 3244 | j2valid[0] = true; |
| 3245 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3246 | { |
| 3247 | if( !j2valid[ij2] ) |
| 3248 | { |
| 3249 | continue; |
| 3250 | } |
| 3251 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3252 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3253 | { |
| 3254 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3255 | { |
| 3256 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3257 | } |
| 3258 | } |
| 3259 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3260 | { |
| 3261 | IkReal evalcond[8]; |
| 3262 | IkReal x164=IKsin(j2); |
| 3263 | IkReal x165=IKcos(j2); |
| 3264 | IkReal x166=((1.0)*gconst40); |
| 3265 | if((((1.0)+(((-1.0)*gconst40*x166)))) < -0.00001) |
| 3266 | continue; |
| 3267 | IkReal x167=IKsqrt(((1.0)+(((-1.0)*gconst40*x166)))); |
| 3268 | IkReal x168=((1.0)*x167); |
| 3269 | evalcond[0]=((-1.0)*x164); |
| 3270 | evalcond[1]=((-1.0)*x165); |
| 3271 | evalcond[2]=(new_r11+((gconst40*x164))); |
| 3272 | evalcond[3]=(new_r10+(((-1.0)*x165*x166))); |
| 3273 | evalcond[4]=(((x164*x167))+new_r01); |
| 3274 | evalcond[5]=(new_r00+(((-1.0)*x165*x168))); |
| 3275 | evalcond[6]=(((new_r01*x167))+((gconst40*new_r11))+x164); |
| 3276 | evalcond[7]=((((-1.0)*new_r00*x168))+(((-1.0)*new_r10*x166))+x165); |
| 3277 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3278 | { |
| 3279 | continue; |
| 3280 | } |
| 3281 | } |
| 3282 | |
| 3283 | { |
| 3284 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3285 | vinfos[0].jointtype = 1; |
| 3286 | vinfos[0].foffset = j0; |
| 3287 | vinfos[0].indices[0] = _ij0[0]; |
| 3288 | vinfos[0].indices[1] = _ij0[1]; |
| 3289 | vinfos[0].maxsolutions = _nj0; |
| 3290 | vinfos[1].jointtype = 1; |
| 3291 | vinfos[1].foffset = j1; |
| 3292 | vinfos[1].indices[0] = _ij1[0]; |
| 3293 | vinfos[1].indices[1] = _ij1[1]; |
| 3294 | vinfos[1].maxsolutions = _nj1; |
| 3295 | vinfos[2].jointtype = 1; |
| 3296 | vinfos[2].foffset = j2; |
| 3297 | vinfos[2].indices[0] = _ij2[0]; |
| 3298 | vinfos[2].indices[1] = _ij2[1]; |
| 3299 | vinfos[2].maxsolutions = _nj2; |
| 3300 | vinfos[3].jointtype = 1; |
| 3301 | vinfos[3].foffset = j3; |
| 3302 | vinfos[3].indices[0] = _ij3[0]; |
| 3303 | vinfos[3].indices[1] = _ij3[1]; |
| 3304 | vinfos[3].maxsolutions = _nj3; |
| 3305 | vinfos[4].jointtype = 1; |
| 3306 | vinfos[4].foffset = j4; |
| 3307 | vinfos[4].indices[0] = _ij4[0]; |
| 3308 | vinfos[4].indices[1] = _ij4[1]; |
| 3309 | vinfos[4].maxsolutions = _nj4; |
| 3310 | vinfos[5].jointtype = 1; |
| 3311 | vinfos[5].foffset = j5; |
| 3312 | vinfos[5].indices[0] = _ij5[0]; |
| 3313 | vinfos[5].indices[1] = _ij5[1]; |
| 3314 | vinfos[5].maxsolutions = _nj5; |
| 3315 | std::vector<int> vfree(0); |
| 3316 | solutions.AddSolution(vinfos,vfree); |
| 3317 | } |
| 3318 | } |
| 3319 | } |
| 3320 | |
| 3321 | } |
| 3322 | |
| 3323 | } |
| 3324 | |
| 3325 | } |
| 3326 | } while(0); |
| 3327 | if( bgotonextstatement ) |
| 3328 | { |
| 3329 | bool bgotonextstatement = true; |
| 3330 | do |
| 3331 | { |
| 3332 | CheckValue<IkReal> x169=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3333 | if(!x169.valid){ |
| 3334 | continue; |
| 3335 | } |
| 3336 | if((((-1.0)*(x169.value))) < -0.00001) |
| 3337 | continue; |
| 3338 | IkReal gconst41=IKsqrt(((-1.0)*(x169.value))); |
| 3339 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959))); |
| 3340 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 3341 | { |
| 3342 | bgotonextstatement=false; |
| 3343 | { |
| 3344 | IkReal j2eval[1]; |
| 3345 | new_r02=0; |
| 3346 | new_r12=0; |
| 3347 | new_r20=0; |
| 3348 | new_r21=0; |
| 3349 | if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| 3350 | continue; |
| 3351 | sj0=IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))); |
| 3352 | cj0=gconst41; |
| 3353 | if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH ) |
| 3354 | continue; |
| 3355 | j0=IKacos(gconst41); |
| 3356 | CheckValue<IkReal> x170=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3357 | if(!x170.valid){ |
| 3358 | continue; |
| 3359 | } |
| 3360 | if((((-1.0)*(x170.value))) < -0.00001) |
| 3361 | continue; |
| 3362 | IkReal gconst41=IKsqrt(((-1.0)*(x170.value))); |
| 3363 | j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 3364 | if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| 3365 | { |
| 3366 | { |
| 3367 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3368 | bool j2valid[1]={false}; |
| 3369 | _nj2 = 1; |
| 3370 | CheckValue<IkReal> x171=IKPowWithIntegerCheck(gconst41,-1); |
| 3371 | if(!x171.valid){ |
| 3372 | continue; |
| 3373 | } |
| 3374 | if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| 3375 | continue; |
| 3376 | if( IKabs(((-1.0)*new_r11*(x171.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x171.value)))+IKsqr(((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10))))-1) <= IKFAST_SINCOS_THRESH ) |
| 3377 | continue; |
| 3378 | j2array[0]=IKatan2(((-1.0)*new_r11*(x171.value)), ((((-1.0)*new_r00*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+((gconst41*new_r10)))); |
| 3379 | sj2array[0]=IKsin(j2array[0]); |
| 3380 | cj2array[0]=IKcos(j2array[0]); |
| 3381 | if( j2array[0] > IKPI ) |
| 3382 | { |
| 3383 | j2array[0]-=IK2PI; |
| 3384 | } |
| 3385 | else if( j2array[0] < -IKPI ) |
| 3386 | { j2array[0]+=IK2PI; |
| 3387 | } |
| 3388 | j2valid[0] = true; |
| 3389 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3390 | { |
| 3391 | if( !j2valid[ij2] ) |
| 3392 | { |
| 3393 | continue; |
| 3394 | } |
| 3395 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3396 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3397 | { |
| 3398 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3399 | { |
| 3400 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3401 | } |
| 3402 | } |
| 3403 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3404 | { |
| 3405 | IkReal evalcond[8]; |
| 3406 | IkReal x172=IKsin(j2); |
| 3407 | IkReal x173=IKcos(j2); |
| 3408 | IkReal x174=((1.0)*gconst41); |
| 3409 | if((((1.0)+(((-1.0)*gconst41*x174)))) < -0.00001) |
| 3410 | continue; |
| 3411 | IkReal x175=IKsqrt(((1.0)+(((-1.0)*gconst41*x174)))); |
| 3412 | IkReal x176=((1.0)*x175); |
| 3413 | evalcond[0]=((-1.0)*x172); |
| 3414 | evalcond[1]=((-1.0)*x173); |
| 3415 | evalcond[2]=(new_r11+((gconst41*x172))); |
| 3416 | evalcond[3]=(new_r10+(((-1.0)*x173*x174))); |
| 3417 | evalcond[4]=(((x173*x175))+new_r00); |
| 3418 | evalcond[5]=(new_r01+(((-1.0)*x172*x176))); |
| 3419 | evalcond[6]=(((gconst41*new_r11))+x172+(((-1.0)*new_r01*x176))); |
| 3420 | evalcond[7]=(((new_r00*x175))+(((-1.0)*new_r10*x174))+x173); |
| 3421 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3422 | { |
| 3423 | continue; |
| 3424 | } |
| 3425 | } |
| 3426 | |
| 3427 | { |
| 3428 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3429 | vinfos[0].jointtype = 1; |
| 3430 | vinfos[0].foffset = j0; |
| 3431 | vinfos[0].indices[0] = _ij0[0]; |
| 3432 | vinfos[0].indices[1] = _ij0[1]; |
| 3433 | vinfos[0].maxsolutions = _nj0; |
| 3434 | vinfos[1].jointtype = 1; |
| 3435 | vinfos[1].foffset = j1; |
| 3436 | vinfos[1].indices[0] = _ij1[0]; |
| 3437 | vinfos[1].indices[1] = _ij1[1]; |
| 3438 | vinfos[1].maxsolutions = _nj1; |
| 3439 | vinfos[2].jointtype = 1; |
| 3440 | vinfos[2].foffset = j2; |
| 3441 | vinfos[2].indices[0] = _ij2[0]; |
| 3442 | vinfos[2].indices[1] = _ij2[1]; |
| 3443 | vinfos[2].maxsolutions = _nj2; |
| 3444 | vinfos[3].jointtype = 1; |
| 3445 | vinfos[3].foffset = j3; |
| 3446 | vinfos[3].indices[0] = _ij3[0]; |
| 3447 | vinfos[3].indices[1] = _ij3[1]; |
| 3448 | vinfos[3].maxsolutions = _nj3; |
| 3449 | vinfos[4].jointtype = 1; |
| 3450 | vinfos[4].foffset = j4; |
| 3451 | vinfos[4].indices[0] = _ij4[0]; |
| 3452 | vinfos[4].indices[1] = _ij4[1]; |
| 3453 | vinfos[4].maxsolutions = _nj4; |
| 3454 | vinfos[5].jointtype = 1; |
| 3455 | vinfos[5].foffset = j5; |
| 3456 | vinfos[5].indices[0] = _ij5[0]; |
| 3457 | vinfos[5].indices[1] = _ij5[1]; |
| 3458 | vinfos[5].maxsolutions = _nj5; |
| 3459 | std::vector<int> vfree(0); |
| 3460 | solutions.AddSolution(vinfos,vfree); |
| 3461 | } |
| 3462 | } |
| 3463 | } |
| 3464 | |
| 3465 | } else |
| 3466 | { |
| 3467 | { |
| 3468 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3469 | bool j2valid[1]={false}; |
| 3470 | _nj2 = 1; |
| 3471 | CheckValue<IkReal> x177=IKPowWithIntegerCheck(IKsign(gconst41),-1); |
| 3472 | if(!x177.valid){ |
| 3473 | continue; |
| 3474 | } |
| 3475 | CheckValue<IkReal> x178 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 3476 | if(!x178.valid){ |
| 3477 | continue; |
| 3478 | } |
| 3479 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x177.value)))+(x178.value)); |
| 3480 | sj2array[0]=IKsin(j2array[0]); |
| 3481 | cj2array[0]=IKcos(j2array[0]); |
| 3482 | if( j2array[0] > IKPI ) |
| 3483 | { |
| 3484 | j2array[0]-=IK2PI; |
| 3485 | } |
| 3486 | else if( j2array[0] < -IKPI ) |
| 3487 | { j2array[0]+=IK2PI; |
| 3488 | } |
| 3489 | j2valid[0] = true; |
| 3490 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3491 | { |
| 3492 | if( !j2valid[ij2] ) |
| 3493 | { |
| 3494 | continue; |
| 3495 | } |
| 3496 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3497 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3498 | { |
| 3499 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3500 | { |
| 3501 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3502 | } |
| 3503 | } |
| 3504 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3505 | { |
| 3506 | IkReal evalcond[8]; |
| 3507 | IkReal x179=IKsin(j2); |
| 3508 | IkReal x180=IKcos(j2); |
| 3509 | IkReal x181=((1.0)*gconst41); |
| 3510 | if((((1.0)+(((-1.0)*gconst41*x181)))) < -0.00001) |
| 3511 | continue; |
| 3512 | IkReal x182=IKsqrt(((1.0)+(((-1.0)*gconst41*x181)))); |
| 3513 | IkReal x183=((1.0)*x182); |
| 3514 | evalcond[0]=((-1.0)*x179); |
| 3515 | evalcond[1]=((-1.0)*x180); |
| 3516 | evalcond[2]=(new_r11+((gconst41*x179))); |
| 3517 | evalcond[3]=((((-1.0)*x180*x181))+new_r10); |
| 3518 | evalcond[4]=(((x180*x182))+new_r00); |
| 3519 | evalcond[5]=(new_r01+(((-1.0)*x179*x183))); |
| 3520 | evalcond[6]=(((gconst41*new_r11))+x179+(((-1.0)*new_r01*x183))); |
| 3521 | evalcond[7]=(((new_r00*x182))+x180+(((-1.0)*new_r10*x181))); |
| 3522 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3523 | { |
| 3524 | continue; |
| 3525 | } |
| 3526 | } |
| 3527 | |
| 3528 | { |
| 3529 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3530 | vinfos[0].jointtype = 1; |
| 3531 | vinfos[0].foffset = j0; |
| 3532 | vinfos[0].indices[0] = _ij0[0]; |
| 3533 | vinfos[0].indices[1] = _ij0[1]; |
| 3534 | vinfos[0].maxsolutions = _nj0; |
| 3535 | vinfos[1].jointtype = 1; |
| 3536 | vinfos[1].foffset = j1; |
| 3537 | vinfos[1].indices[0] = _ij1[0]; |
| 3538 | vinfos[1].indices[1] = _ij1[1]; |
| 3539 | vinfos[1].maxsolutions = _nj1; |
| 3540 | vinfos[2].jointtype = 1; |
| 3541 | vinfos[2].foffset = j2; |
| 3542 | vinfos[2].indices[0] = _ij2[0]; |
| 3543 | vinfos[2].indices[1] = _ij2[1]; |
| 3544 | vinfos[2].maxsolutions = _nj2; |
| 3545 | vinfos[3].jointtype = 1; |
| 3546 | vinfos[3].foffset = j3; |
| 3547 | vinfos[3].indices[0] = _ij3[0]; |
| 3548 | vinfos[3].indices[1] = _ij3[1]; |
| 3549 | vinfos[3].maxsolutions = _nj3; |
| 3550 | vinfos[4].jointtype = 1; |
| 3551 | vinfos[4].foffset = j4; |
| 3552 | vinfos[4].indices[0] = _ij4[0]; |
| 3553 | vinfos[4].indices[1] = _ij4[1]; |
| 3554 | vinfos[4].maxsolutions = _nj4; |
| 3555 | vinfos[5].jointtype = 1; |
| 3556 | vinfos[5].foffset = j5; |
| 3557 | vinfos[5].indices[0] = _ij5[0]; |
| 3558 | vinfos[5].indices[1] = _ij5[1]; |
| 3559 | vinfos[5].maxsolutions = _nj5; |
| 3560 | std::vector<int> vfree(0); |
| 3561 | solutions.AddSolution(vinfos,vfree); |
| 3562 | } |
| 3563 | } |
| 3564 | } |
| 3565 | |
| 3566 | } |
| 3567 | |
| 3568 | } |
| 3569 | |
| 3570 | } |
| 3571 | } while(0); |
| 3572 | if( bgotonextstatement ) |
| 3573 | { |
| 3574 | bool bgotonextstatement = true; |
| 3575 | do |
| 3576 | { |
| 3577 | CheckValue<IkReal> x184=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3578 | if(!x184.valid){ |
| 3579 | continue; |
| 3580 | } |
| 3581 | if((((-1.0)*(x184.value))) < -0.00001) |
| 3582 | continue; |
| 3583 | IkReal gconst41=IKsqrt(((-1.0)*(x184.value))); |
| 3584 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.0)+(IKsign(sj0)))))+(IKabs(((((-1.0)*gconst41))+cj0)))), 6.28318530717959))); |
| 3585 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 3586 | { |
| 3587 | bgotonextstatement=false; |
| 3588 | { |
| 3589 | IkReal j2eval[1]; |
| 3590 | new_r02=0; |
| 3591 | new_r12=0; |
| 3592 | new_r20=0; |
| 3593 | new_r21=0; |
| 3594 | if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| 3595 | continue; |
| 3596 | sj0=((-1.0)*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))); |
| 3597 | cj0=gconst41; |
| 3598 | if( (gconst41) < -1-IKFAST_SINCOS_THRESH || (gconst41) > 1+IKFAST_SINCOS_THRESH ) |
| 3599 | continue; |
| 3600 | j0=((-1.0)*(IKacos(gconst41))); |
| 3601 | CheckValue<IkReal> x185=IKPowWithIntegerCheck(((-1.0)+(new_r22*new_r22)),-1); |
| 3602 | if(!x185.valid){ |
| 3603 | continue; |
| 3604 | } |
| 3605 | if((((-1.0)*(x185.value))) < -0.00001) |
| 3606 | continue; |
| 3607 | IkReal gconst41=IKsqrt(((-1.0)*(x185.value))); |
| 3608 | j2eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 3609 | if( IKabs(j2eval[0]) < 0.0000010000000000 ) |
| 3610 | { |
| 3611 | { |
| 3612 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3613 | bool j2valid[1]={false}; |
| 3614 | _nj2 = 1; |
| 3615 | if((((1.0)+(((-1.0)*(gconst41*gconst41))))) < -0.00001) |
| 3616 | continue; |
| 3617 | CheckValue<IkReal> x186=IKPowWithIntegerCheck(gconst41,-1); |
| 3618 | if(!x186.valid){ |
| 3619 | continue; |
| 3620 | } |
| 3621 | if( IKabs(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x186.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11))))+IKsqr((new_r10*(x186.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 3622 | continue; |
| 3623 | j2array[0]=IKatan2(((((-1.0)*new_r01*(IKsqrt(((1.0)+(((-1.0)*(gconst41*gconst41))))))))+(((-1.0)*gconst41*new_r11))), (new_r10*(x186.value))); |
| 3624 | sj2array[0]=IKsin(j2array[0]); |
| 3625 | cj2array[0]=IKcos(j2array[0]); |
| 3626 | if( j2array[0] > IKPI ) |
| 3627 | { |
| 3628 | j2array[0]-=IK2PI; |
| 3629 | } |
| 3630 | else if( j2array[0] < -IKPI ) |
| 3631 | { j2array[0]+=IK2PI; |
| 3632 | } |
| 3633 | j2valid[0] = true; |
| 3634 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3635 | { |
| 3636 | if( !j2valid[ij2] ) |
| 3637 | { |
| 3638 | continue; |
| 3639 | } |
| 3640 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3641 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3642 | { |
| 3643 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3644 | { |
| 3645 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3646 | } |
| 3647 | } |
| 3648 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3649 | { |
| 3650 | IkReal evalcond[8]; |
| 3651 | IkReal x187=IKsin(j2); |
| 3652 | IkReal x188=IKcos(j2); |
| 3653 | IkReal x189=((1.0)*gconst41); |
| 3654 | if((((1.0)+(((-1.0)*gconst41*x189)))) < -0.00001) |
| 3655 | continue; |
| 3656 | IkReal x190=IKsqrt(((1.0)+(((-1.0)*gconst41*x189)))); |
| 3657 | IkReal x191=((1.0)*x190); |
| 3658 | evalcond[0]=((-1.0)*x187); |
| 3659 | evalcond[1]=((-1.0)*x188); |
| 3660 | evalcond[2]=(new_r11+((gconst41*x187))); |
| 3661 | evalcond[3]=((((-1.0)*x188*x189))+new_r10); |
| 3662 | evalcond[4]=(((x187*x190))+new_r01); |
| 3663 | evalcond[5]=((((-1.0)*x188*x191))+new_r00); |
| 3664 | evalcond[6]=(((new_r01*x190))+((gconst41*new_r11))+x187); |
| 3665 | evalcond[7]=(x188+(((-1.0)*new_r10*x189))+(((-1.0)*new_r00*x191))); |
| 3666 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3667 | { |
| 3668 | continue; |
| 3669 | } |
| 3670 | } |
| 3671 | |
| 3672 | { |
| 3673 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3674 | vinfos[0].jointtype = 1; |
| 3675 | vinfos[0].foffset = j0; |
| 3676 | vinfos[0].indices[0] = _ij0[0]; |
| 3677 | vinfos[0].indices[1] = _ij0[1]; |
| 3678 | vinfos[0].maxsolutions = _nj0; |
| 3679 | vinfos[1].jointtype = 1; |
| 3680 | vinfos[1].foffset = j1; |
| 3681 | vinfos[1].indices[0] = _ij1[0]; |
| 3682 | vinfos[1].indices[1] = _ij1[1]; |
| 3683 | vinfos[1].maxsolutions = _nj1; |
| 3684 | vinfos[2].jointtype = 1; |
| 3685 | vinfos[2].foffset = j2; |
| 3686 | vinfos[2].indices[0] = _ij2[0]; |
| 3687 | vinfos[2].indices[1] = _ij2[1]; |
| 3688 | vinfos[2].maxsolutions = _nj2; |
| 3689 | vinfos[3].jointtype = 1; |
| 3690 | vinfos[3].foffset = j3; |
| 3691 | vinfos[3].indices[0] = _ij3[0]; |
| 3692 | vinfos[3].indices[1] = _ij3[1]; |
| 3693 | vinfos[3].maxsolutions = _nj3; |
| 3694 | vinfos[4].jointtype = 1; |
| 3695 | vinfos[4].foffset = j4; |
| 3696 | vinfos[4].indices[0] = _ij4[0]; |
| 3697 | vinfos[4].indices[1] = _ij4[1]; |
| 3698 | vinfos[4].maxsolutions = _nj4; |
| 3699 | vinfos[5].jointtype = 1; |
| 3700 | vinfos[5].foffset = j5; |
| 3701 | vinfos[5].indices[0] = _ij5[0]; |
| 3702 | vinfos[5].indices[1] = _ij5[1]; |
| 3703 | vinfos[5].maxsolutions = _nj5; |
| 3704 | std::vector<int> vfree(0); |
| 3705 | solutions.AddSolution(vinfos,vfree); |
| 3706 | } |
| 3707 | } |
| 3708 | } |
| 3709 | |
| 3710 | } else |
| 3711 | { |
| 3712 | { |
| 3713 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3714 | bool j2valid[1]={false}; |
| 3715 | _nj2 = 1; |
| 3716 | CheckValue<IkReal> x192=IKPowWithIntegerCheck(IKsign(gconst41),-1); |
| 3717 | if(!x192.valid){ |
| 3718 | continue; |
| 3719 | } |
| 3720 | CheckValue<IkReal> x193 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 3721 | if(!x193.valid){ |
| 3722 | continue; |
| 3723 | } |
| 3724 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x192.value)))+(x193.value)); |
| 3725 | sj2array[0]=IKsin(j2array[0]); |
| 3726 | cj2array[0]=IKcos(j2array[0]); |
| 3727 | if( j2array[0] > IKPI ) |
| 3728 | { |
| 3729 | j2array[0]-=IK2PI; |
| 3730 | } |
| 3731 | else if( j2array[0] < -IKPI ) |
| 3732 | { j2array[0]+=IK2PI; |
| 3733 | } |
| 3734 | j2valid[0] = true; |
| 3735 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3736 | { |
| 3737 | if( !j2valid[ij2] ) |
| 3738 | { |
| 3739 | continue; |
| 3740 | } |
| 3741 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3742 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3743 | { |
| 3744 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3745 | { |
| 3746 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3747 | } |
| 3748 | } |
| 3749 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3750 | { |
| 3751 | IkReal evalcond[8]; |
| 3752 | IkReal x194=IKsin(j2); |
| 3753 | IkReal x195=IKcos(j2); |
| 3754 | IkReal x196=((1.0)*gconst41); |
| 3755 | if((((1.0)+(((-1.0)*gconst41*x196)))) < -0.00001) |
| 3756 | continue; |
| 3757 | IkReal x197=IKsqrt(((1.0)+(((-1.0)*gconst41*x196)))); |
| 3758 | IkReal x198=((1.0)*x197); |
| 3759 | evalcond[0]=((-1.0)*x194); |
| 3760 | evalcond[1]=((-1.0)*x195); |
| 3761 | evalcond[2]=(((gconst41*x194))+new_r11); |
| 3762 | evalcond[3]=((((-1.0)*x195*x196))+new_r10); |
| 3763 | evalcond[4]=(((x194*x197))+new_r01); |
| 3764 | evalcond[5]=((((-1.0)*x195*x198))+new_r00); |
| 3765 | evalcond[6]=(((new_r01*x197))+((gconst41*new_r11))+x194); |
| 3766 | evalcond[7]=(x195+(((-1.0)*new_r10*x196))+(((-1.0)*new_r00*x198))); |
| 3767 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 3768 | { |
| 3769 | continue; |
| 3770 | } |
| 3771 | } |
| 3772 | |
| 3773 | { |
| 3774 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3775 | vinfos[0].jointtype = 1; |
| 3776 | vinfos[0].foffset = j0; |
| 3777 | vinfos[0].indices[0] = _ij0[0]; |
| 3778 | vinfos[0].indices[1] = _ij0[1]; |
| 3779 | vinfos[0].maxsolutions = _nj0; |
| 3780 | vinfos[1].jointtype = 1; |
| 3781 | vinfos[1].foffset = j1; |
| 3782 | vinfos[1].indices[0] = _ij1[0]; |
| 3783 | vinfos[1].indices[1] = _ij1[1]; |
| 3784 | vinfos[1].maxsolutions = _nj1; |
| 3785 | vinfos[2].jointtype = 1; |
| 3786 | vinfos[2].foffset = j2; |
| 3787 | vinfos[2].indices[0] = _ij2[0]; |
| 3788 | vinfos[2].indices[1] = _ij2[1]; |
| 3789 | vinfos[2].maxsolutions = _nj2; |
| 3790 | vinfos[3].jointtype = 1; |
| 3791 | vinfos[3].foffset = j3; |
| 3792 | vinfos[3].indices[0] = _ij3[0]; |
| 3793 | vinfos[3].indices[1] = _ij3[1]; |
| 3794 | vinfos[3].maxsolutions = _nj3; |
| 3795 | vinfos[4].jointtype = 1; |
| 3796 | vinfos[4].foffset = j4; |
| 3797 | vinfos[4].indices[0] = _ij4[0]; |
| 3798 | vinfos[4].indices[1] = _ij4[1]; |
| 3799 | vinfos[4].maxsolutions = _nj4; |
| 3800 | vinfos[5].jointtype = 1; |
| 3801 | vinfos[5].foffset = j5; |
| 3802 | vinfos[5].indices[0] = _ij5[0]; |
| 3803 | vinfos[5].indices[1] = _ij5[1]; |
| 3804 | vinfos[5].maxsolutions = _nj5; |
| 3805 | std::vector<int> vfree(0); |
| 3806 | solutions.AddSolution(vinfos,vfree); |
| 3807 | } |
| 3808 | } |
| 3809 | } |
| 3810 | |
| 3811 | } |
| 3812 | |
| 3813 | } |
| 3814 | |
| 3815 | } |
| 3816 | } while(0); |
| 3817 | if( bgotonextstatement ) |
| 3818 | { |
| 3819 | bool bgotonextstatement = true; |
| 3820 | do |
| 3821 | { |
| 3822 | if( 1 ) |
| 3823 | { |
| 3824 | bgotonextstatement=false; |
| 3825 | continue; // branch miss [j2] |
| 3826 | |
| 3827 | } |
| 3828 | } while(0); |
| 3829 | if( bgotonextstatement ) |
| 3830 | { |
| 3831 | } |
| 3832 | } |
| 3833 | } |
| 3834 | } |
| 3835 | } |
| 3836 | } |
| 3837 | } |
| 3838 | } |
| 3839 | } |
| 3840 | } |
| 3841 | |
| 3842 | } else |
| 3843 | { |
| 3844 | { |
| 3845 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3846 | bool j2valid[1]={false}; |
| 3847 | _nj2 = 1; |
| 3848 | IkReal x199=new_r22*new_r22; |
| 3849 | IkReal x200=((1.0)*new_r22); |
| 3850 | CheckValue<IkReal> x201=IKPowWithIntegerCheck((((cj0*x199))+(((-1.0)*cj0))),-1); |
| 3851 | if(!x201.valid){ |
| 3852 | continue; |
| 3853 | } |
| 3854 | CheckValue<IkReal> x202=IKPowWithIntegerCheck(((((-1.0)*sj0))+((sj0*x199))),-1); |
| 3855 | if(!x202.valid){ |
| 3856 | continue; |
| 3857 | } |
| 3858 | if( IKabs(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((x202.value)*((new_r00+(((-1.0)*new_r11*x200)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11))))+IKsqr(((x202.value)*((new_r00+(((-1.0)*new_r11*x200))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 3859 | continue; |
| 3860 | j2array[0]=IKatan2(((x201.value)*(((((-1.0)*new_r00*x200))+new_r11))), ((x202.value)*((new_r00+(((-1.0)*new_r11*x200)))))); |
| 3861 | sj2array[0]=IKsin(j2array[0]); |
| 3862 | cj2array[0]=IKcos(j2array[0]); |
| 3863 | if( j2array[0] > IKPI ) |
| 3864 | { |
| 3865 | j2array[0]-=IK2PI; |
| 3866 | } |
| 3867 | else if( j2array[0] < -IKPI ) |
| 3868 | { j2array[0]+=IK2PI; |
| 3869 | } |
| 3870 | j2valid[0] = true; |
| 3871 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3872 | { |
| 3873 | if( !j2valid[ij2] ) |
| 3874 | { |
| 3875 | continue; |
| 3876 | } |
| 3877 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3878 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3879 | { |
| 3880 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3881 | { |
| 3882 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3883 | } |
| 3884 | } |
| 3885 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3886 | { |
| 3887 | IkReal evalcond[10]; |
| 3888 | IkReal x203=IKsin(j2); |
| 3889 | IkReal x204=IKcos(j2); |
| 3890 | IkReal x205=((1.0)*sj0); |
| 3891 | IkReal x206=((1.0)*cj0); |
| 3892 | IkReal x207=(new_r22*x203); |
| 3893 | IkReal x208=(new_r22*x204); |
| 3894 | evalcond[0]=(x203+((cj0*new_r11))+(((-1.0)*new_r01*x205))); |
| 3895 | evalcond[1]=(((new_r00*sj0))+x204+(((-1.0)*new_r10*x206))); |
| 3896 | evalcond[2]=(((new_r10*sj0))+x207+((cj0*new_r00))); |
| 3897 | evalcond[3]=(((new_r11*sj0))+x208+((cj0*new_r01))); |
| 3898 | evalcond[4]=(((sj0*x204))+((cj0*x207))+new_r00); |
| 3899 | evalcond[5]=(((sj0*x208))+((cj0*x203))+new_r11); |
| 3900 | evalcond[6]=((((-1.0)*x203*x205))+((cj0*x208))+new_r01); |
| 3901 | evalcond[7]=((((-1.0)*x204*x206))+((sj0*x207))+new_r10); |
| 3902 | evalcond[8]=((((-1.0)*new_r10*new_r22*x205))+(((-1.0)*new_r00*new_r22*x206))+(((-1.0)*x203))); |
| 3903 | evalcond[9]=((((-1.0)*new_r01*new_r22*x206))+(((-1.0)*new_r11*new_r22*x205))+(((-1.0)*x204))); |
| 3904 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) |
| 3905 | { |
| 3906 | continue; |
| 3907 | } |
| 3908 | } |
| 3909 | |
| 3910 | { |
| 3911 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 3912 | vinfos[0].jointtype = 1; |
| 3913 | vinfos[0].foffset = j0; |
| 3914 | vinfos[0].indices[0] = _ij0[0]; |
| 3915 | vinfos[0].indices[1] = _ij0[1]; |
| 3916 | vinfos[0].maxsolutions = _nj0; |
| 3917 | vinfos[1].jointtype = 1; |
| 3918 | vinfos[1].foffset = j1; |
| 3919 | vinfos[1].indices[0] = _ij1[0]; |
| 3920 | vinfos[1].indices[1] = _ij1[1]; |
| 3921 | vinfos[1].maxsolutions = _nj1; |
| 3922 | vinfos[2].jointtype = 1; |
| 3923 | vinfos[2].foffset = j2; |
| 3924 | vinfos[2].indices[0] = _ij2[0]; |
| 3925 | vinfos[2].indices[1] = _ij2[1]; |
| 3926 | vinfos[2].maxsolutions = _nj2; |
| 3927 | vinfos[3].jointtype = 1; |
| 3928 | vinfos[3].foffset = j3; |
| 3929 | vinfos[3].indices[0] = _ij3[0]; |
| 3930 | vinfos[3].indices[1] = _ij3[1]; |
| 3931 | vinfos[3].maxsolutions = _nj3; |
| 3932 | vinfos[4].jointtype = 1; |
| 3933 | vinfos[4].foffset = j4; |
| 3934 | vinfos[4].indices[0] = _ij4[0]; |
| 3935 | vinfos[4].indices[1] = _ij4[1]; |
| 3936 | vinfos[4].maxsolutions = _nj4; |
| 3937 | vinfos[5].jointtype = 1; |
| 3938 | vinfos[5].foffset = j5; |
| 3939 | vinfos[5].indices[0] = _ij5[0]; |
| 3940 | vinfos[5].indices[1] = _ij5[1]; |
| 3941 | vinfos[5].maxsolutions = _nj5; |
| 3942 | std::vector<int> vfree(0); |
| 3943 | solutions.AddSolution(vinfos,vfree); |
| 3944 | } |
| 3945 | } |
| 3946 | } |
| 3947 | |
| 3948 | } |
| 3949 | |
| 3950 | } |
| 3951 | |
| 3952 | } else |
| 3953 | { |
| 3954 | { |
| 3955 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 3956 | bool j2valid[1]={false}; |
| 3957 | _nj2 = 1; |
| 3958 | IkReal x209=((1.0)*new_r00); |
| 3959 | CheckValue<IkReal> x210=IKPowWithIntegerCheck(new_r22,-1); |
| 3960 | if(!x210.valid){ |
| 3961 | continue; |
| 3962 | } |
| 3963 | if( IKabs(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r10))+(((-1.0)*sj0*x209)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0))))))+IKsqr((((cj0*new_r10))+(((-1.0)*sj0*x209))))-1) <= IKFAST_SINCOS_THRESH ) |
| 3964 | continue; |
| 3965 | j2array[0]=IKatan2(((x210.value)*(((((-1.0)*cj0*x209))+(((-1.0)*new_r10*sj0))))), (((cj0*new_r10))+(((-1.0)*sj0*x209)))); |
| 3966 | sj2array[0]=IKsin(j2array[0]); |
| 3967 | cj2array[0]=IKcos(j2array[0]); |
| 3968 | if( j2array[0] > IKPI ) |
| 3969 | { |
| 3970 | j2array[0]-=IK2PI; |
| 3971 | } |
| 3972 | else if( j2array[0] < -IKPI ) |
| 3973 | { j2array[0]+=IK2PI; |
| 3974 | } |
| 3975 | j2valid[0] = true; |
| 3976 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 3977 | { |
| 3978 | if( !j2valid[ij2] ) |
| 3979 | { |
| 3980 | continue; |
| 3981 | } |
| 3982 | _ij2[0] = ij2; _ij2[1] = -1; |
| 3983 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 3984 | { |
| 3985 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 3986 | { |
| 3987 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 3988 | } |
| 3989 | } |
| 3990 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 3991 | { |
| 3992 | IkReal evalcond[10]; |
| 3993 | IkReal x211=IKsin(j2); |
| 3994 | IkReal x212=IKcos(j2); |
| 3995 | IkReal x213=((1.0)*sj0); |
| 3996 | IkReal x214=((1.0)*cj0); |
| 3997 | IkReal x215=(new_r22*x211); |
| 3998 | IkReal x216=(new_r22*x212); |
| 3999 | evalcond[0]=(x211+(((-1.0)*new_r01*x213))+((cj0*new_r11))); |
| 4000 | evalcond[1]=(((new_r00*sj0))+(((-1.0)*new_r10*x214))+x212); |
| 4001 | evalcond[2]=(((new_r10*sj0))+x215+((cj0*new_r00))); |
| 4002 | evalcond[3]=(((new_r11*sj0))+x216+((cj0*new_r01))); |
| 4003 | evalcond[4]=(((cj0*x215))+((sj0*x212))+new_r00); |
| 4004 | evalcond[5]=(((cj0*x211))+((sj0*x216))+new_r11); |
| 4005 | evalcond[6]=(((cj0*x216))+(((-1.0)*x211*x213))+new_r01); |
| 4006 | evalcond[7]=(((sj0*x215))+new_r10+(((-1.0)*x212*x214))); |
| 4007 | evalcond[8]=((((-1.0)*x211))+(((-1.0)*new_r00*new_r22*x214))+(((-1.0)*new_r10*new_r22*x213))); |
| 4008 | evalcond[9]=((((-1.0)*x212))+(((-1.0)*new_r11*new_r22*x213))+(((-1.0)*new_r01*new_r22*x214))); |
| 4009 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) |
| 4010 | { |
| 4011 | continue; |
| 4012 | } |
| 4013 | } |
| 4014 | |
| 4015 | { |
| 4016 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4017 | vinfos[0].jointtype = 1; |
| 4018 | vinfos[0].foffset = j0; |
| 4019 | vinfos[0].indices[0] = _ij0[0]; |
| 4020 | vinfos[0].indices[1] = _ij0[1]; |
| 4021 | vinfos[0].maxsolutions = _nj0; |
| 4022 | vinfos[1].jointtype = 1; |
| 4023 | vinfos[1].foffset = j1; |
| 4024 | vinfos[1].indices[0] = _ij1[0]; |
| 4025 | vinfos[1].indices[1] = _ij1[1]; |
| 4026 | vinfos[1].maxsolutions = _nj1; |
| 4027 | vinfos[2].jointtype = 1; |
| 4028 | vinfos[2].foffset = j2; |
| 4029 | vinfos[2].indices[0] = _ij2[0]; |
| 4030 | vinfos[2].indices[1] = _ij2[1]; |
| 4031 | vinfos[2].maxsolutions = _nj2; |
| 4032 | vinfos[3].jointtype = 1; |
| 4033 | vinfos[3].foffset = j3; |
| 4034 | vinfos[3].indices[0] = _ij3[0]; |
| 4035 | vinfos[3].indices[1] = _ij3[1]; |
| 4036 | vinfos[3].maxsolutions = _nj3; |
| 4037 | vinfos[4].jointtype = 1; |
| 4038 | vinfos[4].foffset = j4; |
| 4039 | vinfos[4].indices[0] = _ij4[0]; |
| 4040 | vinfos[4].indices[1] = _ij4[1]; |
| 4041 | vinfos[4].maxsolutions = _nj4; |
| 4042 | vinfos[5].jointtype = 1; |
| 4043 | vinfos[5].foffset = j5; |
| 4044 | vinfos[5].indices[0] = _ij5[0]; |
| 4045 | vinfos[5].indices[1] = _ij5[1]; |
| 4046 | vinfos[5].maxsolutions = _nj5; |
| 4047 | std::vector<int> vfree(0); |
| 4048 | solutions.AddSolution(vinfos,vfree); |
| 4049 | } |
| 4050 | } |
| 4051 | } |
| 4052 | |
| 4053 | } |
| 4054 | |
| 4055 | } |
| 4056 | |
| 4057 | } else |
| 4058 | { |
| 4059 | { |
| 4060 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4061 | bool j2valid[1]={false}; |
| 4062 | _nj2 = 1; |
| 4063 | IkReal x217=cj0*cj0; |
| 4064 | IkReal x218=((1.0)*new_r00); |
| 4065 | IkReal x219=(cj0*new_r22); |
| 4066 | CheckValue<IkReal> x220=IKPowWithIntegerCheck(IKsign(((1.0)+(((-1.0)*x217))+((x217*(new_r22*new_r22))))),-1); |
| 4067 | if(!x220.valid){ |
| 4068 | continue; |
| 4069 | } |
| 4070 | CheckValue<IkReal> x221 = IKatan2WithCheck(IkReal((((new_r01*sj0))+(((-1.0)*x218*x219)))),IkReal(((((-1.0)*new_r01*x219))+(((-1.0)*sj0*x218)))),IKFAST_ATAN2_MAGTHRESH); |
| 4071 | if(!x221.valid){ |
| 4072 | continue; |
| 4073 | } |
| 4074 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x220.value)))+(x221.value)); |
| 4075 | sj2array[0]=IKsin(j2array[0]); |
| 4076 | cj2array[0]=IKcos(j2array[0]); |
| 4077 | if( j2array[0] > IKPI ) |
| 4078 | { |
| 4079 | j2array[0]-=IK2PI; |
| 4080 | } |
| 4081 | else if( j2array[0] < -IKPI ) |
| 4082 | { j2array[0]+=IK2PI; |
| 4083 | } |
| 4084 | j2valid[0] = true; |
| 4085 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4086 | { |
| 4087 | if( !j2valid[ij2] ) |
| 4088 | { |
| 4089 | continue; |
| 4090 | } |
| 4091 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4092 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4093 | { |
| 4094 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4095 | { |
| 4096 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4097 | } |
| 4098 | } |
| 4099 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4100 | { |
| 4101 | IkReal evalcond[10]; |
| 4102 | IkReal x222=IKsin(j2); |
| 4103 | IkReal x223=IKcos(j2); |
| 4104 | IkReal x224=((1.0)*sj0); |
| 4105 | IkReal x225=((1.0)*cj0); |
| 4106 | IkReal x226=(new_r22*x222); |
| 4107 | IkReal x227=(new_r22*x223); |
| 4108 | evalcond[0]=((((-1.0)*new_r01*x224))+x222+((cj0*new_r11))); |
| 4109 | evalcond[1]=((((-1.0)*new_r10*x225))+((new_r00*sj0))+x223); |
| 4110 | evalcond[2]=(((new_r10*sj0))+x226+((cj0*new_r00))); |
| 4111 | evalcond[3]=(((new_r11*sj0))+x227+((cj0*new_r01))); |
| 4112 | evalcond[4]=(((sj0*x223))+((cj0*x226))+new_r00); |
| 4113 | evalcond[5]=(((sj0*x227))+((cj0*x222))+new_r11); |
| 4114 | evalcond[6]=((((-1.0)*x222*x224))+((cj0*x227))+new_r01); |
| 4115 | evalcond[7]=(((sj0*x226))+(((-1.0)*x223*x225))+new_r10); |
| 4116 | evalcond[8]=((((-1.0)*new_r00*new_r22*x225))+(((-1.0)*new_r10*new_r22*x224))+(((-1.0)*x222))); |
| 4117 | evalcond[9]=((((-1.0)*new_r11*new_r22*x224))+(((-1.0)*new_r01*new_r22*x225))+(((-1.0)*x223))); |
| 4118 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH ) |
| 4119 | { |
| 4120 | continue; |
| 4121 | } |
| 4122 | } |
| 4123 | |
| 4124 | { |
| 4125 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4126 | vinfos[0].jointtype = 1; |
| 4127 | vinfos[0].foffset = j0; |
| 4128 | vinfos[0].indices[0] = _ij0[0]; |
| 4129 | vinfos[0].indices[1] = _ij0[1]; |
| 4130 | vinfos[0].maxsolutions = _nj0; |
| 4131 | vinfos[1].jointtype = 1; |
| 4132 | vinfos[1].foffset = j1; |
| 4133 | vinfos[1].indices[0] = _ij1[0]; |
| 4134 | vinfos[1].indices[1] = _ij1[1]; |
| 4135 | vinfos[1].maxsolutions = _nj1; |
| 4136 | vinfos[2].jointtype = 1; |
| 4137 | vinfos[2].foffset = j2; |
| 4138 | vinfos[2].indices[0] = _ij2[0]; |
| 4139 | vinfos[2].indices[1] = _ij2[1]; |
| 4140 | vinfos[2].maxsolutions = _nj2; |
| 4141 | vinfos[3].jointtype = 1; |
| 4142 | vinfos[3].foffset = j3; |
| 4143 | vinfos[3].indices[0] = _ij3[0]; |
| 4144 | vinfos[3].indices[1] = _ij3[1]; |
| 4145 | vinfos[3].maxsolutions = _nj3; |
| 4146 | vinfos[4].jointtype = 1; |
| 4147 | vinfos[4].foffset = j4; |
| 4148 | vinfos[4].indices[0] = _ij4[0]; |
| 4149 | vinfos[4].indices[1] = _ij4[1]; |
| 4150 | vinfos[4].maxsolutions = _nj4; |
| 4151 | vinfos[5].jointtype = 1; |
| 4152 | vinfos[5].foffset = j5; |
| 4153 | vinfos[5].indices[0] = _ij5[0]; |
| 4154 | vinfos[5].indices[1] = _ij5[1]; |
| 4155 | vinfos[5].maxsolutions = _nj5; |
| 4156 | std::vector<int> vfree(0); |
| 4157 | solutions.AddSolution(vinfos,vfree); |
| 4158 | } |
| 4159 | } |
| 4160 | } |
| 4161 | |
| 4162 | } |
| 4163 | |
| 4164 | } |
| 4165 | } |
| 4166 | |
| 4167 | } |
| 4168 | |
| 4169 | } |
| 4170 | |
| 4171 | } |
| 4172 | } while(0); |
| 4173 | if( bgotonextstatement ) |
| 4174 | { |
| 4175 | bool bgotonextstatement = true; |
| 4176 | do |
| 4177 | { |
| 4178 | if( 1 ) |
| 4179 | { |
| 4180 | bgotonextstatement=false; |
| 4181 | continue; // branch miss [j0, j2] |
| 4182 | |
| 4183 | } |
| 4184 | } while(0); |
| 4185 | if( bgotonextstatement ) |
| 4186 | { |
| 4187 | } |
| 4188 | } |
| 4189 | } |
| 4190 | } |
| 4191 | } |
| 4192 | |
| 4193 | } else |
| 4194 | { |
| 4195 | { |
| 4196 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 4197 | bool j0valid[1]={false}; |
| 4198 | _nj0 = 1; |
| 4199 | CheckValue<IkReal> x229=IKPowWithIntegerCheck(cj1,-1); |
| 4200 | if(!x229.valid){ |
| 4201 | continue; |
| 4202 | } |
| 4203 | IkReal x228=x229.value; |
| 4204 | CheckValue<IkReal> x230=IKPowWithIntegerCheck(new_r12,-1); |
| 4205 | if(!x230.valid){ |
| 4206 | continue; |
| 4207 | } |
| 4208 | CheckValue<IkReal> x231=IKPowWithIntegerCheck(x228,-2); |
| 4209 | if(!x231.valid){ |
| 4210 | continue; |
| 4211 | } |
| 4212 | if( IKabs((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r02*x228)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value)))))+IKsqr((new_r02*x228))-1) <= IKFAST_SINCOS_THRESH ) |
| 4213 | continue; |
| 4214 | j0array[0]=IKatan2((x228*(x230.value)*(((((-1.0)*(new_r02*new_r02)))+(x231.value)))), (new_r02*x228)); |
| 4215 | sj0array[0]=IKsin(j0array[0]); |
| 4216 | cj0array[0]=IKcos(j0array[0]); |
| 4217 | if( j0array[0] > IKPI ) |
| 4218 | { |
| 4219 | j0array[0]-=IK2PI; |
| 4220 | } |
| 4221 | else if( j0array[0] < -IKPI ) |
| 4222 | { j0array[0]+=IK2PI; |
| 4223 | } |
| 4224 | j0valid[0] = true; |
| 4225 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 4226 | { |
| 4227 | if( !j0valid[ij0] ) |
| 4228 | { |
| 4229 | continue; |
| 4230 | } |
| 4231 | _ij0[0] = ij0; _ij0[1] = -1; |
| 4232 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 4233 | { |
| 4234 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 4235 | { |
| 4236 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 4237 | } |
| 4238 | } |
| 4239 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 4240 | { |
| 4241 | IkReal evalcond[8]; |
| 4242 | IkReal x232=IKcos(j0); |
| 4243 | IkReal x233=IKsin(j0); |
| 4244 | IkReal x234=(cj1*x232); |
| 4245 | IkReal x235=(cj1*x233); |
| 4246 | IkReal x236=((1.0)*x233); |
| 4247 | IkReal x237=(new_r02*x232); |
| 4248 | evalcond[0]=(new_r02+(((-1.0)*x234))); |
| 4249 | evalcond[1]=(new_r12+(((-1.0)*x235))); |
| 4250 | evalcond[2]=((((-1.0)*new_r02*x236))+((new_r12*x232))); |
| 4251 | evalcond[3]=(((new_r12*x233))+x237+(((-1.0)*cj1))); |
| 4252 | evalcond[4]=(((new_r10*x235))+((new_r20*sj1))+((new_r00*x234))); |
| 4253 | evalcond[5]=(((new_r11*x235))+((new_r01*x234))+((new_r21*sj1))); |
| 4254 | evalcond[6]=((-1.0)+((new_r02*x234))+((new_r12*x235))+((new_r22*sj1))); |
| 4255 | evalcond[7]=(((cj1*new_r22))+(((-1.0)*sj1*x237))+(((-1.0)*new_r12*sj1*x236))); |
| 4256 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4257 | { |
| 4258 | continue; |
| 4259 | } |
| 4260 | } |
| 4261 | |
| 4262 | { |
| 4263 | IkReal j2eval[3]; |
| 4264 | j2eval[0]=cj1; |
| 4265 | j2eval[1]=IKsign(cj1); |
| 4266 | j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| 4267 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 4268 | { |
| 4269 | { |
| 4270 | IkReal j2eval[2]; |
| 4271 | j2eval[0]=cj1; |
| 4272 | j2eval[1]=sj0; |
| 4273 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| 4274 | { |
| 4275 | { |
| 4276 | IkReal j2eval[3]; |
| 4277 | j2eval[0]=cj1; |
| 4278 | j2eval[1]=sj0; |
| 4279 | j2eval[2]=sj1; |
| 4280 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 4281 | { |
| 4282 | { |
| 4283 | IkReal evalcond[5]; |
| 4284 | bool bgotonextstatement = true; |
| 4285 | do |
| 4286 | { |
| 4287 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| 4288 | evalcond[1]=new_r02; |
| 4289 | evalcond[2]=new_r12; |
| 4290 | evalcond[3]=new_r20; |
| 4291 | evalcond[4]=new_r21; |
| 4292 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 4293 | { |
| 4294 | bgotonextstatement=false; |
| 4295 | { |
| 4296 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4297 | bool j2valid[1]={false}; |
| 4298 | _nj2 = 1; |
| 4299 | IkReal x238=((1.0)*cj0); |
| 4300 | if( IKabs((((new_r01*sj0))+(((-1.0)*new_r00*x238)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+(((-1.0)*new_r00*x238))))+IKsqr(((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238))))-1) <= IKFAST_SINCOS_THRESH ) |
| 4301 | continue; |
| 4302 | j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x238))), ((((-1.0)*new_r00*sj0))+(((-1.0)*new_r01*x238)))); |
| 4303 | sj2array[0]=IKsin(j2array[0]); |
| 4304 | cj2array[0]=IKcos(j2array[0]); |
| 4305 | if( j2array[0] > IKPI ) |
| 4306 | { |
| 4307 | j2array[0]-=IK2PI; |
| 4308 | } |
| 4309 | else if( j2array[0] < -IKPI ) |
| 4310 | { j2array[0]+=IK2PI; |
| 4311 | } |
| 4312 | j2valid[0] = true; |
| 4313 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4314 | { |
| 4315 | if( !j2valid[ij2] ) |
| 4316 | { |
| 4317 | continue; |
| 4318 | } |
| 4319 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4320 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4321 | { |
| 4322 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4323 | { |
| 4324 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4325 | } |
| 4326 | } |
| 4327 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4328 | { |
| 4329 | IkReal evalcond[8]; |
| 4330 | IkReal x239=IKsin(j2); |
| 4331 | IkReal x240=IKcos(j2); |
| 4332 | IkReal x241=((1.0)*cj0); |
| 4333 | IkReal x242=(sj0*x240); |
| 4334 | IkReal x243=(cj0*x239); |
| 4335 | IkReal x244=(sj0*x239); |
| 4336 | IkReal x245=(x243+x242); |
| 4337 | evalcond[0]=(((new_r10*sj0))+x239+((cj0*new_r00))); |
| 4338 | evalcond[1]=(((new_r11*sj0))+x240+((cj0*new_r01))); |
| 4339 | evalcond[2]=((((-1.0)*new_r01*sj0))+x239+((cj0*new_r11))); |
| 4340 | evalcond[3]=(((new_r00*sj0))+x240+(((-1.0)*new_r10*x241))); |
| 4341 | evalcond[4]=(x245+new_r00); |
| 4342 | evalcond[5]=(x245+new_r11); |
| 4343 | evalcond[6]=(((cj0*x240))+(((-1.0)*x244))+new_r01); |
| 4344 | evalcond[7]=(x244+(((-1.0)*x240*x241))+new_r10); |
| 4345 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4346 | { |
| 4347 | continue; |
| 4348 | } |
| 4349 | } |
| 4350 | |
| 4351 | { |
| 4352 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4353 | vinfos[0].jointtype = 1; |
| 4354 | vinfos[0].foffset = j0; |
| 4355 | vinfos[0].indices[0] = _ij0[0]; |
| 4356 | vinfos[0].indices[1] = _ij0[1]; |
| 4357 | vinfos[0].maxsolutions = _nj0; |
| 4358 | vinfos[1].jointtype = 1; |
| 4359 | vinfos[1].foffset = j1; |
| 4360 | vinfos[1].indices[0] = _ij1[0]; |
| 4361 | vinfos[1].indices[1] = _ij1[1]; |
| 4362 | vinfos[1].maxsolutions = _nj1; |
| 4363 | vinfos[2].jointtype = 1; |
| 4364 | vinfos[2].foffset = j2; |
| 4365 | vinfos[2].indices[0] = _ij2[0]; |
| 4366 | vinfos[2].indices[1] = _ij2[1]; |
| 4367 | vinfos[2].maxsolutions = _nj2; |
| 4368 | vinfos[3].jointtype = 1; |
| 4369 | vinfos[3].foffset = j3; |
| 4370 | vinfos[3].indices[0] = _ij3[0]; |
| 4371 | vinfos[3].indices[1] = _ij3[1]; |
| 4372 | vinfos[3].maxsolutions = _nj3; |
| 4373 | vinfos[4].jointtype = 1; |
| 4374 | vinfos[4].foffset = j4; |
| 4375 | vinfos[4].indices[0] = _ij4[0]; |
| 4376 | vinfos[4].indices[1] = _ij4[1]; |
| 4377 | vinfos[4].maxsolutions = _nj4; |
| 4378 | vinfos[5].jointtype = 1; |
| 4379 | vinfos[5].foffset = j5; |
| 4380 | vinfos[5].indices[0] = _ij5[0]; |
| 4381 | vinfos[5].indices[1] = _ij5[1]; |
| 4382 | vinfos[5].maxsolutions = _nj5; |
| 4383 | std::vector<int> vfree(0); |
| 4384 | solutions.AddSolution(vinfos,vfree); |
| 4385 | } |
| 4386 | } |
| 4387 | } |
| 4388 | |
| 4389 | } |
| 4390 | } while(0); |
| 4391 | if( bgotonextstatement ) |
| 4392 | { |
| 4393 | bool bgotonextstatement = true; |
| 4394 | do |
| 4395 | { |
| 4396 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| 4397 | evalcond[1]=new_r02; |
| 4398 | evalcond[2]=new_r12; |
| 4399 | evalcond[3]=new_r20; |
| 4400 | evalcond[4]=new_r21; |
| 4401 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 4402 | { |
| 4403 | bgotonextstatement=false; |
| 4404 | { |
| 4405 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4406 | bool j2valid[1]={false}; |
| 4407 | _nj2 = 1; |
| 4408 | if( IKabs((((new_r01*sj0))+((cj0*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r01))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+((cj0*new_r00))))+IKsqr((((cj0*new_r01))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH ) |
| 4409 | continue; |
| 4410 | j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0)))); |
| 4411 | sj2array[0]=IKsin(j2array[0]); |
| 4412 | cj2array[0]=IKcos(j2array[0]); |
| 4413 | if( j2array[0] > IKPI ) |
| 4414 | { |
| 4415 | j2array[0]-=IK2PI; |
| 4416 | } |
| 4417 | else if( j2array[0] < -IKPI ) |
| 4418 | { j2array[0]+=IK2PI; |
| 4419 | } |
| 4420 | j2valid[0] = true; |
| 4421 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4422 | { |
| 4423 | if( !j2valid[ij2] ) |
| 4424 | { |
| 4425 | continue; |
| 4426 | } |
| 4427 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4428 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4429 | { |
| 4430 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4431 | { |
| 4432 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4433 | } |
| 4434 | } |
| 4435 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4436 | { |
| 4437 | IkReal evalcond[8]; |
| 4438 | IkReal x246=IKsin(j2); |
| 4439 | IkReal x247=IKcos(j2); |
| 4440 | IkReal x248=((1.0)*sj0); |
| 4441 | IkReal x249=((1.0)*cj0); |
| 4442 | IkReal x250=((1.0)*x247); |
| 4443 | IkReal x251=(((x246*x248))+((x247*x249))); |
| 4444 | evalcond[0]=((((-1.0)*new_r01*x248))+x246+((cj0*new_r11))); |
| 4445 | evalcond[1]=(((new_r00*sj0))+x247+(((-1.0)*new_r10*x249))); |
| 4446 | evalcond[2]=((((-1.0)*x246))+((new_r10*sj0))+((cj0*new_r00))); |
| 4447 | evalcond[3]=(((new_r11*sj0))+((cj0*new_r01))+(((-1.0)*x250))); |
| 4448 | evalcond[4]=(new_r00+((sj0*x247))+(((-1.0)*x246*x249))); |
| 4449 | evalcond[5]=(((cj0*x246))+new_r11+(((-1.0)*x247*x248))); |
| 4450 | evalcond[6]=(new_r01+(((-1.0)*x251))); |
| 4451 | evalcond[7]=(new_r10+(((-1.0)*x251))); |
| 4452 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4453 | { |
| 4454 | continue; |
| 4455 | } |
| 4456 | } |
| 4457 | |
| 4458 | { |
| 4459 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4460 | vinfos[0].jointtype = 1; |
| 4461 | vinfos[0].foffset = j0; |
| 4462 | vinfos[0].indices[0] = _ij0[0]; |
| 4463 | vinfos[0].indices[1] = _ij0[1]; |
| 4464 | vinfos[0].maxsolutions = _nj0; |
| 4465 | vinfos[1].jointtype = 1; |
| 4466 | vinfos[1].foffset = j1; |
| 4467 | vinfos[1].indices[0] = _ij1[0]; |
| 4468 | vinfos[1].indices[1] = _ij1[1]; |
| 4469 | vinfos[1].maxsolutions = _nj1; |
| 4470 | vinfos[2].jointtype = 1; |
| 4471 | vinfos[2].foffset = j2; |
| 4472 | vinfos[2].indices[0] = _ij2[0]; |
| 4473 | vinfos[2].indices[1] = _ij2[1]; |
| 4474 | vinfos[2].maxsolutions = _nj2; |
| 4475 | vinfos[3].jointtype = 1; |
| 4476 | vinfos[3].foffset = j3; |
| 4477 | vinfos[3].indices[0] = _ij3[0]; |
| 4478 | vinfos[3].indices[1] = _ij3[1]; |
| 4479 | vinfos[3].maxsolutions = _nj3; |
| 4480 | vinfos[4].jointtype = 1; |
| 4481 | vinfos[4].foffset = j4; |
| 4482 | vinfos[4].indices[0] = _ij4[0]; |
| 4483 | vinfos[4].indices[1] = _ij4[1]; |
| 4484 | vinfos[4].maxsolutions = _nj4; |
| 4485 | vinfos[5].jointtype = 1; |
| 4486 | vinfos[5].foffset = j5; |
| 4487 | vinfos[5].indices[0] = _ij5[0]; |
| 4488 | vinfos[5].indices[1] = _ij5[1]; |
| 4489 | vinfos[5].maxsolutions = _nj5; |
| 4490 | std::vector<int> vfree(0); |
| 4491 | solutions.AddSolution(vinfos,vfree); |
| 4492 | } |
| 4493 | } |
| 4494 | } |
| 4495 | |
| 4496 | } |
| 4497 | } while(0); |
| 4498 | if( bgotonextstatement ) |
| 4499 | { |
| 4500 | bool bgotonextstatement = true; |
| 4501 | do |
| 4502 | { |
| 4503 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| 4504 | evalcond[1]=new_r12; |
| 4505 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 4506 | { |
| 4507 | bgotonextstatement=false; |
| 4508 | { |
| 4509 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4510 | bool j2valid[1]={false}; |
| 4511 | _nj2 = 1; |
| 4512 | if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) |
| 4513 | continue; |
| 4514 | j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| 4515 | sj2array[0]=IKsin(j2array[0]); |
| 4516 | cj2array[0]=IKcos(j2array[0]); |
| 4517 | if( j2array[0] > IKPI ) |
| 4518 | { |
| 4519 | j2array[0]-=IK2PI; |
| 4520 | } |
| 4521 | else if( j2array[0] < -IKPI ) |
| 4522 | { j2array[0]+=IK2PI; |
| 4523 | } |
| 4524 | j2valid[0] = true; |
| 4525 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4526 | { |
| 4527 | if( !j2valid[ij2] ) |
| 4528 | { |
| 4529 | continue; |
| 4530 | } |
| 4531 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4532 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4533 | { |
| 4534 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4535 | { |
| 4536 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4537 | } |
| 4538 | } |
| 4539 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4540 | { |
| 4541 | IkReal evalcond[8]; |
| 4542 | IkReal x252=IKsin(j2); |
| 4543 | IkReal x253=IKcos(j2); |
| 4544 | IkReal x254=((1.0)*sj1); |
| 4545 | IkReal x255=((1.0)*cj1); |
| 4546 | evalcond[0]=(x252+new_r11); |
| 4547 | evalcond[1]=(x253+(((-1.0)*new_r10))); |
| 4548 | evalcond[2]=(((sj1*x252))+new_r00); |
| 4549 | evalcond[3]=(((sj1*x253))+new_r01); |
| 4550 | evalcond[4]=((((-1.0)*x252*x255))+new_r20); |
| 4551 | evalcond[5]=(new_r21+(((-1.0)*x253*x255))); |
| 4552 | evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x254))+(((-1.0)*x252))); |
| 4553 | evalcond[7]=((((-1.0)*new_r01*x254))+((cj1*new_r21))+(((-1.0)*x253))); |
| 4554 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4555 | { |
| 4556 | continue; |
| 4557 | } |
| 4558 | } |
| 4559 | |
| 4560 | { |
| 4561 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4562 | vinfos[0].jointtype = 1; |
| 4563 | vinfos[0].foffset = j0; |
| 4564 | vinfos[0].indices[0] = _ij0[0]; |
| 4565 | vinfos[0].indices[1] = _ij0[1]; |
| 4566 | vinfos[0].maxsolutions = _nj0; |
| 4567 | vinfos[1].jointtype = 1; |
| 4568 | vinfos[1].foffset = j1; |
| 4569 | vinfos[1].indices[0] = _ij1[0]; |
| 4570 | vinfos[1].indices[1] = _ij1[1]; |
| 4571 | vinfos[1].maxsolutions = _nj1; |
| 4572 | vinfos[2].jointtype = 1; |
| 4573 | vinfos[2].foffset = j2; |
| 4574 | vinfos[2].indices[0] = _ij2[0]; |
| 4575 | vinfos[2].indices[1] = _ij2[1]; |
| 4576 | vinfos[2].maxsolutions = _nj2; |
| 4577 | vinfos[3].jointtype = 1; |
| 4578 | vinfos[3].foffset = j3; |
| 4579 | vinfos[3].indices[0] = _ij3[0]; |
| 4580 | vinfos[3].indices[1] = _ij3[1]; |
| 4581 | vinfos[3].maxsolutions = _nj3; |
| 4582 | vinfos[4].jointtype = 1; |
| 4583 | vinfos[4].foffset = j4; |
| 4584 | vinfos[4].indices[0] = _ij4[0]; |
| 4585 | vinfos[4].indices[1] = _ij4[1]; |
| 4586 | vinfos[4].maxsolutions = _nj4; |
| 4587 | vinfos[5].jointtype = 1; |
| 4588 | vinfos[5].foffset = j5; |
| 4589 | vinfos[5].indices[0] = _ij5[0]; |
| 4590 | vinfos[5].indices[1] = _ij5[1]; |
| 4591 | vinfos[5].maxsolutions = _nj5; |
| 4592 | std::vector<int> vfree(0); |
| 4593 | solutions.AddSolution(vinfos,vfree); |
| 4594 | } |
| 4595 | } |
| 4596 | } |
| 4597 | |
| 4598 | } |
| 4599 | } while(0); |
| 4600 | if( bgotonextstatement ) |
| 4601 | { |
| 4602 | bool bgotonextstatement = true; |
| 4603 | do |
| 4604 | { |
| 4605 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| 4606 | evalcond[1]=new_r12; |
| 4607 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 4608 | { |
| 4609 | bgotonextstatement=false; |
| 4610 | { |
| 4611 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4612 | bool j2valid[1]={false}; |
| 4613 | _nj2 = 1; |
| 4614 | if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) |
| 4615 | continue; |
| 4616 | j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| 4617 | sj2array[0]=IKsin(j2array[0]); |
| 4618 | cj2array[0]=IKcos(j2array[0]); |
| 4619 | if( j2array[0] > IKPI ) |
| 4620 | { |
| 4621 | j2array[0]-=IK2PI; |
| 4622 | } |
| 4623 | else if( j2array[0] < -IKPI ) |
| 4624 | { j2array[0]+=IK2PI; |
| 4625 | } |
| 4626 | j2valid[0] = true; |
| 4627 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4628 | { |
| 4629 | if( !j2valid[ij2] ) |
| 4630 | { |
| 4631 | continue; |
| 4632 | } |
| 4633 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4634 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4635 | { |
| 4636 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4637 | { |
| 4638 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4639 | } |
| 4640 | } |
| 4641 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4642 | { |
| 4643 | IkReal evalcond[8]; |
| 4644 | IkReal x256=IKsin(j2); |
| 4645 | IkReal x257=IKcos(j2); |
| 4646 | IkReal x258=((1.0)*cj1); |
| 4647 | evalcond[0]=(x257+new_r10); |
| 4648 | evalcond[1]=(x256+(((-1.0)*new_r11))); |
| 4649 | evalcond[2]=((((-1.0)*x256*x258))+new_r20); |
| 4650 | evalcond[3]=((((-1.0)*x257*x258))+new_r21); |
| 4651 | evalcond[4]=(((sj1*x256))+(((-1.0)*new_r00))); |
| 4652 | evalcond[5]=(((sj1*x257))+(((-1.0)*new_r01))); |
| 4653 | evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x256))); |
| 4654 | evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x257))); |
| 4655 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4656 | { |
| 4657 | continue; |
| 4658 | } |
| 4659 | } |
| 4660 | |
| 4661 | { |
| 4662 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4663 | vinfos[0].jointtype = 1; |
| 4664 | vinfos[0].foffset = j0; |
| 4665 | vinfos[0].indices[0] = _ij0[0]; |
| 4666 | vinfos[0].indices[1] = _ij0[1]; |
| 4667 | vinfos[0].maxsolutions = _nj0; |
| 4668 | vinfos[1].jointtype = 1; |
| 4669 | vinfos[1].foffset = j1; |
| 4670 | vinfos[1].indices[0] = _ij1[0]; |
| 4671 | vinfos[1].indices[1] = _ij1[1]; |
| 4672 | vinfos[1].maxsolutions = _nj1; |
| 4673 | vinfos[2].jointtype = 1; |
| 4674 | vinfos[2].foffset = j2; |
| 4675 | vinfos[2].indices[0] = _ij2[0]; |
| 4676 | vinfos[2].indices[1] = _ij2[1]; |
| 4677 | vinfos[2].maxsolutions = _nj2; |
| 4678 | vinfos[3].jointtype = 1; |
| 4679 | vinfos[3].foffset = j3; |
| 4680 | vinfos[3].indices[0] = _ij3[0]; |
| 4681 | vinfos[3].indices[1] = _ij3[1]; |
| 4682 | vinfos[3].maxsolutions = _nj3; |
| 4683 | vinfos[4].jointtype = 1; |
| 4684 | vinfos[4].foffset = j4; |
| 4685 | vinfos[4].indices[0] = _ij4[0]; |
| 4686 | vinfos[4].indices[1] = _ij4[1]; |
| 4687 | vinfos[4].maxsolutions = _nj4; |
| 4688 | vinfos[5].jointtype = 1; |
| 4689 | vinfos[5].foffset = j5; |
| 4690 | vinfos[5].indices[0] = _ij5[0]; |
| 4691 | vinfos[5].indices[1] = _ij5[1]; |
| 4692 | vinfos[5].maxsolutions = _nj5; |
| 4693 | std::vector<int> vfree(0); |
| 4694 | solutions.AddSolution(vinfos,vfree); |
| 4695 | } |
| 4696 | } |
| 4697 | } |
| 4698 | |
| 4699 | } |
| 4700 | } while(0); |
| 4701 | if( bgotonextstatement ) |
| 4702 | { |
| 4703 | bool bgotonextstatement = true; |
| 4704 | do |
| 4705 | { |
| 4706 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959))); |
| 4707 | evalcond[1]=new_r22; |
| 4708 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 4709 | { |
| 4710 | bgotonextstatement=false; |
| 4711 | { |
| 4712 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4713 | bool j2valid[1]={false}; |
| 4714 | _nj2 = 1; |
| 4715 | if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) |
| 4716 | continue; |
| 4717 | j2array[0]=IKatan2(new_r20, new_r21); |
| 4718 | sj2array[0]=IKsin(j2array[0]); |
| 4719 | cj2array[0]=IKcos(j2array[0]); |
| 4720 | if( j2array[0] > IKPI ) |
| 4721 | { |
| 4722 | j2array[0]-=IK2PI; |
| 4723 | } |
| 4724 | else if( j2array[0] < -IKPI ) |
| 4725 | { j2array[0]+=IK2PI; |
| 4726 | } |
| 4727 | j2valid[0] = true; |
| 4728 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4729 | { |
| 4730 | if( !j2valid[ij2] ) |
| 4731 | { |
| 4732 | continue; |
| 4733 | } |
| 4734 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4735 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4736 | { |
| 4737 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4738 | { |
| 4739 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4740 | } |
| 4741 | } |
| 4742 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4743 | { |
| 4744 | IkReal evalcond[8]; |
| 4745 | IkReal x259=IKcos(j2); |
| 4746 | IkReal x260=IKsin(j2); |
| 4747 | IkReal x261=((1.0)*sj0); |
| 4748 | IkReal x262=((1.0)*x259); |
| 4749 | evalcond[0]=((((-1.0)*x260))+new_r20); |
| 4750 | evalcond[1]=(new_r21+(((-1.0)*x262))); |
| 4751 | evalcond[2]=(((sj0*x259))+new_r00); |
| 4752 | evalcond[3]=(((cj0*x260))+new_r11); |
| 4753 | evalcond[4]=(new_r01+(((-1.0)*x260*x261))); |
| 4754 | evalcond[5]=(new_r10+(((-1.0)*new_r02*x262))); |
| 4755 | evalcond[6]=((((-1.0)*new_r01*x261))+x260+((cj0*new_r11))); |
| 4756 | evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x259); |
| 4757 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4758 | { |
| 4759 | continue; |
| 4760 | } |
| 4761 | } |
| 4762 | |
| 4763 | { |
| 4764 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4765 | vinfos[0].jointtype = 1; |
| 4766 | vinfos[0].foffset = j0; |
| 4767 | vinfos[0].indices[0] = _ij0[0]; |
| 4768 | vinfos[0].indices[1] = _ij0[1]; |
| 4769 | vinfos[0].maxsolutions = _nj0; |
| 4770 | vinfos[1].jointtype = 1; |
| 4771 | vinfos[1].foffset = j1; |
| 4772 | vinfos[1].indices[0] = _ij1[0]; |
| 4773 | vinfos[1].indices[1] = _ij1[1]; |
| 4774 | vinfos[1].maxsolutions = _nj1; |
| 4775 | vinfos[2].jointtype = 1; |
| 4776 | vinfos[2].foffset = j2; |
| 4777 | vinfos[2].indices[0] = _ij2[0]; |
| 4778 | vinfos[2].indices[1] = _ij2[1]; |
| 4779 | vinfos[2].maxsolutions = _nj2; |
| 4780 | vinfos[3].jointtype = 1; |
| 4781 | vinfos[3].foffset = j3; |
| 4782 | vinfos[3].indices[0] = _ij3[0]; |
| 4783 | vinfos[3].indices[1] = _ij3[1]; |
| 4784 | vinfos[3].maxsolutions = _nj3; |
| 4785 | vinfos[4].jointtype = 1; |
| 4786 | vinfos[4].foffset = j4; |
| 4787 | vinfos[4].indices[0] = _ij4[0]; |
| 4788 | vinfos[4].indices[1] = _ij4[1]; |
| 4789 | vinfos[4].maxsolutions = _nj4; |
| 4790 | vinfos[5].jointtype = 1; |
| 4791 | vinfos[5].foffset = j5; |
| 4792 | vinfos[5].indices[0] = _ij5[0]; |
| 4793 | vinfos[5].indices[1] = _ij5[1]; |
| 4794 | vinfos[5].maxsolutions = _nj5; |
| 4795 | std::vector<int> vfree(0); |
| 4796 | solutions.AddSolution(vinfos,vfree); |
| 4797 | } |
| 4798 | } |
| 4799 | } |
| 4800 | |
| 4801 | } |
| 4802 | } while(0); |
| 4803 | if( bgotonextstatement ) |
| 4804 | { |
| 4805 | bool bgotonextstatement = true; |
| 4806 | do |
| 4807 | { |
| 4808 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959))); |
| 4809 | evalcond[1]=new_r22; |
| 4810 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 4811 | { |
| 4812 | bgotonextstatement=false; |
| 4813 | { |
| 4814 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 4815 | bool j2valid[1]={false}; |
| 4816 | _nj2 = 1; |
| 4817 | if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) |
| 4818 | continue; |
| 4819 | j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); |
| 4820 | sj2array[0]=IKsin(j2array[0]); |
| 4821 | cj2array[0]=IKcos(j2array[0]); |
| 4822 | if( j2array[0] > IKPI ) |
| 4823 | { |
| 4824 | j2array[0]-=IK2PI; |
| 4825 | } |
| 4826 | else if( j2array[0] < -IKPI ) |
| 4827 | { j2array[0]+=IK2PI; |
| 4828 | } |
| 4829 | j2valid[0] = true; |
| 4830 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 4831 | { |
| 4832 | if( !j2valid[ij2] ) |
| 4833 | { |
| 4834 | continue; |
| 4835 | } |
| 4836 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4837 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 4838 | { |
| 4839 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4840 | { |
| 4841 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4842 | } |
| 4843 | } |
| 4844 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4845 | { |
| 4846 | IkReal evalcond[8]; |
| 4847 | IkReal x263=IKcos(j2); |
| 4848 | IkReal x264=IKsin(j2); |
| 4849 | IkReal x265=((1.0)*sj0); |
| 4850 | evalcond[0]=(x264+new_r20); |
| 4851 | evalcond[1]=(x263+new_r21); |
| 4852 | evalcond[2]=(new_r00+((sj0*x263))); |
| 4853 | evalcond[3]=(((cj0*x264))+new_r11); |
| 4854 | evalcond[4]=(new_r10+((new_r02*x263))); |
| 4855 | evalcond[5]=(new_r01+(((-1.0)*x264*x265))); |
| 4856 | evalcond[6]=((((-1.0)*new_r01*x265))+x264+((cj0*new_r11))); |
| 4857 | evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x263); |
| 4858 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 4859 | { |
| 4860 | continue; |
| 4861 | } |
| 4862 | } |
| 4863 | |
| 4864 | { |
| 4865 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4866 | vinfos[0].jointtype = 1; |
| 4867 | vinfos[0].foffset = j0; |
| 4868 | vinfos[0].indices[0] = _ij0[0]; |
| 4869 | vinfos[0].indices[1] = _ij0[1]; |
| 4870 | vinfos[0].maxsolutions = _nj0; |
| 4871 | vinfos[1].jointtype = 1; |
| 4872 | vinfos[1].foffset = j1; |
| 4873 | vinfos[1].indices[0] = _ij1[0]; |
| 4874 | vinfos[1].indices[1] = _ij1[1]; |
| 4875 | vinfos[1].maxsolutions = _nj1; |
| 4876 | vinfos[2].jointtype = 1; |
| 4877 | vinfos[2].foffset = j2; |
| 4878 | vinfos[2].indices[0] = _ij2[0]; |
| 4879 | vinfos[2].indices[1] = _ij2[1]; |
| 4880 | vinfos[2].maxsolutions = _nj2; |
| 4881 | vinfos[3].jointtype = 1; |
| 4882 | vinfos[3].foffset = j3; |
| 4883 | vinfos[3].indices[0] = _ij3[0]; |
| 4884 | vinfos[3].indices[1] = _ij3[1]; |
| 4885 | vinfos[3].maxsolutions = _nj3; |
| 4886 | vinfos[4].jointtype = 1; |
| 4887 | vinfos[4].foffset = j4; |
| 4888 | vinfos[4].indices[0] = _ij4[0]; |
| 4889 | vinfos[4].indices[1] = _ij4[1]; |
| 4890 | vinfos[4].maxsolutions = _nj4; |
| 4891 | vinfos[5].jointtype = 1; |
| 4892 | vinfos[5].foffset = j5; |
| 4893 | vinfos[5].indices[0] = _ij5[0]; |
| 4894 | vinfos[5].indices[1] = _ij5[1]; |
| 4895 | vinfos[5].maxsolutions = _nj5; |
| 4896 | std::vector<int> vfree(0); |
| 4897 | solutions.AddSolution(vinfos,vfree); |
| 4898 | } |
| 4899 | } |
| 4900 | } |
| 4901 | |
| 4902 | } |
| 4903 | } while(0); |
| 4904 | if( bgotonextstatement ) |
| 4905 | { |
| 4906 | bool bgotonextstatement = true; |
| 4907 | do |
| 4908 | { |
| 4909 | evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); |
| 4910 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 4911 | { |
| 4912 | bgotonextstatement=false; |
| 4913 | { |
| 4914 | IkReal j2eval[1]; |
| 4915 | new_r21=0; |
| 4916 | new_r20=0; |
| 4917 | new_r02=0; |
| 4918 | new_r12=0; |
| 4919 | j2eval[0]=IKabs(new_r22); |
| 4920 | if( IKabs(j2eval[0]) < 0.0000000100000000 ) |
| 4921 | { |
| 4922 | continue; // no branches [j2] |
| 4923 | |
| 4924 | } else |
| 4925 | { |
| 4926 | IkReal op[2+1], zeror[2]; |
| 4927 | int numroots; |
| 4928 | op[0]=((-1.0)*new_r22); |
| 4929 | op[1]=0; |
| 4930 | op[2]=new_r22; |
| 4931 | polyroots2(op,zeror,numroots); |
| 4932 | IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1]; |
| 4933 | int numsolutions = 0; |
| 4934 | for(int ij2 = 0; ij2 < numroots; ++ij2) |
| 4935 | { |
| 4936 | IkReal htj2 = zeror[ij2]; |
| 4937 | tempj2array[0]=((2.0)*(atan(htj2))); |
| 4938 | for(int kj2 = 0; kj2 < 1; ++kj2) |
| 4939 | { |
| 4940 | j2array[numsolutions] = tempj2array[kj2]; |
| 4941 | if( j2array[numsolutions] > IKPI ) |
| 4942 | { |
| 4943 | j2array[numsolutions]-=IK2PI; |
| 4944 | } |
| 4945 | else if( j2array[numsolutions] < -IKPI ) |
| 4946 | { |
| 4947 | j2array[numsolutions]+=IK2PI; |
| 4948 | } |
| 4949 | sj2array[numsolutions] = IKsin(j2array[numsolutions]); |
| 4950 | cj2array[numsolutions] = IKcos(j2array[numsolutions]); |
| 4951 | numsolutions++; |
| 4952 | } |
| 4953 | } |
| 4954 | bool j2valid[2]={true,true}; |
| 4955 | _nj2 = 2; |
| 4956 | for(int ij2 = 0; ij2 < numsolutions; ++ij2) |
| 4957 | { |
| 4958 | if( !j2valid[ij2] ) |
| 4959 | { |
| 4960 | continue; |
| 4961 | } |
| 4962 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 4963 | htj2 = IKtan(j2/2); |
| 4964 | |
| 4965 | _ij2[0] = ij2; _ij2[1] = -1; |
| 4966 | for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2) |
| 4967 | { |
| 4968 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 4969 | { |
| 4970 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 4971 | } |
| 4972 | } |
| 4973 | { |
| 4974 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 4975 | vinfos[0].jointtype = 1; |
| 4976 | vinfos[0].foffset = j0; |
| 4977 | vinfos[0].indices[0] = _ij0[0]; |
| 4978 | vinfos[0].indices[1] = _ij0[1]; |
| 4979 | vinfos[0].maxsolutions = _nj0; |
| 4980 | vinfos[1].jointtype = 1; |
| 4981 | vinfos[1].foffset = j1; |
| 4982 | vinfos[1].indices[0] = _ij1[0]; |
| 4983 | vinfos[1].indices[1] = _ij1[1]; |
| 4984 | vinfos[1].maxsolutions = _nj1; |
| 4985 | vinfos[2].jointtype = 1; |
| 4986 | vinfos[2].foffset = j2; |
| 4987 | vinfos[2].indices[0] = _ij2[0]; |
| 4988 | vinfos[2].indices[1] = _ij2[1]; |
| 4989 | vinfos[2].maxsolutions = _nj2; |
| 4990 | vinfos[3].jointtype = 1; |
| 4991 | vinfos[3].foffset = j3; |
| 4992 | vinfos[3].indices[0] = _ij3[0]; |
| 4993 | vinfos[3].indices[1] = _ij3[1]; |
| 4994 | vinfos[3].maxsolutions = _nj3; |
| 4995 | vinfos[4].jointtype = 1; |
| 4996 | vinfos[4].foffset = j4; |
| 4997 | vinfos[4].indices[0] = _ij4[0]; |
| 4998 | vinfos[4].indices[1] = _ij4[1]; |
| 4999 | vinfos[4].maxsolutions = _nj4; |
| 5000 | vinfos[5].jointtype = 1; |
| 5001 | vinfos[5].foffset = j5; |
| 5002 | vinfos[5].indices[0] = _ij5[0]; |
| 5003 | vinfos[5].indices[1] = _ij5[1]; |
| 5004 | vinfos[5].maxsolutions = _nj5; |
| 5005 | std::vector<int> vfree(0); |
| 5006 | solutions.AddSolution(vinfos,vfree); |
| 5007 | } |
| 5008 | } |
| 5009 | |
| 5010 | } |
| 5011 | |
| 5012 | } |
| 5013 | |
| 5014 | } |
| 5015 | } while(0); |
| 5016 | if( bgotonextstatement ) |
| 5017 | { |
| 5018 | bool bgotonextstatement = true; |
| 5019 | do |
| 5020 | { |
| 5021 | if( 1 ) |
| 5022 | { |
| 5023 | bgotonextstatement=false; |
| 5024 | continue; // branch miss [j2] |
| 5025 | |
| 5026 | } |
| 5027 | } while(0); |
| 5028 | if( bgotonextstatement ) |
| 5029 | { |
| 5030 | } |
| 5031 | } |
| 5032 | } |
| 5033 | } |
| 5034 | } |
| 5035 | } |
| 5036 | } |
| 5037 | } |
| 5038 | } |
| 5039 | |
| 5040 | } else |
| 5041 | { |
| 5042 | { |
| 5043 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 5044 | bool j2valid[1]={false}; |
| 5045 | _nj2 = 1; |
| 5046 | CheckValue<IkReal> x267=IKPowWithIntegerCheck(cj1,-1); |
| 5047 | if(!x267.valid){ |
| 5048 | continue; |
| 5049 | } |
| 5050 | IkReal x266=x267.value; |
| 5051 | CheckValue<IkReal> x268=IKPowWithIntegerCheck(sj0,-1); |
| 5052 | if(!x268.valid){ |
| 5053 | continue; |
| 5054 | } |
| 5055 | CheckValue<IkReal> x269=IKPowWithIntegerCheck(sj1,-1); |
| 5056 | if(!x269.valid){ |
| 5057 | continue; |
| 5058 | } |
| 5059 | if( IKabs((new_r20*x266)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x266))+IKsqr((x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 5060 | continue; |
| 5061 | j2array[0]=IKatan2((new_r20*x266), (x266*(x268.value)*(x269.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))); |
| 5062 | sj2array[0]=IKsin(j2array[0]); |
| 5063 | cj2array[0]=IKcos(j2array[0]); |
| 5064 | if( j2array[0] > IKPI ) |
| 5065 | { |
| 5066 | j2array[0]-=IK2PI; |
| 5067 | } |
| 5068 | else if( j2array[0] < -IKPI ) |
| 5069 | { j2array[0]+=IK2PI; |
| 5070 | } |
| 5071 | j2valid[0] = true; |
| 5072 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 5073 | { |
| 5074 | if( !j2valid[ij2] ) |
| 5075 | { |
| 5076 | continue; |
| 5077 | } |
| 5078 | _ij2[0] = ij2; _ij2[1] = -1; |
| 5079 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 5080 | { |
| 5081 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 5082 | { |
| 5083 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 5084 | } |
| 5085 | } |
| 5086 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 5087 | { |
| 5088 | IkReal evalcond[12]; |
| 5089 | IkReal x270=IKsin(j2); |
| 5090 | IkReal x271=IKcos(j2); |
| 5091 | IkReal x272=((1.0)*sj0); |
| 5092 | IkReal x273=(cj0*new_r00); |
| 5093 | IkReal x274=((1.0)*cj0); |
| 5094 | IkReal x275=((1.0)*x271); |
| 5095 | IkReal x276=(sj1*x270); |
| 5096 | IkReal x277=(sj1*x271); |
| 5097 | IkReal x278=((1.0)*x270); |
| 5098 | evalcond[0]=((((-1.0)*cj1*x278))+new_r20); |
| 5099 | evalcond[1]=((((-1.0)*cj1*x275))+new_r21); |
| 5100 | evalcond[2]=((((-1.0)*new_r01*x272))+x270+((cj0*new_r11))); |
| 5101 | evalcond[3]=(((new_r00*sj0))+x271+(((-1.0)*new_r10*x274))); |
| 5102 | evalcond[4]=(((new_r10*sj0))+x276+x273); |
| 5103 | evalcond[5]=(((new_r11*sj0))+x277+((cj0*new_r01))); |
| 5104 | evalcond[6]=(new_r00+((sj0*x271))+((cj0*x276))); |
| 5105 | evalcond[7]=(new_r11+((sj0*x277))+((cj0*x270))); |
| 5106 | evalcond[8]=((((-1.0)*x270*x272))+new_r01+((cj0*x277))); |
| 5107 | evalcond[9]=((((-1.0)*x271*x274))+new_r10+((sj0*x276))); |
| 5108 | evalcond[10]=((((-1.0)*new_r10*sj1*x272))+((cj1*new_r20))+(((-1.0)*sj1*x273))+(((-1.0)*x278))); |
| 5109 | evalcond[11]=(((cj1*new_r21))+(((-1.0)*x275))+(((-1.0)*new_r11*sj1*x272))+(((-1.0)*new_r01*sj1*x274))); |
| 5110 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 5111 | { |
| 5112 | continue; |
| 5113 | } |
| 5114 | } |
| 5115 | |
| 5116 | { |
| 5117 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5118 | vinfos[0].jointtype = 1; |
| 5119 | vinfos[0].foffset = j0; |
| 5120 | vinfos[0].indices[0] = _ij0[0]; |
| 5121 | vinfos[0].indices[1] = _ij0[1]; |
| 5122 | vinfos[0].maxsolutions = _nj0; |
| 5123 | vinfos[1].jointtype = 1; |
| 5124 | vinfos[1].foffset = j1; |
| 5125 | vinfos[1].indices[0] = _ij1[0]; |
| 5126 | vinfos[1].indices[1] = _ij1[1]; |
| 5127 | vinfos[1].maxsolutions = _nj1; |
| 5128 | vinfos[2].jointtype = 1; |
| 5129 | vinfos[2].foffset = j2; |
| 5130 | vinfos[2].indices[0] = _ij2[0]; |
| 5131 | vinfos[2].indices[1] = _ij2[1]; |
| 5132 | vinfos[2].maxsolutions = _nj2; |
| 5133 | vinfos[3].jointtype = 1; |
| 5134 | vinfos[3].foffset = j3; |
| 5135 | vinfos[3].indices[0] = _ij3[0]; |
| 5136 | vinfos[3].indices[1] = _ij3[1]; |
| 5137 | vinfos[3].maxsolutions = _nj3; |
| 5138 | vinfos[4].jointtype = 1; |
| 5139 | vinfos[4].foffset = j4; |
| 5140 | vinfos[4].indices[0] = _ij4[0]; |
| 5141 | vinfos[4].indices[1] = _ij4[1]; |
| 5142 | vinfos[4].maxsolutions = _nj4; |
| 5143 | vinfos[5].jointtype = 1; |
| 5144 | vinfos[5].foffset = j5; |
| 5145 | vinfos[5].indices[0] = _ij5[0]; |
| 5146 | vinfos[5].indices[1] = _ij5[1]; |
| 5147 | vinfos[5].maxsolutions = _nj5; |
| 5148 | std::vector<int> vfree(0); |
| 5149 | solutions.AddSolution(vinfos,vfree); |
| 5150 | } |
| 5151 | } |
| 5152 | } |
| 5153 | |
| 5154 | } |
| 5155 | |
| 5156 | } |
| 5157 | |
| 5158 | } else |
| 5159 | { |
| 5160 | { |
| 5161 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 5162 | bool j2valid[1]={false}; |
| 5163 | _nj2 = 1; |
| 5164 | CheckValue<IkReal> x280=IKPowWithIntegerCheck(cj1,-1); |
| 5165 | if(!x280.valid){ |
| 5166 | continue; |
| 5167 | } |
| 5168 | IkReal x279=x280.value; |
| 5169 | CheckValue<IkReal> x281=IKPowWithIntegerCheck(sj0,-1); |
| 5170 | if(!x281.valid){ |
| 5171 | continue; |
| 5172 | } |
| 5173 | if( IKabs((new_r20*x279)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x279))+IKsqr((x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 5174 | continue; |
| 5175 | j2array[0]=IKatan2((new_r20*x279), (x279*(x281.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))); |
| 5176 | sj2array[0]=IKsin(j2array[0]); |
| 5177 | cj2array[0]=IKcos(j2array[0]); |
| 5178 | if( j2array[0] > IKPI ) |
| 5179 | { |
| 5180 | j2array[0]-=IK2PI; |
| 5181 | } |
| 5182 | else if( j2array[0] < -IKPI ) |
| 5183 | { j2array[0]+=IK2PI; |
| 5184 | } |
| 5185 | j2valid[0] = true; |
| 5186 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 5187 | { |
| 5188 | if( !j2valid[ij2] ) |
| 5189 | { |
| 5190 | continue; |
| 5191 | } |
| 5192 | _ij2[0] = ij2; _ij2[1] = -1; |
| 5193 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 5194 | { |
| 5195 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 5196 | { |
| 5197 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 5198 | } |
| 5199 | } |
| 5200 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 5201 | { |
| 5202 | IkReal evalcond[12]; |
| 5203 | IkReal x282=IKsin(j2); |
| 5204 | IkReal x283=IKcos(j2); |
| 5205 | IkReal x284=((1.0)*sj0); |
| 5206 | IkReal x285=(cj0*new_r00); |
| 5207 | IkReal x286=((1.0)*cj0); |
| 5208 | IkReal x287=((1.0)*x283); |
| 5209 | IkReal x288=(sj1*x282); |
| 5210 | IkReal x289=(sj1*x283); |
| 5211 | IkReal x290=((1.0)*x282); |
| 5212 | evalcond[0]=((((-1.0)*cj1*x290))+new_r20); |
| 5213 | evalcond[1]=((((-1.0)*cj1*x287))+new_r21); |
| 5214 | evalcond[2]=(x282+(((-1.0)*new_r01*x284))+((cj0*new_r11))); |
| 5215 | evalcond[3]=(((new_r00*sj0))+x283+(((-1.0)*new_r10*x286))); |
| 5216 | evalcond[4]=(((new_r10*sj0))+x288+x285); |
| 5217 | evalcond[5]=(((new_r11*sj0))+x289+((cj0*new_r01))); |
| 5218 | evalcond[6]=(((cj0*x288))+((sj0*x283))+new_r00); |
| 5219 | evalcond[7]=(((cj0*x282))+((sj0*x289))+new_r11); |
| 5220 | evalcond[8]=(((cj0*x289))+(((-1.0)*x282*x284))+new_r01); |
| 5221 | evalcond[9]=(((sj0*x288))+new_r10+(((-1.0)*x283*x286))); |
| 5222 | evalcond[10]=(((cj1*new_r20))+(((-1.0)*x290))+(((-1.0)*new_r10*sj1*x284))+(((-1.0)*sj1*x285))); |
| 5223 | evalcond[11]=((((-1.0)*new_r01*sj1*x286))+((cj1*new_r21))+(((-1.0)*new_r11*sj1*x284))+(((-1.0)*x287))); |
| 5224 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 5225 | { |
| 5226 | continue; |
| 5227 | } |
| 5228 | } |
| 5229 | |
| 5230 | { |
| 5231 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5232 | vinfos[0].jointtype = 1; |
| 5233 | vinfos[0].foffset = j0; |
| 5234 | vinfos[0].indices[0] = _ij0[0]; |
| 5235 | vinfos[0].indices[1] = _ij0[1]; |
| 5236 | vinfos[0].maxsolutions = _nj0; |
| 5237 | vinfos[1].jointtype = 1; |
| 5238 | vinfos[1].foffset = j1; |
| 5239 | vinfos[1].indices[0] = _ij1[0]; |
| 5240 | vinfos[1].indices[1] = _ij1[1]; |
| 5241 | vinfos[1].maxsolutions = _nj1; |
| 5242 | vinfos[2].jointtype = 1; |
| 5243 | vinfos[2].foffset = j2; |
| 5244 | vinfos[2].indices[0] = _ij2[0]; |
| 5245 | vinfos[2].indices[1] = _ij2[1]; |
| 5246 | vinfos[2].maxsolutions = _nj2; |
| 5247 | vinfos[3].jointtype = 1; |
| 5248 | vinfos[3].foffset = j3; |
| 5249 | vinfos[3].indices[0] = _ij3[0]; |
| 5250 | vinfos[3].indices[1] = _ij3[1]; |
| 5251 | vinfos[3].maxsolutions = _nj3; |
| 5252 | vinfos[4].jointtype = 1; |
| 5253 | vinfos[4].foffset = j4; |
| 5254 | vinfos[4].indices[0] = _ij4[0]; |
| 5255 | vinfos[4].indices[1] = _ij4[1]; |
| 5256 | vinfos[4].maxsolutions = _nj4; |
| 5257 | vinfos[5].jointtype = 1; |
| 5258 | vinfos[5].foffset = j5; |
| 5259 | vinfos[5].indices[0] = _ij5[0]; |
| 5260 | vinfos[5].indices[1] = _ij5[1]; |
| 5261 | vinfos[5].maxsolutions = _nj5; |
| 5262 | std::vector<int> vfree(0); |
| 5263 | solutions.AddSolution(vinfos,vfree); |
| 5264 | } |
| 5265 | } |
| 5266 | } |
| 5267 | |
| 5268 | } |
| 5269 | |
| 5270 | } |
| 5271 | |
| 5272 | } else |
| 5273 | { |
| 5274 | { |
| 5275 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 5276 | bool j2valid[1]={false}; |
| 5277 | _nj2 = 1; |
| 5278 | CheckValue<IkReal> x291=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| 5279 | if(!x291.valid){ |
| 5280 | continue; |
| 5281 | } |
| 5282 | CheckValue<IkReal> x292 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| 5283 | if(!x292.valid){ |
| 5284 | continue; |
| 5285 | } |
| 5286 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x291.value)))+(x292.value)); |
| 5287 | sj2array[0]=IKsin(j2array[0]); |
| 5288 | cj2array[0]=IKcos(j2array[0]); |
| 5289 | if( j2array[0] > IKPI ) |
| 5290 | { |
| 5291 | j2array[0]-=IK2PI; |
| 5292 | } |
| 5293 | else if( j2array[0] < -IKPI ) |
| 5294 | { j2array[0]+=IK2PI; |
| 5295 | } |
| 5296 | j2valid[0] = true; |
| 5297 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 5298 | { |
| 5299 | if( !j2valid[ij2] ) |
| 5300 | { |
| 5301 | continue; |
| 5302 | } |
| 5303 | _ij2[0] = ij2; _ij2[1] = -1; |
| 5304 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 5305 | { |
| 5306 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 5307 | { |
| 5308 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 5309 | } |
| 5310 | } |
| 5311 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 5312 | { |
| 5313 | IkReal evalcond[12]; |
| 5314 | IkReal x293=IKsin(j2); |
| 5315 | IkReal x294=IKcos(j2); |
| 5316 | IkReal x295=((1.0)*sj0); |
| 5317 | IkReal x296=(cj0*new_r00); |
| 5318 | IkReal x297=((1.0)*cj0); |
| 5319 | IkReal x298=((1.0)*x294); |
| 5320 | IkReal x299=(sj1*x293); |
| 5321 | IkReal x300=(sj1*x294); |
| 5322 | IkReal x301=((1.0)*x293); |
| 5323 | evalcond[0]=((((-1.0)*cj1*x301))+new_r20); |
| 5324 | evalcond[1]=((((-1.0)*cj1*x298))+new_r21); |
| 5325 | evalcond[2]=((((-1.0)*new_r01*x295))+x293+((cj0*new_r11))); |
| 5326 | evalcond[3]=((((-1.0)*new_r10*x297))+((new_r00*sj0))+x294); |
| 5327 | evalcond[4]=(((new_r10*sj0))+x299+x296); |
| 5328 | evalcond[5]=(((new_r11*sj0))+x300+((cj0*new_r01))); |
| 5329 | evalcond[6]=(((sj0*x294))+new_r00+((cj0*x299))); |
| 5330 | evalcond[7]=(((sj0*x300))+new_r11+((cj0*x293))); |
| 5331 | evalcond[8]=((((-1.0)*x293*x295))+((cj0*x300))+new_r01); |
| 5332 | evalcond[9]=(((sj0*x299))+new_r10+(((-1.0)*x294*x297))); |
| 5333 | evalcond[10]=((((-1.0)*new_r10*sj1*x295))+(((-1.0)*sj1*x296))+((cj1*new_r20))+(((-1.0)*x301))); |
| 5334 | evalcond[11]=((((-1.0)*new_r11*sj1*x295))+((cj1*new_r21))+(((-1.0)*x298))+(((-1.0)*new_r01*sj1*x297))); |
| 5335 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 5336 | { |
| 5337 | continue; |
| 5338 | } |
| 5339 | } |
| 5340 | |
| 5341 | { |
| 5342 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5343 | vinfos[0].jointtype = 1; |
| 5344 | vinfos[0].foffset = j0; |
| 5345 | vinfos[0].indices[0] = _ij0[0]; |
| 5346 | vinfos[0].indices[1] = _ij0[1]; |
| 5347 | vinfos[0].maxsolutions = _nj0; |
| 5348 | vinfos[1].jointtype = 1; |
| 5349 | vinfos[1].foffset = j1; |
| 5350 | vinfos[1].indices[0] = _ij1[0]; |
| 5351 | vinfos[1].indices[1] = _ij1[1]; |
| 5352 | vinfos[1].maxsolutions = _nj1; |
| 5353 | vinfos[2].jointtype = 1; |
| 5354 | vinfos[2].foffset = j2; |
| 5355 | vinfos[2].indices[0] = _ij2[0]; |
| 5356 | vinfos[2].indices[1] = _ij2[1]; |
| 5357 | vinfos[2].maxsolutions = _nj2; |
| 5358 | vinfos[3].jointtype = 1; |
| 5359 | vinfos[3].foffset = j3; |
| 5360 | vinfos[3].indices[0] = _ij3[0]; |
| 5361 | vinfos[3].indices[1] = _ij3[1]; |
| 5362 | vinfos[3].maxsolutions = _nj3; |
| 5363 | vinfos[4].jointtype = 1; |
| 5364 | vinfos[4].foffset = j4; |
| 5365 | vinfos[4].indices[0] = _ij4[0]; |
| 5366 | vinfos[4].indices[1] = _ij4[1]; |
| 5367 | vinfos[4].maxsolutions = _nj4; |
| 5368 | vinfos[5].jointtype = 1; |
| 5369 | vinfos[5].foffset = j5; |
| 5370 | vinfos[5].indices[0] = _ij5[0]; |
| 5371 | vinfos[5].indices[1] = _ij5[1]; |
| 5372 | vinfos[5].maxsolutions = _nj5; |
| 5373 | std::vector<int> vfree(0); |
| 5374 | solutions.AddSolution(vinfos,vfree); |
| 5375 | } |
| 5376 | } |
| 5377 | } |
| 5378 | |
| 5379 | } |
| 5380 | |
| 5381 | } |
| 5382 | } |
| 5383 | } |
| 5384 | |
| 5385 | } |
| 5386 | |
| 5387 | } |
| 5388 | |
| 5389 | } else |
| 5390 | { |
| 5391 | { |
| 5392 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 5393 | bool j2valid[1]={false}; |
| 5394 | _nj2 = 1; |
| 5395 | CheckValue<IkReal> x302=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| 5396 | if(!x302.valid){ |
| 5397 | continue; |
| 5398 | } |
| 5399 | CheckValue<IkReal> x303 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| 5400 | if(!x303.valid){ |
| 5401 | continue; |
| 5402 | } |
| 5403 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x302.value)))+(x303.value)); |
| 5404 | sj2array[0]=IKsin(j2array[0]); |
| 5405 | cj2array[0]=IKcos(j2array[0]); |
| 5406 | if( j2array[0] > IKPI ) |
| 5407 | { |
| 5408 | j2array[0]-=IK2PI; |
| 5409 | } |
| 5410 | else if( j2array[0] < -IKPI ) |
| 5411 | { j2array[0]+=IK2PI; |
| 5412 | } |
| 5413 | j2valid[0] = true; |
| 5414 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 5415 | { |
| 5416 | if( !j2valid[ij2] ) |
| 5417 | { |
| 5418 | continue; |
| 5419 | } |
| 5420 | _ij2[0] = ij2; _ij2[1] = -1; |
| 5421 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 5422 | { |
| 5423 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 5424 | { |
| 5425 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 5426 | } |
| 5427 | } |
| 5428 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 5429 | { |
| 5430 | IkReal evalcond[2]; |
| 5431 | IkReal x304=((1.0)*cj1); |
| 5432 | evalcond[0]=((((-1.0)*x304*(IKsin(j2))))+new_r20); |
| 5433 | evalcond[1]=((((-1.0)*x304*(IKcos(j2))))+new_r21); |
| 5434 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH ) |
| 5435 | { |
| 5436 | continue; |
| 5437 | } |
| 5438 | } |
| 5439 | |
| 5440 | { |
| 5441 | IkReal j0eval[3]; |
| 5442 | j0eval[0]=cj1; |
| 5443 | j0eval[1]=IKsign(cj1); |
| 5444 | j0eval[2]=((IKabs(new_r12))+(IKabs(new_r02))); |
| 5445 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5446 | { |
| 5447 | { |
| 5448 | IkReal j0eval[2]; |
| 5449 | j0eval[0]=cj1; |
| 5450 | j0eval[1]=new_r01; |
| 5451 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 5452 | { |
| 5453 | { |
| 5454 | IkReal evalcond[5]; |
| 5455 | bool bgotonextstatement = true; |
| 5456 | do |
| 5457 | { |
| 5458 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| 5459 | evalcond[1]=new_r02; |
| 5460 | evalcond[2]=new_r12; |
| 5461 | evalcond[3]=new_r20; |
| 5462 | evalcond[4]=new_r21; |
| 5463 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 5464 | { |
| 5465 | bgotonextstatement=false; |
| 5466 | { |
| 5467 | IkReal j0eval[3]; |
| 5468 | sj1=1.0; |
| 5469 | cj1=0; |
| 5470 | j1=1.5707963267949; |
| 5471 | IkReal x305=(((new_r00*new_r11))+(((-1.0)*new_r01*new_r10))); |
| 5472 | j0eval[0]=x305; |
| 5473 | j0eval[1]=((IKabs((((new_r01*sj2))+(((-1.0)*cj2*new_r00)))))+(IKabs((((cj2*new_r10))+(((-1.0)*new_r11*sj2)))))); |
| 5474 | j0eval[2]=IKsign(x305); |
| 5475 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5476 | { |
| 5477 | { |
| 5478 | IkReal j0eval[3]; |
| 5479 | sj1=1.0; |
| 5480 | cj1=0; |
| 5481 | j1=1.5707963267949; |
| 5482 | IkReal x306=(((cj2*new_r01))+(((-1.0)*new_r11*sj2))); |
| 5483 | j0eval[0]=x306; |
| 5484 | j0eval[1]=((IKabs((((cj2*sj2))+(((-1.0)*new_r00*new_r01)))))+(IKabs(((((-1.0)*(cj2*cj2)))+((new_r00*new_r11)))))); |
| 5485 | j0eval[2]=IKsign(x306); |
| 5486 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5487 | { |
| 5488 | { |
| 5489 | IkReal j0eval[3]; |
| 5490 | sj1=1.0; |
| 5491 | cj1=0; |
| 5492 | j1=1.5707963267949; |
| 5493 | IkReal x307=((1.0)*sj2); |
| 5494 | IkReal x308=(((cj2*new_r00))+(((-1.0)*new_r10*x307))); |
| 5495 | j0eval[0]=x308; |
| 5496 | j0eval[1]=IKsign(x308); |
| 5497 | j0eval[2]=((IKabs(((((-1.0)*cj2*x307))+((new_r10*new_r11)))))+(IKabs(((1.0)+(((-1.0)*(cj2*cj2)))+(((-1.0)*new_r00*new_r11)))))); |
| 5498 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5499 | { |
| 5500 | { |
| 5501 | IkReal evalcond[1]; |
| 5502 | bool bgotonextstatement = true; |
| 5503 | do |
| 5504 | { |
| 5505 | IkReal x311 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| 5506 | if(IKabs(x311)==0){ |
| 5507 | continue; |
| 5508 | } |
| 5509 | IkReal x309=pow(x311,-0.5); |
| 5510 | IkReal x310=((-1.0)*x309); |
| 5511 | CheckValue<IkReal> x312 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 5512 | if(!x312.valid){ |
| 5513 | continue; |
| 5514 | } |
| 5515 | IkReal gconst16=((-1.0)*(x312.value)); |
| 5516 | IkReal gconst17=(new_r00*x310); |
| 5517 | IkReal gconst18=(new_r10*x310); |
| 5518 | CheckValue<IkReal> x313 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 5519 | if(!x313.valid){ |
| 5520 | continue; |
| 5521 | } |
| 5522 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x313.value)+j2)))), 6.28318530717959))); |
| 5523 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 5524 | { |
| 5525 | bgotonextstatement=false; |
| 5526 | { |
| 5527 | IkReal j0eval[3]; |
| 5528 | CheckValue<IkReal> x317 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 5529 | if(!x317.valid){ |
| 5530 | continue; |
| 5531 | } |
| 5532 | IkReal x314=((-1.0)*(x317.value)); |
| 5533 | IkReal x315=x309; |
| 5534 | IkReal x316=((-1.0)*x315); |
| 5535 | sj1=1.0; |
| 5536 | cj1=0; |
| 5537 | j1=1.5707963267949; |
| 5538 | sj2=gconst17; |
| 5539 | cj2=gconst18; |
| 5540 | j2=x314; |
| 5541 | IkReal gconst16=x314; |
| 5542 | IkReal gconst17=(new_r00*x316); |
| 5543 | IkReal gconst18=(new_r10*x316); |
| 5544 | IkReal x318=new_r10*new_r10; |
| 5545 | IkReal x319=(new_r00*new_r11); |
| 5546 | IkReal x320=(x319+(((-1.0)*new_r01*new_r10))); |
| 5547 | IkReal x321=x309; |
| 5548 | IkReal x322=((1.0)*x321); |
| 5549 | j0eval[0]=x320; |
| 5550 | j0eval[1]=IKsign(x320); |
| 5551 | j0eval[2]=((IKabs((((new_r00*new_r10*x321))+(((-1.0)*new_r00*new_r01*x322)))))+(IKabs(((((-1.0)*x318*x322))+((x319*x321)))))); |
| 5552 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5553 | { |
| 5554 | { |
| 5555 | IkReal j0eval[1]; |
| 5556 | CheckValue<IkReal> x326 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 5557 | if(!x326.valid){ |
| 5558 | continue; |
| 5559 | } |
| 5560 | IkReal x323=((-1.0)*(x326.value)); |
| 5561 | IkReal x324=x309; |
| 5562 | IkReal x325=((-1.0)*x324); |
| 5563 | sj1=1.0; |
| 5564 | cj1=0; |
| 5565 | j1=1.5707963267949; |
| 5566 | sj2=gconst17; |
| 5567 | cj2=gconst18; |
| 5568 | j2=x323; |
| 5569 | IkReal gconst16=x323; |
| 5570 | IkReal gconst17=(new_r00*x325); |
| 5571 | IkReal gconst18=(new_r10*x325); |
| 5572 | IkReal x327=new_r10*new_r10; |
| 5573 | IkReal x328=((1.0)*new_r00); |
| 5574 | CheckValue<IkReal> x331=IKPowWithIntegerCheck((x327+(new_r00*new_r00)),-1); |
| 5575 | if(!x331.valid){ |
| 5576 | continue; |
| 5577 | } |
| 5578 | IkReal x329=x331.value; |
| 5579 | IkReal x330=(x327*x329); |
| 5580 | j0eval[0]=((IKabs((((new_r00*new_r01*x330))+(((-1.0)*new_r10*x328*x329))+((new_r01*x329*(new_r00*new_r00*new_r00))))))+(IKabs((x330+(((-1.0)*new_r11*x328)))))); |
| 5581 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 5582 | { |
| 5583 | { |
| 5584 | IkReal j0eval[3]; |
| 5585 | CheckValue<IkReal> x335 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 5586 | if(!x335.valid){ |
| 5587 | continue; |
| 5588 | } |
| 5589 | IkReal x332=((-1.0)*(x335.value)); |
| 5590 | IkReal x333=x309; |
| 5591 | IkReal x334=((-1.0)*x333); |
| 5592 | sj1=1.0; |
| 5593 | cj1=0; |
| 5594 | j1=1.5707963267949; |
| 5595 | sj2=gconst17; |
| 5596 | cj2=gconst18; |
| 5597 | j2=x332; |
| 5598 | IkReal gconst16=x332; |
| 5599 | IkReal gconst17=(new_r00*x334); |
| 5600 | IkReal gconst18=(new_r10*x334); |
| 5601 | IkReal x336=new_r00*new_r00; |
| 5602 | IkReal x337=(new_r00*new_r01); |
| 5603 | IkReal x338=(((new_r10*new_r11))+x337); |
| 5604 | IkReal x339=x309; |
| 5605 | IkReal x340=(new_r00*x339); |
| 5606 | j0eval[0]=x338; |
| 5607 | j0eval[1]=IKsign(x338); |
| 5608 | j0eval[2]=((IKabs((((new_r11*x340))+(((-1.0)*x336*x339)))))+(IKabs((((x337*x339))+((new_r10*x340)))))); |
| 5609 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5610 | { |
| 5611 | { |
| 5612 | IkReal evalcond[3]; |
| 5613 | bool bgotonextstatement = true; |
| 5614 | do |
| 5615 | { |
| 5616 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| 5617 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 5618 | { |
| 5619 | bgotonextstatement=false; |
| 5620 | { |
| 5621 | IkReal j0eval[1]; |
| 5622 | IkReal x341=((-1.0)*new_r10); |
| 5623 | CheckValue<IkReal> x343 = IKatan2WithCheck(IkReal(0),IkReal(x341),IKFAST_ATAN2_MAGTHRESH); |
| 5624 | if(!x343.valid){ |
| 5625 | continue; |
| 5626 | } |
| 5627 | IkReal x342=((-1.0)*(x343.value)); |
| 5628 | sj1=1.0; |
| 5629 | cj1=0; |
| 5630 | j1=1.5707963267949; |
| 5631 | sj2=gconst17; |
| 5632 | cj2=gconst18; |
| 5633 | j2=x342; |
| 5634 | new_r11=0; |
| 5635 | new_r00=0; |
| 5636 | IkReal gconst16=x342; |
| 5637 | IkReal gconst17=0; |
| 5638 | IkReal x344 = new_r10*new_r10; |
| 5639 | if(IKabs(x344)==0){ |
| 5640 | continue; |
| 5641 | } |
| 5642 | IkReal gconst18=(x341*(pow(x344,-0.5))); |
| 5643 | j0eval[0]=new_r10; |
| 5644 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 5645 | { |
| 5646 | { |
| 5647 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 5648 | bool j0valid[2]={false}; |
| 5649 | _nj0 = 2; |
| 5650 | CheckValue<IkReal> x345=IKPowWithIntegerCheck(gconst18,-1); |
| 5651 | if(!x345.valid){ |
| 5652 | continue; |
| 5653 | } |
| 5654 | cj0array[0]=(new_r10*(x345.value)); |
| 5655 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 5656 | { |
| 5657 | j0valid[0] = j0valid[1] = true; |
| 5658 | j0array[0] = IKacos(cj0array[0]); |
| 5659 | sj0array[0] = IKsin(j0array[0]); |
| 5660 | cj0array[1] = cj0array[0]; |
| 5661 | j0array[1] = -j0array[0]; |
| 5662 | sj0array[1] = -sj0array[0]; |
| 5663 | } |
| 5664 | else if( isnan(cj0array[0]) ) |
| 5665 | { |
| 5666 | // probably any value will work |
| 5667 | j0valid[0] = true; |
| 5668 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 5669 | } |
| 5670 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 5671 | { |
| 5672 | if( !j0valid[ij0] ) |
| 5673 | { |
| 5674 | continue; |
| 5675 | } |
| 5676 | _ij0[0] = ij0; _ij0[1] = -1; |
| 5677 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 5678 | { |
| 5679 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 5680 | { |
| 5681 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 5682 | } |
| 5683 | } |
| 5684 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 5685 | { |
| 5686 | IkReal evalcond[6]; |
| 5687 | IkReal x346=IKsin(j0); |
| 5688 | IkReal x347=IKcos(j0); |
| 5689 | evalcond[0]=(new_r10*x346); |
| 5690 | evalcond[1]=(gconst18*x346); |
| 5691 | evalcond[2]=((-1.0)*new_r01*x346); |
| 5692 | evalcond[3]=(gconst18+((new_r01*x347))); |
| 5693 | evalcond[4]=(((gconst18*x347))+new_r01); |
| 5694 | evalcond[5]=(gconst18+(((-1.0)*new_r10*x347))); |
| 5695 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 5696 | { |
| 5697 | continue; |
| 5698 | } |
| 5699 | } |
| 5700 | |
| 5701 | { |
| 5702 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5703 | vinfos[0].jointtype = 1; |
| 5704 | vinfos[0].foffset = j0; |
| 5705 | vinfos[0].indices[0] = _ij0[0]; |
| 5706 | vinfos[0].indices[1] = _ij0[1]; |
| 5707 | vinfos[0].maxsolutions = _nj0; |
| 5708 | vinfos[1].jointtype = 1; |
| 5709 | vinfos[1].foffset = j1; |
| 5710 | vinfos[1].indices[0] = _ij1[0]; |
| 5711 | vinfos[1].indices[1] = _ij1[1]; |
| 5712 | vinfos[1].maxsolutions = _nj1; |
| 5713 | vinfos[2].jointtype = 1; |
| 5714 | vinfos[2].foffset = j2; |
| 5715 | vinfos[2].indices[0] = _ij2[0]; |
| 5716 | vinfos[2].indices[1] = _ij2[1]; |
| 5717 | vinfos[2].maxsolutions = _nj2; |
| 5718 | vinfos[3].jointtype = 1; |
| 5719 | vinfos[3].foffset = j3; |
| 5720 | vinfos[3].indices[0] = _ij3[0]; |
| 5721 | vinfos[3].indices[1] = _ij3[1]; |
| 5722 | vinfos[3].maxsolutions = _nj3; |
| 5723 | vinfos[4].jointtype = 1; |
| 5724 | vinfos[4].foffset = j4; |
| 5725 | vinfos[4].indices[0] = _ij4[0]; |
| 5726 | vinfos[4].indices[1] = _ij4[1]; |
| 5727 | vinfos[4].maxsolutions = _nj4; |
| 5728 | vinfos[5].jointtype = 1; |
| 5729 | vinfos[5].foffset = j5; |
| 5730 | vinfos[5].indices[0] = _ij5[0]; |
| 5731 | vinfos[5].indices[1] = _ij5[1]; |
| 5732 | vinfos[5].maxsolutions = _nj5; |
| 5733 | std::vector<int> vfree(0); |
| 5734 | solutions.AddSolution(vinfos,vfree); |
| 5735 | } |
| 5736 | } |
| 5737 | } |
| 5738 | |
| 5739 | } else |
| 5740 | { |
| 5741 | { |
| 5742 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 5743 | bool j0valid[2]={false}; |
| 5744 | _nj0 = 2; |
| 5745 | CheckValue<IkReal> x348=IKPowWithIntegerCheck(new_r10,-1); |
| 5746 | if(!x348.valid){ |
| 5747 | continue; |
| 5748 | } |
| 5749 | cj0array[0]=(gconst18*(x348.value)); |
| 5750 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 5751 | { |
| 5752 | j0valid[0] = j0valid[1] = true; |
| 5753 | j0array[0] = IKacos(cj0array[0]); |
| 5754 | sj0array[0] = IKsin(j0array[0]); |
| 5755 | cj0array[1] = cj0array[0]; |
| 5756 | j0array[1] = -j0array[0]; |
| 5757 | sj0array[1] = -sj0array[0]; |
| 5758 | } |
| 5759 | else if( isnan(cj0array[0]) ) |
| 5760 | { |
| 5761 | // probably any value will work |
| 5762 | j0valid[0] = true; |
| 5763 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 5764 | } |
| 5765 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 5766 | { |
| 5767 | if( !j0valid[ij0] ) |
| 5768 | { |
| 5769 | continue; |
| 5770 | } |
| 5771 | _ij0[0] = ij0; _ij0[1] = -1; |
| 5772 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 5773 | { |
| 5774 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 5775 | { |
| 5776 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 5777 | } |
| 5778 | } |
| 5779 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 5780 | { |
| 5781 | IkReal evalcond[6]; |
| 5782 | IkReal x349=IKsin(j0); |
| 5783 | IkReal x350=IKcos(j0); |
| 5784 | IkReal x351=(gconst18*x350); |
| 5785 | evalcond[0]=(new_r10*x349); |
| 5786 | evalcond[1]=(gconst18*x349); |
| 5787 | evalcond[2]=((-1.0)*new_r01*x349); |
| 5788 | evalcond[3]=(((new_r01*x350))+gconst18); |
| 5789 | evalcond[4]=(x351+new_r01); |
| 5790 | evalcond[5]=((((-1.0)*x351))+new_r10); |
| 5791 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 5792 | { |
| 5793 | continue; |
| 5794 | } |
| 5795 | } |
| 5796 | |
| 5797 | { |
| 5798 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5799 | vinfos[0].jointtype = 1; |
| 5800 | vinfos[0].foffset = j0; |
| 5801 | vinfos[0].indices[0] = _ij0[0]; |
| 5802 | vinfos[0].indices[1] = _ij0[1]; |
| 5803 | vinfos[0].maxsolutions = _nj0; |
| 5804 | vinfos[1].jointtype = 1; |
| 5805 | vinfos[1].foffset = j1; |
| 5806 | vinfos[1].indices[0] = _ij1[0]; |
| 5807 | vinfos[1].indices[1] = _ij1[1]; |
| 5808 | vinfos[1].maxsolutions = _nj1; |
| 5809 | vinfos[2].jointtype = 1; |
| 5810 | vinfos[2].foffset = j2; |
| 5811 | vinfos[2].indices[0] = _ij2[0]; |
| 5812 | vinfos[2].indices[1] = _ij2[1]; |
| 5813 | vinfos[2].maxsolutions = _nj2; |
| 5814 | vinfos[3].jointtype = 1; |
| 5815 | vinfos[3].foffset = j3; |
| 5816 | vinfos[3].indices[0] = _ij3[0]; |
| 5817 | vinfos[3].indices[1] = _ij3[1]; |
| 5818 | vinfos[3].maxsolutions = _nj3; |
| 5819 | vinfos[4].jointtype = 1; |
| 5820 | vinfos[4].foffset = j4; |
| 5821 | vinfos[4].indices[0] = _ij4[0]; |
| 5822 | vinfos[4].indices[1] = _ij4[1]; |
| 5823 | vinfos[4].maxsolutions = _nj4; |
| 5824 | vinfos[5].jointtype = 1; |
| 5825 | vinfos[5].foffset = j5; |
| 5826 | vinfos[5].indices[0] = _ij5[0]; |
| 5827 | vinfos[5].indices[1] = _ij5[1]; |
| 5828 | vinfos[5].maxsolutions = _nj5; |
| 5829 | std::vector<int> vfree(0); |
| 5830 | solutions.AddSolution(vinfos,vfree); |
| 5831 | } |
| 5832 | } |
| 5833 | } |
| 5834 | |
| 5835 | } |
| 5836 | |
| 5837 | } |
| 5838 | |
| 5839 | } |
| 5840 | } while(0); |
| 5841 | if( bgotonextstatement ) |
| 5842 | { |
| 5843 | bool bgotonextstatement = true; |
| 5844 | do |
| 5845 | { |
| 5846 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 5847 | evalcond[1]=gconst17; |
| 5848 | evalcond[2]=gconst18; |
| 5849 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| 5850 | { |
| 5851 | bgotonextstatement=false; |
| 5852 | { |
| 5853 | IkReal j0eval[3]; |
| 5854 | IkReal x352=((-1.0)*new_r10); |
| 5855 | CheckValue<IkReal> x354 = IKatan2WithCheck(IkReal(new_r00),IkReal(x352),IKFAST_ATAN2_MAGTHRESH); |
| 5856 | if(!x354.valid){ |
| 5857 | continue; |
| 5858 | } |
| 5859 | IkReal x353=((-1.0)*(x354.value)); |
| 5860 | sj1=1.0; |
| 5861 | cj1=0; |
| 5862 | j1=1.5707963267949; |
| 5863 | sj2=gconst17; |
| 5864 | cj2=gconst18; |
| 5865 | j2=x353; |
| 5866 | new_r11=0; |
| 5867 | new_r01=0; |
| 5868 | new_r22=0; |
| 5869 | new_r20=0; |
| 5870 | IkReal gconst16=x353; |
| 5871 | IkReal gconst17=((-1.0)*new_r00); |
| 5872 | IkReal gconst18=x352; |
| 5873 | j0eval[0]=1.0; |
| 5874 | j0eval[1]=1.0; |
| 5875 | j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10)))); |
| 5876 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5877 | { |
| 5878 | { |
| 5879 | IkReal j0eval[3]; |
| 5880 | IkReal x355=((-1.0)*new_r10); |
| 5881 | CheckValue<IkReal> x357 = IKatan2WithCheck(IkReal(new_r00),IkReal(x355),IKFAST_ATAN2_MAGTHRESH); |
| 5882 | if(!x357.valid){ |
| 5883 | continue; |
| 5884 | } |
| 5885 | IkReal x356=((-1.0)*(x357.value)); |
| 5886 | sj1=1.0; |
| 5887 | cj1=0; |
| 5888 | j1=1.5707963267949; |
| 5889 | sj2=gconst17; |
| 5890 | cj2=gconst18; |
| 5891 | j2=x356; |
| 5892 | new_r11=0; |
| 5893 | new_r01=0; |
| 5894 | new_r22=0; |
| 5895 | new_r20=0; |
| 5896 | IkReal gconst16=x356; |
| 5897 | IkReal gconst17=((-1.0)*new_r00); |
| 5898 | IkReal gconst18=x355; |
| 5899 | j0eval[0]=1.0; |
| 5900 | j0eval[1]=1.0; |
| 5901 | j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| 5902 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5903 | { |
| 5904 | { |
| 5905 | IkReal j0eval[3]; |
| 5906 | IkReal x358=((-1.0)*new_r10); |
| 5907 | CheckValue<IkReal> x360 = IKatan2WithCheck(IkReal(new_r00),IkReal(x358),IKFAST_ATAN2_MAGTHRESH); |
| 5908 | if(!x360.valid){ |
| 5909 | continue; |
| 5910 | } |
| 5911 | IkReal x359=((-1.0)*(x360.value)); |
| 5912 | sj1=1.0; |
| 5913 | cj1=0; |
| 5914 | j1=1.5707963267949; |
| 5915 | sj2=gconst17; |
| 5916 | cj2=gconst18; |
| 5917 | j2=x359; |
| 5918 | new_r11=0; |
| 5919 | new_r01=0; |
| 5920 | new_r22=0; |
| 5921 | new_r20=0; |
| 5922 | IkReal gconst16=x359; |
| 5923 | IkReal gconst17=((-1.0)*new_r00); |
| 5924 | IkReal gconst18=x358; |
| 5925 | j0eval[0]=-1.0; |
| 5926 | j0eval[1]=-1.0; |
| 5927 | j0eval[2]=((IKabs(((-1.0)+(new_r10*new_r10))))+(IKabs((new_r00*new_r10)))); |
| 5928 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 5929 | { |
| 5930 | continue; // 3 cases reached |
| 5931 | |
| 5932 | } else |
| 5933 | { |
| 5934 | { |
| 5935 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 5936 | bool j0valid[1]={false}; |
| 5937 | _nj0 = 1; |
| 5938 | CheckValue<IkReal> x361=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst17*gconst17)))+(((-1.0)*(gconst18*gconst18))))),-1); |
| 5939 | if(!x361.valid){ |
| 5940 | continue; |
| 5941 | } |
| 5942 | CheckValue<IkReal> x362 = IKatan2WithCheck(IkReal((gconst18*new_r00)),IkReal((gconst17*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 5943 | if(!x362.valid){ |
| 5944 | continue; |
| 5945 | } |
| 5946 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x361.value)))+(x362.value)); |
| 5947 | sj0array[0]=IKsin(j0array[0]); |
| 5948 | cj0array[0]=IKcos(j0array[0]); |
| 5949 | if( j0array[0] > IKPI ) |
| 5950 | { |
| 5951 | j0array[0]-=IK2PI; |
| 5952 | } |
| 5953 | else if( j0array[0] < -IKPI ) |
| 5954 | { j0array[0]+=IK2PI; |
| 5955 | } |
| 5956 | j0valid[0] = true; |
| 5957 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 5958 | { |
| 5959 | if( !j0valid[ij0] ) |
| 5960 | { |
| 5961 | continue; |
| 5962 | } |
| 5963 | _ij0[0] = ij0; _ij0[1] = -1; |
| 5964 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 5965 | { |
| 5966 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 5967 | { |
| 5968 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 5969 | } |
| 5970 | } |
| 5971 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 5972 | { |
| 5973 | IkReal evalcond[6]; |
| 5974 | IkReal x363=IKcos(j0); |
| 5975 | IkReal x364=IKsin(j0); |
| 5976 | IkReal x365=(gconst17*x363); |
| 5977 | IkReal x366=(gconst18*x364); |
| 5978 | IkReal x367=((1.0)*x363); |
| 5979 | IkReal x368=(gconst17*x364); |
| 5980 | IkReal x369=(x365+x366); |
| 5981 | evalcond[0]=x369; |
| 5982 | evalcond[1]=(gconst17+((new_r00*x363))+((new_r10*x364))); |
| 5983 | evalcond[2]=(x369+new_r00); |
| 5984 | evalcond[3]=(((gconst18*x363))+(((-1.0)*x368))); |
| 5985 | evalcond[4]=(gconst18+((new_r00*x364))+(((-1.0)*new_r10*x367))); |
| 5986 | evalcond[5]=((((-1.0)*gconst18*x367))+x368+new_r10); |
| 5987 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 5988 | { |
| 5989 | continue; |
| 5990 | } |
| 5991 | } |
| 5992 | |
| 5993 | { |
| 5994 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 5995 | vinfos[0].jointtype = 1; |
| 5996 | vinfos[0].foffset = j0; |
| 5997 | vinfos[0].indices[0] = _ij0[0]; |
| 5998 | vinfos[0].indices[1] = _ij0[1]; |
| 5999 | vinfos[0].maxsolutions = _nj0; |
| 6000 | vinfos[1].jointtype = 1; |
| 6001 | vinfos[1].foffset = j1; |
| 6002 | vinfos[1].indices[0] = _ij1[0]; |
| 6003 | vinfos[1].indices[1] = _ij1[1]; |
| 6004 | vinfos[1].maxsolutions = _nj1; |
| 6005 | vinfos[2].jointtype = 1; |
| 6006 | vinfos[2].foffset = j2; |
| 6007 | vinfos[2].indices[0] = _ij2[0]; |
| 6008 | vinfos[2].indices[1] = _ij2[1]; |
| 6009 | vinfos[2].maxsolutions = _nj2; |
| 6010 | vinfos[3].jointtype = 1; |
| 6011 | vinfos[3].foffset = j3; |
| 6012 | vinfos[3].indices[0] = _ij3[0]; |
| 6013 | vinfos[3].indices[1] = _ij3[1]; |
| 6014 | vinfos[3].maxsolutions = _nj3; |
| 6015 | vinfos[4].jointtype = 1; |
| 6016 | vinfos[4].foffset = j4; |
| 6017 | vinfos[4].indices[0] = _ij4[0]; |
| 6018 | vinfos[4].indices[1] = _ij4[1]; |
| 6019 | vinfos[4].maxsolutions = _nj4; |
| 6020 | vinfos[5].jointtype = 1; |
| 6021 | vinfos[5].foffset = j5; |
| 6022 | vinfos[5].indices[0] = _ij5[0]; |
| 6023 | vinfos[5].indices[1] = _ij5[1]; |
| 6024 | vinfos[5].maxsolutions = _nj5; |
| 6025 | std::vector<int> vfree(0); |
| 6026 | solutions.AddSolution(vinfos,vfree); |
| 6027 | } |
| 6028 | } |
| 6029 | } |
| 6030 | |
| 6031 | } |
| 6032 | |
| 6033 | } |
| 6034 | |
| 6035 | } else |
| 6036 | { |
| 6037 | { |
| 6038 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 6039 | bool j0valid[1]={false}; |
| 6040 | _nj0 = 1; |
| 6041 | CheckValue<IkReal> x370 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(((-1.0)*(gconst18*gconst18))),IKFAST_ATAN2_MAGTHRESH); |
| 6042 | if(!x370.valid){ |
| 6043 | continue; |
| 6044 | } |
| 6045 | CheckValue<IkReal> x371=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1); |
| 6046 | if(!x371.valid){ |
| 6047 | continue; |
| 6048 | } |
| 6049 | j0array[0]=((-1.5707963267949)+(x370.value)+(((1.5707963267949)*(x371.value)))); |
| 6050 | sj0array[0]=IKsin(j0array[0]); |
| 6051 | cj0array[0]=IKcos(j0array[0]); |
| 6052 | if( j0array[0] > IKPI ) |
| 6053 | { |
| 6054 | j0array[0]-=IK2PI; |
| 6055 | } |
| 6056 | else if( j0array[0] < -IKPI ) |
| 6057 | { j0array[0]+=IK2PI; |
| 6058 | } |
| 6059 | j0valid[0] = true; |
| 6060 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 6061 | { |
| 6062 | if( !j0valid[ij0] ) |
| 6063 | { |
| 6064 | continue; |
| 6065 | } |
| 6066 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6067 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 6068 | { |
| 6069 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6070 | { |
| 6071 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6072 | } |
| 6073 | } |
| 6074 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6075 | { |
| 6076 | IkReal evalcond[6]; |
| 6077 | IkReal x372=IKcos(j0); |
| 6078 | IkReal x373=IKsin(j0); |
| 6079 | IkReal x374=(gconst17*x372); |
| 6080 | IkReal x375=(gconst18*x373); |
| 6081 | IkReal x376=((1.0)*x372); |
| 6082 | IkReal x377=(gconst17*x373); |
| 6083 | IkReal x378=(x375+x374); |
| 6084 | evalcond[0]=x378; |
| 6085 | evalcond[1]=(gconst17+((new_r00*x372))+((new_r10*x373))); |
| 6086 | evalcond[2]=(x378+new_r00); |
| 6087 | evalcond[3]=((((-1.0)*x377))+((gconst18*x372))); |
| 6088 | evalcond[4]=(gconst18+((new_r00*x373))+(((-1.0)*new_r10*x376))); |
| 6089 | evalcond[5]=((((-1.0)*gconst18*x376))+x377+new_r10); |
| 6090 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 6091 | { |
| 6092 | continue; |
| 6093 | } |
| 6094 | } |
| 6095 | |
| 6096 | { |
| 6097 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6098 | vinfos[0].jointtype = 1; |
| 6099 | vinfos[0].foffset = j0; |
| 6100 | vinfos[0].indices[0] = _ij0[0]; |
| 6101 | vinfos[0].indices[1] = _ij0[1]; |
| 6102 | vinfos[0].maxsolutions = _nj0; |
| 6103 | vinfos[1].jointtype = 1; |
| 6104 | vinfos[1].foffset = j1; |
| 6105 | vinfos[1].indices[0] = _ij1[0]; |
| 6106 | vinfos[1].indices[1] = _ij1[1]; |
| 6107 | vinfos[1].maxsolutions = _nj1; |
| 6108 | vinfos[2].jointtype = 1; |
| 6109 | vinfos[2].foffset = j2; |
| 6110 | vinfos[2].indices[0] = _ij2[0]; |
| 6111 | vinfos[2].indices[1] = _ij2[1]; |
| 6112 | vinfos[2].maxsolutions = _nj2; |
| 6113 | vinfos[3].jointtype = 1; |
| 6114 | vinfos[3].foffset = j3; |
| 6115 | vinfos[3].indices[0] = _ij3[0]; |
| 6116 | vinfos[3].indices[1] = _ij3[1]; |
| 6117 | vinfos[3].maxsolutions = _nj3; |
| 6118 | vinfos[4].jointtype = 1; |
| 6119 | vinfos[4].foffset = j4; |
| 6120 | vinfos[4].indices[0] = _ij4[0]; |
| 6121 | vinfos[4].indices[1] = _ij4[1]; |
| 6122 | vinfos[4].maxsolutions = _nj4; |
| 6123 | vinfos[5].jointtype = 1; |
| 6124 | vinfos[5].foffset = j5; |
| 6125 | vinfos[5].indices[0] = _ij5[0]; |
| 6126 | vinfos[5].indices[1] = _ij5[1]; |
| 6127 | vinfos[5].maxsolutions = _nj5; |
| 6128 | std::vector<int> vfree(0); |
| 6129 | solutions.AddSolution(vinfos,vfree); |
| 6130 | } |
| 6131 | } |
| 6132 | } |
| 6133 | |
| 6134 | } |
| 6135 | |
| 6136 | } |
| 6137 | |
| 6138 | } else |
| 6139 | { |
| 6140 | { |
| 6141 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 6142 | bool j0valid[1]={false}; |
| 6143 | _nj0 = 1; |
| 6144 | CheckValue<IkReal> x379 = IKatan2WithCheck(IkReal((gconst17*gconst18)),IkReal(gconst17*gconst17),IKFAST_ATAN2_MAGTHRESH); |
| 6145 | if(!x379.valid){ |
| 6146 | continue; |
| 6147 | } |
| 6148 | CheckValue<IkReal> x380=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst17*new_r00))+(((-1.0)*gconst18*new_r10)))),-1); |
| 6149 | if(!x380.valid){ |
| 6150 | continue; |
| 6151 | } |
| 6152 | j0array[0]=((-1.5707963267949)+(x379.value)+(((1.5707963267949)*(x380.value)))); |
| 6153 | sj0array[0]=IKsin(j0array[0]); |
| 6154 | cj0array[0]=IKcos(j0array[0]); |
| 6155 | if( j0array[0] > IKPI ) |
| 6156 | { |
| 6157 | j0array[0]-=IK2PI; |
| 6158 | } |
| 6159 | else if( j0array[0] < -IKPI ) |
| 6160 | { j0array[0]+=IK2PI; |
| 6161 | } |
| 6162 | j0valid[0] = true; |
| 6163 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 6164 | { |
| 6165 | if( !j0valid[ij0] ) |
| 6166 | { |
| 6167 | continue; |
| 6168 | } |
| 6169 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6170 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 6171 | { |
| 6172 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6173 | { |
| 6174 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6175 | } |
| 6176 | } |
| 6177 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6178 | { |
| 6179 | IkReal evalcond[6]; |
| 6180 | IkReal x381=IKcos(j0); |
| 6181 | IkReal x382=IKsin(j0); |
| 6182 | IkReal x383=(gconst17*x381); |
| 6183 | IkReal x384=(gconst18*x382); |
| 6184 | IkReal x385=((1.0)*x381); |
| 6185 | IkReal x386=(gconst17*x382); |
| 6186 | IkReal x387=(x384+x383); |
| 6187 | evalcond[0]=x387; |
| 6188 | evalcond[1]=(((new_r00*x381))+gconst17+((new_r10*x382))); |
| 6189 | evalcond[2]=(x387+new_r00); |
| 6190 | evalcond[3]=((((-1.0)*x386))+((gconst18*x381))); |
| 6191 | evalcond[4]=((((-1.0)*new_r10*x385))+((new_r00*x382))+gconst18); |
| 6192 | evalcond[5]=(x386+(((-1.0)*gconst18*x385))+new_r10); |
| 6193 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 6194 | { |
| 6195 | continue; |
| 6196 | } |
| 6197 | } |
| 6198 | |
| 6199 | { |
| 6200 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6201 | vinfos[0].jointtype = 1; |
| 6202 | vinfos[0].foffset = j0; |
| 6203 | vinfos[0].indices[0] = _ij0[0]; |
| 6204 | vinfos[0].indices[1] = _ij0[1]; |
| 6205 | vinfos[0].maxsolutions = _nj0; |
| 6206 | vinfos[1].jointtype = 1; |
| 6207 | vinfos[1].foffset = j1; |
| 6208 | vinfos[1].indices[0] = _ij1[0]; |
| 6209 | vinfos[1].indices[1] = _ij1[1]; |
| 6210 | vinfos[1].maxsolutions = _nj1; |
| 6211 | vinfos[2].jointtype = 1; |
| 6212 | vinfos[2].foffset = j2; |
| 6213 | vinfos[2].indices[0] = _ij2[0]; |
| 6214 | vinfos[2].indices[1] = _ij2[1]; |
| 6215 | vinfos[2].maxsolutions = _nj2; |
| 6216 | vinfos[3].jointtype = 1; |
| 6217 | vinfos[3].foffset = j3; |
| 6218 | vinfos[3].indices[0] = _ij3[0]; |
| 6219 | vinfos[3].indices[1] = _ij3[1]; |
| 6220 | vinfos[3].maxsolutions = _nj3; |
| 6221 | vinfos[4].jointtype = 1; |
| 6222 | vinfos[4].foffset = j4; |
| 6223 | vinfos[4].indices[0] = _ij4[0]; |
| 6224 | vinfos[4].indices[1] = _ij4[1]; |
| 6225 | vinfos[4].maxsolutions = _nj4; |
| 6226 | vinfos[5].jointtype = 1; |
| 6227 | vinfos[5].foffset = j5; |
| 6228 | vinfos[5].indices[0] = _ij5[0]; |
| 6229 | vinfos[5].indices[1] = _ij5[1]; |
| 6230 | vinfos[5].maxsolutions = _nj5; |
| 6231 | std::vector<int> vfree(0); |
| 6232 | solutions.AddSolution(vinfos,vfree); |
| 6233 | } |
| 6234 | } |
| 6235 | } |
| 6236 | |
| 6237 | } |
| 6238 | |
| 6239 | } |
| 6240 | |
| 6241 | } |
| 6242 | } while(0); |
| 6243 | if( bgotonextstatement ) |
| 6244 | { |
| 6245 | bool bgotonextstatement = true; |
| 6246 | do |
| 6247 | { |
| 6248 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| 6249 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 6250 | { |
| 6251 | bgotonextstatement=false; |
| 6252 | { |
| 6253 | IkReal j0eval[1]; |
| 6254 | CheckValue<IkReal> x389 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 6255 | if(!x389.valid){ |
| 6256 | continue; |
| 6257 | } |
| 6258 | IkReal x388=((-1.0)*(x389.value)); |
| 6259 | sj1=1.0; |
| 6260 | cj1=0; |
| 6261 | j1=1.5707963267949; |
| 6262 | sj2=gconst17; |
| 6263 | cj2=gconst18; |
| 6264 | j2=x388; |
| 6265 | new_r01=0; |
| 6266 | new_r10=0; |
| 6267 | IkReal gconst16=x388; |
| 6268 | IkReal x390 = new_r00*new_r00; |
| 6269 | if(IKabs(x390)==0){ |
| 6270 | continue; |
| 6271 | } |
| 6272 | IkReal gconst17=((-1.0)*new_r00*(pow(x390,-0.5))); |
| 6273 | IkReal gconst18=0; |
| 6274 | j0eval[0]=new_r11; |
| 6275 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 6276 | { |
| 6277 | { |
| 6278 | IkReal j0eval[1]; |
| 6279 | CheckValue<IkReal> x392 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 6280 | if(!x392.valid){ |
| 6281 | continue; |
| 6282 | } |
| 6283 | IkReal x391=((-1.0)*(x392.value)); |
| 6284 | sj1=1.0; |
| 6285 | cj1=0; |
| 6286 | j1=1.5707963267949; |
| 6287 | sj2=gconst17; |
| 6288 | cj2=gconst18; |
| 6289 | j2=x391; |
| 6290 | new_r01=0; |
| 6291 | new_r10=0; |
| 6292 | IkReal gconst16=x391; |
| 6293 | IkReal x393 = new_r00*new_r00; |
| 6294 | if(IKabs(x393)==0){ |
| 6295 | continue; |
| 6296 | } |
| 6297 | IkReal gconst17=((-1.0)*new_r00*(pow(x393,-0.5))); |
| 6298 | IkReal gconst18=0; |
| 6299 | j0eval[0]=new_r00; |
| 6300 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 6301 | { |
| 6302 | { |
| 6303 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 6304 | bool j0valid[2]={false}; |
| 6305 | _nj0 = 2; |
| 6306 | CheckValue<IkReal> x394=IKPowWithIntegerCheck(gconst17,-1); |
| 6307 | if(!x394.valid){ |
| 6308 | continue; |
| 6309 | } |
| 6310 | cj0array[0]=((-1.0)*new_r00*(x394.value)); |
| 6311 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 6312 | { |
| 6313 | j0valid[0] = j0valid[1] = true; |
| 6314 | j0array[0] = IKacos(cj0array[0]); |
| 6315 | sj0array[0] = IKsin(j0array[0]); |
| 6316 | cj0array[1] = cj0array[0]; |
| 6317 | j0array[1] = -j0array[0]; |
| 6318 | sj0array[1] = -sj0array[0]; |
| 6319 | } |
| 6320 | else if( isnan(cj0array[0]) ) |
| 6321 | { |
| 6322 | // probably any value will work |
| 6323 | j0valid[0] = true; |
| 6324 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 6325 | } |
| 6326 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 6327 | { |
| 6328 | if( !j0valid[ij0] ) |
| 6329 | { |
| 6330 | continue; |
| 6331 | } |
| 6332 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6333 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 6334 | { |
| 6335 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6336 | { |
| 6337 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6338 | } |
| 6339 | } |
| 6340 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6341 | { |
| 6342 | IkReal evalcond[6]; |
| 6343 | IkReal x395=IKsin(j0); |
| 6344 | IkReal x396=IKcos(j0); |
| 6345 | evalcond[0]=(new_r00*x395); |
| 6346 | evalcond[1]=(new_r11*x395); |
| 6347 | evalcond[2]=((-1.0)*gconst17*x395); |
| 6348 | evalcond[3]=(((new_r11*x396))+gconst17); |
| 6349 | evalcond[4]=(gconst17+((new_r00*x396))); |
| 6350 | evalcond[5]=(new_r11+((gconst17*x396))); |
| 6351 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 6352 | { |
| 6353 | continue; |
| 6354 | } |
| 6355 | } |
| 6356 | |
| 6357 | { |
| 6358 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6359 | vinfos[0].jointtype = 1; |
| 6360 | vinfos[0].foffset = j0; |
| 6361 | vinfos[0].indices[0] = _ij0[0]; |
| 6362 | vinfos[0].indices[1] = _ij0[1]; |
| 6363 | vinfos[0].maxsolutions = _nj0; |
| 6364 | vinfos[1].jointtype = 1; |
| 6365 | vinfos[1].foffset = j1; |
| 6366 | vinfos[1].indices[0] = _ij1[0]; |
| 6367 | vinfos[1].indices[1] = _ij1[1]; |
| 6368 | vinfos[1].maxsolutions = _nj1; |
| 6369 | vinfos[2].jointtype = 1; |
| 6370 | vinfos[2].foffset = j2; |
| 6371 | vinfos[2].indices[0] = _ij2[0]; |
| 6372 | vinfos[2].indices[1] = _ij2[1]; |
| 6373 | vinfos[2].maxsolutions = _nj2; |
| 6374 | vinfos[3].jointtype = 1; |
| 6375 | vinfos[3].foffset = j3; |
| 6376 | vinfos[3].indices[0] = _ij3[0]; |
| 6377 | vinfos[3].indices[1] = _ij3[1]; |
| 6378 | vinfos[3].maxsolutions = _nj3; |
| 6379 | vinfos[4].jointtype = 1; |
| 6380 | vinfos[4].foffset = j4; |
| 6381 | vinfos[4].indices[0] = _ij4[0]; |
| 6382 | vinfos[4].indices[1] = _ij4[1]; |
| 6383 | vinfos[4].maxsolutions = _nj4; |
| 6384 | vinfos[5].jointtype = 1; |
| 6385 | vinfos[5].foffset = j5; |
| 6386 | vinfos[5].indices[0] = _ij5[0]; |
| 6387 | vinfos[5].indices[1] = _ij5[1]; |
| 6388 | vinfos[5].maxsolutions = _nj5; |
| 6389 | std::vector<int> vfree(0); |
| 6390 | solutions.AddSolution(vinfos,vfree); |
| 6391 | } |
| 6392 | } |
| 6393 | } |
| 6394 | |
| 6395 | } else |
| 6396 | { |
| 6397 | { |
| 6398 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 6399 | bool j0valid[2]={false}; |
| 6400 | _nj0 = 2; |
| 6401 | CheckValue<IkReal> x397=IKPowWithIntegerCheck(new_r00,-1); |
| 6402 | if(!x397.valid){ |
| 6403 | continue; |
| 6404 | } |
| 6405 | cj0array[0]=((-1.0)*gconst17*(x397.value)); |
| 6406 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 6407 | { |
| 6408 | j0valid[0] = j0valid[1] = true; |
| 6409 | j0array[0] = IKacos(cj0array[0]); |
| 6410 | sj0array[0] = IKsin(j0array[0]); |
| 6411 | cj0array[1] = cj0array[0]; |
| 6412 | j0array[1] = -j0array[0]; |
| 6413 | sj0array[1] = -sj0array[0]; |
| 6414 | } |
| 6415 | else if( isnan(cj0array[0]) ) |
| 6416 | { |
| 6417 | // probably any value will work |
| 6418 | j0valid[0] = true; |
| 6419 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 6420 | } |
| 6421 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 6422 | { |
| 6423 | if( !j0valid[ij0] ) |
| 6424 | { |
| 6425 | continue; |
| 6426 | } |
| 6427 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6428 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 6429 | { |
| 6430 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6431 | { |
| 6432 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6433 | } |
| 6434 | } |
| 6435 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6436 | { |
| 6437 | IkReal evalcond[6]; |
| 6438 | IkReal x398=IKsin(j0); |
| 6439 | IkReal x399=IKcos(j0); |
| 6440 | IkReal x400=(gconst17*x399); |
| 6441 | evalcond[0]=(new_r00*x398); |
| 6442 | evalcond[1]=(new_r11*x398); |
| 6443 | evalcond[2]=((-1.0)*gconst17*x398); |
| 6444 | evalcond[3]=(((new_r11*x399))+gconst17); |
| 6445 | evalcond[4]=(x400+new_r00); |
| 6446 | evalcond[5]=(x400+new_r11); |
| 6447 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 6448 | { |
| 6449 | continue; |
| 6450 | } |
| 6451 | } |
| 6452 | |
| 6453 | { |
| 6454 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6455 | vinfos[0].jointtype = 1; |
| 6456 | vinfos[0].foffset = j0; |
| 6457 | vinfos[0].indices[0] = _ij0[0]; |
| 6458 | vinfos[0].indices[1] = _ij0[1]; |
| 6459 | vinfos[0].maxsolutions = _nj0; |
| 6460 | vinfos[1].jointtype = 1; |
| 6461 | vinfos[1].foffset = j1; |
| 6462 | vinfos[1].indices[0] = _ij1[0]; |
| 6463 | vinfos[1].indices[1] = _ij1[1]; |
| 6464 | vinfos[1].maxsolutions = _nj1; |
| 6465 | vinfos[2].jointtype = 1; |
| 6466 | vinfos[2].foffset = j2; |
| 6467 | vinfos[2].indices[0] = _ij2[0]; |
| 6468 | vinfos[2].indices[1] = _ij2[1]; |
| 6469 | vinfos[2].maxsolutions = _nj2; |
| 6470 | vinfos[3].jointtype = 1; |
| 6471 | vinfos[3].foffset = j3; |
| 6472 | vinfos[3].indices[0] = _ij3[0]; |
| 6473 | vinfos[3].indices[1] = _ij3[1]; |
| 6474 | vinfos[3].maxsolutions = _nj3; |
| 6475 | vinfos[4].jointtype = 1; |
| 6476 | vinfos[4].foffset = j4; |
| 6477 | vinfos[4].indices[0] = _ij4[0]; |
| 6478 | vinfos[4].indices[1] = _ij4[1]; |
| 6479 | vinfos[4].maxsolutions = _nj4; |
| 6480 | vinfos[5].jointtype = 1; |
| 6481 | vinfos[5].foffset = j5; |
| 6482 | vinfos[5].indices[0] = _ij5[0]; |
| 6483 | vinfos[5].indices[1] = _ij5[1]; |
| 6484 | vinfos[5].maxsolutions = _nj5; |
| 6485 | std::vector<int> vfree(0); |
| 6486 | solutions.AddSolution(vinfos,vfree); |
| 6487 | } |
| 6488 | } |
| 6489 | } |
| 6490 | |
| 6491 | } |
| 6492 | |
| 6493 | } |
| 6494 | |
| 6495 | } else |
| 6496 | { |
| 6497 | { |
| 6498 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 6499 | bool j0valid[2]={false}; |
| 6500 | _nj0 = 2; |
| 6501 | CheckValue<IkReal> x401=IKPowWithIntegerCheck(new_r11,-1); |
| 6502 | if(!x401.valid){ |
| 6503 | continue; |
| 6504 | } |
| 6505 | cj0array[0]=((-1.0)*gconst17*(x401.value)); |
| 6506 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 6507 | { |
| 6508 | j0valid[0] = j0valid[1] = true; |
| 6509 | j0array[0] = IKacos(cj0array[0]); |
| 6510 | sj0array[0] = IKsin(j0array[0]); |
| 6511 | cj0array[1] = cj0array[0]; |
| 6512 | j0array[1] = -j0array[0]; |
| 6513 | sj0array[1] = -sj0array[0]; |
| 6514 | } |
| 6515 | else if( isnan(cj0array[0]) ) |
| 6516 | { |
| 6517 | // probably any value will work |
| 6518 | j0valid[0] = true; |
| 6519 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 6520 | } |
| 6521 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 6522 | { |
| 6523 | if( !j0valid[ij0] ) |
| 6524 | { |
| 6525 | continue; |
| 6526 | } |
| 6527 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6528 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 6529 | { |
| 6530 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6531 | { |
| 6532 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6533 | } |
| 6534 | } |
| 6535 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6536 | { |
| 6537 | IkReal evalcond[6]; |
| 6538 | IkReal x402=IKsin(j0); |
| 6539 | IkReal x403=IKcos(j0); |
| 6540 | IkReal x404=(gconst17*x403); |
| 6541 | evalcond[0]=(new_r00*x402); |
| 6542 | evalcond[1]=(new_r11*x402); |
| 6543 | evalcond[2]=((-1.0)*gconst17*x402); |
| 6544 | evalcond[3]=(gconst17+((new_r00*x403))); |
| 6545 | evalcond[4]=(x404+new_r00); |
| 6546 | evalcond[5]=(x404+new_r11); |
| 6547 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 6548 | { |
| 6549 | continue; |
| 6550 | } |
| 6551 | } |
| 6552 | |
| 6553 | { |
| 6554 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6555 | vinfos[0].jointtype = 1; |
| 6556 | vinfos[0].foffset = j0; |
| 6557 | vinfos[0].indices[0] = _ij0[0]; |
| 6558 | vinfos[0].indices[1] = _ij0[1]; |
| 6559 | vinfos[0].maxsolutions = _nj0; |
| 6560 | vinfos[1].jointtype = 1; |
| 6561 | vinfos[1].foffset = j1; |
| 6562 | vinfos[1].indices[0] = _ij1[0]; |
| 6563 | vinfos[1].indices[1] = _ij1[1]; |
| 6564 | vinfos[1].maxsolutions = _nj1; |
| 6565 | vinfos[2].jointtype = 1; |
| 6566 | vinfos[2].foffset = j2; |
| 6567 | vinfos[2].indices[0] = _ij2[0]; |
| 6568 | vinfos[2].indices[1] = _ij2[1]; |
| 6569 | vinfos[2].maxsolutions = _nj2; |
| 6570 | vinfos[3].jointtype = 1; |
| 6571 | vinfos[3].foffset = j3; |
| 6572 | vinfos[3].indices[0] = _ij3[0]; |
| 6573 | vinfos[3].indices[1] = _ij3[1]; |
| 6574 | vinfos[3].maxsolutions = _nj3; |
| 6575 | vinfos[4].jointtype = 1; |
| 6576 | vinfos[4].foffset = j4; |
| 6577 | vinfos[4].indices[0] = _ij4[0]; |
| 6578 | vinfos[4].indices[1] = _ij4[1]; |
| 6579 | vinfos[4].maxsolutions = _nj4; |
| 6580 | vinfos[5].jointtype = 1; |
| 6581 | vinfos[5].foffset = j5; |
| 6582 | vinfos[5].indices[0] = _ij5[0]; |
| 6583 | vinfos[5].indices[1] = _ij5[1]; |
| 6584 | vinfos[5].maxsolutions = _nj5; |
| 6585 | std::vector<int> vfree(0); |
| 6586 | solutions.AddSolution(vinfos,vfree); |
| 6587 | } |
| 6588 | } |
| 6589 | } |
| 6590 | |
| 6591 | } |
| 6592 | |
| 6593 | } |
| 6594 | |
| 6595 | } |
| 6596 | } while(0); |
| 6597 | if( bgotonextstatement ) |
| 6598 | { |
| 6599 | bool bgotonextstatement = true; |
| 6600 | do |
| 6601 | { |
| 6602 | evalcond[0]=IKabs(new_r00); |
| 6603 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 6604 | { |
| 6605 | bgotonextstatement=false; |
| 6606 | { |
| 6607 | IkReal j0eval[1]; |
| 6608 | IkReal x405=((-1.0)*new_r10); |
| 6609 | CheckValue<IkReal> x407 = IKatan2WithCheck(IkReal(0),IkReal(x405),IKFAST_ATAN2_MAGTHRESH); |
| 6610 | if(!x407.valid){ |
| 6611 | continue; |
| 6612 | } |
| 6613 | IkReal x406=((-1.0)*(x407.value)); |
| 6614 | sj1=1.0; |
| 6615 | cj1=0; |
| 6616 | j1=1.5707963267949; |
| 6617 | sj2=gconst17; |
| 6618 | cj2=gconst18; |
| 6619 | j2=x406; |
| 6620 | new_r00=0; |
| 6621 | IkReal gconst16=x406; |
| 6622 | IkReal gconst17=0; |
| 6623 | IkReal x408 = new_r10*new_r10; |
| 6624 | if(IKabs(x408)==0){ |
| 6625 | continue; |
| 6626 | } |
| 6627 | IkReal gconst18=(x405*(pow(x408,-0.5))); |
| 6628 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 6629 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 6630 | { |
| 6631 | { |
| 6632 | IkReal j0eval[1]; |
| 6633 | IkReal x409=((-1.0)*new_r10); |
| 6634 | CheckValue<IkReal> x411 = IKatan2WithCheck(IkReal(0),IkReal(x409),IKFAST_ATAN2_MAGTHRESH); |
| 6635 | if(!x411.valid){ |
| 6636 | continue; |
| 6637 | } |
| 6638 | IkReal x410=((-1.0)*(x411.value)); |
| 6639 | sj1=1.0; |
| 6640 | cj1=0; |
| 6641 | j1=1.5707963267949; |
| 6642 | sj2=gconst17; |
| 6643 | cj2=gconst18; |
| 6644 | j2=x410; |
| 6645 | new_r00=0; |
| 6646 | IkReal gconst16=x410; |
| 6647 | IkReal gconst17=0; |
| 6648 | IkReal x412 = new_r10*new_r10; |
| 6649 | if(IKabs(x412)==0){ |
| 6650 | continue; |
| 6651 | } |
| 6652 | IkReal gconst18=(x409*(pow(x412,-0.5))); |
| 6653 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 6654 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 6655 | { |
| 6656 | { |
| 6657 | IkReal j0eval[1]; |
| 6658 | IkReal x413=((-1.0)*new_r10); |
| 6659 | CheckValue<IkReal> x415 = IKatan2WithCheck(IkReal(0),IkReal(x413),IKFAST_ATAN2_MAGTHRESH); |
| 6660 | if(!x415.valid){ |
| 6661 | continue; |
| 6662 | } |
| 6663 | IkReal x414=((-1.0)*(x415.value)); |
| 6664 | sj1=1.0; |
| 6665 | cj1=0; |
| 6666 | j1=1.5707963267949; |
| 6667 | sj2=gconst17; |
| 6668 | cj2=gconst18; |
| 6669 | j2=x414; |
| 6670 | new_r00=0; |
| 6671 | IkReal gconst16=x414; |
| 6672 | IkReal gconst17=0; |
| 6673 | IkReal x416 = new_r10*new_r10; |
| 6674 | if(IKabs(x416)==0){ |
| 6675 | continue; |
| 6676 | } |
| 6677 | IkReal gconst18=(x413*(pow(x416,-0.5))); |
| 6678 | j0eval[0]=new_r10; |
| 6679 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 6680 | { |
| 6681 | continue; // 3 cases reached |
| 6682 | |
| 6683 | } else |
| 6684 | { |
| 6685 | { |
| 6686 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 6687 | bool j0valid[1]={false}; |
| 6688 | _nj0 = 1; |
| 6689 | CheckValue<IkReal> x417=IKPowWithIntegerCheck(gconst18,-1); |
| 6690 | if(!x417.valid){ |
| 6691 | continue; |
| 6692 | } |
| 6693 | CheckValue<IkReal> x418=IKPowWithIntegerCheck(new_r10,-1); |
| 6694 | if(!x418.valid){ |
| 6695 | continue; |
| 6696 | } |
| 6697 | if( IKabs(((-1.0)*new_r11*(x417.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst18*(x418.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x417.value)))+IKsqr((gconst18*(x418.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 6698 | continue; |
| 6699 | j0array[0]=IKatan2(((-1.0)*new_r11*(x417.value)), (gconst18*(x418.value))); |
| 6700 | sj0array[0]=IKsin(j0array[0]); |
| 6701 | cj0array[0]=IKcos(j0array[0]); |
| 6702 | if( j0array[0] > IKPI ) |
| 6703 | { |
| 6704 | j0array[0]-=IK2PI; |
| 6705 | } |
| 6706 | else if( j0array[0] < -IKPI ) |
| 6707 | { j0array[0]+=IK2PI; |
| 6708 | } |
| 6709 | j0valid[0] = true; |
| 6710 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 6711 | { |
| 6712 | if( !j0valid[ij0] ) |
| 6713 | { |
| 6714 | continue; |
| 6715 | } |
| 6716 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6717 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 6718 | { |
| 6719 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6720 | { |
| 6721 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6722 | } |
| 6723 | } |
| 6724 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6725 | { |
| 6726 | IkReal evalcond[8]; |
| 6727 | IkReal x419=IKsin(j0); |
| 6728 | IkReal x420=IKcos(j0); |
| 6729 | IkReal x421=(gconst18*x419); |
| 6730 | IkReal x422=((1.0)*x420); |
| 6731 | evalcond[0]=(new_r10*x419); |
| 6732 | evalcond[1]=x421; |
| 6733 | evalcond[2]=(x421+new_r11); |
| 6734 | evalcond[3]=(((gconst18*x420))+new_r01); |
| 6735 | evalcond[4]=(gconst18+(((-1.0)*new_r10*x422))); |
| 6736 | evalcond[5]=((((-1.0)*gconst18*x422))+new_r10); |
| 6737 | evalcond[6]=((((-1.0)*new_r01*x419))+((new_r11*x420))); |
| 6738 | evalcond[7]=(gconst18+((new_r11*x419))+((new_r01*x420))); |
| 6739 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 6740 | { |
| 6741 | continue; |
| 6742 | } |
| 6743 | } |
| 6744 | |
| 6745 | { |
| 6746 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6747 | vinfos[0].jointtype = 1; |
| 6748 | vinfos[0].foffset = j0; |
| 6749 | vinfos[0].indices[0] = _ij0[0]; |
| 6750 | vinfos[0].indices[1] = _ij0[1]; |
| 6751 | vinfos[0].maxsolutions = _nj0; |
| 6752 | vinfos[1].jointtype = 1; |
| 6753 | vinfos[1].foffset = j1; |
| 6754 | vinfos[1].indices[0] = _ij1[0]; |
| 6755 | vinfos[1].indices[1] = _ij1[1]; |
| 6756 | vinfos[1].maxsolutions = _nj1; |
| 6757 | vinfos[2].jointtype = 1; |
| 6758 | vinfos[2].foffset = j2; |
| 6759 | vinfos[2].indices[0] = _ij2[0]; |
| 6760 | vinfos[2].indices[1] = _ij2[1]; |
| 6761 | vinfos[2].maxsolutions = _nj2; |
| 6762 | vinfos[3].jointtype = 1; |
| 6763 | vinfos[3].foffset = j3; |
| 6764 | vinfos[3].indices[0] = _ij3[0]; |
| 6765 | vinfos[3].indices[1] = _ij3[1]; |
| 6766 | vinfos[3].maxsolutions = _nj3; |
| 6767 | vinfos[4].jointtype = 1; |
| 6768 | vinfos[4].foffset = j4; |
| 6769 | vinfos[4].indices[0] = _ij4[0]; |
| 6770 | vinfos[4].indices[1] = _ij4[1]; |
| 6771 | vinfos[4].maxsolutions = _nj4; |
| 6772 | vinfos[5].jointtype = 1; |
| 6773 | vinfos[5].foffset = j5; |
| 6774 | vinfos[5].indices[0] = _ij5[0]; |
| 6775 | vinfos[5].indices[1] = _ij5[1]; |
| 6776 | vinfos[5].maxsolutions = _nj5; |
| 6777 | std::vector<int> vfree(0); |
| 6778 | solutions.AddSolution(vinfos,vfree); |
| 6779 | } |
| 6780 | } |
| 6781 | } |
| 6782 | |
| 6783 | } |
| 6784 | |
| 6785 | } |
| 6786 | |
| 6787 | } else |
| 6788 | { |
| 6789 | { |
| 6790 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 6791 | bool j0valid[1]={false}; |
| 6792 | _nj0 = 1; |
| 6793 | CheckValue<IkReal> x423=IKPowWithIntegerCheck(IKsign(gconst18),-1); |
| 6794 | if(!x423.valid){ |
| 6795 | continue; |
| 6796 | } |
| 6797 | CheckValue<IkReal> x424 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 6798 | if(!x424.valid){ |
| 6799 | continue; |
| 6800 | } |
| 6801 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x423.value)))+(x424.value)); |
| 6802 | sj0array[0]=IKsin(j0array[0]); |
| 6803 | cj0array[0]=IKcos(j0array[0]); |
| 6804 | if( j0array[0] > IKPI ) |
| 6805 | { |
| 6806 | j0array[0]-=IK2PI; |
| 6807 | } |
| 6808 | else if( j0array[0] < -IKPI ) |
| 6809 | { j0array[0]+=IK2PI; |
| 6810 | } |
| 6811 | j0valid[0] = true; |
| 6812 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 6813 | { |
| 6814 | if( !j0valid[ij0] ) |
| 6815 | { |
| 6816 | continue; |
| 6817 | } |
| 6818 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6819 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 6820 | { |
| 6821 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6822 | { |
| 6823 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6824 | } |
| 6825 | } |
| 6826 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6827 | { |
| 6828 | IkReal evalcond[8]; |
| 6829 | IkReal x425=IKsin(j0); |
| 6830 | IkReal x426=IKcos(j0); |
| 6831 | IkReal x427=(gconst18*x425); |
| 6832 | IkReal x428=((1.0)*x426); |
| 6833 | evalcond[0]=(new_r10*x425); |
| 6834 | evalcond[1]=x427; |
| 6835 | evalcond[2]=(x427+new_r11); |
| 6836 | evalcond[3]=(((gconst18*x426))+new_r01); |
| 6837 | evalcond[4]=(gconst18+(((-1.0)*new_r10*x428))); |
| 6838 | evalcond[5]=((((-1.0)*gconst18*x428))+new_r10); |
| 6839 | evalcond[6]=((((-1.0)*new_r01*x425))+((new_r11*x426))); |
| 6840 | evalcond[7]=(gconst18+((new_r11*x425))+((new_r01*x426))); |
| 6841 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 6842 | { |
| 6843 | continue; |
| 6844 | } |
| 6845 | } |
| 6846 | |
| 6847 | { |
| 6848 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6849 | vinfos[0].jointtype = 1; |
| 6850 | vinfos[0].foffset = j0; |
| 6851 | vinfos[0].indices[0] = _ij0[0]; |
| 6852 | vinfos[0].indices[1] = _ij0[1]; |
| 6853 | vinfos[0].maxsolutions = _nj0; |
| 6854 | vinfos[1].jointtype = 1; |
| 6855 | vinfos[1].foffset = j1; |
| 6856 | vinfos[1].indices[0] = _ij1[0]; |
| 6857 | vinfos[1].indices[1] = _ij1[1]; |
| 6858 | vinfos[1].maxsolutions = _nj1; |
| 6859 | vinfos[2].jointtype = 1; |
| 6860 | vinfos[2].foffset = j2; |
| 6861 | vinfos[2].indices[0] = _ij2[0]; |
| 6862 | vinfos[2].indices[1] = _ij2[1]; |
| 6863 | vinfos[2].maxsolutions = _nj2; |
| 6864 | vinfos[3].jointtype = 1; |
| 6865 | vinfos[3].foffset = j3; |
| 6866 | vinfos[3].indices[0] = _ij3[0]; |
| 6867 | vinfos[3].indices[1] = _ij3[1]; |
| 6868 | vinfos[3].maxsolutions = _nj3; |
| 6869 | vinfos[4].jointtype = 1; |
| 6870 | vinfos[4].foffset = j4; |
| 6871 | vinfos[4].indices[0] = _ij4[0]; |
| 6872 | vinfos[4].indices[1] = _ij4[1]; |
| 6873 | vinfos[4].maxsolutions = _nj4; |
| 6874 | vinfos[5].jointtype = 1; |
| 6875 | vinfos[5].foffset = j5; |
| 6876 | vinfos[5].indices[0] = _ij5[0]; |
| 6877 | vinfos[5].indices[1] = _ij5[1]; |
| 6878 | vinfos[5].maxsolutions = _nj5; |
| 6879 | std::vector<int> vfree(0); |
| 6880 | solutions.AddSolution(vinfos,vfree); |
| 6881 | } |
| 6882 | } |
| 6883 | } |
| 6884 | |
| 6885 | } |
| 6886 | |
| 6887 | } |
| 6888 | |
| 6889 | } else |
| 6890 | { |
| 6891 | { |
| 6892 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 6893 | bool j0valid[1]={false}; |
| 6894 | _nj0 = 1; |
| 6895 | CheckValue<IkReal> x429=IKPowWithIntegerCheck(IKsign(gconst18),-1); |
| 6896 | if(!x429.valid){ |
| 6897 | continue; |
| 6898 | } |
| 6899 | CheckValue<IkReal> x430 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 6900 | if(!x430.valid){ |
| 6901 | continue; |
| 6902 | } |
| 6903 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x429.value)))+(x430.value)); |
| 6904 | sj0array[0]=IKsin(j0array[0]); |
| 6905 | cj0array[0]=IKcos(j0array[0]); |
| 6906 | if( j0array[0] > IKPI ) |
| 6907 | { |
| 6908 | j0array[0]-=IK2PI; |
| 6909 | } |
| 6910 | else if( j0array[0] < -IKPI ) |
| 6911 | { j0array[0]+=IK2PI; |
| 6912 | } |
| 6913 | j0valid[0] = true; |
| 6914 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 6915 | { |
| 6916 | if( !j0valid[ij0] ) |
| 6917 | { |
| 6918 | continue; |
| 6919 | } |
| 6920 | _ij0[0] = ij0; _ij0[1] = -1; |
| 6921 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 6922 | { |
| 6923 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 6924 | { |
| 6925 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 6926 | } |
| 6927 | } |
| 6928 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 6929 | { |
| 6930 | IkReal evalcond[8]; |
| 6931 | IkReal x431=IKsin(j0); |
| 6932 | IkReal x432=IKcos(j0); |
| 6933 | IkReal x433=(gconst18*x431); |
| 6934 | IkReal x434=((1.0)*x432); |
| 6935 | evalcond[0]=(new_r10*x431); |
| 6936 | evalcond[1]=x433; |
| 6937 | evalcond[2]=(x433+new_r11); |
| 6938 | evalcond[3]=(new_r01+((gconst18*x432))); |
| 6939 | evalcond[4]=(gconst18+(((-1.0)*new_r10*x434))); |
| 6940 | evalcond[5]=((((-1.0)*gconst18*x434))+new_r10); |
| 6941 | evalcond[6]=(((new_r11*x432))+(((-1.0)*new_r01*x431))); |
| 6942 | evalcond[7]=(((new_r01*x432))+gconst18+((new_r11*x431))); |
| 6943 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 6944 | { |
| 6945 | continue; |
| 6946 | } |
| 6947 | } |
| 6948 | |
| 6949 | { |
| 6950 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 6951 | vinfos[0].jointtype = 1; |
| 6952 | vinfos[0].foffset = j0; |
| 6953 | vinfos[0].indices[0] = _ij0[0]; |
| 6954 | vinfos[0].indices[1] = _ij0[1]; |
| 6955 | vinfos[0].maxsolutions = _nj0; |
| 6956 | vinfos[1].jointtype = 1; |
| 6957 | vinfos[1].foffset = j1; |
| 6958 | vinfos[1].indices[0] = _ij1[0]; |
| 6959 | vinfos[1].indices[1] = _ij1[1]; |
| 6960 | vinfos[1].maxsolutions = _nj1; |
| 6961 | vinfos[2].jointtype = 1; |
| 6962 | vinfos[2].foffset = j2; |
| 6963 | vinfos[2].indices[0] = _ij2[0]; |
| 6964 | vinfos[2].indices[1] = _ij2[1]; |
| 6965 | vinfos[2].maxsolutions = _nj2; |
| 6966 | vinfos[3].jointtype = 1; |
| 6967 | vinfos[3].foffset = j3; |
| 6968 | vinfos[3].indices[0] = _ij3[0]; |
| 6969 | vinfos[3].indices[1] = _ij3[1]; |
| 6970 | vinfos[3].maxsolutions = _nj3; |
| 6971 | vinfos[4].jointtype = 1; |
| 6972 | vinfos[4].foffset = j4; |
| 6973 | vinfos[4].indices[0] = _ij4[0]; |
| 6974 | vinfos[4].indices[1] = _ij4[1]; |
| 6975 | vinfos[4].maxsolutions = _nj4; |
| 6976 | vinfos[5].jointtype = 1; |
| 6977 | vinfos[5].foffset = j5; |
| 6978 | vinfos[5].indices[0] = _ij5[0]; |
| 6979 | vinfos[5].indices[1] = _ij5[1]; |
| 6980 | vinfos[5].maxsolutions = _nj5; |
| 6981 | std::vector<int> vfree(0); |
| 6982 | solutions.AddSolution(vinfos,vfree); |
| 6983 | } |
| 6984 | } |
| 6985 | } |
| 6986 | |
| 6987 | } |
| 6988 | |
| 6989 | } |
| 6990 | |
| 6991 | } |
| 6992 | } while(0); |
| 6993 | if( bgotonextstatement ) |
| 6994 | { |
| 6995 | bool bgotonextstatement = true; |
| 6996 | do |
| 6997 | { |
| 6998 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 6999 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 7000 | { |
| 7001 | bgotonextstatement=false; |
| 7002 | { |
| 7003 | IkReal j0eval[1]; |
| 7004 | CheckValue<IkReal> x436 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 7005 | if(!x436.valid){ |
| 7006 | continue; |
| 7007 | } |
| 7008 | IkReal x435=((-1.0)*(x436.value)); |
| 7009 | sj1=1.0; |
| 7010 | cj1=0; |
| 7011 | j1=1.5707963267949; |
| 7012 | sj2=gconst17; |
| 7013 | cj2=gconst18; |
| 7014 | j2=x435; |
| 7015 | new_r11=0; |
| 7016 | new_r10=0; |
| 7017 | new_r22=0; |
| 7018 | new_r02=0; |
| 7019 | IkReal gconst16=x435; |
| 7020 | IkReal x437 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 7021 | if(IKabs(x437)==0){ |
| 7022 | continue; |
| 7023 | } |
| 7024 | IkReal gconst17=((-1.0)*new_r00*(pow(x437,-0.5))); |
| 7025 | IkReal gconst18=0; |
| 7026 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 7027 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 7028 | { |
| 7029 | { |
| 7030 | IkReal j0eval[2]; |
| 7031 | CheckValue<IkReal> x439 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 7032 | if(!x439.valid){ |
| 7033 | continue; |
| 7034 | } |
| 7035 | IkReal x438=((-1.0)*(x439.value)); |
| 7036 | sj1=1.0; |
| 7037 | cj1=0; |
| 7038 | j1=1.5707963267949; |
| 7039 | sj2=gconst17; |
| 7040 | cj2=gconst18; |
| 7041 | j2=x438; |
| 7042 | new_r11=0; |
| 7043 | new_r10=0; |
| 7044 | new_r22=0; |
| 7045 | new_r02=0; |
| 7046 | IkReal gconst16=x438; |
| 7047 | IkReal x440 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 7048 | if(IKabs(x440)==0){ |
| 7049 | continue; |
| 7050 | } |
| 7051 | IkReal gconst17=((-1.0)*new_r00*(pow(x440,-0.5))); |
| 7052 | IkReal gconst18=0; |
| 7053 | j0eval[0]=new_r01; |
| 7054 | j0eval[1]=new_r00; |
| 7055 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 7056 | { |
| 7057 | { |
| 7058 | IkReal j0eval[1]; |
| 7059 | CheckValue<IkReal> x442 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 7060 | if(!x442.valid){ |
| 7061 | continue; |
| 7062 | } |
| 7063 | IkReal x441=((-1.0)*(x442.value)); |
| 7064 | sj1=1.0; |
| 7065 | cj1=0; |
| 7066 | j1=1.5707963267949; |
| 7067 | sj2=gconst17; |
| 7068 | cj2=gconst18; |
| 7069 | j2=x441; |
| 7070 | new_r11=0; |
| 7071 | new_r10=0; |
| 7072 | new_r22=0; |
| 7073 | new_r02=0; |
| 7074 | IkReal gconst16=x441; |
| 7075 | IkReal x443 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 7076 | if(IKabs(x443)==0){ |
| 7077 | continue; |
| 7078 | } |
| 7079 | IkReal gconst17=((-1.0)*new_r00*(pow(x443,-0.5))); |
| 7080 | IkReal gconst18=0; |
| 7081 | j0eval[0]=new_r00; |
| 7082 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 7083 | { |
| 7084 | continue; // 3 cases reached |
| 7085 | |
| 7086 | } else |
| 7087 | { |
| 7088 | { |
| 7089 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7090 | bool j0valid[1]={false}; |
| 7091 | _nj0 = 1; |
| 7092 | CheckValue<IkReal> x444=IKPowWithIntegerCheck(gconst17,-1); |
| 7093 | if(!x444.valid){ |
| 7094 | continue; |
| 7095 | } |
| 7096 | CheckValue<IkReal> x445=IKPowWithIntegerCheck(new_r00,-1); |
| 7097 | if(!x445.valid){ |
| 7098 | continue; |
| 7099 | } |
| 7100 | if( IKabs((new_r01*(x444.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst17*(x445.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x444.value)))+IKsqr(((-1.0)*gconst17*(x445.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 7101 | continue; |
| 7102 | j0array[0]=IKatan2((new_r01*(x444.value)), ((-1.0)*gconst17*(x445.value))); |
| 7103 | sj0array[0]=IKsin(j0array[0]); |
| 7104 | cj0array[0]=IKcos(j0array[0]); |
| 7105 | if( j0array[0] > IKPI ) |
| 7106 | { |
| 7107 | j0array[0]-=IK2PI; |
| 7108 | } |
| 7109 | else if( j0array[0] < -IKPI ) |
| 7110 | { j0array[0]+=IK2PI; |
| 7111 | } |
| 7112 | j0valid[0] = true; |
| 7113 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7114 | { |
| 7115 | if( !j0valid[ij0] ) |
| 7116 | { |
| 7117 | continue; |
| 7118 | } |
| 7119 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7120 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7121 | { |
| 7122 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7123 | { |
| 7124 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7125 | } |
| 7126 | } |
| 7127 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7128 | { |
| 7129 | IkReal evalcond[8]; |
| 7130 | IkReal x446=IKcos(j0); |
| 7131 | IkReal x447=IKsin(j0); |
| 7132 | IkReal x448=(gconst17*x446); |
| 7133 | IkReal x449=((1.0)*x447); |
| 7134 | evalcond[0]=(new_r00*x447); |
| 7135 | evalcond[1]=(new_r01*x446); |
| 7136 | evalcond[2]=x448; |
| 7137 | evalcond[3]=(gconst17*x447); |
| 7138 | evalcond[4]=(((new_r00*x446))+gconst17); |
| 7139 | evalcond[5]=(x448+new_r00); |
| 7140 | evalcond[6]=((((-1.0)*new_r01*x449))+gconst17); |
| 7141 | evalcond[7]=((((-1.0)*gconst17*x449))+new_r01); |
| 7142 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7143 | { |
| 7144 | continue; |
| 7145 | } |
| 7146 | } |
| 7147 | |
| 7148 | { |
| 7149 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7150 | vinfos[0].jointtype = 1; |
| 7151 | vinfos[0].foffset = j0; |
| 7152 | vinfos[0].indices[0] = _ij0[0]; |
| 7153 | vinfos[0].indices[1] = _ij0[1]; |
| 7154 | vinfos[0].maxsolutions = _nj0; |
| 7155 | vinfos[1].jointtype = 1; |
| 7156 | vinfos[1].foffset = j1; |
| 7157 | vinfos[1].indices[0] = _ij1[0]; |
| 7158 | vinfos[1].indices[1] = _ij1[1]; |
| 7159 | vinfos[1].maxsolutions = _nj1; |
| 7160 | vinfos[2].jointtype = 1; |
| 7161 | vinfos[2].foffset = j2; |
| 7162 | vinfos[2].indices[0] = _ij2[0]; |
| 7163 | vinfos[2].indices[1] = _ij2[1]; |
| 7164 | vinfos[2].maxsolutions = _nj2; |
| 7165 | vinfos[3].jointtype = 1; |
| 7166 | vinfos[3].foffset = j3; |
| 7167 | vinfos[3].indices[0] = _ij3[0]; |
| 7168 | vinfos[3].indices[1] = _ij3[1]; |
| 7169 | vinfos[3].maxsolutions = _nj3; |
| 7170 | vinfos[4].jointtype = 1; |
| 7171 | vinfos[4].foffset = j4; |
| 7172 | vinfos[4].indices[0] = _ij4[0]; |
| 7173 | vinfos[4].indices[1] = _ij4[1]; |
| 7174 | vinfos[4].maxsolutions = _nj4; |
| 7175 | vinfos[5].jointtype = 1; |
| 7176 | vinfos[5].foffset = j5; |
| 7177 | vinfos[5].indices[0] = _ij5[0]; |
| 7178 | vinfos[5].indices[1] = _ij5[1]; |
| 7179 | vinfos[5].maxsolutions = _nj5; |
| 7180 | std::vector<int> vfree(0); |
| 7181 | solutions.AddSolution(vinfos,vfree); |
| 7182 | } |
| 7183 | } |
| 7184 | } |
| 7185 | |
| 7186 | } |
| 7187 | |
| 7188 | } |
| 7189 | |
| 7190 | } else |
| 7191 | { |
| 7192 | { |
| 7193 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7194 | bool j0valid[1]={false}; |
| 7195 | _nj0 = 1; |
| 7196 | CheckValue<IkReal> x450=IKPowWithIntegerCheck(new_r01,-1); |
| 7197 | if(!x450.valid){ |
| 7198 | continue; |
| 7199 | } |
| 7200 | CheckValue<IkReal> x451=IKPowWithIntegerCheck(new_r00,-1); |
| 7201 | if(!x451.valid){ |
| 7202 | continue; |
| 7203 | } |
| 7204 | if( IKabs((gconst17*(x450.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst17*(x451.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst17*(x450.value)))+IKsqr(((-1.0)*gconst17*(x451.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 7205 | continue; |
| 7206 | j0array[0]=IKatan2((gconst17*(x450.value)), ((-1.0)*gconst17*(x451.value))); |
| 7207 | sj0array[0]=IKsin(j0array[0]); |
| 7208 | cj0array[0]=IKcos(j0array[0]); |
| 7209 | if( j0array[0] > IKPI ) |
| 7210 | { |
| 7211 | j0array[0]-=IK2PI; |
| 7212 | } |
| 7213 | else if( j0array[0] < -IKPI ) |
| 7214 | { j0array[0]+=IK2PI; |
| 7215 | } |
| 7216 | j0valid[0] = true; |
| 7217 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7218 | { |
| 7219 | if( !j0valid[ij0] ) |
| 7220 | { |
| 7221 | continue; |
| 7222 | } |
| 7223 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7224 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7225 | { |
| 7226 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7227 | { |
| 7228 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7229 | } |
| 7230 | } |
| 7231 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7232 | { |
| 7233 | IkReal evalcond[8]; |
| 7234 | IkReal x452=IKcos(j0); |
| 7235 | IkReal x453=IKsin(j0); |
| 7236 | IkReal x454=(gconst17*x452); |
| 7237 | IkReal x455=((1.0)*x453); |
| 7238 | evalcond[0]=(new_r00*x453); |
| 7239 | evalcond[1]=(new_r01*x452); |
| 7240 | evalcond[2]=x454; |
| 7241 | evalcond[3]=(gconst17*x453); |
| 7242 | evalcond[4]=(((new_r00*x452))+gconst17); |
| 7243 | evalcond[5]=(x454+new_r00); |
| 7244 | evalcond[6]=((((-1.0)*new_r01*x455))+gconst17); |
| 7245 | evalcond[7]=((((-1.0)*gconst17*x455))+new_r01); |
| 7246 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7247 | { |
| 7248 | continue; |
| 7249 | } |
| 7250 | } |
| 7251 | |
| 7252 | { |
| 7253 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7254 | vinfos[0].jointtype = 1; |
| 7255 | vinfos[0].foffset = j0; |
| 7256 | vinfos[0].indices[0] = _ij0[0]; |
| 7257 | vinfos[0].indices[1] = _ij0[1]; |
| 7258 | vinfos[0].maxsolutions = _nj0; |
| 7259 | vinfos[1].jointtype = 1; |
| 7260 | vinfos[1].foffset = j1; |
| 7261 | vinfos[1].indices[0] = _ij1[0]; |
| 7262 | vinfos[1].indices[1] = _ij1[1]; |
| 7263 | vinfos[1].maxsolutions = _nj1; |
| 7264 | vinfos[2].jointtype = 1; |
| 7265 | vinfos[2].foffset = j2; |
| 7266 | vinfos[2].indices[0] = _ij2[0]; |
| 7267 | vinfos[2].indices[1] = _ij2[1]; |
| 7268 | vinfos[2].maxsolutions = _nj2; |
| 7269 | vinfos[3].jointtype = 1; |
| 7270 | vinfos[3].foffset = j3; |
| 7271 | vinfos[3].indices[0] = _ij3[0]; |
| 7272 | vinfos[3].indices[1] = _ij3[1]; |
| 7273 | vinfos[3].maxsolutions = _nj3; |
| 7274 | vinfos[4].jointtype = 1; |
| 7275 | vinfos[4].foffset = j4; |
| 7276 | vinfos[4].indices[0] = _ij4[0]; |
| 7277 | vinfos[4].indices[1] = _ij4[1]; |
| 7278 | vinfos[4].maxsolutions = _nj4; |
| 7279 | vinfos[5].jointtype = 1; |
| 7280 | vinfos[5].foffset = j5; |
| 7281 | vinfos[5].indices[0] = _ij5[0]; |
| 7282 | vinfos[5].indices[1] = _ij5[1]; |
| 7283 | vinfos[5].maxsolutions = _nj5; |
| 7284 | std::vector<int> vfree(0); |
| 7285 | solutions.AddSolution(vinfos,vfree); |
| 7286 | } |
| 7287 | } |
| 7288 | } |
| 7289 | |
| 7290 | } |
| 7291 | |
| 7292 | } |
| 7293 | |
| 7294 | } else |
| 7295 | { |
| 7296 | { |
| 7297 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7298 | bool j0valid[1]={false}; |
| 7299 | _nj0 = 1; |
| 7300 | CheckValue<IkReal> x456=IKPowWithIntegerCheck(IKsign(gconst17),-1); |
| 7301 | if(!x456.valid){ |
| 7302 | continue; |
| 7303 | } |
| 7304 | CheckValue<IkReal> x457 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 7305 | if(!x457.valid){ |
| 7306 | continue; |
| 7307 | } |
| 7308 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x456.value)))+(x457.value)); |
| 7309 | sj0array[0]=IKsin(j0array[0]); |
| 7310 | cj0array[0]=IKcos(j0array[0]); |
| 7311 | if( j0array[0] > IKPI ) |
| 7312 | { |
| 7313 | j0array[0]-=IK2PI; |
| 7314 | } |
| 7315 | else if( j0array[0] < -IKPI ) |
| 7316 | { j0array[0]+=IK2PI; |
| 7317 | } |
| 7318 | j0valid[0] = true; |
| 7319 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7320 | { |
| 7321 | if( !j0valid[ij0] ) |
| 7322 | { |
| 7323 | continue; |
| 7324 | } |
| 7325 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7326 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7327 | { |
| 7328 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7329 | { |
| 7330 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7331 | } |
| 7332 | } |
| 7333 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7334 | { |
| 7335 | IkReal evalcond[8]; |
| 7336 | IkReal x458=IKcos(j0); |
| 7337 | IkReal x459=IKsin(j0); |
| 7338 | IkReal x460=(gconst17*x458); |
| 7339 | IkReal x461=((1.0)*x459); |
| 7340 | evalcond[0]=(new_r00*x459); |
| 7341 | evalcond[1]=(new_r01*x458); |
| 7342 | evalcond[2]=x460; |
| 7343 | evalcond[3]=(gconst17*x459); |
| 7344 | evalcond[4]=(((new_r00*x458))+gconst17); |
| 7345 | evalcond[5]=(x460+new_r00); |
| 7346 | evalcond[6]=(gconst17+(((-1.0)*new_r01*x461))); |
| 7347 | evalcond[7]=((((-1.0)*gconst17*x461))+new_r01); |
| 7348 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7349 | { |
| 7350 | continue; |
| 7351 | } |
| 7352 | } |
| 7353 | |
| 7354 | { |
| 7355 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7356 | vinfos[0].jointtype = 1; |
| 7357 | vinfos[0].foffset = j0; |
| 7358 | vinfos[0].indices[0] = _ij0[0]; |
| 7359 | vinfos[0].indices[1] = _ij0[1]; |
| 7360 | vinfos[0].maxsolutions = _nj0; |
| 7361 | vinfos[1].jointtype = 1; |
| 7362 | vinfos[1].foffset = j1; |
| 7363 | vinfos[1].indices[0] = _ij1[0]; |
| 7364 | vinfos[1].indices[1] = _ij1[1]; |
| 7365 | vinfos[1].maxsolutions = _nj1; |
| 7366 | vinfos[2].jointtype = 1; |
| 7367 | vinfos[2].foffset = j2; |
| 7368 | vinfos[2].indices[0] = _ij2[0]; |
| 7369 | vinfos[2].indices[1] = _ij2[1]; |
| 7370 | vinfos[2].maxsolutions = _nj2; |
| 7371 | vinfos[3].jointtype = 1; |
| 7372 | vinfos[3].foffset = j3; |
| 7373 | vinfos[3].indices[0] = _ij3[0]; |
| 7374 | vinfos[3].indices[1] = _ij3[1]; |
| 7375 | vinfos[3].maxsolutions = _nj3; |
| 7376 | vinfos[4].jointtype = 1; |
| 7377 | vinfos[4].foffset = j4; |
| 7378 | vinfos[4].indices[0] = _ij4[0]; |
| 7379 | vinfos[4].indices[1] = _ij4[1]; |
| 7380 | vinfos[4].maxsolutions = _nj4; |
| 7381 | vinfos[5].jointtype = 1; |
| 7382 | vinfos[5].foffset = j5; |
| 7383 | vinfos[5].indices[0] = _ij5[0]; |
| 7384 | vinfos[5].indices[1] = _ij5[1]; |
| 7385 | vinfos[5].maxsolutions = _nj5; |
| 7386 | std::vector<int> vfree(0); |
| 7387 | solutions.AddSolution(vinfos,vfree); |
| 7388 | } |
| 7389 | } |
| 7390 | } |
| 7391 | |
| 7392 | } |
| 7393 | |
| 7394 | } |
| 7395 | |
| 7396 | } |
| 7397 | } while(0); |
| 7398 | if( bgotonextstatement ) |
| 7399 | { |
| 7400 | bool bgotonextstatement = true; |
| 7401 | do |
| 7402 | { |
| 7403 | if( 1 ) |
| 7404 | { |
| 7405 | bgotonextstatement=false; |
| 7406 | continue; // branch miss [j0] |
| 7407 | |
| 7408 | } |
| 7409 | } while(0); |
| 7410 | if( bgotonextstatement ) |
| 7411 | { |
| 7412 | } |
| 7413 | } |
| 7414 | } |
| 7415 | } |
| 7416 | } |
| 7417 | } |
| 7418 | } |
| 7419 | |
| 7420 | } else |
| 7421 | { |
| 7422 | { |
| 7423 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7424 | bool j0valid[1]={false}; |
| 7425 | _nj0 = 1; |
| 7426 | IkReal x462=((1.0)*gconst17); |
| 7427 | CheckValue<IkReal> x463=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 7428 | if(!x463.valid){ |
| 7429 | continue; |
| 7430 | } |
| 7431 | CheckValue<IkReal> x464 = IKatan2WithCheck(IkReal(((((-1.0)*new_r11*x462))+((gconst17*new_r00)))),IkReal(((((-1.0)*new_r10*x462))+(((-1.0)*new_r01*x462)))),IKFAST_ATAN2_MAGTHRESH); |
| 7432 | if(!x464.valid){ |
| 7433 | continue; |
| 7434 | } |
| 7435 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x463.value)))+(x464.value)); |
| 7436 | sj0array[0]=IKsin(j0array[0]); |
| 7437 | cj0array[0]=IKcos(j0array[0]); |
| 7438 | if( j0array[0] > IKPI ) |
| 7439 | { |
| 7440 | j0array[0]-=IK2PI; |
| 7441 | } |
| 7442 | else if( j0array[0] < -IKPI ) |
| 7443 | { j0array[0]+=IK2PI; |
| 7444 | } |
| 7445 | j0valid[0] = true; |
| 7446 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7447 | { |
| 7448 | if( !j0valid[ij0] ) |
| 7449 | { |
| 7450 | continue; |
| 7451 | } |
| 7452 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7453 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7454 | { |
| 7455 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7456 | { |
| 7457 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7458 | } |
| 7459 | } |
| 7460 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7461 | { |
| 7462 | IkReal evalcond[8]; |
| 7463 | IkReal x465=IKsin(j0); |
| 7464 | IkReal x466=IKcos(j0); |
| 7465 | IkReal x467=(gconst17*x466); |
| 7466 | IkReal x468=(gconst18*x465); |
| 7467 | IkReal x469=(gconst17*x465); |
| 7468 | IkReal x470=((1.0)*x466); |
| 7469 | IkReal x471=(x468+x467); |
| 7470 | evalcond[0]=(((new_r10*x465))+((new_r00*x466))+gconst17); |
| 7471 | evalcond[1]=(((new_r11*x465))+((new_r01*x466))+gconst18); |
| 7472 | evalcond[2]=(x471+new_r00); |
| 7473 | evalcond[3]=(x471+new_r11); |
| 7474 | evalcond[4]=(((new_r11*x466))+gconst17+(((-1.0)*new_r01*x465))); |
| 7475 | evalcond[5]=(((new_r00*x465))+gconst18+(((-1.0)*new_r10*x470))); |
| 7476 | evalcond[6]=((((-1.0)*x469))+((gconst18*x466))+new_r01); |
| 7477 | evalcond[7]=((((-1.0)*gconst18*x470))+x469+new_r10); |
| 7478 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7479 | { |
| 7480 | continue; |
| 7481 | } |
| 7482 | } |
| 7483 | |
| 7484 | { |
| 7485 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7486 | vinfos[0].jointtype = 1; |
| 7487 | vinfos[0].foffset = j0; |
| 7488 | vinfos[0].indices[0] = _ij0[0]; |
| 7489 | vinfos[0].indices[1] = _ij0[1]; |
| 7490 | vinfos[0].maxsolutions = _nj0; |
| 7491 | vinfos[1].jointtype = 1; |
| 7492 | vinfos[1].foffset = j1; |
| 7493 | vinfos[1].indices[0] = _ij1[0]; |
| 7494 | vinfos[1].indices[1] = _ij1[1]; |
| 7495 | vinfos[1].maxsolutions = _nj1; |
| 7496 | vinfos[2].jointtype = 1; |
| 7497 | vinfos[2].foffset = j2; |
| 7498 | vinfos[2].indices[0] = _ij2[0]; |
| 7499 | vinfos[2].indices[1] = _ij2[1]; |
| 7500 | vinfos[2].maxsolutions = _nj2; |
| 7501 | vinfos[3].jointtype = 1; |
| 7502 | vinfos[3].foffset = j3; |
| 7503 | vinfos[3].indices[0] = _ij3[0]; |
| 7504 | vinfos[3].indices[1] = _ij3[1]; |
| 7505 | vinfos[3].maxsolutions = _nj3; |
| 7506 | vinfos[4].jointtype = 1; |
| 7507 | vinfos[4].foffset = j4; |
| 7508 | vinfos[4].indices[0] = _ij4[0]; |
| 7509 | vinfos[4].indices[1] = _ij4[1]; |
| 7510 | vinfos[4].maxsolutions = _nj4; |
| 7511 | vinfos[5].jointtype = 1; |
| 7512 | vinfos[5].foffset = j5; |
| 7513 | vinfos[5].indices[0] = _ij5[0]; |
| 7514 | vinfos[5].indices[1] = _ij5[1]; |
| 7515 | vinfos[5].maxsolutions = _nj5; |
| 7516 | std::vector<int> vfree(0); |
| 7517 | solutions.AddSolution(vinfos,vfree); |
| 7518 | } |
| 7519 | } |
| 7520 | } |
| 7521 | |
| 7522 | } |
| 7523 | |
| 7524 | } |
| 7525 | |
| 7526 | } else |
| 7527 | { |
| 7528 | { |
| 7529 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7530 | bool j0valid[1]={false}; |
| 7531 | _nj0 = 1; |
| 7532 | IkReal x472=((1.0)*gconst18); |
| 7533 | CheckValue<IkReal> x473 = IKatan2WithCheck(IkReal(((((-1.0)*gconst17*x472))+((new_r00*new_r01)))),IkReal(((gconst18*gconst18)+(((-1.0)*new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 7534 | if(!x473.valid){ |
| 7535 | continue; |
| 7536 | } |
| 7537 | CheckValue<IkReal> x474=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r01*x472))+((gconst17*new_r11)))),-1); |
| 7538 | if(!x474.valid){ |
| 7539 | continue; |
| 7540 | } |
| 7541 | j0array[0]=((-1.5707963267949)+(x473.value)+(((1.5707963267949)*(x474.value)))); |
| 7542 | sj0array[0]=IKsin(j0array[0]); |
| 7543 | cj0array[0]=IKcos(j0array[0]); |
| 7544 | if( j0array[0] > IKPI ) |
| 7545 | { |
| 7546 | j0array[0]-=IK2PI; |
| 7547 | } |
| 7548 | else if( j0array[0] < -IKPI ) |
| 7549 | { j0array[0]+=IK2PI; |
| 7550 | } |
| 7551 | j0valid[0] = true; |
| 7552 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7553 | { |
| 7554 | if( !j0valid[ij0] ) |
| 7555 | { |
| 7556 | continue; |
| 7557 | } |
| 7558 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7559 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7560 | { |
| 7561 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7562 | { |
| 7563 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7564 | } |
| 7565 | } |
| 7566 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7567 | { |
| 7568 | IkReal evalcond[8]; |
| 7569 | IkReal x475=IKsin(j0); |
| 7570 | IkReal x476=IKcos(j0); |
| 7571 | IkReal x477=(gconst17*x476); |
| 7572 | IkReal x478=(gconst18*x475); |
| 7573 | IkReal x479=(gconst17*x475); |
| 7574 | IkReal x480=((1.0)*x476); |
| 7575 | IkReal x481=(x477+x478); |
| 7576 | evalcond[0]=(((new_r10*x475))+gconst17+((new_r00*x476))); |
| 7577 | evalcond[1]=(((new_r01*x476))+gconst18+((new_r11*x475))); |
| 7578 | evalcond[2]=(x481+new_r00); |
| 7579 | evalcond[3]=(x481+new_r11); |
| 7580 | evalcond[4]=(gconst17+((new_r11*x476))+(((-1.0)*new_r01*x475))); |
| 7581 | evalcond[5]=((((-1.0)*new_r10*x480))+gconst18+((new_r00*x475))); |
| 7582 | evalcond[6]=((((-1.0)*x479))+((gconst18*x476))+new_r01); |
| 7583 | evalcond[7]=(x479+(((-1.0)*gconst18*x480))+new_r10); |
| 7584 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7585 | { |
| 7586 | continue; |
| 7587 | } |
| 7588 | } |
| 7589 | |
| 7590 | { |
| 7591 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7592 | vinfos[0].jointtype = 1; |
| 7593 | vinfos[0].foffset = j0; |
| 7594 | vinfos[0].indices[0] = _ij0[0]; |
| 7595 | vinfos[0].indices[1] = _ij0[1]; |
| 7596 | vinfos[0].maxsolutions = _nj0; |
| 7597 | vinfos[1].jointtype = 1; |
| 7598 | vinfos[1].foffset = j1; |
| 7599 | vinfos[1].indices[0] = _ij1[0]; |
| 7600 | vinfos[1].indices[1] = _ij1[1]; |
| 7601 | vinfos[1].maxsolutions = _nj1; |
| 7602 | vinfos[2].jointtype = 1; |
| 7603 | vinfos[2].foffset = j2; |
| 7604 | vinfos[2].indices[0] = _ij2[0]; |
| 7605 | vinfos[2].indices[1] = _ij2[1]; |
| 7606 | vinfos[2].maxsolutions = _nj2; |
| 7607 | vinfos[3].jointtype = 1; |
| 7608 | vinfos[3].foffset = j3; |
| 7609 | vinfos[3].indices[0] = _ij3[0]; |
| 7610 | vinfos[3].indices[1] = _ij3[1]; |
| 7611 | vinfos[3].maxsolutions = _nj3; |
| 7612 | vinfos[4].jointtype = 1; |
| 7613 | vinfos[4].foffset = j4; |
| 7614 | vinfos[4].indices[0] = _ij4[0]; |
| 7615 | vinfos[4].indices[1] = _ij4[1]; |
| 7616 | vinfos[4].maxsolutions = _nj4; |
| 7617 | vinfos[5].jointtype = 1; |
| 7618 | vinfos[5].foffset = j5; |
| 7619 | vinfos[5].indices[0] = _ij5[0]; |
| 7620 | vinfos[5].indices[1] = _ij5[1]; |
| 7621 | vinfos[5].maxsolutions = _nj5; |
| 7622 | std::vector<int> vfree(0); |
| 7623 | solutions.AddSolution(vinfos,vfree); |
| 7624 | } |
| 7625 | } |
| 7626 | } |
| 7627 | |
| 7628 | } |
| 7629 | |
| 7630 | } |
| 7631 | |
| 7632 | } else |
| 7633 | { |
| 7634 | { |
| 7635 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 7636 | bool j0valid[1]={false}; |
| 7637 | _nj0 = 1; |
| 7638 | CheckValue<IkReal> x482=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| 7639 | if(!x482.valid){ |
| 7640 | continue; |
| 7641 | } |
| 7642 | CheckValue<IkReal> x483 = IKatan2WithCheck(IkReal(((((-1.0)*gconst18*new_r00))+((gconst17*new_r01)))),IkReal((((gconst18*new_r10))+(((-1.0)*gconst17*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 7643 | if(!x483.valid){ |
| 7644 | continue; |
| 7645 | } |
| 7646 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x482.value)))+(x483.value)); |
| 7647 | sj0array[0]=IKsin(j0array[0]); |
| 7648 | cj0array[0]=IKcos(j0array[0]); |
| 7649 | if( j0array[0] > IKPI ) |
| 7650 | { |
| 7651 | j0array[0]-=IK2PI; |
| 7652 | } |
| 7653 | else if( j0array[0] < -IKPI ) |
| 7654 | { j0array[0]+=IK2PI; |
| 7655 | } |
| 7656 | j0valid[0] = true; |
| 7657 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 7658 | { |
| 7659 | if( !j0valid[ij0] ) |
| 7660 | { |
| 7661 | continue; |
| 7662 | } |
| 7663 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7664 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 7665 | { |
| 7666 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7667 | { |
| 7668 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7669 | } |
| 7670 | } |
| 7671 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7672 | { |
| 7673 | IkReal evalcond[8]; |
| 7674 | IkReal x484=IKsin(j0); |
| 7675 | IkReal x485=IKcos(j0); |
| 7676 | IkReal x486=(gconst17*x485); |
| 7677 | IkReal x487=(gconst18*x484); |
| 7678 | IkReal x488=(gconst17*x484); |
| 7679 | IkReal x489=((1.0)*x485); |
| 7680 | IkReal x490=(x487+x486); |
| 7681 | evalcond[0]=(gconst17+((new_r10*x484))+((new_r00*x485))); |
| 7682 | evalcond[1]=(((new_r11*x484))+gconst18+((new_r01*x485))); |
| 7683 | evalcond[2]=(x490+new_r00); |
| 7684 | evalcond[3]=(x490+new_r11); |
| 7685 | evalcond[4]=((((-1.0)*new_r01*x484))+((new_r11*x485))+gconst17); |
| 7686 | evalcond[5]=((((-1.0)*new_r10*x489))+gconst18+((new_r00*x484))); |
| 7687 | evalcond[6]=((((-1.0)*x488))+new_r01+((gconst18*x485))); |
| 7688 | evalcond[7]=(x488+(((-1.0)*gconst18*x489))+new_r10); |
| 7689 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 7690 | { |
| 7691 | continue; |
| 7692 | } |
| 7693 | } |
| 7694 | |
| 7695 | { |
| 7696 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7697 | vinfos[0].jointtype = 1; |
| 7698 | vinfos[0].foffset = j0; |
| 7699 | vinfos[0].indices[0] = _ij0[0]; |
| 7700 | vinfos[0].indices[1] = _ij0[1]; |
| 7701 | vinfos[0].maxsolutions = _nj0; |
| 7702 | vinfos[1].jointtype = 1; |
| 7703 | vinfos[1].foffset = j1; |
| 7704 | vinfos[1].indices[0] = _ij1[0]; |
| 7705 | vinfos[1].indices[1] = _ij1[1]; |
| 7706 | vinfos[1].maxsolutions = _nj1; |
| 7707 | vinfos[2].jointtype = 1; |
| 7708 | vinfos[2].foffset = j2; |
| 7709 | vinfos[2].indices[0] = _ij2[0]; |
| 7710 | vinfos[2].indices[1] = _ij2[1]; |
| 7711 | vinfos[2].maxsolutions = _nj2; |
| 7712 | vinfos[3].jointtype = 1; |
| 7713 | vinfos[3].foffset = j3; |
| 7714 | vinfos[3].indices[0] = _ij3[0]; |
| 7715 | vinfos[3].indices[1] = _ij3[1]; |
| 7716 | vinfos[3].maxsolutions = _nj3; |
| 7717 | vinfos[4].jointtype = 1; |
| 7718 | vinfos[4].foffset = j4; |
| 7719 | vinfos[4].indices[0] = _ij4[0]; |
| 7720 | vinfos[4].indices[1] = _ij4[1]; |
| 7721 | vinfos[4].maxsolutions = _nj4; |
| 7722 | vinfos[5].jointtype = 1; |
| 7723 | vinfos[5].foffset = j5; |
| 7724 | vinfos[5].indices[0] = _ij5[0]; |
| 7725 | vinfos[5].indices[1] = _ij5[1]; |
| 7726 | vinfos[5].maxsolutions = _nj5; |
| 7727 | std::vector<int> vfree(0); |
| 7728 | solutions.AddSolution(vinfos,vfree); |
| 7729 | } |
| 7730 | } |
| 7731 | } |
| 7732 | |
| 7733 | } |
| 7734 | |
| 7735 | } |
| 7736 | |
| 7737 | } |
| 7738 | } while(0); |
| 7739 | if( bgotonextstatement ) |
| 7740 | { |
| 7741 | bool bgotonextstatement = true; |
| 7742 | do |
| 7743 | { |
| 7744 | IkReal x493 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| 7745 | if(IKabs(x493)==0){ |
| 7746 | continue; |
| 7747 | } |
| 7748 | IkReal x491=pow(x493,-0.5); |
| 7749 | IkReal x492=((1.0)*x491); |
| 7750 | CheckValue<IkReal> x494 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7751 | if(!x494.valid){ |
| 7752 | continue; |
| 7753 | } |
| 7754 | IkReal gconst19=((3.14159265358979)+(((-1.0)*(x494.value)))); |
| 7755 | IkReal gconst20=(new_r00*x492); |
| 7756 | IkReal gconst21=(new_r10*x492); |
| 7757 | CheckValue<IkReal> x495 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7758 | if(!x495.valid){ |
| 7759 | continue; |
| 7760 | } |
| 7761 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x495.value)+j2)))), 6.28318530717959))); |
| 7762 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 7763 | { |
| 7764 | bgotonextstatement=false; |
| 7765 | { |
| 7766 | IkReal j0eval[3]; |
| 7767 | CheckValue<IkReal> x499 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7768 | if(!x499.valid){ |
| 7769 | continue; |
| 7770 | } |
| 7771 | IkReal x496=((1.0)*(x499.value)); |
| 7772 | IkReal x497=x491; |
| 7773 | IkReal x498=((1.0)*x497); |
| 7774 | sj1=1.0; |
| 7775 | cj1=0; |
| 7776 | j1=1.5707963267949; |
| 7777 | sj2=gconst20; |
| 7778 | cj2=gconst21; |
| 7779 | j2=((3.14159265)+(((-1.0)*x496))); |
| 7780 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x496))); |
| 7781 | IkReal gconst20=(new_r00*x498); |
| 7782 | IkReal gconst21=(new_r10*x498); |
| 7783 | IkReal x500=new_r10*new_r10; |
| 7784 | IkReal x501=((1.0)*new_r10); |
| 7785 | IkReal x502=(new_r00*new_r11); |
| 7786 | IkReal x503=((((-1.0)*new_r01*x501))+x502); |
| 7787 | IkReal x504=x491; |
| 7788 | IkReal x505=(new_r00*x504); |
| 7789 | j0eval[0]=x503; |
| 7790 | j0eval[1]=IKsign(x503); |
| 7791 | j0eval[2]=((IKabs((((x500*x504))+(((-1.0)*x502*x504)))))+(IKabs(((((-1.0)*x501*x505))+((new_r01*x505)))))); |
| 7792 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 7793 | { |
| 7794 | { |
| 7795 | IkReal j0eval[1]; |
| 7796 | CheckValue<IkReal> x509 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7797 | if(!x509.valid){ |
| 7798 | continue; |
| 7799 | } |
| 7800 | IkReal x506=((1.0)*(x509.value)); |
| 7801 | IkReal x507=x491; |
| 7802 | IkReal x508=((1.0)*x507); |
| 7803 | sj1=1.0; |
| 7804 | cj1=0; |
| 7805 | j1=1.5707963267949; |
| 7806 | sj2=gconst20; |
| 7807 | cj2=gconst21; |
| 7808 | j2=((3.14159265)+(((-1.0)*x506))); |
| 7809 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x506))); |
| 7810 | IkReal gconst20=(new_r00*x508); |
| 7811 | IkReal gconst21=(new_r10*x508); |
| 7812 | IkReal x510=new_r10*new_r10; |
| 7813 | IkReal x511=new_r00*new_r00*new_r00; |
| 7814 | CheckValue<IkReal> x515=IKPowWithIntegerCheck((x510+(new_r00*new_r00)),-1); |
| 7815 | if(!x515.valid){ |
| 7816 | continue; |
| 7817 | } |
| 7818 | IkReal x512=x515.value; |
| 7819 | IkReal x513=((1.0)*x512); |
| 7820 | IkReal x514=(x510*x512); |
| 7821 | j0eval[0]=((IKabs(((((-1.0)*new_r00*new_r11*x510*x513))+x514+(((-1.0)*new_r11*x511*x513)))))+(IKabs((((new_r00*new_r01*x514))+(((-1.0)*new_r00*new_r10*x513))+((new_r01*x511*x512)))))); |
| 7822 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 7823 | { |
| 7824 | { |
| 7825 | IkReal j0eval[3]; |
| 7826 | CheckValue<IkReal> x519 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7827 | if(!x519.valid){ |
| 7828 | continue; |
| 7829 | } |
| 7830 | IkReal x516=((1.0)*(x519.value)); |
| 7831 | IkReal x517=x491; |
| 7832 | IkReal x518=((1.0)*x517); |
| 7833 | sj1=1.0; |
| 7834 | cj1=0; |
| 7835 | j1=1.5707963267949; |
| 7836 | sj2=gconst20; |
| 7837 | cj2=gconst21; |
| 7838 | j2=((3.14159265)+(((-1.0)*x516))); |
| 7839 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x516))); |
| 7840 | IkReal gconst20=(new_r00*x518); |
| 7841 | IkReal gconst21=(new_r10*x518); |
| 7842 | IkReal x520=new_r00*new_r00; |
| 7843 | IkReal x521=(new_r00*new_r01); |
| 7844 | IkReal x522=(((new_r10*new_r11))+x521); |
| 7845 | IkReal x523=x491; |
| 7846 | IkReal x524=((1.0)*x523); |
| 7847 | j0eval[0]=x522; |
| 7848 | j0eval[1]=((IKabs(((((-1.0)*new_r00*new_r11*x524))+((x520*x523)))))+(IKabs(((((-1.0)*x521*x524))+(((-1.0)*new_r00*new_r10*x524)))))); |
| 7849 | j0eval[2]=IKsign(x522); |
| 7850 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 7851 | { |
| 7852 | { |
| 7853 | IkReal evalcond[3]; |
| 7854 | bool bgotonextstatement = true; |
| 7855 | do |
| 7856 | { |
| 7857 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| 7858 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 7859 | { |
| 7860 | bgotonextstatement=false; |
| 7861 | { |
| 7862 | IkReal j0eval[1]; |
| 7863 | CheckValue<IkReal> x526 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 7864 | if(!x526.valid){ |
| 7865 | continue; |
| 7866 | } |
| 7867 | IkReal x525=((1.0)*(x526.value)); |
| 7868 | sj1=1.0; |
| 7869 | cj1=0; |
| 7870 | j1=1.5707963267949; |
| 7871 | sj2=gconst20; |
| 7872 | cj2=gconst21; |
| 7873 | j2=((3.14159265)+(((-1.0)*x525))); |
| 7874 | new_r11=0; |
| 7875 | new_r00=0; |
| 7876 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x525))); |
| 7877 | IkReal gconst20=0; |
| 7878 | IkReal x527 = new_r10*new_r10; |
| 7879 | if(IKabs(x527)==0){ |
| 7880 | continue; |
| 7881 | } |
| 7882 | IkReal gconst21=((1.0)*new_r10*(pow(x527,-0.5))); |
| 7883 | j0eval[0]=new_r10; |
| 7884 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 7885 | { |
| 7886 | { |
| 7887 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 7888 | bool j0valid[2]={false}; |
| 7889 | _nj0 = 2; |
| 7890 | CheckValue<IkReal> x528=IKPowWithIntegerCheck(gconst21,-1); |
| 7891 | if(!x528.valid){ |
| 7892 | continue; |
| 7893 | } |
| 7894 | cj0array[0]=(new_r10*(x528.value)); |
| 7895 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 7896 | { |
| 7897 | j0valid[0] = j0valid[1] = true; |
| 7898 | j0array[0] = IKacos(cj0array[0]); |
| 7899 | sj0array[0] = IKsin(j0array[0]); |
| 7900 | cj0array[1] = cj0array[0]; |
| 7901 | j0array[1] = -j0array[0]; |
| 7902 | sj0array[1] = -sj0array[0]; |
| 7903 | } |
| 7904 | else if( isnan(cj0array[0]) ) |
| 7905 | { |
| 7906 | // probably any value will work |
| 7907 | j0valid[0] = true; |
| 7908 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 7909 | } |
| 7910 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 7911 | { |
| 7912 | if( !j0valid[ij0] ) |
| 7913 | { |
| 7914 | continue; |
| 7915 | } |
| 7916 | _ij0[0] = ij0; _ij0[1] = -1; |
| 7917 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 7918 | { |
| 7919 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 7920 | { |
| 7921 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 7922 | } |
| 7923 | } |
| 7924 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 7925 | { |
| 7926 | IkReal evalcond[6]; |
| 7927 | IkReal x529=IKsin(j0); |
| 7928 | IkReal x530=IKcos(j0); |
| 7929 | evalcond[0]=(new_r10*x529); |
| 7930 | evalcond[1]=(gconst21*x529); |
| 7931 | evalcond[2]=((-1.0)*new_r01*x529); |
| 7932 | evalcond[3]=(((new_r01*x530))+gconst21); |
| 7933 | evalcond[4]=(new_r01+((gconst21*x530))); |
| 7934 | evalcond[5]=(gconst21+(((-1.0)*new_r10*x530))); |
| 7935 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 7936 | { |
| 7937 | continue; |
| 7938 | } |
| 7939 | } |
| 7940 | |
| 7941 | { |
| 7942 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 7943 | vinfos[0].jointtype = 1; |
| 7944 | vinfos[0].foffset = j0; |
| 7945 | vinfos[0].indices[0] = _ij0[0]; |
| 7946 | vinfos[0].indices[1] = _ij0[1]; |
| 7947 | vinfos[0].maxsolutions = _nj0; |
| 7948 | vinfos[1].jointtype = 1; |
| 7949 | vinfos[1].foffset = j1; |
| 7950 | vinfos[1].indices[0] = _ij1[0]; |
| 7951 | vinfos[1].indices[1] = _ij1[1]; |
| 7952 | vinfos[1].maxsolutions = _nj1; |
| 7953 | vinfos[2].jointtype = 1; |
| 7954 | vinfos[2].foffset = j2; |
| 7955 | vinfos[2].indices[0] = _ij2[0]; |
| 7956 | vinfos[2].indices[1] = _ij2[1]; |
| 7957 | vinfos[2].maxsolutions = _nj2; |
| 7958 | vinfos[3].jointtype = 1; |
| 7959 | vinfos[3].foffset = j3; |
| 7960 | vinfos[3].indices[0] = _ij3[0]; |
| 7961 | vinfos[3].indices[1] = _ij3[1]; |
| 7962 | vinfos[3].maxsolutions = _nj3; |
| 7963 | vinfos[4].jointtype = 1; |
| 7964 | vinfos[4].foffset = j4; |
| 7965 | vinfos[4].indices[0] = _ij4[0]; |
| 7966 | vinfos[4].indices[1] = _ij4[1]; |
| 7967 | vinfos[4].maxsolutions = _nj4; |
| 7968 | vinfos[5].jointtype = 1; |
| 7969 | vinfos[5].foffset = j5; |
| 7970 | vinfos[5].indices[0] = _ij5[0]; |
| 7971 | vinfos[5].indices[1] = _ij5[1]; |
| 7972 | vinfos[5].maxsolutions = _nj5; |
| 7973 | std::vector<int> vfree(0); |
| 7974 | solutions.AddSolution(vinfos,vfree); |
| 7975 | } |
| 7976 | } |
| 7977 | } |
| 7978 | |
| 7979 | } else |
| 7980 | { |
| 7981 | { |
| 7982 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 7983 | bool j0valid[2]={false}; |
| 7984 | _nj0 = 2; |
| 7985 | CheckValue<IkReal> x531=IKPowWithIntegerCheck(new_r10,-1); |
| 7986 | if(!x531.valid){ |
| 7987 | continue; |
| 7988 | } |
| 7989 | cj0array[0]=(gconst21*(x531.value)); |
| 7990 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 7991 | { |
| 7992 | j0valid[0] = j0valid[1] = true; |
| 7993 | j0array[0] = IKacos(cj0array[0]); |
| 7994 | sj0array[0] = IKsin(j0array[0]); |
| 7995 | cj0array[1] = cj0array[0]; |
| 7996 | j0array[1] = -j0array[0]; |
| 7997 | sj0array[1] = -sj0array[0]; |
| 7998 | } |
| 7999 | else if( isnan(cj0array[0]) ) |
| 8000 | { |
| 8001 | // probably any value will work |
| 8002 | j0valid[0] = true; |
| 8003 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 8004 | } |
| 8005 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 8006 | { |
| 8007 | if( !j0valid[ij0] ) |
| 8008 | { |
| 8009 | continue; |
| 8010 | } |
| 8011 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8012 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 8013 | { |
| 8014 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8015 | { |
| 8016 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8017 | } |
| 8018 | } |
| 8019 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8020 | { |
| 8021 | IkReal evalcond[6]; |
| 8022 | IkReal x532=IKsin(j0); |
| 8023 | IkReal x533=IKcos(j0); |
| 8024 | IkReal x534=(gconst21*x533); |
| 8025 | evalcond[0]=(new_r10*x532); |
| 8026 | evalcond[1]=(gconst21*x532); |
| 8027 | evalcond[2]=((-1.0)*new_r01*x532); |
| 8028 | evalcond[3]=(((new_r01*x533))+gconst21); |
| 8029 | evalcond[4]=(x534+new_r01); |
| 8030 | evalcond[5]=((((-1.0)*x534))+new_r10); |
| 8031 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8032 | { |
| 8033 | continue; |
| 8034 | } |
| 8035 | } |
| 8036 | |
| 8037 | { |
| 8038 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8039 | vinfos[0].jointtype = 1; |
| 8040 | vinfos[0].foffset = j0; |
| 8041 | vinfos[0].indices[0] = _ij0[0]; |
| 8042 | vinfos[0].indices[1] = _ij0[1]; |
| 8043 | vinfos[0].maxsolutions = _nj0; |
| 8044 | vinfos[1].jointtype = 1; |
| 8045 | vinfos[1].foffset = j1; |
| 8046 | vinfos[1].indices[0] = _ij1[0]; |
| 8047 | vinfos[1].indices[1] = _ij1[1]; |
| 8048 | vinfos[1].maxsolutions = _nj1; |
| 8049 | vinfos[2].jointtype = 1; |
| 8050 | vinfos[2].foffset = j2; |
| 8051 | vinfos[2].indices[0] = _ij2[0]; |
| 8052 | vinfos[2].indices[1] = _ij2[1]; |
| 8053 | vinfos[2].maxsolutions = _nj2; |
| 8054 | vinfos[3].jointtype = 1; |
| 8055 | vinfos[3].foffset = j3; |
| 8056 | vinfos[3].indices[0] = _ij3[0]; |
| 8057 | vinfos[3].indices[1] = _ij3[1]; |
| 8058 | vinfos[3].maxsolutions = _nj3; |
| 8059 | vinfos[4].jointtype = 1; |
| 8060 | vinfos[4].foffset = j4; |
| 8061 | vinfos[4].indices[0] = _ij4[0]; |
| 8062 | vinfos[4].indices[1] = _ij4[1]; |
| 8063 | vinfos[4].maxsolutions = _nj4; |
| 8064 | vinfos[5].jointtype = 1; |
| 8065 | vinfos[5].foffset = j5; |
| 8066 | vinfos[5].indices[0] = _ij5[0]; |
| 8067 | vinfos[5].indices[1] = _ij5[1]; |
| 8068 | vinfos[5].maxsolutions = _nj5; |
| 8069 | std::vector<int> vfree(0); |
| 8070 | solutions.AddSolution(vinfos,vfree); |
| 8071 | } |
| 8072 | } |
| 8073 | } |
| 8074 | |
| 8075 | } |
| 8076 | |
| 8077 | } |
| 8078 | |
| 8079 | } |
| 8080 | } while(0); |
| 8081 | if( bgotonextstatement ) |
| 8082 | { |
| 8083 | bool bgotonextstatement = true; |
| 8084 | do |
| 8085 | { |
| 8086 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 8087 | evalcond[1]=gconst20; |
| 8088 | evalcond[2]=gconst21; |
| 8089 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| 8090 | { |
| 8091 | bgotonextstatement=false; |
| 8092 | { |
| 8093 | IkReal j0eval[3]; |
| 8094 | CheckValue<IkReal> x536 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8095 | if(!x536.valid){ |
| 8096 | continue; |
| 8097 | } |
| 8098 | IkReal x535=((1.0)*(x536.value)); |
| 8099 | sj1=1.0; |
| 8100 | cj1=0; |
| 8101 | j1=1.5707963267949; |
| 8102 | sj2=gconst20; |
| 8103 | cj2=gconst21; |
| 8104 | j2=((3.14159265)+(((-1.0)*x535))); |
| 8105 | new_r11=0; |
| 8106 | new_r01=0; |
| 8107 | new_r22=0; |
| 8108 | new_r20=0; |
| 8109 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x535))); |
| 8110 | IkReal gconst20=((1.0)*new_r00); |
| 8111 | IkReal gconst21=((1.0)*new_r10); |
| 8112 | j0eval[0]=-1.0; |
| 8113 | j0eval[1]=-1.0; |
| 8114 | j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| 8115 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 8116 | { |
| 8117 | { |
| 8118 | IkReal j0eval[4]; |
| 8119 | CheckValue<IkReal> x538 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8120 | if(!x538.valid){ |
| 8121 | continue; |
| 8122 | } |
| 8123 | IkReal x537=((1.0)*(x538.value)); |
| 8124 | sj1=1.0; |
| 8125 | cj1=0; |
| 8126 | j1=1.5707963267949; |
| 8127 | sj2=gconst20; |
| 8128 | cj2=gconst21; |
| 8129 | j2=((3.14159265)+(((-1.0)*x537))); |
| 8130 | new_r11=0; |
| 8131 | new_r01=0; |
| 8132 | new_r22=0; |
| 8133 | new_r20=0; |
| 8134 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x537))); |
| 8135 | IkReal gconst20=((1.0)*new_r00); |
| 8136 | IkReal gconst21=((1.0)*new_r10); |
| 8137 | j0eval[0]=-1.0; |
| 8138 | j0eval[1]=-1.0; |
| 8139 | j0eval[2]=new_r10; |
| 8140 | j0eval[3]=1.0; |
| 8141 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| 8142 | { |
| 8143 | { |
| 8144 | IkReal j0eval[3]; |
| 8145 | CheckValue<IkReal> x540 = IKatan2WithCheck(IkReal(new_r00),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8146 | if(!x540.valid){ |
| 8147 | continue; |
| 8148 | } |
| 8149 | IkReal x539=((1.0)*(x540.value)); |
| 8150 | sj1=1.0; |
| 8151 | cj1=0; |
| 8152 | j1=1.5707963267949; |
| 8153 | sj2=gconst20; |
| 8154 | cj2=gconst21; |
| 8155 | j2=((3.14159265)+(((-1.0)*x539))); |
| 8156 | new_r11=0; |
| 8157 | new_r01=0; |
| 8158 | new_r22=0; |
| 8159 | new_r20=0; |
| 8160 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x539))); |
| 8161 | IkReal gconst20=((1.0)*new_r00); |
| 8162 | IkReal gconst21=((1.0)*new_r10); |
| 8163 | j0eval[0]=-1.0; |
| 8164 | j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| 8165 | j0eval[2]=-1.0; |
| 8166 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 8167 | { |
| 8168 | continue; // 3 cases reached |
| 8169 | |
| 8170 | } else |
| 8171 | { |
| 8172 | { |
| 8173 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 8174 | bool j0valid[1]={false}; |
| 8175 | _nj0 = 1; |
| 8176 | CheckValue<IkReal> x541 = IKatan2WithCheck(IkReal((gconst21*new_r00)),IkReal((gconst20*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 8177 | if(!x541.valid){ |
| 8178 | continue; |
| 8179 | } |
| 8180 | CheckValue<IkReal> x542=IKPowWithIntegerCheck(IKsign(((((-1.0)*(gconst20*gconst20)))+(((-1.0)*(gconst21*gconst21))))),-1); |
| 8181 | if(!x542.valid){ |
| 8182 | continue; |
| 8183 | } |
| 8184 | j0array[0]=((-1.5707963267949)+(x541.value)+(((1.5707963267949)*(x542.value)))); |
| 8185 | sj0array[0]=IKsin(j0array[0]); |
| 8186 | cj0array[0]=IKcos(j0array[0]); |
| 8187 | if( j0array[0] > IKPI ) |
| 8188 | { |
| 8189 | j0array[0]-=IK2PI; |
| 8190 | } |
| 8191 | else if( j0array[0] < -IKPI ) |
| 8192 | { j0array[0]+=IK2PI; |
| 8193 | } |
| 8194 | j0valid[0] = true; |
| 8195 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 8196 | { |
| 8197 | if( !j0valid[ij0] ) |
| 8198 | { |
| 8199 | continue; |
| 8200 | } |
| 8201 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8202 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 8203 | { |
| 8204 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8205 | { |
| 8206 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8207 | } |
| 8208 | } |
| 8209 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8210 | { |
| 8211 | IkReal evalcond[6]; |
| 8212 | IkReal x543=IKcos(j0); |
| 8213 | IkReal x544=IKsin(j0); |
| 8214 | IkReal x545=(gconst21*x544); |
| 8215 | IkReal x546=(gconst20*x543); |
| 8216 | IkReal x547=((1.0)*x543); |
| 8217 | IkReal x548=(gconst20*x544); |
| 8218 | IkReal x549=(x545+x546); |
| 8219 | evalcond[0]=x549; |
| 8220 | evalcond[1]=(((new_r00*x543))+((new_r10*x544))+gconst20); |
| 8221 | evalcond[2]=(x549+new_r00); |
| 8222 | evalcond[3]=((((-1.0)*x548))+((gconst21*x543))); |
| 8223 | evalcond[4]=(((new_r00*x544))+gconst21+(((-1.0)*new_r10*x547))); |
| 8224 | evalcond[5]=(x548+new_r10+(((-1.0)*gconst21*x547))); |
| 8225 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8226 | { |
| 8227 | continue; |
| 8228 | } |
| 8229 | } |
| 8230 | |
| 8231 | { |
| 8232 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8233 | vinfos[0].jointtype = 1; |
| 8234 | vinfos[0].foffset = j0; |
| 8235 | vinfos[0].indices[0] = _ij0[0]; |
| 8236 | vinfos[0].indices[1] = _ij0[1]; |
| 8237 | vinfos[0].maxsolutions = _nj0; |
| 8238 | vinfos[1].jointtype = 1; |
| 8239 | vinfos[1].foffset = j1; |
| 8240 | vinfos[1].indices[0] = _ij1[0]; |
| 8241 | vinfos[1].indices[1] = _ij1[1]; |
| 8242 | vinfos[1].maxsolutions = _nj1; |
| 8243 | vinfos[2].jointtype = 1; |
| 8244 | vinfos[2].foffset = j2; |
| 8245 | vinfos[2].indices[0] = _ij2[0]; |
| 8246 | vinfos[2].indices[1] = _ij2[1]; |
| 8247 | vinfos[2].maxsolutions = _nj2; |
| 8248 | vinfos[3].jointtype = 1; |
| 8249 | vinfos[3].foffset = j3; |
| 8250 | vinfos[3].indices[0] = _ij3[0]; |
| 8251 | vinfos[3].indices[1] = _ij3[1]; |
| 8252 | vinfos[3].maxsolutions = _nj3; |
| 8253 | vinfos[4].jointtype = 1; |
| 8254 | vinfos[4].foffset = j4; |
| 8255 | vinfos[4].indices[0] = _ij4[0]; |
| 8256 | vinfos[4].indices[1] = _ij4[1]; |
| 8257 | vinfos[4].maxsolutions = _nj4; |
| 8258 | vinfos[5].jointtype = 1; |
| 8259 | vinfos[5].foffset = j5; |
| 8260 | vinfos[5].indices[0] = _ij5[0]; |
| 8261 | vinfos[5].indices[1] = _ij5[1]; |
| 8262 | vinfos[5].maxsolutions = _nj5; |
| 8263 | std::vector<int> vfree(0); |
| 8264 | solutions.AddSolution(vinfos,vfree); |
| 8265 | } |
| 8266 | } |
| 8267 | } |
| 8268 | |
| 8269 | } |
| 8270 | |
| 8271 | } |
| 8272 | |
| 8273 | } else |
| 8274 | { |
| 8275 | { |
| 8276 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 8277 | bool j0valid[1]={false}; |
| 8278 | _nj0 = 1; |
| 8279 | CheckValue<IkReal> x550 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(((-1.0)*(gconst21*gconst21))),IKFAST_ATAN2_MAGTHRESH); |
| 8280 | if(!x550.valid){ |
| 8281 | continue; |
| 8282 | } |
| 8283 | CheckValue<IkReal> x551=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1); |
| 8284 | if(!x551.valid){ |
| 8285 | continue; |
| 8286 | } |
| 8287 | j0array[0]=((-1.5707963267949)+(x550.value)+(((1.5707963267949)*(x551.value)))); |
| 8288 | sj0array[0]=IKsin(j0array[0]); |
| 8289 | cj0array[0]=IKcos(j0array[0]); |
| 8290 | if( j0array[0] > IKPI ) |
| 8291 | { |
| 8292 | j0array[0]-=IK2PI; |
| 8293 | } |
| 8294 | else if( j0array[0] < -IKPI ) |
| 8295 | { j0array[0]+=IK2PI; |
| 8296 | } |
| 8297 | j0valid[0] = true; |
| 8298 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 8299 | { |
| 8300 | if( !j0valid[ij0] ) |
| 8301 | { |
| 8302 | continue; |
| 8303 | } |
| 8304 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8305 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 8306 | { |
| 8307 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8308 | { |
| 8309 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8310 | } |
| 8311 | } |
| 8312 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8313 | { |
| 8314 | IkReal evalcond[6]; |
| 8315 | IkReal x552=IKcos(j0); |
| 8316 | IkReal x553=IKsin(j0); |
| 8317 | IkReal x554=(gconst21*x553); |
| 8318 | IkReal x555=(gconst20*x552); |
| 8319 | IkReal x556=((1.0)*x552); |
| 8320 | IkReal x557=(gconst20*x553); |
| 8321 | IkReal x558=(x555+x554); |
| 8322 | evalcond[0]=x558; |
| 8323 | evalcond[1]=(((new_r10*x553))+gconst20+((new_r00*x552))); |
| 8324 | evalcond[2]=(x558+new_r00); |
| 8325 | evalcond[3]=((((-1.0)*x557))+((gconst21*x552))); |
| 8326 | evalcond[4]=(gconst21+(((-1.0)*new_r10*x556))+((new_r00*x553))); |
| 8327 | evalcond[5]=(x557+(((-1.0)*gconst21*x556))+new_r10); |
| 8328 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8329 | { |
| 8330 | continue; |
| 8331 | } |
| 8332 | } |
| 8333 | |
| 8334 | { |
| 8335 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8336 | vinfos[0].jointtype = 1; |
| 8337 | vinfos[0].foffset = j0; |
| 8338 | vinfos[0].indices[0] = _ij0[0]; |
| 8339 | vinfos[0].indices[1] = _ij0[1]; |
| 8340 | vinfos[0].maxsolutions = _nj0; |
| 8341 | vinfos[1].jointtype = 1; |
| 8342 | vinfos[1].foffset = j1; |
| 8343 | vinfos[1].indices[0] = _ij1[0]; |
| 8344 | vinfos[1].indices[1] = _ij1[1]; |
| 8345 | vinfos[1].maxsolutions = _nj1; |
| 8346 | vinfos[2].jointtype = 1; |
| 8347 | vinfos[2].foffset = j2; |
| 8348 | vinfos[2].indices[0] = _ij2[0]; |
| 8349 | vinfos[2].indices[1] = _ij2[1]; |
| 8350 | vinfos[2].maxsolutions = _nj2; |
| 8351 | vinfos[3].jointtype = 1; |
| 8352 | vinfos[3].foffset = j3; |
| 8353 | vinfos[3].indices[0] = _ij3[0]; |
| 8354 | vinfos[3].indices[1] = _ij3[1]; |
| 8355 | vinfos[3].maxsolutions = _nj3; |
| 8356 | vinfos[4].jointtype = 1; |
| 8357 | vinfos[4].foffset = j4; |
| 8358 | vinfos[4].indices[0] = _ij4[0]; |
| 8359 | vinfos[4].indices[1] = _ij4[1]; |
| 8360 | vinfos[4].maxsolutions = _nj4; |
| 8361 | vinfos[5].jointtype = 1; |
| 8362 | vinfos[5].foffset = j5; |
| 8363 | vinfos[5].indices[0] = _ij5[0]; |
| 8364 | vinfos[5].indices[1] = _ij5[1]; |
| 8365 | vinfos[5].maxsolutions = _nj5; |
| 8366 | std::vector<int> vfree(0); |
| 8367 | solutions.AddSolution(vinfos,vfree); |
| 8368 | } |
| 8369 | } |
| 8370 | } |
| 8371 | |
| 8372 | } |
| 8373 | |
| 8374 | } |
| 8375 | |
| 8376 | } else |
| 8377 | { |
| 8378 | { |
| 8379 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 8380 | bool j0valid[1]={false}; |
| 8381 | _nj0 = 1; |
| 8382 | CheckValue<IkReal> x559 = IKatan2WithCheck(IkReal((gconst20*gconst21)),IkReal(gconst20*gconst20),IKFAST_ATAN2_MAGTHRESH); |
| 8383 | if(!x559.valid){ |
| 8384 | continue; |
| 8385 | } |
| 8386 | CheckValue<IkReal> x560=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst21*new_r10))+(((-1.0)*gconst20*new_r00)))),-1); |
| 8387 | if(!x560.valid){ |
| 8388 | continue; |
| 8389 | } |
| 8390 | j0array[0]=((-1.5707963267949)+(x559.value)+(((1.5707963267949)*(x560.value)))); |
| 8391 | sj0array[0]=IKsin(j0array[0]); |
| 8392 | cj0array[0]=IKcos(j0array[0]); |
| 8393 | if( j0array[0] > IKPI ) |
| 8394 | { |
| 8395 | j0array[0]-=IK2PI; |
| 8396 | } |
| 8397 | else if( j0array[0] < -IKPI ) |
| 8398 | { j0array[0]+=IK2PI; |
| 8399 | } |
| 8400 | j0valid[0] = true; |
| 8401 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 8402 | { |
| 8403 | if( !j0valid[ij0] ) |
| 8404 | { |
| 8405 | continue; |
| 8406 | } |
| 8407 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8408 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 8409 | { |
| 8410 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8411 | { |
| 8412 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8413 | } |
| 8414 | } |
| 8415 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8416 | { |
| 8417 | IkReal evalcond[6]; |
| 8418 | IkReal x561=IKcos(j0); |
| 8419 | IkReal x562=IKsin(j0); |
| 8420 | IkReal x563=(gconst21*x562); |
| 8421 | IkReal x564=(gconst20*x561); |
| 8422 | IkReal x565=((1.0)*x561); |
| 8423 | IkReal x566=(gconst20*x562); |
| 8424 | IkReal x567=(x564+x563); |
| 8425 | evalcond[0]=x567; |
| 8426 | evalcond[1]=(((new_r00*x561))+gconst20+((new_r10*x562))); |
| 8427 | evalcond[2]=(x567+new_r00); |
| 8428 | evalcond[3]=(((gconst21*x561))+(((-1.0)*x566))); |
| 8429 | evalcond[4]=(((new_r00*x562))+gconst21+(((-1.0)*new_r10*x565))); |
| 8430 | evalcond[5]=((((-1.0)*gconst21*x565))+x566+new_r10); |
| 8431 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8432 | { |
| 8433 | continue; |
| 8434 | } |
| 8435 | } |
| 8436 | |
| 8437 | { |
| 8438 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8439 | vinfos[0].jointtype = 1; |
| 8440 | vinfos[0].foffset = j0; |
| 8441 | vinfos[0].indices[0] = _ij0[0]; |
| 8442 | vinfos[0].indices[1] = _ij0[1]; |
| 8443 | vinfos[0].maxsolutions = _nj0; |
| 8444 | vinfos[1].jointtype = 1; |
| 8445 | vinfos[1].foffset = j1; |
| 8446 | vinfos[1].indices[0] = _ij1[0]; |
| 8447 | vinfos[1].indices[1] = _ij1[1]; |
| 8448 | vinfos[1].maxsolutions = _nj1; |
| 8449 | vinfos[2].jointtype = 1; |
| 8450 | vinfos[2].foffset = j2; |
| 8451 | vinfos[2].indices[0] = _ij2[0]; |
| 8452 | vinfos[2].indices[1] = _ij2[1]; |
| 8453 | vinfos[2].maxsolutions = _nj2; |
| 8454 | vinfos[3].jointtype = 1; |
| 8455 | vinfos[3].foffset = j3; |
| 8456 | vinfos[3].indices[0] = _ij3[0]; |
| 8457 | vinfos[3].indices[1] = _ij3[1]; |
| 8458 | vinfos[3].maxsolutions = _nj3; |
| 8459 | vinfos[4].jointtype = 1; |
| 8460 | vinfos[4].foffset = j4; |
| 8461 | vinfos[4].indices[0] = _ij4[0]; |
| 8462 | vinfos[4].indices[1] = _ij4[1]; |
| 8463 | vinfos[4].maxsolutions = _nj4; |
| 8464 | vinfos[5].jointtype = 1; |
| 8465 | vinfos[5].foffset = j5; |
| 8466 | vinfos[5].indices[0] = _ij5[0]; |
| 8467 | vinfos[5].indices[1] = _ij5[1]; |
| 8468 | vinfos[5].maxsolutions = _nj5; |
| 8469 | std::vector<int> vfree(0); |
| 8470 | solutions.AddSolution(vinfos,vfree); |
| 8471 | } |
| 8472 | } |
| 8473 | } |
| 8474 | |
| 8475 | } |
| 8476 | |
| 8477 | } |
| 8478 | |
| 8479 | } |
| 8480 | } while(0); |
| 8481 | if( bgotonextstatement ) |
| 8482 | { |
| 8483 | bool bgotonextstatement = true; |
| 8484 | do |
| 8485 | { |
| 8486 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| 8487 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 8488 | { |
| 8489 | bgotonextstatement=false; |
| 8490 | { |
| 8491 | IkReal j0eval[1]; |
| 8492 | CheckValue<IkReal> x569 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 8493 | if(!x569.valid){ |
| 8494 | continue; |
| 8495 | } |
| 8496 | IkReal x568=((1.0)*(x569.value)); |
| 8497 | sj1=1.0; |
| 8498 | cj1=0; |
| 8499 | j1=1.5707963267949; |
| 8500 | sj2=gconst20; |
| 8501 | cj2=gconst21; |
| 8502 | j2=((3.14159265)+(((-1.0)*x568))); |
| 8503 | new_r01=0; |
| 8504 | new_r10=0; |
| 8505 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x568))); |
| 8506 | IkReal x570 = new_r00*new_r00; |
| 8507 | if(IKabs(x570)==0){ |
| 8508 | continue; |
| 8509 | } |
| 8510 | IkReal gconst20=((1.0)*new_r00*(pow(x570,-0.5))); |
| 8511 | IkReal gconst21=0; |
| 8512 | j0eval[0]=new_r11; |
| 8513 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 8514 | { |
| 8515 | { |
| 8516 | IkReal j0eval[1]; |
| 8517 | CheckValue<IkReal> x572 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 8518 | if(!x572.valid){ |
| 8519 | continue; |
| 8520 | } |
| 8521 | IkReal x571=((1.0)*(x572.value)); |
| 8522 | sj1=1.0; |
| 8523 | cj1=0; |
| 8524 | j1=1.5707963267949; |
| 8525 | sj2=gconst20; |
| 8526 | cj2=gconst21; |
| 8527 | j2=((3.14159265)+(((-1.0)*x571))); |
| 8528 | new_r01=0; |
| 8529 | new_r10=0; |
| 8530 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x571))); |
| 8531 | IkReal x573 = new_r00*new_r00; |
| 8532 | if(IKabs(x573)==0){ |
| 8533 | continue; |
| 8534 | } |
| 8535 | IkReal gconst20=((1.0)*new_r00*(pow(x573,-0.5))); |
| 8536 | IkReal gconst21=0; |
| 8537 | j0eval[0]=new_r00; |
| 8538 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 8539 | { |
| 8540 | { |
| 8541 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 8542 | bool j0valid[2]={false}; |
| 8543 | _nj0 = 2; |
| 8544 | CheckValue<IkReal> x574=IKPowWithIntegerCheck(gconst20,-1); |
| 8545 | if(!x574.valid){ |
| 8546 | continue; |
| 8547 | } |
| 8548 | cj0array[0]=((-1.0)*new_r00*(x574.value)); |
| 8549 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 8550 | { |
| 8551 | j0valid[0] = j0valid[1] = true; |
| 8552 | j0array[0] = IKacos(cj0array[0]); |
| 8553 | sj0array[0] = IKsin(j0array[0]); |
| 8554 | cj0array[1] = cj0array[0]; |
| 8555 | j0array[1] = -j0array[0]; |
| 8556 | sj0array[1] = -sj0array[0]; |
| 8557 | } |
| 8558 | else if( isnan(cj0array[0]) ) |
| 8559 | { |
| 8560 | // probably any value will work |
| 8561 | j0valid[0] = true; |
| 8562 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 8563 | } |
| 8564 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 8565 | { |
| 8566 | if( !j0valid[ij0] ) |
| 8567 | { |
| 8568 | continue; |
| 8569 | } |
| 8570 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8571 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 8572 | { |
| 8573 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8574 | { |
| 8575 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8576 | } |
| 8577 | } |
| 8578 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8579 | { |
| 8580 | IkReal evalcond[6]; |
| 8581 | IkReal x575=IKsin(j0); |
| 8582 | IkReal x576=IKcos(j0); |
| 8583 | evalcond[0]=(new_r00*x575); |
| 8584 | evalcond[1]=(new_r11*x575); |
| 8585 | evalcond[2]=((-1.0)*gconst20*x575); |
| 8586 | evalcond[3]=(((new_r11*x576))+gconst20); |
| 8587 | evalcond[4]=(((new_r00*x576))+gconst20); |
| 8588 | evalcond[5]=(((gconst20*x576))+new_r11); |
| 8589 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8590 | { |
| 8591 | continue; |
| 8592 | } |
| 8593 | } |
| 8594 | |
| 8595 | { |
| 8596 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8597 | vinfos[0].jointtype = 1; |
| 8598 | vinfos[0].foffset = j0; |
| 8599 | vinfos[0].indices[0] = _ij0[0]; |
| 8600 | vinfos[0].indices[1] = _ij0[1]; |
| 8601 | vinfos[0].maxsolutions = _nj0; |
| 8602 | vinfos[1].jointtype = 1; |
| 8603 | vinfos[1].foffset = j1; |
| 8604 | vinfos[1].indices[0] = _ij1[0]; |
| 8605 | vinfos[1].indices[1] = _ij1[1]; |
| 8606 | vinfos[1].maxsolutions = _nj1; |
| 8607 | vinfos[2].jointtype = 1; |
| 8608 | vinfos[2].foffset = j2; |
| 8609 | vinfos[2].indices[0] = _ij2[0]; |
| 8610 | vinfos[2].indices[1] = _ij2[1]; |
| 8611 | vinfos[2].maxsolutions = _nj2; |
| 8612 | vinfos[3].jointtype = 1; |
| 8613 | vinfos[3].foffset = j3; |
| 8614 | vinfos[3].indices[0] = _ij3[0]; |
| 8615 | vinfos[3].indices[1] = _ij3[1]; |
| 8616 | vinfos[3].maxsolutions = _nj3; |
| 8617 | vinfos[4].jointtype = 1; |
| 8618 | vinfos[4].foffset = j4; |
| 8619 | vinfos[4].indices[0] = _ij4[0]; |
| 8620 | vinfos[4].indices[1] = _ij4[1]; |
| 8621 | vinfos[4].maxsolutions = _nj4; |
| 8622 | vinfos[5].jointtype = 1; |
| 8623 | vinfos[5].foffset = j5; |
| 8624 | vinfos[5].indices[0] = _ij5[0]; |
| 8625 | vinfos[5].indices[1] = _ij5[1]; |
| 8626 | vinfos[5].maxsolutions = _nj5; |
| 8627 | std::vector<int> vfree(0); |
| 8628 | solutions.AddSolution(vinfos,vfree); |
| 8629 | } |
| 8630 | } |
| 8631 | } |
| 8632 | |
| 8633 | } else |
| 8634 | { |
| 8635 | { |
| 8636 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 8637 | bool j0valid[2]={false}; |
| 8638 | _nj0 = 2; |
| 8639 | CheckValue<IkReal> x577=IKPowWithIntegerCheck(new_r00,-1); |
| 8640 | if(!x577.valid){ |
| 8641 | continue; |
| 8642 | } |
| 8643 | cj0array[0]=((-1.0)*gconst20*(x577.value)); |
| 8644 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 8645 | { |
| 8646 | j0valid[0] = j0valid[1] = true; |
| 8647 | j0array[0] = IKacos(cj0array[0]); |
| 8648 | sj0array[0] = IKsin(j0array[0]); |
| 8649 | cj0array[1] = cj0array[0]; |
| 8650 | j0array[1] = -j0array[0]; |
| 8651 | sj0array[1] = -sj0array[0]; |
| 8652 | } |
| 8653 | else if( isnan(cj0array[0]) ) |
| 8654 | { |
| 8655 | // probably any value will work |
| 8656 | j0valid[0] = true; |
| 8657 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 8658 | } |
| 8659 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 8660 | { |
| 8661 | if( !j0valid[ij0] ) |
| 8662 | { |
| 8663 | continue; |
| 8664 | } |
| 8665 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8666 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 8667 | { |
| 8668 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8669 | { |
| 8670 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8671 | } |
| 8672 | } |
| 8673 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8674 | { |
| 8675 | IkReal evalcond[6]; |
| 8676 | IkReal x578=IKsin(j0); |
| 8677 | IkReal x579=IKcos(j0); |
| 8678 | IkReal x580=(gconst20*x579); |
| 8679 | evalcond[0]=(new_r00*x578); |
| 8680 | evalcond[1]=(new_r11*x578); |
| 8681 | evalcond[2]=((-1.0)*gconst20*x578); |
| 8682 | evalcond[3]=(((new_r11*x579))+gconst20); |
| 8683 | evalcond[4]=(x580+new_r00); |
| 8684 | evalcond[5]=(x580+new_r11); |
| 8685 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8686 | { |
| 8687 | continue; |
| 8688 | } |
| 8689 | } |
| 8690 | |
| 8691 | { |
| 8692 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8693 | vinfos[0].jointtype = 1; |
| 8694 | vinfos[0].foffset = j0; |
| 8695 | vinfos[0].indices[0] = _ij0[0]; |
| 8696 | vinfos[0].indices[1] = _ij0[1]; |
| 8697 | vinfos[0].maxsolutions = _nj0; |
| 8698 | vinfos[1].jointtype = 1; |
| 8699 | vinfos[1].foffset = j1; |
| 8700 | vinfos[1].indices[0] = _ij1[0]; |
| 8701 | vinfos[1].indices[1] = _ij1[1]; |
| 8702 | vinfos[1].maxsolutions = _nj1; |
| 8703 | vinfos[2].jointtype = 1; |
| 8704 | vinfos[2].foffset = j2; |
| 8705 | vinfos[2].indices[0] = _ij2[0]; |
| 8706 | vinfos[2].indices[1] = _ij2[1]; |
| 8707 | vinfos[2].maxsolutions = _nj2; |
| 8708 | vinfos[3].jointtype = 1; |
| 8709 | vinfos[3].foffset = j3; |
| 8710 | vinfos[3].indices[0] = _ij3[0]; |
| 8711 | vinfos[3].indices[1] = _ij3[1]; |
| 8712 | vinfos[3].maxsolutions = _nj3; |
| 8713 | vinfos[4].jointtype = 1; |
| 8714 | vinfos[4].foffset = j4; |
| 8715 | vinfos[4].indices[0] = _ij4[0]; |
| 8716 | vinfos[4].indices[1] = _ij4[1]; |
| 8717 | vinfos[4].maxsolutions = _nj4; |
| 8718 | vinfos[5].jointtype = 1; |
| 8719 | vinfos[5].foffset = j5; |
| 8720 | vinfos[5].indices[0] = _ij5[0]; |
| 8721 | vinfos[5].indices[1] = _ij5[1]; |
| 8722 | vinfos[5].maxsolutions = _nj5; |
| 8723 | std::vector<int> vfree(0); |
| 8724 | solutions.AddSolution(vinfos,vfree); |
| 8725 | } |
| 8726 | } |
| 8727 | } |
| 8728 | |
| 8729 | } |
| 8730 | |
| 8731 | } |
| 8732 | |
| 8733 | } else |
| 8734 | { |
| 8735 | { |
| 8736 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 8737 | bool j0valid[2]={false}; |
| 8738 | _nj0 = 2; |
| 8739 | CheckValue<IkReal> x581=IKPowWithIntegerCheck(new_r11,-1); |
| 8740 | if(!x581.valid){ |
| 8741 | continue; |
| 8742 | } |
| 8743 | cj0array[0]=((-1.0)*gconst20*(x581.value)); |
| 8744 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 8745 | { |
| 8746 | j0valid[0] = j0valid[1] = true; |
| 8747 | j0array[0] = IKacos(cj0array[0]); |
| 8748 | sj0array[0] = IKsin(j0array[0]); |
| 8749 | cj0array[1] = cj0array[0]; |
| 8750 | j0array[1] = -j0array[0]; |
| 8751 | sj0array[1] = -sj0array[0]; |
| 8752 | } |
| 8753 | else if( isnan(cj0array[0]) ) |
| 8754 | { |
| 8755 | // probably any value will work |
| 8756 | j0valid[0] = true; |
| 8757 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 8758 | } |
| 8759 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 8760 | { |
| 8761 | if( !j0valid[ij0] ) |
| 8762 | { |
| 8763 | continue; |
| 8764 | } |
| 8765 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8766 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 8767 | { |
| 8768 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8769 | { |
| 8770 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8771 | } |
| 8772 | } |
| 8773 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8774 | { |
| 8775 | IkReal evalcond[6]; |
| 8776 | IkReal x582=IKsin(j0); |
| 8777 | IkReal x583=IKcos(j0); |
| 8778 | IkReal x584=(gconst20*x583); |
| 8779 | evalcond[0]=(new_r00*x582); |
| 8780 | evalcond[1]=(new_r11*x582); |
| 8781 | evalcond[2]=((-1.0)*gconst20*x582); |
| 8782 | evalcond[3]=(gconst20+((new_r00*x583))); |
| 8783 | evalcond[4]=(x584+new_r00); |
| 8784 | evalcond[5]=(x584+new_r11); |
| 8785 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 8786 | { |
| 8787 | continue; |
| 8788 | } |
| 8789 | } |
| 8790 | |
| 8791 | { |
| 8792 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8793 | vinfos[0].jointtype = 1; |
| 8794 | vinfos[0].foffset = j0; |
| 8795 | vinfos[0].indices[0] = _ij0[0]; |
| 8796 | vinfos[0].indices[1] = _ij0[1]; |
| 8797 | vinfos[0].maxsolutions = _nj0; |
| 8798 | vinfos[1].jointtype = 1; |
| 8799 | vinfos[1].foffset = j1; |
| 8800 | vinfos[1].indices[0] = _ij1[0]; |
| 8801 | vinfos[1].indices[1] = _ij1[1]; |
| 8802 | vinfos[1].maxsolutions = _nj1; |
| 8803 | vinfos[2].jointtype = 1; |
| 8804 | vinfos[2].foffset = j2; |
| 8805 | vinfos[2].indices[0] = _ij2[0]; |
| 8806 | vinfos[2].indices[1] = _ij2[1]; |
| 8807 | vinfos[2].maxsolutions = _nj2; |
| 8808 | vinfos[3].jointtype = 1; |
| 8809 | vinfos[3].foffset = j3; |
| 8810 | vinfos[3].indices[0] = _ij3[0]; |
| 8811 | vinfos[3].indices[1] = _ij3[1]; |
| 8812 | vinfos[3].maxsolutions = _nj3; |
| 8813 | vinfos[4].jointtype = 1; |
| 8814 | vinfos[4].foffset = j4; |
| 8815 | vinfos[4].indices[0] = _ij4[0]; |
| 8816 | vinfos[4].indices[1] = _ij4[1]; |
| 8817 | vinfos[4].maxsolutions = _nj4; |
| 8818 | vinfos[5].jointtype = 1; |
| 8819 | vinfos[5].foffset = j5; |
| 8820 | vinfos[5].indices[0] = _ij5[0]; |
| 8821 | vinfos[5].indices[1] = _ij5[1]; |
| 8822 | vinfos[5].maxsolutions = _nj5; |
| 8823 | std::vector<int> vfree(0); |
| 8824 | solutions.AddSolution(vinfos,vfree); |
| 8825 | } |
| 8826 | } |
| 8827 | } |
| 8828 | |
| 8829 | } |
| 8830 | |
| 8831 | } |
| 8832 | |
| 8833 | } |
| 8834 | } while(0); |
| 8835 | if( bgotonextstatement ) |
| 8836 | { |
| 8837 | bool bgotonextstatement = true; |
| 8838 | do |
| 8839 | { |
| 8840 | evalcond[0]=IKabs(new_r00); |
| 8841 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 8842 | { |
| 8843 | bgotonextstatement=false; |
| 8844 | { |
| 8845 | IkReal j0eval[1]; |
| 8846 | CheckValue<IkReal> x586 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8847 | if(!x586.valid){ |
| 8848 | continue; |
| 8849 | } |
| 8850 | IkReal x585=((1.0)*(x586.value)); |
| 8851 | sj1=1.0; |
| 8852 | cj1=0; |
| 8853 | j1=1.5707963267949; |
| 8854 | sj2=gconst20; |
| 8855 | cj2=gconst21; |
| 8856 | j2=((3.14159265)+(((-1.0)*x585))); |
| 8857 | new_r00=0; |
| 8858 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x585))); |
| 8859 | IkReal gconst20=0; |
| 8860 | IkReal x587 = new_r10*new_r10; |
| 8861 | if(IKabs(x587)==0){ |
| 8862 | continue; |
| 8863 | } |
| 8864 | IkReal gconst21=((1.0)*new_r10*(pow(x587,-0.5))); |
| 8865 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 8866 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 8867 | { |
| 8868 | { |
| 8869 | IkReal j0eval[1]; |
| 8870 | CheckValue<IkReal> x589 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8871 | if(!x589.valid){ |
| 8872 | continue; |
| 8873 | } |
| 8874 | IkReal x588=((1.0)*(x589.value)); |
| 8875 | sj1=1.0; |
| 8876 | cj1=0; |
| 8877 | j1=1.5707963267949; |
| 8878 | sj2=gconst20; |
| 8879 | cj2=gconst21; |
| 8880 | j2=((3.14159265)+(((-1.0)*x588))); |
| 8881 | new_r00=0; |
| 8882 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x588))); |
| 8883 | IkReal gconst20=0; |
| 8884 | IkReal x590 = new_r10*new_r10; |
| 8885 | if(IKabs(x590)==0){ |
| 8886 | continue; |
| 8887 | } |
| 8888 | IkReal gconst21=((1.0)*new_r10*(pow(x590,-0.5))); |
| 8889 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 8890 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 8891 | { |
| 8892 | { |
| 8893 | IkReal j0eval[1]; |
| 8894 | CheckValue<IkReal> x592 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 8895 | if(!x592.valid){ |
| 8896 | continue; |
| 8897 | } |
| 8898 | IkReal x591=((1.0)*(x592.value)); |
| 8899 | sj1=1.0; |
| 8900 | cj1=0; |
| 8901 | j1=1.5707963267949; |
| 8902 | sj2=gconst20; |
| 8903 | cj2=gconst21; |
| 8904 | j2=((3.14159265)+(((-1.0)*x591))); |
| 8905 | new_r00=0; |
| 8906 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x591))); |
| 8907 | IkReal gconst20=0; |
| 8908 | IkReal x593 = new_r10*new_r10; |
| 8909 | if(IKabs(x593)==0){ |
| 8910 | continue; |
| 8911 | } |
| 8912 | IkReal gconst21=((1.0)*new_r10*(pow(x593,-0.5))); |
| 8913 | j0eval[0]=new_r10; |
| 8914 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 8915 | { |
| 8916 | continue; // 3 cases reached |
| 8917 | |
| 8918 | } else |
| 8919 | { |
| 8920 | { |
| 8921 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 8922 | bool j0valid[1]={false}; |
| 8923 | _nj0 = 1; |
| 8924 | CheckValue<IkReal> x594=IKPowWithIntegerCheck(gconst21,-1); |
| 8925 | if(!x594.valid){ |
| 8926 | continue; |
| 8927 | } |
| 8928 | CheckValue<IkReal> x595=IKPowWithIntegerCheck(new_r10,-1); |
| 8929 | if(!x595.valid){ |
| 8930 | continue; |
| 8931 | } |
| 8932 | if( IKabs(((-1.0)*new_r11*(x594.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst21*(x595.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11*(x594.value)))+IKsqr((gconst21*(x595.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 8933 | continue; |
| 8934 | j0array[0]=IKatan2(((-1.0)*new_r11*(x594.value)), (gconst21*(x595.value))); |
| 8935 | sj0array[0]=IKsin(j0array[0]); |
| 8936 | cj0array[0]=IKcos(j0array[0]); |
| 8937 | if( j0array[0] > IKPI ) |
| 8938 | { |
| 8939 | j0array[0]-=IK2PI; |
| 8940 | } |
| 8941 | else if( j0array[0] < -IKPI ) |
| 8942 | { j0array[0]+=IK2PI; |
| 8943 | } |
| 8944 | j0valid[0] = true; |
| 8945 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 8946 | { |
| 8947 | if( !j0valid[ij0] ) |
| 8948 | { |
| 8949 | continue; |
| 8950 | } |
| 8951 | _ij0[0] = ij0; _ij0[1] = -1; |
| 8952 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 8953 | { |
| 8954 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 8955 | { |
| 8956 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 8957 | } |
| 8958 | } |
| 8959 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 8960 | { |
| 8961 | IkReal evalcond[8]; |
| 8962 | IkReal x596=IKsin(j0); |
| 8963 | IkReal x597=IKcos(j0); |
| 8964 | IkReal x598=(gconst21*x596); |
| 8965 | IkReal x599=((1.0)*x597); |
| 8966 | evalcond[0]=(new_r10*x596); |
| 8967 | evalcond[1]=x598; |
| 8968 | evalcond[2]=(x598+new_r11); |
| 8969 | evalcond[3]=(((gconst21*x597))+new_r01); |
| 8970 | evalcond[4]=((((-1.0)*new_r10*x599))+gconst21); |
| 8971 | evalcond[5]=((((-1.0)*gconst21*x599))+new_r10); |
| 8972 | evalcond[6]=(((new_r11*x597))+(((-1.0)*new_r01*x596))); |
| 8973 | evalcond[7]=(((new_r11*x596))+gconst21+((new_r01*x597))); |
| 8974 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 8975 | { |
| 8976 | continue; |
| 8977 | } |
| 8978 | } |
| 8979 | |
| 8980 | { |
| 8981 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 8982 | vinfos[0].jointtype = 1; |
| 8983 | vinfos[0].foffset = j0; |
| 8984 | vinfos[0].indices[0] = _ij0[0]; |
| 8985 | vinfos[0].indices[1] = _ij0[1]; |
| 8986 | vinfos[0].maxsolutions = _nj0; |
| 8987 | vinfos[1].jointtype = 1; |
| 8988 | vinfos[1].foffset = j1; |
| 8989 | vinfos[1].indices[0] = _ij1[0]; |
| 8990 | vinfos[1].indices[1] = _ij1[1]; |
| 8991 | vinfos[1].maxsolutions = _nj1; |
| 8992 | vinfos[2].jointtype = 1; |
| 8993 | vinfos[2].foffset = j2; |
| 8994 | vinfos[2].indices[0] = _ij2[0]; |
| 8995 | vinfos[2].indices[1] = _ij2[1]; |
| 8996 | vinfos[2].maxsolutions = _nj2; |
| 8997 | vinfos[3].jointtype = 1; |
| 8998 | vinfos[3].foffset = j3; |
| 8999 | vinfos[3].indices[0] = _ij3[0]; |
| 9000 | vinfos[3].indices[1] = _ij3[1]; |
| 9001 | vinfos[3].maxsolutions = _nj3; |
| 9002 | vinfos[4].jointtype = 1; |
| 9003 | vinfos[4].foffset = j4; |
| 9004 | vinfos[4].indices[0] = _ij4[0]; |
| 9005 | vinfos[4].indices[1] = _ij4[1]; |
| 9006 | vinfos[4].maxsolutions = _nj4; |
| 9007 | vinfos[5].jointtype = 1; |
| 9008 | vinfos[5].foffset = j5; |
| 9009 | vinfos[5].indices[0] = _ij5[0]; |
| 9010 | vinfos[5].indices[1] = _ij5[1]; |
| 9011 | vinfos[5].maxsolutions = _nj5; |
| 9012 | std::vector<int> vfree(0); |
| 9013 | solutions.AddSolution(vinfos,vfree); |
| 9014 | } |
| 9015 | } |
| 9016 | } |
| 9017 | |
| 9018 | } |
| 9019 | |
| 9020 | } |
| 9021 | |
| 9022 | } else |
| 9023 | { |
| 9024 | { |
| 9025 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9026 | bool j0valid[1]={false}; |
| 9027 | _nj0 = 1; |
| 9028 | CheckValue<IkReal> x600=IKPowWithIntegerCheck(IKsign(gconst21),-1); |
| 9029 | if(!x600.valid){ |
| 9030 | continue; |
| 9031 | } |
| 9032 | CheckValue<IkReal> x601 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 9033 | if(!x601.valid){ |
| 9034 | continue; |
| 9035 | } |
| 9036 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x600.value)))+(x601.value)); |
| 9037 | sj0array[0]=IKsin(j0array[0]); |
| 9038 | cj0array[0]=IKcos(j0array[0]); |
| 9039 | if( j0array[0] > IKPI ) |
| 9040 | { |
| 9041 | j0array[0]-=IK2PI; |
| 9042 | } |
| 9043 | else if( j0array[0] < -IKPI ) |
| 9044 | { j0array[0]+=IK2PI; |
| 9045 | } |
| 9046 | j0valid[0] = true; |
| 9047 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9048 | { |
| 9049 | if( !j0valid[ij0] ) |
| 9050 | { |
| 9051 | continue; |
| 9052 | } |
| 9053 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9054 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9055 | { |
| 9056 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9057 | { |
| 9058 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9059 | } |
| 9060 | } |
| 9061 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9062 | { |
| 9063 | IkReal evalcond[8]; |
| 9064 | IkReal x602=IKsin(j0); |
| 9065 | IkReal x603=IKcos(j0); |
| 9066 | IkReal x604=(gconst21*x602); |
| 9067 | IkReal x605=((1.0)*x603); |
| 9068 | evalcond[0]=(new_r10*x602); |
| 9069 | evalcond[1]=x604; |
| 9070 | evalcond[2]=(x604+new_r11); |
| 9071 | evalcond[3]=(((gconst21*x603))+new_r01); |
| 9072 | evalcond[4]=((((-1.0)*new_r10*x605))+gconst21); |
| 9073 | evalcond[5]=(new_r10+(((-1.0)*gconst21*x605))); |
| 9074 | evalcond[6]=(((new_r11*x603))+(((-1.0)*new_r01*x602))); |
| 9075 | evalcond[7]=(gconst21+((new_r11*x602))+((new_r01*x603))); |
| 9076 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9077 | { |
| 9078 | continue; |
| 9079 | } |
| 9080 | } |
| 9081 | |
| 9082 | { |
| 9083 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9084 | vinfos[0].jointtype = 1; |
| 9085 | vinfos[0].foffset = j0; |
| 9086 | vinfos[0].indices[0] = _ij0[0]; |
| 9087 | vinfos[0].indices[1] = _ij0[1]; |
| 9088 | vinfos[0].maxsolutions = _nj0; |
| 9089 | vinfos[1].jointtype = 1; |
| 9090 | vinfos[1].foffset = j1; |
| 9091 | vinfos[1].indices[0] = _ij1[0]; |
| 9092 | vinfos[1].indices[1] = _ij1[1]; |
| 9093 | vinfos[1].maxsolutions = _nj1; |
| 9094 | vinfos[2].jointtype = 1; |
| 9095 | vinfos[2].foffset = j2; |
| 9096 | vinfos[2].indices[0] = _ij2[0]; |
| 9097 | vinfos[2].indices[1] = _ij2[1]; |
| 9098 | vinfos[2].maxsolutions = _nj2; |
| 9099 | vinfos[3].jointtype = 1; |
| 9100 | vinfos[3].foffset = j3; |
| 9101 | vinfos[3].indices[0] = _ij3[0]; |
| 9102 | vinfos[3].indices[1] = _ij3[1]; |
| 9103 | vinfos[3].maxsolutions = _nj3; |
| 9104 | vinfos[4].jointtype = 1; |
| 9105 | vinfos[4].foffset = j4; |
| 9106 | vinfos[4].indices[0] = _ij4[0]; |
| 9107 | vinfos[4].indices[1] = _ij4[1]; |
| 9108 | vinfos[4].maxsolutions = _nj4; |
| 9109 | vinfos[5].jointtype = 1; |
| 9110 | vinfos[5].foffset = j5; |
| 9111 | vinfos[5].indices[0] = _ij5[0]; |
| 9112 | vinfos[5].indices[1] = _ij5[1]; |
| 9113 | vinfos[5].maxsolutions = _nj5; |
| 9114 | std::vector<int> vfree(0); |
| 9115 | solutions.AddSolution(vinfos,vfree); |
| 9116 | } |
| 9117 | } |
| 9118 | } |
| 9119 | |
| 9120 | } |
| 9121 | |
| 9122 | } |
| 9123 | |
| 9124 | } else |
| 9125 | { |
| 9126 | { |
| 9127 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9128 | bool j0valid[1]={false}; |
| 9129 | _nj0 = 1; |
| 9130 | CheckValue<IkReal> x606=IKPowWithIntegerCheck(IKsign(gconst21),-1); |
| 9131 | if(!x606.valid){ |
| 9132 | continue; |
| 9133 | } |
| 9134 | CheckValue<IkReal> x607 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 9135 | if(!x607.valid){ |
| 9136 | continue; |
| 9137 | } |
| 9138 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x606.value)))+(x607.value)); |
| 9139 | sj0array[0]=IKsin(j0array[0]); |
| 9140 | cj0array[0]=IKcos(j0array[0]); |
| 9141 | if( j0array[0] > IKPI ) |
| 9142 | { |
| 9143 | j0array[0]-=IK2PI; |
| 9144 | } |
| 9145 | else if( j0array[0] < -IKPI ) |
| 9146 | { j0array[0]+=IK2PI; |
| 9147 | } |
| 9148 | j0valid[0] = true; |
| 9149 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9150 | { |
| 9151 | if( !j0valid[ij0] ) |
| 9152 | { |
| 9153 | continue; |
| 9154 | } |
| 9155 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9156 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9157 | { |
| 9158 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9159 | { |
| 9160 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9161 | } |
| 9162 | } |
| 9163 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9164 | { |
| 9165 | IkReal evalcond[8]; |
| 9166 | IkReal x608=IKsin(j0); |
| 9167 | IkReal x609=IKcos(j0); |
| 9168 | IkReal x610=(gconst21*x608); |
| 9169 | IkReal x611=((1.0)*x609); |
| 9170 | evalcond[0]=(new_r10*x608); |
| 9171 | evalcond[1]=x610; |
| 9172 | evalcond[2]=(x610+new_r11); |
| 9173 | evalcond[3]=(((gconst21*x609))+new_r01); |
| 9174 | evalcond[4]=(gconst21+(((-1.0)*new_r10*x611))); |
| 9175 | evalcond[5]=((((-1.0)*gconst21*x611))+new_r10); |
| 9176 | evalcond[6]=(((new_r11*x609))+(((-1.0)*new_r01*x608))); |
| 9177 | evalcond[7]=(gconst21+((new_r11*x608))+((new_r01*x609))); |
| 9178 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9179 | { |
| 9180 | continue; |
| 9181 | } |
| 9182 | } |
| 9183 | |
| 9184 | { |
| 9185 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9186 | vinfos[0].jointtype = 1; |
| 9187 | vinfos[0].foffset = j0; |
| 9188 | vinfos[0].indices[0] = _ij0[0]; |
| 9189 | vinfos[0].indices[1] = _ij0[1]; |
| 9190 | vinfos[0].maxsolutions = _nj0; |
| 9191 | vinfos[1].jointtype = 1; |
| 9192 | vinfos[1].foffset = j1; |
| 9193 | vinfos[1].indices[0] = _ij1[0]; |
| 9194 | vinfos[1].indices[1] = _ij1[1]; |
| 9195 | vinfos[1].maxsolutions = _nj1; |
| 9196 | vinfos[2].jointtype = 1; |
| 9197 | vinfos[2].foffset = j2; |
| 9198 | vinfos[2].indices[0] = _ij2[0]; |
| 9199 | vinfos[2].indices[1] = _ij2[1]; |
| 9200 | vinfos[2].maxsolutions = _nj2; |
| 9201 | vinfos[3].jointtype = 1; |
| 9202 | vinfos[3].foffset = j3; |
| 9203 | vinfos[3].indices[0] = _ij3[0]; |
| 9204 | vinfos[3].indices[1] = _ij3[1]; |
| 9205 | vinfos[3].maxsolutions = _nj3; |
| 9206 | vinfos[4].jointtype = 1; |
| 9207 | vinfos[4].foffset = j4; |
| 9208 | vinfos[4].indices[0] = _ij4[0]; |
| 9209 | vinfos[4].indices[1] = _ij4[1]; |
| 9210 | vinfos[4].maxsolutions = _nj4; |
| 9211 | vinfos[5].jointtype = 1; |
| 9212 | vinfos[5].foffset = j5; |
| 9213 | vinfos[5].indices[0] = _ij5[0]; |
| 9214 | vinfos[5].indices[1] = _ij5[1]; |
| 9215 | vinfos[5].maxsolutions = _nj5; |
| 9216 | std::vector<int> vfree(0); |
| 9217 | solutions.AddSolution(vinfos,vfree); |
| 9218 | } |
| 9219 | } |
| 9220 | } |
| 9221 | |
| 9222 | } |
| 9223 | |
| 9224 | } |
| 9225 | |
| 9226 | } |
| 9227 | } while(0); |
| 9228 | if( bgotonextstatement ) |
| 9229 | { |
| 9230 | bool bgotonextstatement = true; |
| 9231 | do |
| 9232 | { |
| 9233 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 9234 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 9235 | { |
| 9236 | bgotonextstatement=false; |
| 9237 | { |
| 9238 | IkReal j0eval[1]; |
| 9239 | CheckValue<IkReal> x613 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 9240 | if(!x613.valid){ |
| 9241 | continue; |
| 9242 | } |
| 9243 | IkReal x612=((1.0)*(x613.value)); |
| 9244 | sj1=1.0; |
| 9245 | cj1=0; |
| 9246 | j1=1.5707963267949; |
| 9247 | sj2=gconst20; |
| 9248 | cj2=gconst21; |
| 9249 | j2=((3.14159265)+(((-1.0)*x612))); |
| 9250 | new_r11=0; |
| 9251 | new_r10=0; |
| 9252 | new_r22=0; |
| 9253 | new_r02=0; |
| 9254 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x612))); |
| 9255 | IkReal x614 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 9256 | if(IKabs(x614)==0){ |
| 9257 | continue; |
| 9258 | } |
| 9259 | IkReal gconst20=((1.0)*new_r00*(pow(x614,-0.5))); |
| 9260 | IkReal gconst21=0; |
| 9261 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 9262 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 9263 | { |
| 9264 | { |
| 9265 | IkReal j0eval[2]; |
| 9266 | CheckValue<IkReal> x616 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 9267 | if(!x616.valid){ |
| 9268 | continue; |
| 9269 | } |
| 9270 | IkReal x615=((1.0)*(x616.value)); |
| 9271 | sj1=1.0; |
| 9272 | cj1=0; |
| 9273 | j1=1.5707963267949; |
| 9274 | sj2=gconst20; |
| 9275 | cj2=gconst21; |
| 9276 | j2=((3.14159265)+(((-1.0)*x615))); |
| 9277 | new_r11=0; |
| 9278 | new_r10=0; |
| 9279 | new_r22=0; |
| 9280 | new_r02=0; |
| 9281 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x615))); |
| 9282 | IkReal x617 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 9283 | if(IKabs(x617)==0){ |
| 9284 | continue; |
| 9285 | } |
| 9286 | IkReal gconst20=((1.0)*new_r00*(pow(x617,-0.5))); |
| 9287 | IkReal gconst21=0; |
| 9288 | j0eval[0]=new_r01; |
| 9289 | j0eval[1]=new_r00; |
| 9290 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 9291 | { |
| 9292 | { |
| 9293 | IkReal j0eval[1]; |
| 9294 | CheckValue<IkReal> x619 = IKatan2WithCheck(IkReal(new_r00),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 9295 | if(!x619.valid){ |
| 9296 | continue; |
| 9297 | } |
| 9298 | IkReal x618=((1.0)*(x619.value)); |
| 9299 | sj1=1.0; |
| 9300 | cj1=0; |
| 9301 | j1=1.5707963267949; |
| 9302 | sj2=gconst20; |
| 9303 | cj2=gconst21; |
| 9304 | j2=((3.14159265)+(((-1.0)*x618))); |
| 9305 | new_r11=0; |
| 9306 | new_r10=0; |
| 9307 | new_r22=0; |
| 9308 | new_r02=0; |
| 9309 | IkReal gconst19=((3.14159265358979)+(((-1.0)*x618))); |
| 9310 | IkReal x620 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 9311 | if(IKabs(x620)==0){ |
| 9312 | continue; |
| 9313 | } |
| 9314 | IkReal gconst20=((1.0)*new_r00*(pow(x620,-0.5))); |
| 9315 | IkReal gconst21=0; |
| 9316 | j0eval[0]=new_r00; |
| 9317 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 9318 | { |
| 9319 | continue; // 3 cases reached |
| 9320 | |
| 9321 | } else |
| 9322 | { |
| 9323 | { |
| 9324 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9325 | bool j0valid[1]={false}; |
| 9326 | _nj0 = 1; |
| 9327 | CheckValue<IkReal> x621=IKPowWithIntegerCheck(gconst20,-1); |
| 9328 | if(!x621.valid){ |
| 9329 | continue; |
| 9330 | } |
| 9331 | CheckValue<IkReal> x622=IKPowWithIntegerCheck(new_r00,-1); |
| 9332 | if(!x622.valid){ |
| 9333 | continue; |
| 9334 | } |
| 9335 | if( IKabs((new_r01*(x621.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst20*(x622.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x621.value)))+IKsqr(((-1.0)*gconst20*(x622.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 9336 | continue; |
| 9337 | j0array[0]=IKatan2((new_r01*(x621.value)), ((-1.0)*gconst20*(x622.value))); |
| 9338 | sj0array[0]=IKsin(j0array[0]); |
| 9339 | cj0array[0]=IKcos(j0array[0]); |
| 9340 | if( j0array[0] > IKPI ) |
| 9341 | { |
| 9342 | j0array[0]-=IK2PI; |
| 9343 | } |
| 9344 | else if( j0array[0] < -IKPI ) |
| 9345 | { j0array[0]+=IK2PI; |
| 9346 | } |
| 9347 | j0valid[0] = true; |
| 9348 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9349 | { |
| 9350 | if( !j0valid[ij0] ) |
| 9351 | { |
| 9352 | continue; |
| 9353 | } |
| 9354 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9355 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9356 | { |
| 9357 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9358 | { |
| 9359 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9360 | } |
| 9361 | } |
| 9362 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9363 | { |
| 9364 | IkReal evalcond[8]; |
| 9365 | IkReal x623=IKcos(j0); |
| 9366 | IkReal x624=IKsin(j0); |
| 9367 | IkReal x625=(gconst20*x623); |
| 9368 | IkReal x626=((1.0)*x624); |
| 9369 | evalcond[0]=(new_r00*x624); |
| 9370 | evalcond[1]=(new_r01*x623); |
| 9371 | evalcond[2]=x625; |
| 9372 | evalcond[3]=(gconst20*x624); |
| 9373 | evalcond[4]=(gconst20+((new_r00*x623))); |
| 9374 | evalcond[5]=(x625+new_r00); |
| 9375 | evalcond[6]=((((-1.0)*new_r01*x626))+gconst20); |
| 9376 | evalcond[7]=(new_r01+(((-1.0)*gconst20*x626))); |
| 9377 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9378 | { |
| 9379 | continue; |
| 9380 | } |
| 9381 | } |
| 9382 | |
| 9383 | { |
| 9384 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9385 | vinfos[0].jointtype = 1; |
| 9386 | vinfos[0].foffset = j0; |
| 9387 | vinfos[0].indices[0] = _ij0[0]; |
| 9388 | vinfos[0].indices[1] = _ij0[1]; |
| 9389 | vinfos[0].maxsolutions = _nj0; |
| 9390 | vinfos[1].jointtype = 1; |
| 9391 | vinfos[1].foffset = j1; |
| 9392 | vinfos[1].indices[0] = _ij1[0]; |
| 9393 | vinfos[1].indices[1] = _ij1[1]; |
| 9394 | vinfos[1].maxsolutions = _nj1; |
| 9395 | vinfos[2].jointtype = 1; |
| 9396 | vinfos[2].foffset = j2; |
| 9397 | vinfos[2].indices[0] = _ij2[0]; |
| 9398 | vinfos[2].indices[1] = _ij2[1]; |
| 9399 | vinfos[2].maxsolutions = _nj2; |
| 9400 | vinfos[3].jointtype = 1; |
| 9401 | vinfos[3].foffset = j3; |
| 9402 | vinfos[3].indices[0] = _ij3[0]; |
| 9403 | vinfos[3].indices[1] = _ij3[1]; |
| 9404 | vinfos[3].maxsolutions = _nj3; |
| 9405 | vinfos[4].jointtype = 1; |
| 9406 | vinfos[4].foffset = j4; |
| 9407 | vinfos[4].indices[0] = _ij4[0]; |
| 9408 | vinfos[4].indices[1] = _ij4[1]; |
| 9409 | vinfos[4].maxsolutions = _nj4; |
| 9410 | vinfos[5].jointtype = 1; |
| 9411 | vinfos[5].foffset = j5; |
| 9412 | vinfos[5].indices[0] = _ij5[0]; |
| 9413 | vinfos[5].indices[1] = _ij5[1]; |
| 9414 | vinfos[5].maxsolutions = _nj5; |
| 9415 | std::vector<int> vfree(0); |
| 9416 | solutions.AddSolution(vinfos,vfree); |
| 9417 | } |
| 9418 | } |
| 9419 | } |
| 9420 | |
| 9421 | } |
| 9422 | |
| 9423 | } |
| 9424 | |
| 9425 | } else |
| 9426 | { |
| 9427 | { |
| 9428 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9429 | bool j0valid[1]={false}; |
| 9430 | _nj0 = 1; |
| 9431 | CheckValue<IkReal> x627=IKPowWithIntegerCheck(new_r01,-1); |
| 9432 | if(!x627.valid){ |
| 9433 | continue; |
| 9434 | } |
| 9435 | CheckValue<IkReal> x628=IKPowWithIntegerCheck(new_r00,-1); |
| 9436 | if(!x628.valid){ |
| 9437 | continue; |
| 9438 | } |
| 9439 | if( IKabs((gconst20*(x627.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst20*(x628.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst20*(x627.value)))+IKsqr(((-1.0)*gconst20*(x628.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 9440 | continue; |
| 9441 | j0array[0]=IKatan2((gconst20*(x627.value)), ((-1.0)*gconst20*(x628.value))); |
| 9442 | sj0array[0]=IKsin(j0array[0]); |
| 9443 | cj0array[0]=IKcos(j0array[0]); |
| 9444 | if( j0array[0] > IKPI ) |
| 9445 | { |
| 9446 | j0array[0]-=IK2PI; |
| 9447 | } |
| 9448 | else if( j0array[0] < -IKPI ) |
| 9449 | { j0array[0]+=IK2PI; |
| 9450 | } |
| 9451 | j0valid[0] = true; |
| 9452 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9453 | { |
| 9454 | if( !j0valid[ij0] ) |
| 9455 | { |
| 9456 | continue; |
| 9457 | } |
| 9458 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9459 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9460 | { |
| 9461 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9462 | { |
| 9463 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9464 | } |
| 9465 | } |
| 9466 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9467 | { |
| 9468 | IkReal evalcond[8]; |
| 9469 | IkReal x629=IKcos(j0); |
| 9470 | IkReal x630=IKsin(j0); |
| 9471 | IkReal x631=(gconst20*x629); |
| 9472 | IkReal x632=((1.0)*x630); |
| 9473 | evalcond[0]=(new_r00*x630); |
| 9474 | evalcond[1]=(new_r01*x629); |
| 9475 | evalcond[2]=x631; |
| 9476 | evalcond[3]=(gconst20*x630); |
| 9477 | evalcond[4]=(gconst20+((new_r00*x629))); |
| 9478 | evalcond[5]=(x631+new_r00); |
| 9479 | evalcond[6]=((((-1.0)*new_r01*x632))+gconst20); |
| 9480 | evalcond[7]=((((-1.0)*gconst20*x632))+new_r01); |
| 9481 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9482 | { |
| 9483 | continue; |
| 9484 | } |
| 9485 | } |
| 9486 | |
| 9487 | { |
| 9488 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9489 | vinfos[0].jointtype = 1; |
| 9490 | vinfos[0].foffset = j0; |
| 9491 | vinfos[0].indices[0] = _ij0[0]; |
| 9492 | vinfos[0].indices[1] = _ij0[1]; |
| 9493 | vinfos[0].maxsolutions = _nj0; |
| 9494 | vinfos[1].jointtype = 1; |
| 9495 | vinfos[1].foffset = j1; |
| 9496 | vinfos[1].indices[0] = _ij1[0]; |
| 9497 | vinfos[1].indices[1] = _ij1[1]; |
| 9498 | vinfos[1].maxsolutions = _nj1; |
| 9499 | vinfos[2].jointtype = 1; |
| 9500 | vinfos[2].foffset = j2; |
| 9501 | vinfos[2].indices[0] = _ij2[0]; |
| 9502 | vinfos[2].indices[1] = _ij2[1]; |
| 9503 | vinfos[2].maxsolutions = _nj2; |
| 9504 | vinfos[3].jointtype = 1; |
| 9505 | vinfos[3].foffset = j3; |
| 9506 | vinfos[3].indices[0] = _ij3[0]; |
| 9507 | vinfos[3].indices[1] = _ij3[1]; |
| 9508 | vinfos[3].maxsolutions = _nj3; |
| 9509 | vinfos[4].jointtype = 1; |
| 9510 | vinfos[4].foffset = j4; |
| 9511 | vinfos[4].indices[0] = _ij4[0]; |
| 9512 | vinfos[4].indices[1] = _ij4[1]; |
| 9513 | vinfos[4].maxsolutions = _nj4; |
| 9514 | vinfos[5].jointtype = 1; |
| 9515 | vinfos[5].foffset = j5; |
| 9516 | vinfos[5].indices[0] = _ij5[0]; |
| 9517 | vinfos[5].indices[1] = _ij5[1]; |
| 9518 | vinfos[5].maxsolutions = _nj5; |
| 9519 | std::vector<int> vfree(0); |
| 9520 | solutions.AddSolution(vinfos,vfree); |
| 9521 | } |
| 9522 | } |
| 9523 | } |
| 9524 | |
| 9525 | } |
| 9526 | |
| 9527 | } |
| 9528 | |
| 9529 | } else |
| 9530 | { |
| 9531 | { |
| 9532 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9533 | bool j0valid[1]={false}; |
| 9534 | _nj0 = 1; |
| 9535 | CheckValue<IkReal> x633 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 9536 | if(!x633.valid){ |
| 9537 | continue; |
| 9538 | } |
| 9539 | CheckValue<IkReal> x634=IKPowWithIntegerCheck(IKsign(gconst20),-1); |
| 9540 | if(!x634.valid){ |
| 9541 | continue; |
| 9542 | } |
| 9543 | j0array[0]=((-1.5707963267949)+(x633.value)+(((1.5707963267949)*(x634.value)))); |
| 9544 | sj0array[0]=IKsin(j0array[0]); |
| 9545 | cj0array[0]=IKcos(j0array[0]); |
| 9546 | if( j0array[0] > IKPI ) |
| 9547 | { |
| 9548 | j0array[0]-=IK2PI; |
| 9549 | } |
| 9550 | else if( j0array[0] < -IKPI ) |
| 9551 | { j0array[0]+=IK2PI; |
| 9552 | } |
| 9553 | j0valid[0] = true; |
| 9554 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9555 | { |
| 9556 | if( !j0valid[ij0] ) |
| 9557 | { |
| 9558 | continue; |
| 9559 | } |
| 9560 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9561 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9562 | { |
| 9563 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9564 | { |
| 9565 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9566 | } |
| 9567 | } |
| 9568 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9569 | { |
| 9570 | IkReal evalcond[8]; |
| 9571 | IkReal x635=IKcos(j0); |
| 9572 | IkReal x636=IKsin(j0); |
| 9573 | IkReal x637=(gconst20*x635); |
| 9574 | IkReal x638=((1.0)*x636); |
| 9575 | evalcond[0]=(new_r00*x636); |
| 9576 | evalcond[1]=(new_r01*x635); |
| 9577 | evalcond[2]=x637; |
| 9578 | evalcond[3]=(gconst20*x636); |
| 9579 | evalcond[4]=(gconst20+((new_r00*x635))); |
| 9580 | evalcond[5]=(x637+new_r00); |
| 9581 | evalcond[6]=((((-1.0)*new_r01*x638))+gconst20); |
| 9582 | evalcond[7]=((((-1.0)*gconst20*x638))+new_r01); |
| 9583 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9584 | { |
| 9585 | continue; |
| 9586 | } |
| 9587 | } |
| 9588 | |
| 9589 | { |
| 9590 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9591 | vinfos[0].jointtype = 1; |
| 9592 | vinfos[0].foffset = j0; |
| 9593 | vinfos[0].indices[0] = _ij0[0]; |
| 9594 | vinfos[0].indices[1] = _ij0[1]; |
| 9595 | vinfos[0].maxsolutions = _nj0; |
| 9596 | vinfos[1].jointtype = 1; |
| 9597 | vinfos[1].foffset = j1; |
| 9598 | vinfos[1].indices[0] = _ij1[0]; |
| 9599 | vinfos[1].indices[1] = _ij1[1]; |
| 9600 | vinfos[1].maxsolutions = _nj1; |
| 9601 | vinfos[2].jointtype = 1; |
| 9602 | vinfos[2].foffset = j2; |
| 9603 | vinfos[2].indices[0] = _ij2[0]; |
| 9604 | vinfos[2].indices[1] = _ij2[1]; |
| 9605 | vinfos[2].maxsolutions = _nj2; |
| 9606 | vinfos[3].jointtype = 1; |
| 9607 | vinfos[3].foffset = j3; |
| 9608 | vinfos[3].indices[0] = _ij3[0]; |
| 9609 | vinfos[3].indices[1] = _ij3[1]; |
| 9610 | vinfos[3].maxsolutions = _nj3; |
| 9611 | vinfos[4].jointtype = 1; |
| 9612 | vinfos[4].foffset = j4; |
| 9613 | vinfos[4].indices[0] = _ij4[0]; |
| 9614 | vinfos[4].indices[1] = _ij4[1]; |
| 9615 | vinfos[4].maxsolutions = _nj4; |
| 9616 | vinfos[5].jointtype = 1; |
| 9617 | vinfos[5].foffset = j5; |
| 9618 | vinfos[5].indices[0] = _ij5[0]; |
| 9619 | vinfos[5].indices[1] = _ij5[1]; |
| 9620 | vinfos[5].maxsolutions = _nj5; |
| 9621 | std::vector<int> vfree(0); |
| 9622 | solutions.AddSolution(vinfos,vfree); |
| 9623 | } |
| 9624 | } |
| 9625 | } |
| 9626 | |
| 9627 | } |
| 9628 | |
| 9629 | } |
| 9630 | |
| 9631 | } |
| 9632 | } while(0); |
| 9633 | if( bgotonextstatement ) |
| 9634 | { |
| 9635 | bool bgotonextstatement = true; |
| 9636 | do |
| 9637 | { |
| 9638 | if( 1 ) |
| 9639 | { |
| 9640 | bgotonextstatement=false; |
| 9641 | continue; // branch miss [j0] |
| 9642 | |
| 9643 | } |
| 9644 | } while(0); |
| 9645 | if( bgotonextstatement ) |
| 9646 | { |
| 9647 | } |
| 9648 | } |
| 9649 | } |
| 9650 | } |
| 9651 | } |
| 9652 | } |
| 9653 | } |
| 9654 | |
| 9655 | } else |
| 9656 | { |
| 9657 | { |
| 9658 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9659 | bool j0valid[1]={false}; |
| 9660 | _nj0 = 1; |
| 9661 | IkReal x639=((1.0)*gconst20); |
| 9662 | CheckValue<IkReal> x640=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 9663 | if(!x640.valid){ |
| 9664 | continue; |
| 9665 | } |
| 9666 | CheckValue<IkReal> x641 = IKatan2WithCheck(IkReal((((gconst20*new_r00))+(((-1.0)*new_r11*x639)))),IkReal(((((-1.0)*new_r01*x639))+(((-1.0)*new_r10*x639)))),IKFAST_ATAN2_MAGTHRESH); |
| 9667 | if(!x641.valid){ |
| 9668 | continue; |
| 9669 | } |
| 9670 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x640.value)))+(x641.value)); |
| 9671 | sj0array[0]=IKsin(j0array[0]); |
| 9672 | cj0array[0]=IKcos(j0array[0]); |
| 9673 | if( j0array[0] > IKPI ) |
| 9674 | { |
| 9675 | j0array[0]-=IK2PI; |
| 9676 | } |
| 9677 | else if( j0array[0] < -IKPI ) |
| 9678 | { j0array[0]+=IK2PI; |
| 9679 | } |
| 9680 | j0valid[0] = true; |
| 9681 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9682 | { |
| 9683 | if( !j0valid[ij0] ) |
| 9684 | { |
| 9685 | continue; |
| 9686 | } |
| 9687 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9688 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9689 | { |
| 9690 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9691 | { |
| 9692 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9693 | } |
| 9694 | } |
| 9695 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9696 | { |
| 9697 | IkReal evalcond[8]; |
| 9698 | IkReal x642=IKsin(j0); |
| 9699 | IkReal x643=IKcos(j0); |
| 9700 | IkReal x644=(gconst21*x642); |
| 9701 | IkReal x645=(gconst20*x643); |
| 9702 | IkReal x646=((1.0)*x643); |
| 9703 | IkReal x647=(gconst20*x642); |
| 9704 | IkReal x648=(x645+x644); |
| 9705 | evalcond[0]=(gconst20+((new_r10*x642))+((new_r00*x643))); |
| 9706 | evalcond[1]=(gconst21+((new_r11*x642))+((new_r01*x643))); |
| 9707 | evalcond[2]=(x648+new_r00); |
| 9708 | evalcond[3]=(x648+new_r11); |
| 9709 | evalcond[4]=((((-1.0)*new_r01*x642))+gconst20+((new_r11*x643))); |
| 9710 | evalcond[5]=(gconst21+(((-1.0)*new_r10*x646))+((new_r00*x642))); |
| 9711 | evalcond[6]=((((-1.0)*x647))+((gconst21*x643))+new_r01); |
| 9712 | evalcond[7]=((((-1.0)*gconst21*x646))+x647+new_r10); |
| 9713 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9714 | { |
| 9715 | continue; |
| 9716 | } |
| 9717 | } |
| 9718 | |
| 9719 | { |
| 9720 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9721 | vinfos[0].jointtype = 1; |
| 9722 | vinfos[0].foffset = j0; |
| 9723 | vinfos[0].indices[0] = _ij0[0]; |
| 9724 | vinfos[0].indices[1] = _ij0[1]; |
| 9725 | vinfos[0].maxsolutions = _nj0; |
| 9726 | vinfos[1].jointtype = 1; |
| 9727 | vinfos[1].foffset = j1; |
| 9728 | vinfos[1].indices[0] = _ij1[0]; |
| 9729 | vinfos[1].indices[1] = _ij1[1]; |
| 9730 | vinfos[1].maxsolutions = _nj1; |
| 9731 | vinfos[2].jointtype = 1; |
| 9732 | vinfos[2].foffset = j2; |
| 9733 | vinfos[2].indices[0] = _ij2[0]; |
| 9734 | vinfos[2].indices[1] = _ij2[1]; |
| 9735 | vinfos[2].maxsolutions = _nj2; |
| 9736 | vinfos[3].jointtype = 1; |
| 9737 | vinfos[3].foffset = j3; |
| 9738 | vinfos[3].indices[0] = _ij3[0]; |
| 9739 | vinfos[3].indices[1] = _ij3[1]; |
| 9740 | vinfos[3].maxsolutions = _nj3; |
| 9741 | vinfos[4].jointtype = 1; |
| 9742 | vinfos[4].foffset = j4; |
| 9743 | vinfos[4].indices[0] = _ij4[0]; |
| 9744 | vinfos[4].indices[1] = _ij4[1]; |
| 9745 | vinfos[4].maxsolutions = _nj4; |
| 9746 | vinfos[5].jointtype = 1; |
| 9747 | vinfos[5].foffset = j5; |
| 9748 | vinfos[5].indices[0] = _ij5[0]; |
| 9749 | vinfos[5].indices[1] = _ij5[1]; |
| 9750 | vinfos[5].maxsolutions = _nj5; |
| 9751 | std::vector<int> vfree(0); |
| 9752 | solutions.AddSolution(vinfos,vfree); |
| 9753 | } |
| 9754 | } |
| 9755 | } |
| 9756 | |
| 9757 | } |
| 9758 | |
| 9759 | } |
| 9760 | |
| 9761 | } else |
| 9762 | { |
| 9763 | { |
| 9764 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9765 | bool j0valid[1]={false}; |
| 9766 | _nj0 = 1; |
| 9767 | IkReal x649=((1.0)*gconst21); |
| 9768 | CheckValue<IkReal> x650 = IKatan2WithCheck(IkReal(((((-1.0)*gconst20*x649))+((new_r00*new_r01)))),IkReal(((gconst21*gconst21)+(((-1.0)*new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 9769 | if(!x650.valid){ |
| 9770 | continue; |
| 9771 | } |
| 9772 | CheckValue<IkReal> x651=IKPowWithIntegerCheck(IKsign((((gconst20*new_r11))+(((-1.0)*new_r01*x649)))),-1); |
| 9773 | if(!x651.valid){ |
| 9774 | continue; |
| 9775 | } |
| 9776 | j0array[0]=((-1.5707963267949)+(x650.value)+(((1.5707963267949)*(x651.value)))); |
| 9777 | sj0array[0]=IKsin(j0array[0]); |
| 9778 | cj0array[0]=IKcos(j0array[0]); |
| 9779 | if( j0array[0] > IKPI ) |
| 9780 | { |
| 9781 | j0array[0]-=IK2PI; |
| 9782 | } |
| 9783 | else if( j0array[0] < -IKPI ) |
| 9784 | { j0array[0]+=IK2PI; |
| 9785 | } |
| 9786 | j0valid[0] = true; |
| 9787 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9788 | { |
| 9789 | if( !j0valid[ij0] ) |
| 9790 | { |
| 9791 | continue; |
| 9792 | } |
| 9793 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9794 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9795 | { |
| 9796 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9797 | { |
| 9798 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9799 | } |
| 9800 | } |
| 9801 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9802 | { |
| 9803 | IkReal evalcond[8]; |
| 9804 | IkReal x652=IKsin(j0); |
| 9805 | IkReal x653=IKcos(j0); |
| 9806 | IkReal x654=(gconst21*x652); |
| 9807 | IkReal x655=(gconst20*x653); |
| 9808 | IkReal x656=((1.0)*x653); |
| 9809 | IkReal x657=(gconst20*x652); |
| 9810 | IkReal x658=(x654+x655); |
| 9811 | evalcond[0]=(gconst20+((new_r10*x652))+((new_r00*x653))); |
| 9812 | evalcond[1]=(gconst21+((new_r01*x653))+((new_r11*x652))); |
| 9813 | evalcond[2]=(x658+new_r00); |
| 9814 | evalcond[3]=(x658+new_r11); |
| 9815 | evalcond[4]=(gconst20+(((-1.0)*new_r01*x652))+((new_r11*x653))); |
| 9816 | evalcond[5]=(gconst21+(((-1.0)*new_r10*x656))+((new_r00*x652))); |
| 9817 | evalcond[6]=((((-1.0)*x657))+((gconst21*x653))+new_r01); |
| 9818 | evalcond[7]=((((-1.0)*gconst21*x656))+x657+new_r10); |
| 9819 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9820 | { |
| 9821 | continue; |
| 9822 | } |
| 9823 | } |
| 9824 | |
| 9825 | { |
| 9826 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9827 | vinfos[0].jointtype = 1; |
| 9828 | vinfos[0].foffset = j0; |
| 9829 | vinfos[0].indices[0] = _ij0[0]; |
| 9830 | vinfos[0].indices[1] = _ij0[1]; |
| 9831 | vinfos[0].maxsolutions = _nj0; |
| 9832 | vinfos[1].jointtype = 1; |
| 9833 | vinfos[1].foffset = j1; |
| 9834 | vinfos[1].indices[0] = _ij1[0]; |
| 9835 | vinfos[1].indices[1] = _ij1[1]; |
| 9836 | vinfos[1].maxsolutions = _nj1; |
| 9837 | vinfos[2].jointtype = 1; |
| 9838 | vinfos[2].foffset = j2; |
| 9839 | vinfos[2].indices[0] = _ij2[0]; |
| 9840 | vinfos[2].indices[1] = _ij2[1]; |
| 9841 | vinfos[2].maxsolutions = _nj2; |
| 9842 | vinfos[3].jointtype = 1; |
| 9843 | vinfos[3].foffset = j3; |
| 9844 | vinfos[3].indices[0] = _ij3[0]; |
| 9845 | vinfos[3].indices[1] = _ij3[1]; |
| 9846 | vinfos[3].maxsolutions = _nj3; |
| 9847 | vinfos[4].jointtype = 1; |
| 9848 | vinfos[4].foffset = j4; |
| 9849 | vinfos[4].indices[0] = _ij4[0]; |
| 9850 | vinfos[4].indices[1] = _ij4[1]; |
| 9851 | vinfos[4].maxsolutions = _nj4; |
| 9852 | vinfos[5].jointtype = 1; |
| 9853 | vinfos[5].foffset = j5; |
| 9854 | vinfos[5].indices[0] = _ij5[0]; |
| 9855 | vinfos[5].indices[1] = _ij5[1]; |
| 9856 | vinfos[5].maxsolutions = _nj5; |
| 9857 | std::vector<int> vfree(0); |
| 9858 | solutions.AddSolution(vinfos,vfree); |
| 9859 | } |
| 9860 | } |
| 9861 | } |
| 9862 | |
| 9863 | } |
| 9864 | |
| 9865 | } |
| 9866 | |
| 9867 | } else |
| 9868 | { |
| 9869 | { |
| 9870 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 9871 | bool j0valid[1]={false}; |
| 9872 | _nj0 = 1; |
| 9873 | CheckValue<IkReal> x659 = IKatan2WithCheck(IkReal(((((-1.0)*gconst21*new_r00))+((gconst20*new_r01)))),IkReal((((gconst21*new_r10))+(((-1.0)*gconst20*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 9874 | if(!x659.valid){ |
| 9875 | continue; |
| 9876 | } |
| 9877 | CheckValue<IkReal> x660=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| 9878 | if(!x660.valid){ |
| 9879 | continue; |
| 9880 | } |
| 9881 | j0array[0]=((-1.5707963267949)+(x659.value)+(((1.5707963267949)*(x660.value)))); |
| 9882 | sj0array[0]=IKsin(j0array[0]); |
| 9883 | cj0array[0]=IKcos(j0array[0]); |
| 9884 | if( j0array[0] > IKPI ) |
| 9885 | { |
| 9886 | j0array[0]-=IK2PI; |
| 9887 | } |
| 9888 | else if( j0array[0] < -IKPI ) |
| 9889 | { j0array[0]+=IK2PI; |
| 9890 | } |
| 9891 | j0valid[0] = true; |
| 9892 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 9893 | { |
| 9894 | if( !j0valid[ij0] ) |
| 9895 | { |
| 9896 | continue; |
| 9897 | } |
| 9898 | _ij0[0] = ij0; _ij0[1] = -1; |
| 9899 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 9900 | { |
| 9901 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 9902 | { |
| 9903 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 9904 | } |
| 9905 | } |
| 9906 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 9907 | { |
| 9908 | IkReal evalcond[8]; |
| 9909 | IkReal x661=IKsin(j0); |
| 9910 | IkReal x662=IKcos(j0); |
| 9911 | IkReal x663=(gconst21*x661); |
| 9912 | IkReal x664=(gconst20*x662); |
| 9913 | IkReal x665=((1.0)*x662); |
| 9914 | IkReal x666=(gconst20*x661); |
| 9915 | IkReal x667=(x663+x664); |
| 9916 | evalcond[0]=(gconst20+((new_r10*x661))+((new_r00*x662))); |
| 9917 | evalcond[1]=(gconst21+((new_r11*x661))+((new_r01*x662))); |
| 9918 | evalcond[2]=(x667+new_r00); |
| 9919 | evalcond[3]=(x667+new_r11); |
| 9920 | evalcond[4]=(gconst20+((new_r11*x662))+(((-1.0)*new_r01*x661))); |
| 9921 | evalcond[5]=(gconst21+(((-1.0)*new_r10*x665))+((new_r00*x661))); |
| 9922 | evalcond[6]=((((-1.0)*x666))+((gconst21*x662))+new_r01); |
| 9923 | evalcond[7]=((((-1.0)*gconst21*x665))+x666+new_r10); |
| 9924 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 9925 | { |
| 9926 | continue; |
| 9927 | } |
| 9928 | } |
| 9929 | |
| 9930 | { |
| 9931 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 9932 | vinfos[0].jointtype = 1; |
| 9933 | vinfos[0].foffset = j0; |
| 9934 | vinfos[0].indices[0] = _ij0[0]; |
| 9935 | vinfos[0].indices[1] = _ij0[1]; |
| 9936 | vinfos[0].maxsolutions = _nj0; |
| 9937 | vinfos[1].jointtype = 1; |
| 9938 | vinfos[1].foffset = j1; |
| 9939 | vinfos[1].indices[0] = _ij1[0]; |
| 9940 | vinfos[1].indices[1] = _ij1[1]; |
| 9941 | vinfos[1].maxsolutions = _nj1; |
| 9942 | vinfos[2].jointtype = 1; |
| 9943 | vinfos[2].foffset = j2; |
| 9944 | vinfos[2].indices[0] = _ij2[0]; |
| 9945 | vinfos[2].indices[1] = _ij2[1]; |
| 9946 | vinfos[2].maxsolutions = _nj2; |
| 9947 | vinfos[3].jointtype = 1; |
| 9948 | vinfos[3].foffset = j3; |
| 9949 | vinfos[3].indices[0] = _ij3[0]; |
| 9950 | vinfos[3].indices[1] = _ij3[1]; |
| 9951 | vinfos[3].maxsolutions = _nj3; |
| 9952 | vinfos[4].jointtype = 1; |
| 9953 | vinfos[4].foffset = j4; |
| 9954 | vinfos[4].indices[0] = _ij4[0]; |
| 9955 | vinfos[4].indices[1] = _ij4[1]; |
| 9956 | vinfos[4].maxsolutions = _nj4; |
| 9957 | vinfos[5].jointtype = 1; |
| 9958 | vinfos[5].foffset = j5; |
| 9959 | vinfos[5].indices[0] = _ij5[0]; |
| 9960 | vinfos[5].indices[1] = _ij5[1]; |
| 9961 | vinfos[5].maxsolutions = _nj5; |
| 9962 | std::vector<int> vfree(0); |
| 9963 | solutions.AddSolution(vinfos,vfree); |
| 9964 | } |
| 9965 | } |
| 9966 | } |
| 9967 | |
| 9968 | } |
| 9969 | |
| 9970 | } |
| 9971 | |
| 9972 | } |
| 9973 | } while(0); |
| 9974 | if( bgotonextstatement ) |
| 9975 | { |
| 9976 | bool bgotonextstatement = true; |
| 9977 | do |
| 9978 | { |
| 9979 | IkReal x668=((-1.0)*new_r11); |
| 9980 | IkReal x670 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| 9981 | if(IKabs(x670)==0){ |
| 9982 | continue; |
| 9983 | } |
| 9984 | IkReal x669=pow(x670,-0.5); |
| 9985 | CheckValue<IkReal> x671 = IKatan2WithCheck(IkReal(new_r01),IkReal(x668),IKFAST_ATAN2_MAGTHRESH); |
| 9986 | if(!x671.valid){ |
| 9987 | continue; |
| 9988 | } |
| 9989 | IkReal gconst22=((-1.0)*(x671.value)); |
| 9990 | IkReal gconst23=((-1.0)*new_r01*x669); |
| 9991 | IkReal gconst24=(x668*x669); |
| 9992 | CheckValue<IkReal> x672 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 9993 | if(!x672.valid){ |
| 9994 | continue; |
| 9995 | } |
| 9996 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x672.value)+j2)))), 6.28318530717959))); |
| 9997 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 9998 | { |
| 9999 | bgotonextstatement=false; |
| 10000 | { |
| 10001 | IkReal j0eval[3]; |
| 10002 | IkReal x673=((-1.0)*new_r11); |
| 10003 | CheckValue<IkReal> x676 = IKatan2WithCheck(IkReal(new_r01),IkReal(x673),IKFAST_ATAN2_MAGTHRESH); |
| 10004 | if(!x676.valid){ |
| 10005 | continue; |
| 10006 | } |
| 10007 | IkReal x674=((-1.0)*(x676.value)); |
| 10008 | IkReal x675=x669; |
| 10009 | sj1=1.0; |
| 10010 | cj1=0; |
| 10011 | j1=1.5707963267949; |
| 10012 | sj2=gconst23; |
| 10013 | cj2=gconst24; |
| 10014 | j2=x674; |
| 10015 | IkReal gconst22=x674; |
| 10016 | IkReal gconst23=((-1.0)*new_r01*x675); |
| 10017 | IkReal gconst24=(x673*x675); |
| 10018 | IkReal x677=new_r01*new_r01; |
| 10019 | IkReal x678=((1.0)*new_r10); |
| 10020 | IkReal x679=((((-1.0)*new_r01*x678))+((new_r00*new_r11))); |
| 10021 | IkReal x680=x669; |
| 10022 | IkReal x681=(new_r11*x680); |
| 10023 | j0eval[0]=x679; |
| 10024 | j0eval[1]=IKsign(x679); |
| 10025 | j0eval[2]=((IKabs(((((-1.0)*x678*x681))+((new_r01*x681)))))+(IKabs((((new_r00*x681))+(((-1.0)*x677*x680)))))); |
| 10026 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 10027 | { |
| 10028 | { |
| 10029 | IkReal j0eval[3]; |
| 10030 | IkReal x682=((-1.0)*new_r11); |
| 10031 | CheckValue<IkReal> x685 = IKatan2WithCheck(IkReal(new_r01),IkReal(x682),IKFAST_ATAN2_MAGTHRESH); |
| 10032 | if(!x685.valid){ |
| 10033 | continue; |
| 10034 | } |
| 10035 | IkReal x683=((-1.0)*(x685.value)); |
| 10036 | IkReal x684=x669; |
| 10037 | sj1=1.0; |
| 10038 | cj1=0; |
| 10039 | j1=1.5707963267949; |
| 10040 | sj2=gconst23; |
| 10041 | cj2=gconst24; |
| 10042 | j2=x683; |
| 10043 | IkReal gconst22=x683; |
| 10044 | IkReal gconst23=((-1.0)*new_r01*x684); |
| 10045 | IkReal gconst24=(x682*x684); |
| 10046 | IkReal x686=new_r01*new_r01; |
| 10047 | IkReal x687=(((new_r10*new_r11))+((new_r00*new_r01))); |
| 10048 | IkReal x688=x669; |
| 10049 | IkReal x689=(new_r01*x688); |
| 10050 | j0eval[0]=x687; |
| 10051 | j0eval[1]=((IKabs(((((-1.0)*new_r00*x689))+((new_r11*x689)))))+(IKabs((((x686*x688))+((new_r10*x689)))))); |
| 10052 | j0eval[2]=IKsign(x687); |
| 10053 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 10054 | { |
| 10055 | { |
| 10056 | IkReal j0eval[1]; |
| 10057 | IkReal x690=((-1.0)*new_r11); |
| 10058 | CheckValue<IkReal> x693 = IKatan2WithCheck(IkReal(new_r01),IkReal(x690),IKFAST_ATAN2_MAGTHRESH); |
| 10059 | if(!x693.valid){ |
| 10060 | continue; |
| 10061 | } |
| 10062 | IkReal x691=((-1.0)*(x693.value)); |
| 10063 | IkReal x692=x669; |
| 10064 | sj1=1.0; |
| 10065 | cj1=0; |
| 10066 | j1=1.5707963267949; |
| 10067 | sj2=gconst23; |
| 10068 | cj2=gconst24; |
| 10069 | j2=x691; |
| 10070 | IkReal gconst22=x691; |
| 10071 | IkReal gconst23=((-1.0)*new_r01*x692); |
| 10072 | IkReal gconst24=(x690*x692); |
| 10073 | IkReal x694=new_r01*new_r01; |
| 10074 | CheckValue<IkReal> x696=IKPowWithIntegerCheck(((new_r11*new_r11)+x694),-1); |
| 10075 | if(!x696.valid){ |
| 10076 | continue; |
| 10077 | } |
| 10078 | IkReal x695=x696.value; |
| 10079 | j0eval[0]=((IKabs(((((-1.0)*x694*x695))+(new_r00*new_r00))))+(IKabs((((new_r01*new_r11*x695))+(((-1.0)*new_r00*new_r10)))))); |
| 10080 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 10081 | { |
| 10082 | { |
| 10083 | IkReal evalcond[3]; |
| 10084 | bool bgotonextstatement = true; |
| 10085 | do |
| 10086 | { |
| 10087 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 10088 | evalcond[1]=gconst24; |
| 10089 | evalcond[2]=gconst23; |
| 10090 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 ) |
| 10091 | { |
| 10092 | bgotonextstatement=false; |
| 10093 | { |
| 10094 | IkReal j0eval[3]; |
| 10095 | IkReal x697=((-1.0)*new_r11); |
| 10096 | CheckValue<IkReal> x699 = IKatan2WithCheck(IkReal(new_r01),IkReal(x697),IKFAST_ATAN2_MAGTHRESH); |
| 10097 | if(!x699.valid){ |
| 10098 | continue; |
| 10099 | } |
| 10100 | IkReal x698=((-1.0)*(x699.value)); |
| 10101 | sj1=1.0; |
| 10102 | cj1=0; |
| 10103 | j1=1.5707963267949; |
| 10104 | sj2=gconst23; |
| 10105 | cj2=gconst24; |
| 10106 | j2=x698; |
| 10107 | new_r00=0; |
| 10108 | new_r10=0; |
| 10109 | new_r21=0; |
| 10110 | new_r22=0; |
| 10111 | IkReal gconst22=x698; |
| 10112 | IkReal gconst23=((-1.0)*new_r01); |
| 10113 | IkReal gconst24=x697; |
| 10114 | j0eval[0]=-1.0; |
| 10115 | j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| 10116 | j0eval[2]=-1.0; |
| 10117 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 10118 | { |
| 10119 | { |
| 10120 | IkReal j0eval[3]; |
| 10121 | IkReal x700=((-1.0)*new_r11); |
| 10122 | CheckValue<IkReal> x702 = IKatan2WithCheck(IkReal(new_r01),IkReal(x700),IKFAST_ATAN2_MAGTHRESH); |
| 10123 | if(!x702.valid){ |
| 10124 | continue; |
| 10125 | } |
| 10126 | IkReal x701=((-1.0)*(x702.value)); |
| 10127 | sj1=1.0; |
| 10128 | cj1=0; |
| 10129 | j1=1.5707963267949; |
| 10130 | sj2=gconst23; |
| 10131 | cj2=gconst24; |
| 10132 | j2=x701; |
| 10133 | new_r00=0; |
| 10134 | new_r10=0; |
| 10135 | new_r21=0; |
| 10136 | new_r22=0; |
| 10137 | IkReal gconst22=x701; |
| 10138 | IkReal gconst23=((-1.0)*new_r01); |
| 10139 | IkReal gconst24=x700; |
| 10140 | j0eval[0]=1.0; |
| 10141 | j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| 10142 | j0eval[2]=1.0; |
| 10143 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 10144 | { |
| 10145 | { |
| 10146 | IkReal j0eval[3]; |
| 10147 | IkReal x703=((-1.0)*new_r11); |
| 10148 | CheckValue<IkReal> x705 = IKatan2WithCheck(IkReal(new_r01),IkReal(x703),IKFAST_ATAN2_MAGTHRESH); |
| 10149 | if(!x705.valid){ |
| 10150 | continue; |
| 10151 | } |
| 10152 | IkReal x704=((-1.0)*(x705.value)); |
| 10153 | sj1=1.0; |
| 10154 | cj1=0; |
| 10155 | j1=1.5707963267949; |
| 10156 | sj2=gconst23; |
| 10157 | cj2=gconst24; |
| 10158 | j2=x704; |
| 10159 | new_r00=0; |
| 10160 | new_r10=0; |
| 10161 | new_r21=0; |
| 10162 | new_r22=0; |
| 10163 | IkReal gconst22=x704; |
| 10164 | IkReal gconst23=((-1.0)*new_r01); |
| 10165 | IkReal gconst24=x703; |
| 10166 | j0eval[0]=1.0; |
| 10167 | j0eval[1]=1.0; |
| 10168 | j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))); |
| 10169 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 10170 | { |
| 10171 | continue; // 3 cases reached |
| 10172 | |
| 10173 | } else |
| 10174 | { |
| 10175 | { |
| 10176 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10177 | bool j0valid[1]={false}; |
| 10178 | _nj0 = 1; |
| 10179 | CheckValue<IkReal> x706 = IKatan2WithCheck(IkReal(gconst24*gconst24),IkReal((gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH); |
| 10180 | if(!x706.valid){ |
| 10181 | continue; |
| 10182 | } |
| 10183 | CheckValue<IkReal> x707=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst24*new_r11))+(((-1.0)*gconst23*new_r01)))),-1); |
| 10184 | if(!x707.valid){ |
| 10185 | continue; |
| 10186 | } |
| 10187 | j0array[0]=((-1.5707963267949)+(x706.value)+(((1.5707963267949)*(x707.value)))); |
| 10188 | sj0array[0]=IKsin(j0array[0]); |
| 10189 | cj0array[0]=IKcos(j0array[0]); |
| 10190 | if( j0array[0] > IKPI ) |
| 10191 | { |
| 10192 | j0array[0]-=IK2PI; |
| 10193 | } |
| 10194 | else if( j0array[0] < -IKPI ) |
| 10195 | { j0array[0]+=IK2PI; |
| 10196 | } |
| 10197 | j0valid[0] = true; |
| 10198 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10199 | { |
| 10200 | if( !j0valid[ij0] ) |
| 10201 | { |
| 10202 | continue; |
| 10203 | } |
| 10204 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10205 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10206 | { |
| 10207 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10208 | { |
| 10209 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10210 | } |
| 10211 | } |
| 10212 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10213 | { |
| 10214 | IkReal evalcond[6]; |
| 10215 | IkReal x708=IKsin(j0); |
| 10216 | IkReal x709=IKcos(j0); |
| 10217 | IkReal x710=(gconst23*x709); |
| 10218 | IkReal x711=(gconst24*x708); |
| 10219 | IkReal x712=(gconst24*x709); |
| 10220 | IkReal x713=((1.0)*x708); |
| 10221 | IkReal x714=(x711+x710); |
| 10222 | evalcond[0]=x714; |
| 10223 | evalcond[1]=(((new_r01*x709))+gconst24+((new_r11*x708))); |
| 10224 | evalcond[2]=(x714+new_r11); |
| 10225 | evalcond[3]=((((-1.0)*x712))+((gconst23*x708))); |
| 10226 | evalcond[4]=(gconst23+((new_r11*x709))+(((-1.0)*new_r01*x713))); |
| 10227 | evalcond[5]=((((-1.0)*gconst23*x713))+x712+new_r01); |
| 10228 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 10229 | { |
| 10230 | continue; |
| 10231 | } |
| 10232 | } |
| 10233 | |
| 10234 | { |
| 10235 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10236 | vinfos[0].jointtype = 1; |
| 10237 | vinfos[0].foffset = j0; |
| 10238 | vinfos[0].indices[0] = _ij0[0]; |
| 10239 | vinfos[0].indices[1] = _ij0[1]; |
| 10240 | vinfos[0].maxsolutions = _nj0; |
| 10241 | vinfos[1].jointtype = 1; |
| 10242 | vinfos[1].foffset = j1; |
| 10243 | vinfos[1].indices[0] = _ij1[0]; |
| 10244 | vinfos[1].indices[1] = _ij1[1]; |
| 10245 | vinfos[1].maxsolutions = _nj1; |
| 10246 | vinfos[2].jointtype = 1; |
| 10247 | vinfos[2].foffset = j2; |
| 10248 | vinfos[2].indices[0] = _ij2[0]; |
| 10249 | vinfos[2].indices[1] = _ij2[1]; |
| 10250 | vinfos[2].maxsolutions = _nj2; |
| 10251 | vinfos[3].jointtype = 1; |
| 10252 | vinfos[3].foffset = j3; |
| 10253 | vinfos[3].indices[0] = _ij3[0]; |
| 10254 | vinfos[3].indices[1] = _ij3[1]; |
| 10255 | vinfos[3].maxsolutions = _nj3; |
| 10256 | vinfos[4].jointtype = 1; |
| 10257 | vinfos[4].foffset = j4; |
| 10258 | vinfos[4].indices[0] = _ij4[0]; |
| 10259 | vinfos[4].indices[1] = _ij4[1]; |
| 10260 | vinfos[4].maxsolutions = _nj4; |
| 10261 | vinfos[5].jointtype = 1; |
| 10262 | vinfos[5].foffset = j5; |
| 10263 | vinfos[5].indices[0] = _ij5[0]; |
| 10264 | vinfos[5].indices[1] = _ij5[1]; |
| 10265 | vinfos[5].maxsolutions = _nj5; |
| 10266 | std::vector<int> vfree(0); |
| 10267 | solutions.AddSolution(vinfos,vfree); |
| 10268 | } |
| 10269 | } |
| 10270 | } |
| 10271 | |
| 10272 | } |
| 10273 | |
| 10274 | } |
| 10275 | |
| 10276 | } else |
| 10277 | { |
| 10278 | { |
| 10279 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10280 | bool j0valid[1]={false}; |
| 10281 | _nj0 = 1; |
| 10282 | CheckValue<IkReal> x715=IKPowWithIntegerCheck(IKsign(((gconst23*gconst23)+(gconst24*gconst24))),-1); |
| 10283 | if(!x715.valid){ |
| 10284 | continue; |
| 10285 | } |
| 10286 | CheckValue<IkReal> x716 = IKatan2WithCheck(IkReal((gconst23*new_r01)),IkReal(((-1.0)*gconst24*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 10287 | if(!x716.valid){ |
| 10288 | continue; |
| 10289 | } |
| 10290 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x715.value)))+(x716.value)); |
| 10291 | sj0array[0]=IKsin(j0array[0]); |
| 10292 | cj0array[0]=IKcos(j0array[0]); |
| 10293 | if( j0array[0] > IKPI ) |
| 10294 | { |
| 10295 | j0array[0]-=IK2PI; |
| 10296 | } |
| 10297 | else if( j0array[0] < -IKPI ) |
| 10298 | { j0array[0]+=IK2PI; |
| 10299 | } |
| 10300 | j0valid[0] = true; |
| 10301 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10302 | { |
| 10303 | if( !j0valid[ij0] ) |
| 10304 | { |
| 10305 | continue; |
| 10306 | } |
| 10307 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10308 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10309 | { |
| 10310 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10311 | { |
| 10312 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10313 | } |
| 10314 | } |
| 10315 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10316 | { |
| 10317 | IkReal evalcond[6]; |
| 10318 | IkReal x717=IKsin(j0); |
| 10319 | IkReal x718=IKcos(j0); |
| 10320 | IkReal x719=(gconst23*x718); |
| 10321 | IkReal x720=(gconst24*x717); |
| 10322 | IkReal x721=(gconst24*x718); |
| 10323 | IkReal x722=((1.0)*x717); |
| 10324 | IkReal x723=(x719+x720); |
| 10325 | evalcond[0]=x723; |
| 10326 | evalcond[1]=(((new_r01*x718))+gconst24+((new_r11*x717))); |
| 10327 | evalcond[2]=(x723+new_r11); |
| 10328 | evalcond[3]=((((-1.0)*x721))+((gconst23*x717))); |
| 10329 | evalcond[4]=(gconst23+((new_r11*x718))+(((-1.0)*new_r01*x722))); |
| 10330 | evalcond[5]=((((-1.0)*gconst23*x722))+x721+new_r01); |
| 10331 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 10332 | { |
| 10333 | continue; |
| 10334 | } |
| 10335 | } |
| 10336 | |
| 10337 | { |
| 10338 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10339 | vinfos[0].jointtype = 1; |
| 10340 | vinfos[0].foffset = j0; |
| 10341 | vinfos[0].indices[0] = _ij0[0]; |
| 10342 | vinfos[0].indices[1] = _ij0[1]; |
| 10343 | vinfos[0].maxsolutions = _nj0; |
| 10344 | vinfos[1].jointtype = 1; |
| 10345 | vinfos[1].foffset = j1; |
| 10346 | vinfos[1].indices[0] = _ij1[0]; |
| 10347 | vinfos[1].indices[1] = _ij1[1]; |
| 10348 | vinfos[1].maxsolutions = _nj1; |
| 10349 | vinfos[2].jointtype = 1; |
| 10350 | vinfos[2].foffset = j2; |
| 10351 | vinfos[2].indices[0] = _ij2[0]; |
| 10352 | vinfos[2].indices[1] = _ij2[1]; |
| 10353 | vinfos[2].maxsolutions = _nj2; |
| 10354 | vinfos[3].jointtype = 1; |
| 10355 | vinfos[3].foffset = j3; |
| 10356 | vinfos[3].indices[0] = _ij3[0]; |
| 10357 | vinfos[3].indices[1] = _ij3[1]; |
| 10358 | vinfos[3].maxsolutions = _nj3; |
| 10359 | vinfos[4].jointtype = 1; |
| 10360 | vinfos[4].foffset = j4; |
| 10361 | vinfos[4].indices[0] = _ij4[0]; |
| 10362 | vinfos[4].indices[1] = _ij4[1]; |
| 10363 | vinfos[4].maxsolutions = _nj4; |
| 10364 | vinfos[5].jointtype = 1; |
| 10365 | vinfos[5].foffset = j5; |
| 10366 | vinfos[5].indices[0] = _ij5[0]; |
| 10367 | vinfos[5].indices[1] = _ij5[1]; |
| 10368 | vinfos[5].maxsolutions = _nj5; |
| 10369 | std::vector<int> vfree(0); |
| 10370 | solutions.AddSolution(vinfos,vfree); |
| 10371 | } |
| 10372 | } |
| 10373 | } |
| 10374 | |
| 10375 | } |
| 10376 | |
| 10377 | } |
| 10378 | |
| 10379 | } else |
| 10380 | { |
| 10381 | { |
| 10382 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10383 | bool j0valid[1]={false}; |
| 10384 | _nj0 = 1; |
| 10385 | CheckValue<IkReal> x724 = IKatan2WithCheck(IkReal(gconst23*gconst23),IkReal(((-1.0)*gconst23*gconst24)),IKFAST_ATAN2_MAGTHRESH); |
| 10386 | if(!x724.valid){ |
| 10387 | continue; |
| 10388 | } |
| 10389 | CheckValue<IkReal> x725=IKPowWithIntegerCheck(IKsign((((gconst23*new_r01))+((gconst24*new_r11)))),-1); |
| 10390 | if(!x725.valid){ |
| 10391 | continue; |
| 10392 | } |
| 10393 | j0array[0]=((-1.5707963267949)+(x724.value)+(((1.5707963267949)*(x725.value)))); |
| 10394 | sj0array[0]=IKsin(j0array[0]); |
| 10395 | cj0array[0]=IKcos(j0array[0]); |
| 10396 | if( j0array[0] > IKPI ) |
| 10397 | { |
| 10398 | j0array[0]-=IK2PI; |
| 10399 | } |
| 10400 | else if( j0array[0] < -IKPI ) |
| 10401 | { j0array[0]+=IK2PI; |
| 10402 | } |
| 10403 | j0valid[0] = true; |
| 10404 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10405 | { |
| 10406 | if( !j0valid[ij0] ) |
| 10407 | { |
| 10408 | continue; |
| 10409 | } |
| 10410 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10411 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10412 | { |
| 10413 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10414 | { |
| 10415 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10416 | } |
| 10417 | } |
| 10418 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10419 | { |
| 10420 | IkReal evalcond[6]; |
| 10421 | IkReal x726=IKsin(j0); |
| 10422 | IkReal x727=IKcos(j0); |
| 10423 | IkReal x728=(gconst23*x727); |
| 10424 | IkReal x729=(gconst24*x726); |
| 10425 | IkReal x730=(gconst24*x727); |
| 10426 | IkReal x731=((1.0)*x726); |
| 10427 | IkReal x732=(x728+x729); |
| 10428 | evalcond[0]=x732; |
| 10429 | evalcond[1]=(gconst24+((new_r01*x727))+((new_r11*x726))); |
| 10430 | evalcond[2]=(x732+new_r11); |
| 10431 | evalcond[3]=((((-1.0)*x730))+((gconst23*x726))); |
| 10432 | evalcond[4]=(gconst23+(((-1.0)*new_r01*x731))+((new_r11*x727))); |
| 10433 | evalcond[5]=((((-1.0)*gconst23*x731))+x730+new_r01); |
| 10434 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 10435 | { |
| 10436 | continue; |
| 10437 | } |
| 10438 | } |
| 10439 | |
| 10440 | { |
| 10441 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10442 | vinfos[0].jointtype = 1; |
| 10443 | vinfos[0].foffset = j0; |
| 10444 | vinfos[0].indices[0] = _ij0[0]; |
| 10445 | vinfos[0].indices[1] = _ij0[1]; |
| 10446 | vinfos[0].maxsolutions = _nj0; |
| 10447 | vinfos[1].jointtype = 1; |
| 10448 | vinfos[1].foffset = j1; |
| 10449 | vinfos[1].indices[0] = _ij1[0]; |
| 10450 | vinfos[1].indices[1] = _ij1[1]; |
| 10451 | vinfos[1].maxsolutions = _nj1; |
| 10452 | vinfos[2].jointtype = 1; |
| 10453 | vinfos[2].foffset = j2; |
| 10454 | vinfos[2].indices[0] = _ij2[0]; |
| 10455 | vinfos[2].indices[1] = _ij2[1]; |
| 10456 | vinfos[2].maxsolutions = _nj2; |
| 10457 | vinfos[3].jointtype = 1; |
| 10458 | vinfos[3].foffset = j3; |
| 10459 | vinfos[3].indices[0] = _ij3[0]; |
| 10460 | vinfos[3].indices[1] = _ij3[1]; |
| 10461 | vinfos[3].maxsolutions = _nj3; |
| 10462 | vinfos[4].jointtype = 1; |
| 10463 | vinfos[4].foffset = j4; |
| 10464 | vinfos[4].indices[0] = _ij4[0]; |
| 10465 | vinfos[4].indices[1] = _ij4[1]; |
| 10466 | vinfos[4].maxsolutions = _nj4; |
| 10467 | vinfos[5].jointtype = 1; |
| 10468 | vinfos[5].foffset = j5; |
| 10469 | vinfos[5].indices[0] = _ij5[0]; |
| 10470 | vinfos[5].indices[1] = _ij5[1]; |
| 10471 | vinfos[5].maxsolutions = _nj5; |
| 10472 | std::vector<int> vfree(0); |
| 10473 | solutions.AddSolution(vinfos,vfree); |
| 10474 | } |
| 10475 | } |
| 10476 | } |
| 10477 | |
| 10478 | } |
| 10479 | |
| 10480 | } |
| 10481 | |
| 10482 | } |
| 10483 | } while(0); |
| 10484 | if( bgotonextstatement ) |
| 10485 | { |
| 10486 | bool bgotonextstatement = true; |
| 10487 | do |
| 10488 | { |
| 10489 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 10490 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 10491 | { |
| 10492 | bgotonextstatement=false; |
| 10493 | { |
| 10494 | IkReal j0eval[1]; |
| 10495 | IkReal x733=((-1.0)*new_r11); |
| 10496 | CheckValue<IkReal> x735 = IKatan2WithCheck(IkReal(0),IkReal(x733),IKFAST_ATAN2_MAGTHRESH); |
| 10497 | if(!x735.valid){ |
| 10498 | continue; |
| 10499 | } |
| 10500 | IkReal x734=((-1.0)*(x735.value)); |
| 10501 | sj1=1.0; |
| 10502 | cj1=0; |
| 10503 | j1=1.5707963267949; |
| 10504 | sj2=gconst23; |
| 10505 | cj2=gconst24; |
| 10506 | j2=x734; |
| 10507 | new_r00=0; |
| 10508 | new_r01=0; |
| 10509 | new_r12=0; |
| 10510 | new_r22=0; |
| 10511 | IkReal gconst22=x734; |
| 10512 | IkReal gconst23=0; |
| 10513 | IkReal x736 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 10514 | if(IKabs(x736)==0){ |
| 10515 | continue; |
| 10516 | } |
| 10517 | IkReal gconst24=(x733*(pow(x736,-0.5))); |
| 10518 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 10519 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 10520 | { |
| 10521 | { |
| 10522 | IkReal j0eval[2]; |
| 10523 | IkReal x737=((-1.0)*new_r11); |
| 10524 | CheckValue<IkReal> x739 = IKatan2WithCheck(IkReal(0),IkReal(x737),IKFAST_ATAN2_MAGTHRESH); |
| 10525 | if(!x739.valid){ |
| 10526 | continue; |
| 10527 | } |
| 10528 | IkReal x738=((-1.0)*(x739.value)); |
| 10529 | sj1=1.0; |
| 10530 | cj1=0; |
| 10531 | j1=1.5707963267949; |
| 10532 | sj2=gconst23; |
| 10533 | cj2=gconst24; |
| 10534 | j2=x738; |
| 10535 | new_r00=0; |
| 10536 | new_r01=0; |
| 10537 | new_r12=0; |
| 10538 | new_r22=0; |
| 10539 | IkReal gconst22=x738; |
| 10540 | IkReal gconst23=0; |
| 10541 | IkReal x740 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 10542 | if(IKabs(x740)==0){ |
| 10543 | continue; |
| 10544 | } |
| 10545 | IkReal gconst24=(x737*(pow(x740,-0.5))); |
| 10546 | j0eval[0]=new_r11; |
| 10547 | j0eval[1]=new_r10; |
| 10548 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 10549 | { |
| 10550 | { |
| 10551 | IkReal j0eval[1]; |
| 10552 | IkReal x741=((-1.0)*new_r11); |
| 10553 | CheckValue<IkReal> x743 = IKatan2WithCheck(IkReal(0),IkReal(x741),IKFAST_ATAN2_MAGTHRESH); |
| 10554 | if(!x743.valid){ |
| 10555 | continue; |
| 10556 | } |
| 10557 | IkReal x742=((-1.0)*(x743.value)); |
| 10558 | sj1=1.0; |
| 10559 | cj1=0; |
| 10560 | j1=1.5707963267949; |
| 10561 | sj2=gconst23; |
| 10562 | cj2=gconst24; |
| 10563 | j2=x742; |
| 10564 | new_r00=0; |
| 10565 | new_r01=0; |
| 10566 | new_r12=0; |
| 10567 | new_r22=0; |
| 10568 | IkReal gconst22=x742; |
| 10569 | IkReal gconst23=0; |
| 10570 | IkReal x744 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 10571 | if(IKabs(x744)==0){ |
| 10572 | continue; |
| 10573 | } |
| 10574 | IkReal gconst24=(x741*(pow(x744,-0.5))); |
| 10575 | j0eval[0]=new_r11; |
| 10576 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 10577 | { |
| 10578 | continue; // 3 cases reached |
| 10579 | |
| 10580 | } else |
| 10581 | { |
| 10582 | { |
| 10583 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10584 | bool j0valid[1]={false}; |
| 10585 | _nj0 = 1; |
| 10586 | CheckValue<IkReal> x745=IKPowWithIntegerCheck(new_r11,-1); |
| 10587 | if(!x745.valid){ |
| 10588 | continue; |
| 10589 | } |
| 10590 | CheckValue<IkReal> x746=IKPowWithIntegerCheck(gconst24,-1); |
| 10591 | if(!x746.valid){ |
| 10592 | continue; |
| 10593 | } |
| 10594 | if( IKabs(((-1.0)*gconst24*(x745.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r10*(x746.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst24*(x745.value)))+IKsqr((new_r10*(x746.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 10595 | continue; |
| 10596 | j0array[0]=IKatan2(((-1.0)*gconst24*(x745.value)), (new_r10*(x746.value))); |
| 10597 | sj0array[0]=IKsin(j0array[0]); |
| 10598 | cj0array[0]=IKcos(j0array[0]); |
| 10599 | if( j0array[0] > IKPI ) |
| 10600 | { |
| 10601 | j0array[0]-=IK2PI; |
| 10602 | } |
| 10603 | else if( j0array[0] < -IKPI ) |
| 10604 | { j0array[0]+=IK2PI; |
| 10605 | } |
| 10606 | j0valid[0] = true; |
| 10607 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10608 | { |
| 10609 | if( !j0valid[ij0] ) |
| 10610 | { |
| 10611 | continue; |
| 10612 | } |
| 10613 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10614 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10615 | { |
| 10616 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10617 | { |
| 10618 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10619 | } |
| 10620 | } |
| 10621 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10622 | { |
| 10623 | IkReal evalcond[8]; |
| 10624 | IkReal x747=IKsin(j0); |
| 10625 | IkReal x748=IKcos(j0); |
| 10626 | IkReal x749=(gconst24*x747); |
| 10627 | IkReal x750=((1.0)*x748); |
| 10628 | evalcond[0]=(new_r11*x748); |
| 10629 | evalcond[1]=(new_r10*x747); |
| 10630 | evalcond[2]=x749; |
| 10631 | evalcond[3]=(gconst24*x748); |
| 10632 | evalcond[4]=(gconst24+((new_r11*x747))); |
| 10633 | evalcond[5]=(x749+new_r11); |
| 10634 | evalcond[6]=(gconst24+(((-1.0)*new_r10*x750))); |
| 10635 | evalcond[7]=((((-1.0)*gconst24*x750))+new_r10); |
| 10636 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 10637 | { |
| 10638 | continue; |
| 10639 | } |
| 10640 | } |
| 10641 | |
| 10642 | { |
| 10643 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10644 | vinfos[0].jointtype = 1; |
| 10645 | vinfos[0].foffset = j0; |
| 10646 | vinfos[0].indices[0] = _ij0[0]; |
| 10647 | vinfos[0].indices[1] = _ij0[1]; |
| 10648 | vinfos[0].maxsolutions = _nj0; |
| 10649 | vinfos[1].jointtype = 1; |
| 10650 | vinfos[1].foffset = j1; |
| 10651 | vinfos[1].indices[0] = _ij1[0]; |
| 10652 | vinfos[1].indices[1] = _ij1[1]; |
| 10653 | vinfos[1].maxsolutions = _nj1; |
| 10654 | vinfos[2].jointtype = 1; |
| 10655 | vinfos[2].foffset = j2; |
| 10656 | vinfos[2].indices[0] = _ij2[0]; |
| 10657 | vinfos[2].indices[1] = _ij2[1]; |
| 10658 | vinfos[2].maxsolutions = _nj2; |
| 10659 | vinfos[3].jointtype = 1; |
| 10660 | vinfos[3].foffset = j3; |
| 10661 | vinfos[3].indices[0] = _ij3[0]; |
| 10662 | vinfos[3].indices[1] = _ij3[1]; |
| 10663 | vinfos[3].maxsolutions = _nj3; |
| 10664 | vinfos[4].jointtype = 1; |
| 10665 | vinfos[4].foffset = j4; |
| 10666 | vinfos[4].indices[0] = _ij4[0]; |
| 10667 | vinfos[4].indices[1] = _ij4[1]; |
| 10668 | vinfos[4].maxsolutions = _nj4; |
| 10669 | vinfos[5].jointtype = 1; |
| 10670 | vinfos[5].foffset = j5; |
| 10671 | vinfos[5].indices[0] = _ij5[0]; |
| 10672 | vinfos[5].indices[1] = _ij5[1]; |
| 10673 | vinfos[5].maxsolutions = _nj5; |
| 10674 | std::vector<int> vfree(0); |
| 10675 | solutions.AddSolution(vinfos,vfree); |
| 10676 | } |
| 10677 | } |
| 10678 | } |
| 10679 | |
| 10680 | } |
| 10681 | |
| 10682 | } |
| 10683 | |
| 10684 | } else |
| 10685 | { |
| 10686 | { |
| 10687 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10688 | bool j0valid[1]={false}; |
| 10689 | _nj0 = 1; |
| 10690 | CheckValue<IkReal> x751=IKPowWithIntegerCheck(new_r11,-1); |
| 10691 | if(!x751.valid){ |
| 10692 | continue; |
| 10693 | } |
| 10694 | CheckValue<IkReal> x752=IKPowWithIntegerCheck(new_r10,-1); |
| 10695 | if(!x752.valid){ |
| 10696 | continue; |
| 10697 | } |
| 10698 | if( IKabs(((-1.0)*gconst24*(x751.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst24*(x752.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst24*(x751.value)))+IKsqr((gconst24*(x752.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 10699 | continue; |
| 10700 | j0array[0]=IKatan2(((-1.0)*gconst24*(x751.value)), (gconst24*(x752.value))); |
| 10701 | sj0array[0]=IKsin(j0array[0]); |
| 10702 | cj0array[0]=IKcos(j0array[0]); |
| 10703 | if( j0array[0] > IKPI ) |
| 10704 | { |
| 10705 | j0array[0]-=IK2PI; |
| 10706 | } |
| 10707 | else if( j0array[0] < -IKPI ) |
| 10708 | { j0array[0]+=IK2PI; |
| 10709 | } |
| 10710 | j0valid[0] = true; |
| 10711 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10712 | { |
| 10713 | if( !j0valid[ij0] ) |
| 10714 | { |
| 10715 | continue; |
| 10716 | } |
| 10717 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10718 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10719 | { |
| 10720 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10721 | { |
| 10722 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10723 | } |
| 10724 | } |
| 10725 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10726 | { |
| 10727 | IkReal evalcond[8]; |
| 10728 | IkReal x753=IKsin(j0); |
| 10729 | IkReal x754=IKcos(j0); |
| 10730 | IkReal x755=(gconst24*x753); |
| 10731 | IkReal x756=((1.0)*x754); |
| 10732 | evalcond[0]=(new_r11*x754); |
| 10733 | evalcond[1]=(new_r10*x753); |
| 10734 | evalcond[2]=x755; |
| 10735 | evalcond[3]=(gconst24*x754); |
| 10736 | evalcond[4]=(gconst24+((new_r11*x753))); |
| 10737 | evalcond[5]=(x755+new_r11); |
| 10738 | evalcond[6]=(gconst24+(((-1.0)*new_r10*x756))); |
| 10739 | evalcond[7]=((((-1.0)*gconst24*x756))+new_r10); |
| 10740 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 10741 | { |
| 10742 | continue; |
| 10743 | } |
| 10744 | } |
| 10745 | |
| 10746 | { |
| 10747 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10748 | vinfos[0].jointtype = 1; |
| 10749 | vinfos[0].foffset = j0; |
| 10750 | vinfos[0].indices[0] = _ij0[0]; |
| 10751 | vinfos[0].indices[1] = _ij0[1]; |
| 10752 | vinfos[0].maxsolutions = _nj0; |
| 10753 | vinfos[1].jointtype = 1; |
| 10754 | vinfos[1].foffset = j1; |
| 10755 | vinfos[1].indices[0] = _ij1[0]; |
| 10756 | vinfos[1].indices[1] = _ij1[1]; |
| 10757 | vinfos[1].maxsolutions = _nj1; |
| 10758 | vinfos[2].jointtype = 1; |
| 10759 | vinfos[2].foffset = j2; |
| 10760 | vinfos[2].indices[0] = _ij2[0]; |
| 10761 | vinfos[2].indices[1] = _ij2[1]; |
| 10762 | vinfos[2].maxsolutions = _nj2; |
| 10763 | vinfos[3].jointtype = 1; |
| 10764 | vinfos[3].foffset = j3; |
| 10765 | vinfos[3].indices[0] = _ij3[0]; |
| 10766 | vinfos[3].indices[1] = _ij3[1]; |
| 10767 | vinfos[3].maxsolutions = _nj3; |
| 10768 | vinfos[4].jointtype = 1; |
| 10769 | vinfos[4].foffset = j4; |
| 10770 | vinfos[4].indices[0] = _ij4[0]; |
| 10771 | vinfos[4].indices[1] = _ij4[1]; |
| 10772 | vinfos[4].maxsolutions = _nj4; |
| 10773 | vinfos[5].jointtype = 1; |
| 10774 | vinfos[5].foffset = j5; |
| 10775 | vinfos[5].indices[0] = _ij5[0]; |
| 10776 | vinfos[5].indices[1] = _ij5[1]; |
| 10777 | vinfos[5].maxsolutions = _nj5; |
| 10778 | std::vector<int> vfree(0); |
| 10779 | solutions.AddSolution(vinfos,vfree); |
| 10780 | } |
| 10781 | } |
| 10782 | } |
| 10783 | |
| 10784 | } |
| 10785 | |
| 10786 | } |
| 10787 | |
| 10788 | } else |
| 10789 | { |
| 10790 | { |
| 10791 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10792 | bool j0valid[1]={false}; |
| 10793 | _nj0 = 1; |
| 10794 | CheckValue<IkReal> x757=IKPowWithIntegerCheck(IKsign(gconst24),-1); |
| 10795 | if(!x757.valid){ |
| 10796 | continue; |
| 10797 | } |
| 10798 | CheckValue<IkReal> x758 = IKatan2WithCheck(IkReal(((-1.0)*new_r11)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 10799 | if(!x758.valid){ |
| 10800 | continue; |
| 10801 | } |
| 10802 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x757.value)))+(x758.value)); |
| 10803 | sj0array[0]=IKsin(j0array[0]); |
| 10804 | cj0array[0]=IKcos(j0array[0]); |
| 10805 | if( j0array[0] > IKPI ) |
| 10806 | { |
| 10807 | j0array[0]-=IK2PI; |
| 10808 | } |
| 10809 | else if( j0array[0] < -IKPI ) |
| 10810 | { j0array[0]+=IK2PI; |
| 10811 | } |
| 10812 | j0valid[0] = true; |
| 10813 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 10814 | { |
| 10815 | if( !j0valid[ij0] ) |
| 10816 | { |
| 10817 | continue; |
| 10818 | } |
| 10819 | _ij0[0] = ij0; _ij0[1] = -1; |
| 10820 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 10821 | { |
| 10822 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 10823 | { |
| 10824 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 10825 | } |
| 10826 | } |
| 10827 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 10828 | { |
| 10829 | IkReal evalcond[8]; |
| 10830 | IkReal x759=IKsin(j0); |
| 10831 | IkReal x760=IKcos(j0); |
| 10832 | IkReal x761=(gconst24*x759); |
| 10833 | IkReal x762=((1.0)*x760); |
| 10834 | evalcond[0]=(new_r11*x760); |
| 10835 | evalcond[1]=(new_r10*x759); |
| 10836 | evalcond[2]=x761; |
| 10837 | evalcond[3]=(gconst24*x760); |
| 10838 | evalcond[4]=(gconst24+((new_r11*x759))); |
| 10839 | evalcond[5]=(x761+new_r11); |
| 10840 | evalcond[6]=(gconst24+(((-1.0)*new_r10*x762))); |
| 10841 | evalcond[7]=((((-1.0)*gconst24*x762))+new_r10); |
| 10842 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 10843 | { |
| 10844 | continue; |
| 10845 | } |
| 10846 | } |
| 10847 | |
| 10848 | { |
| 10849 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 10850 | vinfos[0].jointtype = 1; |
| 10851 | vinfos[0].foffset = j0; |
| 10852 | vinfos[0].indices[0] = _ij0[0]; |
| 10853 | vinfos[0].indices[1] = _ij0[1]; |
| 10854 | vinfos[0].maxsolutions = _nj0; |
| 10855 | vinfos[1].jointtype = 1; |
| 10856 | vinfos[1].foffset = j1; |
| 10857 | vinfos[1].indices[0] = _ij1[0]; |
| 10858 | vinfos[1].indices[1] = _ij1[1]; |
| 10859 | vinfos[1].maxsolutions = _nj1; |
| 10860 | vinfos[2].jointtype = 1; |
| 10861 | vinfos[2].foffset = j2; |
| 10862 | vinfos[2].indices[0] = _ij2[0]; |
| 10863 | vinfos[2].indices[1] = _ij2[1]; |
| 10864 | vinfos[2].maxsolutions = _nj2; |
| 10865 | vinfos[3].jointtype = 1; |
| 10866 | vinfos[3].foffset = j3; |
| 10867 | vinfos[3].indices[0] = _ij3[0]; |
| 10868 | vinfos[3].indices[1] = _ij3[1]; |
| 10869 | vinfos[3].maxsolutions = _nj3; |
| 10870 | vinfos[4].jointtype = 1; |
| 10871 | vinfos[4].foffset = j4; |
| 10872 | vinfos[4].indices[0] = _ij4[0]; |
| 10873 | vinfos[4].indices[1] = _ij4[1]; |
| 10874 | vinfos[4].maxsolutions = _nj4; |
| 10875 | vinfos[5].jointtype = 1; |
| 10876 | vinfos[5].foffset = j5; |
| 10877 | vinfos[5].indices[0] = _ij5[0]; |
| 10878 | vinfos[5].indices[1] = _ij5[1]; |
| 10879 | vinfos[5].maxsolutions = _nj5; |
| 10880 | std::vector<int> vfree(0); |
| 10881 | solutions.AddSolution(vinfos,vfree); |
| 10882 | } |
| 10883 | } |
| 10884 | } |
| 10885 | |
| 10886 | } |
| 10887 | |
| 10888 | } |
| 10889 | |
| 10890 | } |
| 10891 | } while(0); |
| 10892 | if( bgotonextstatement ) |
| 10893 | { |
| 10894 | bool bgotonextstatement = true; |
| 10895 | do |
| 10896 | { |
| 10897 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 10898 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 10899 | { |
| 10900 | bgotonextstatement=false; |
| 10901 | { |
| 10902 | IkReal j0eval[1]; |
| 10903 | CheckValue<IkReal> x764 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 10904 | if(!x764.valid){ |
| 10905 | continue; |
| 10906 | } |
| 10907 | IkReal x763=((-1.0)*(x764.value)); |
| 10908 | sj1=1.0; |
| 10909 | cj1=0; |
| 10910 | j1=1.5707963267949; |
| 10911 | sj2=gconst23; |
| 10912 | cj2=gconst24; |
| 10913 | j2=x763; |
| 10914 | new_r11=0; |
| 10915 | new_r10=0; |
| 10916 | new_r22=0; |
| 10917 | new_r02=0; |
| 10918 | IkReal gconst22=x763; |
| 10919 | IkReal x765 = new_r01*new_r01; |
| 10920 | if(IKabs(x765)==0){ |
| 10921 | continue; |
| 10922 | } |
| 10923 | IkReal gconst23=((-1.0)*new_r01*(pow(x765,-0.5))); |
| 10924 | IkReal gconst24=0; |
| 10925 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 10926 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 10927 | { |
| 10928 | { |
| 10929 | IkReal j0eval[2]; |
| 10930 | CheckValue<IkReal> x767 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 10931 | if(!x767.valid){ |
| 10932 | continue; |
| 10933 | } |
| 10934 | IkReal x766=((-1.0)*(x767.value)); |
| 10935 | sj1=1.0; |
| 10936 | cj1=0; |
| 10937 | j1=1.5707963267949; |
| 10938 | sj2=gconst23; |
| 10939 | cj2=gconst24; |
| 10940 | j2=x766; |
| 10941 | new_r11=0; |
| 10942 | new_r10=0; |
| 10943 | new_r22=0; |
| 10944 | new_r02=0; |
| 10945 | IkReal gconst22=x766; |
| 10946 | IkReal x768 = new_r01*new_r01; |
| 10947 | if(IKabs(x768)==0){ |
| 10948 | continue; |
| 10949 | } |
| 10950 | IkReal gconst23=((-1.0)*new_r01*(pow(x768,-0.5))); |
| 10951 | IkReal gconst24=0; |
| 10952 | j0eval[0]=new_r01; |
| 10953 | j0eval[1]=new_r00; |
| 10954 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 10955 | { |
| 10956 | { |
| 10957 | IkReal j0eval[1]; |
| 10958 | CheckValue<IkReal> x770 = IKatan2WithCheck(IkReal(new_r01),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 10959 | if(!x770.valid){ |
| 10960 | continue; |
| 10961 | } |
| 10962 | IkReal x769=((-1.0)*(x770.value)); |
| 10963 | sj1=1.0; |
| 10964 | cj1=0; |
| 10965 | j1=1.5707963267949; |
| 10966 | sj2=gconst23; |
| 10967 | cj2=gconst24; |
| 10968 | j2=x769; |
| 10969 | new_r11=0; |
| 10970 | new_r10=0; |
| 10971 | new_r22=0; |
| 10972 | new_r02=0; |
| 10973 | IkReal gconst22=x769; |
| 10974 | IkReal x771 = new_r01*new_r01; |
| 10975 | if(IKabs(x771)==0){ |
| 10976 | continue; |
| 10977 | } |
| 10978 | IkReal gconst23=((-1.0)*new_r01*(pow(x771,-0.5))); |
| 10979 | IkReal gconst24=0; |
| 10980 | j0eval[0]=new_r00; |
| 10981 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 10982 | { |
| 10983 | continue; // 3 cases reached |
| 10984 | |
| 10985 | } else |
| 10986 | { |
| 10987 | { |
| 10988 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 10989 | bool j0valid[1]={false}; |
| 10990 | _nj0 = 1; |
| 10991 | CheckValue<IkReal> x772=IKPowWithIntegerCheck(gconst23,-1); |
| 10992 | if(!x772.valid){ |
| 10993 | continue; |
| 10994 | } |
| 10995 | CheckValue<IkReal> x773=IKPowWithIntegerCheck(new_r00,-1); |
| 10996 | if(!x773.valid){ |
| 10997 | continue; |
| 10998 | } |
| 10999 | if( IKabs((new_r01*(x772.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst23*(x773.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r01*(x772.value)))+IKsqr(((-1.0)*gconst23*(x773.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 11000 | continue; |
| 11001 | j0array[0]=IKatan2((new_r01*(x772.value)), ((-1.0)*gconst23*(x773.value))); |
| 11002 | sj0array[0]=IKsin(j0array[0]); |
| 11003 | cj0array[0]=IKcos(j0array[0]); |
| 11004 | if( j0array[0] > IKPI ) |
| 11005 | { |
| 11006 | j0array[0]-=IK2PI; |
| 11007 | } |
| 11008 | else if( j0array[0] < -IKPI ) |
| 11009 | { j0array[0]+=IK2PI; |
| 11010 | } |
| 11011 | j0valid[0] = true; |
| 11012 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11013 | { |
| 11014 | if( !j0valid[ij0] ) |
| 11015 | { |
| 11016 | continue; |
| 11017 | } |
| 11018 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11019 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11020 | { |
| 11021 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11022 | { |
| 11023 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11024 | } |
| 11025 | } |
| 11026 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11027 | { |
| 11028 | IkReal evalcond[8]; |
| 11029 | IkReal x774=IKcos(j0); |
| 11030 | IkReal x775=IKsin(j0); |
| 11031 | IkReal x776=(gconst23*x774); |
| 11032 | IkReal x777=(gconst23*x775); |
| 11033 | evalcond[0]=(new_r00*x775); |
| 11034 | evalcond[1]=(new_r01*x774); |
| 11035 | evalcond[2]=x776; |
| 11036 | evalcond[3]=x777; |
| 11037 | evalcond[4]=(gconst23+((new_r00*x774))); |
| 11038 | evalcond[5]=(x776+new_r00); |
| 11039 | evalcond[6]=(gconst23+(((-1.0)*new_r01*x775))); |
| 11040 | evalcond[7]=(new_r01+(((-1.0)*x777))); |
| 11041 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11042 | { |
| 11043 | continue; |
| 11044 | } |
| 11045 | } |
| 11046 | |
| 11047 | { |
| 11048 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11049 | vinfos[0].jointtype = 1; |
| 11050 | vinfos[0].foffset = j0; |
| 11051 | vinfos[0].indices[0] = _ij0[0]; |
| 11052 | vinfos[0].indices[1] = _ij0[1]; |
| 11053 | vinfos[0].maxsolutions = _nj0; |
| 11054 | vinfos[1].jointtype = 1; |
| 11055 | vinfos[1].foffset = j1; |
| 11056 | vinfos[1].indices[0] = _ij1[0]; |
| 11057 | vinfos[1].indices[1] = _ij1[1]; |
| 11058 | vinfos[1].maxsolutions = _nj1; |
| 11059 | vinfos[2].jointtype = 1; |
| 11060 | vinfos[2].foffset = j2; |
| 11061 | vinfos[2].indices[0] = _ij2[0]; |
| 11062 | vinfos[2].indices[1] = _ij2[1]; |
| 11063 | vinfos[2].maxsolutions = _nj2; |
| 11064 | vinfos[3].jointtype = 1; |
| 11065 | vinfos[3].foffset = j3; |
| 11066 | vinfos[3].indices[0] = _ij3[0]; |
| 11067 | vinfos[3].indices[1] = _ij3[1]; |
| 11068 | vinfos[3].maxsolutions = _nj3; |
| 11069 | vinfos[4].jointtype = 1; |
| 11070 | vinfos[4].foffset = j4; |
| 11071 | vinfos[4].indices[0] = _ij4[0]; |
| 11072 | vinfos[4].indices[1] = _ij4[1]; |
| 11073 | vinfos[4].maxsolutions = _nj4; |
| 11074 | vinfos[5].jointtype = 1; |
| 11075 | vinfos[5].foffset = j5; |
| 11076 | vinfos[5].indices[0] = _ij5[0]; |
| 11077 | vinfos[5].indices[1] = _ij5[1]; |
| 11078 | vinfos[5].maxsolutions = _nj5; |
| 11079 | std::vector<int> vfree(0); |
| 11080 | solutions.AddSolution(vinfos,vfree); |
| 11081 | } |
| 11082 | } |
| 11083 | } |
| 11084 | |
| 11085 | } |
| 11086 | |
| 11087 | } |
| 11088 | |
| 11089 | } else |
| 11090 | { |
| 11091 | { |
| 11092 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11093 | bool j0valid[1]={false}; |
| 11094 | _nj0 = 1; |
| 11095 | CheckValue<IkReal> x778=IKPowWithIntegerCheck(new_r01,-1); |
| 11096 | if(!x778.valid){ |
| 11097 | continue; |
| 11098 | } |
| 11099 | CheckValue<IkReal> x779=IKPowWithIntegerCheck(new_r00,-1); |
| 11100 | if(!x779.valid){ |
| 11101 | continue; |
| 11102 | } |
| 11103 | if( IKabs((gconst23*(x778.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst23*(x779.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst23*(x778.value)))+IKsqr(((-1.0)*gconst23*(x779.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 11104 | continue; |
| 11105 | j0array[0]=IKatan2((gconst23*(x778.value)), ((-1.0)*gconst23*(x779.value))); |
| 11106 | sj0array[0]=IKsin(j0array[0]); |
| 11107 | cj0array[0]=IKcos(j0array[0]); |
| 11108 | if( j0array[0] > IKPI ) |
| 11109 | { |
| 11110 | j0array[0]-=IK2PI; |
| 11111 | } |
| 11112 | else if( j0array[0] < -IKPI ) |
| 11113 | { j0array[0]+=IK2PI; |
| 11114 | } |
| 11115 | j0valid[0] = true; |
| 11116 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11117 | { |
| 11118 | if( !j0valid[ij0] ) |
| 11119 | { |
| 11120 | continue; |
| 11121 | } |
| 11122 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11123 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11124 | { |
| 11125 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11126 | { |
| 11127 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11128 | } |
| 11129 | } |
| 11130 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11131 | { |
| 11132 | IkReal evalcond[8]; |
| 11133 | IkReal x780=IKcos(j0); |
| 11134 | IkReal x781=IKsin(j0); |
| 11135 | IkReal x782=(gconst23*x780); |
| 11136 | IkReal x783=(gconst23*x781); |
| 11137 | evalcond[0]=(new_r00*x781); |
| 11138 | evalcond[1]=(new_r01*x780); |
| 11139 | evalcond[2]=x782; |
| 11140 | evalcond[3]=x783; |
| 11141 | evalcond[4]=(gconst23+((new_r00*x780))); |
| 11142 | evalcond[5]=(x782+new_r00); |
| 11143 | evalcond[6]=(gconst23+(((-1.0)*new_r01*x781))); |
| 11144 | evalcond[7]=((((-1.0)*x783))+new_r01); |
| 11145 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11146 | { |
| 11147 | continue; |
| 11148 | } |
| 11149 | } |
| 11150 | |
| 11151 | { |
| 11152 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11153 | vinfos[0].jointtype = 1; |
| 11154 | vinfos[0].foffset = j0; |
| 11155 | vinfos[0].indices[0] = _ij0[0]; |
| 11156 | vinfos[0].indices[1] = _ij0[1]; |
| 11157 | vinfos[0].maxsolutions = _nj0; |
| 11158 | vinfos[1].jointtype = 1; |
| 11159 | vinfos[1].foffset = j1; |
| 11160 | vinfos[1].indices[0] = _ij1[0]; |
| 11161 | vinfos[1].indices[1] = _ij1[1]; |
| 11162 | vinfos[1].maxsolutions = _nj1; |
| 11163 | vinfos[2].jointtype = 1; |
| 11164 | vinfos[2].foffset = j2; |
| 11165 | vinfos[2].indices[0] = _ij2[0]; |
| 11166 | vinfos[2].indices[1] = _ij2[1]; |
| 11167 | vinfos[2].maxsolutions = _nj2; |
| 11168 | vinfos[3].jointtype = 1; |
| 11169 | vinfos[3].foffset = j3; |
| 11170 | vinfos[3].indices[0] = _ij3[0]; |
| 11171 | vinfos[3].indices[1] = _ij3[1]; |
| 11172 | vinfos[3].maxsolutions = _nj3; |
| 11173 | vinfos[4].jointtype = 1; |
| 11174 | vinfos[4].foffset = j4; |
| 11175 | vinfos[4].indices[0] = _ij4[0]; |
| 11176 | vinfos[4].indices[1] = _ij4[1]; |
| 11177 | vinfos[4].maxsolutions = _nj4; |
| 11178 | vinfos[5].jointtype = 1; |
| 11179 | vinfos[5].foffset = j5; |
| 11180 | vinfos[5].indices[0] = _ij5[0]; |
| 11181 | vinfos[5].indices[1] = _ij5[1]; |
| 11182 | vinfos[5].maxsolutions = _nj5; |
| 11183 | std::vector<int> vfree(0); |
| 11184 | solutions.AddSolution(vinfos,vfree); |
| 11185 | } |
| 11186 | } |
| 11187 | } |
| 11188 | |
| 11189 | } |
| 11190 | |
| 11191 | } |
| 11192 | |
| 11193 | } else |
| 11194 | { |
| 11195 | { |
| 11196 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11197 | bool j0valid[1]={false}; |
| 11198 | _nj0 = 1; |
| 11199 | CheckValue<IkReal> x784 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 11200 | if(!x784.valid){ |
| 11201 | continue; |
| 11202 | } |
| 11203 | CheckValue<IkReal> x785=IKPowWithIntegerCheck(IKsign(gconst23),-1); |
| 11204 | if(!x785.valid){ |
| 11205 | continue; |
| 11206 | } |
| 11207 | j0array[0]=((-1.5707963267949)+(x784.value)+(((1.5707963267949)*(x785.value)))); |
| 11208 | sj0array[0]=IKsin(j0array[0]); |
| 11209 | cj0array[0]=IKcos(j0array[0]); |
| 11210 | if( j0array[0] > IKPI ) |
| 11211 | { |
| 11212 | j0array[0]-=IK2PI; |
| 11213 | } |
| 11214 | else if( j0array[0] < -IKPI ) |
| 11215 | { j0array[0]+=IK2PI; |
| 11216 | } |
| 11217 | j0valid[0] = true; |
| 11218 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11219 | { |
| 11220 | if( !j0valid[ij0] ) |
| 11221 | { |
| 11222 | continue; |
| 11223 | } |
| 11224 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11225 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11226 | { |
| 11227 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11228 | { |
| 11229 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11230 | } |
| 11231 | } |
| 11232 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11233 | { |
| 11234 | IkReal evalcond[8]; |
| 11235 | IkReal x786=IKcos(j0); |
| 11236 | IkReal x787=IKsin(j0); |
| 11237 | IkReal x788=(gconst23*x786); |
| 11238 | IkReal x789=(gconst23*x787); |
| 11239 | evalcond[0]=(new_r00*x787); |
| 11240 | evalcond[1]=(new_r01*x786); |
| 11241 | evalcond[2]=x788; |
| 11242 | evalcond[3]=x789; |
| 11243 | evalcond[4]=(gconst23+((new_r00*x786))); |
| 11244 | evalcond[5]=(x788+new_r00); |
| 11245 | evalcond[6]=(gconst23+(((-1.0)*new_r01*x787))); |
| 11246 | evalcond[7]=((((-1.0)*x789))+new_r01); |
| 11247 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11248 | { |
| 11249 | continue; |
| 11250 | } |
| 11251 | } |
| 11252 | |
| 11253 | { |
| 11254 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11255 | vinfos[0].jointtype = 1; |
| 11256 | vinfos[0].foffset = j0; |
| 11257 | vinfos[0].indices[0] = _ij0[0]; |
| 11258 | vinfos[0].indices[1] = _ij0[1]; |
| 11259 | vinfos[0].maxsolutions = _nj0; |
| 11260 | vinfos[1].jointtype = 1; |
| 11261 | vinfos[1].foffset = j1; |
| 11262 | vinfos[1].indices[0] = _ij1[0]; |
| 11263 | vinfos[1].indices[1] = _ij1[1]; |
| 11264 | vinfos[1].maxsolutions = _nj1; |
| 11265 | vinfos[2].jointtype = 1; |
| 11266 | vinfos[2].foffset = j2; |
| 11267 | vinfos[2].indices[0] = _ij2[0]; |
| 11268 | vinfos[2].indices[1] = _ij2[1]; |
| 11269 | vinfos[2].maxsolutions = _nj2; |
| 11270 | vinfos[3].jointtype = 1; |
| 11271 | vinfos[3].foffset = j3; |
| 11272 | vinfos[3].indices[0] = _ij3[0]; |
| 11273 | vinfos[3].indices[1] = _ij3[1]; |
| 11274 | vinfos[3].maxsolutions = _nj3; |
| 11275 | vinfos[4].jointtype = 1; |
| 11276 | vinfos[4].foffset = j4; |
| 11277 | vinfos[4].indices[0] = _ij4[0]; |
| 11278 | vinfos[4].indices[1] = _ij4[1]; |
| 11279 | vinfos[4].maxsolutions = _nj4; |
| 11280 | vinfos[5].jointtype = 1; |
| 11281 | vinfos[5].foffset = j5; |
| 11282 | vinfos[5].indices[0] = _ij5[0]; |
| 11283 | vinfos[5].indices[1] = _ij5[1]; |
| 11284 | vinfos[5].maxsolutions = _nj5; |
| 11285 | std::vector<int> vfree(0); |
| 11286 | solutions.AddSolution(vinfos,vfree); |
| 11287 | } |
| 11288 | } |
| 11289 | } |
| 11290 | |
| 11291 | } |
| 11292 | |
| 11293 | } |
| 11294 | |
| 11295 | } |
| 11296 | } while(0); |
| 11297 | if( bgotonextstatement ) |
| 11298 | { |
| 11299 | bool bgotonextstatement = true; |
| 11300 | do |
| 11301 | { |
| 11302 | if( 1 ) |
| 11303 | { |
| 11304 | bgotonextstatement=false; |
| 11305 | continue; // branch miss [j0] |
| 11306 | |
| 11307 | } |
| 11308 | } while(0); |
| 11309 | if( bgotonextstatement ) |
| 11310 | { |
| 11311 | } |
| 11312 | } |
| 11313 | } |
| 11314 | } |
| 11315 | } |
| 11316 | |
| 11317 | } else |
| 11318 | { |
| 11319 | { |
| 11320 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11321 | bool j0valid[1]={false}; |
| 11322 | _nj0 = 1; |
| 11323 | IkReal x790=((1.0)*new_r00); |
| 11324 | CheckValue<IkReal> x791=IKPowWithIntegerCheck(IKsign((((gconst23*new_r10))+(((-1.0)*gconst24*x790)))),-1); |
| 11325 | if(!x791.valid){ |
| 11326 | continue; |
| 11327 | } |
| 11328 | CheckValue<IkReal> x792 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst23*gconst23)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x790))+((gconst23*gconst24)))),IKFAST_ATAN2_MAGTHRESH); |
| 11329 | if(!x792.valid){ |
| 11330 | continue; |
| 11331 | } |
| 11332 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x791.value)))+(x792.value)); |
| 11333 | sj0array[0]=IKsin(j0array[0]); |
| 11334 | cj0array[0]=IKcos(j0array[0]); |
| 11335 | if( j0array[0] > IKPI ) |
| 11336 | { |
| 11337 | j0array[0]-=IK2PI; |
| 11338 | } |
| 11339 | else if( j0array[0] < -IKPI ) |
| 11340 | { j0array[0]+=IK2PI; |
| 11341 | } |
| 11342 | j0valid[0] = true; |
| 11343 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11344 | { |
| 11345 | if( !j0valid[ij0] ) |
| 11346 | { |
| 11347 | continue; |
| 11348 | } |
| 11349 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11350 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11351 | { |
| 11352 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11353 | { |
| 11354 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11355 | } |
| 11356 | } |
| 11357 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11358 | { |
| 11359 | IkReal evalcond[8]; |
| 11360 | IkReal x793=IKsin(j0); |
| 11361 | IkReal x794=IKcos(j0); |
| 11362 | IkReal x795=(gconst23*x794); |
| 11363 | IkReal x796=(gconst24*x793); |
| 11364 | IkReal x797=((1.0)*x794); |
| 11365 | IkReal x798=((1.0)*x793); |
| 11366 | IkReal x799=(x795+x796); |
| 11367 | evalcond[0]=(((new_r10*x793))+gconst23+((new_r00*x794))); |
| 11368 | evalcond[1]=(((new_r11*x793))+gconst24+((new_r01*x794))); |
| 11369 | evalcond[2]=(x799+new_r00); |
| 11370 | evalcond[3]=(x799+new_r11); |
| 11371 | evalcond[4]=((((-1.0)*new_r01*x798))+((new_r11*x794))+gconst23); |
| 11372 | evalcond[5]=(gconst24+(((-1.0)*new_r10*x797))+((new_r00*x793))); |
| 11373 | evalcond[6]=((((-1.0)*gconst23*x798))+((gconst24*x794))+new_r01); |
| 11374 | evalcond[7]=((((-1.0)*gconst24*x797))+((gconst23*x793))+new_r10); |
| 11375 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11376 | { |
| 11377 | continue; |
| 11378 | } |
| 11379 | } |
| 11380 | |
| 11381 | { |
| 11382 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11383 | vinfos[0].jointtype = 1; |
| 11384 | vinfos[0].foffset = j0; |
| 11385 | vinfos[0].indices[0] = _ij0[0]; |
| 11386 | vinfos[0].indices[1] = _ij0[1]; |
| 11387 | vinfos[0].maxsolutions = _nj0; |
| 11388 | vinfos[1].jointtype = 1; |
| 11389 | vinfos[1].foffset = j1; |
| 11390 | vinfos[1].indices[0] = _ij1[0]; |
| 11391 | vinfos[1].indices[1] = _ij1[1]; |
| 11392 | vinfos[1].maxsolutions = _nj1; |
| 11393 | vinfos[2].jointtype = 1; |
| 11394 | vinfos[2].foffset = j2; |
| 11395 | vinfos[2].indices[0] = _ij2[0]; |
| 11396 | vinfos[2].indices[1] = _ij2[1]; |
| 11397 | vinfos[2].maxsolutions = _nj2; |
| 11398 | vinfos[3].jointtype = 1; |
| 11399 | vinfos[3].foffset = j3; |
| 11400 | vinfos[3].indices[0] = _ij3[0]; |
| 11401 | vinfos[3].indices[1] = _ij3[1]; |
| 11402 | vinfos[3].maxsolutions = _nj3; |
| 11403 | vinfos[4].jointtype = 1; |
| 11404 | vinfos[4].foffset = j4; |
| 11405 | vinfos[4].indices[0] = _ij4[0]; |
| 11406 | vinfos[4].indices[1] = _ij4[1]; |
| 11407 | vinfos[4].maxsolutions = _nj4; |
| 11408 | vinfos[5].jointtype = 1; |
| 11409 | vinfos[5].foffset = j5; |
| 11410 | vinfos[5].indices[0] = _ij5[0]; |
| 11411 | vinfos[5].indices[1] = _ij5[1]; |
| 11412 | vinfos[5].maxsolutions = _nj5; |
| 11413 | std::vector<int> vfree(0); |
| 11414 | solutions.AddSolution(vinfos,vfree); |
| 11415 | } |
| 11416 | } |
| 11417 | } |
| 11418 | |
| 11419 | } |
| 11420 | |
| 11421 | } |
| 11422 | |
| 11423 | } else |
| 11424 | { |
| 11425 | { |
| 11426 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11427 | bool j0valid[1]={false}; |
| 11428 | _nj0 = 1; |
| 11429 | IkReal x800=((1.0)*gconst23); |
| 11430 | CheckValue<IkReal> x801 = IKatan2WithCheck(IkReal((((gconst23*new_r00))+(((-1.0)*new_r11*x800)))),IkReal(((((-1.0)*new_r01*x800))+(((-1.0)*new_r10*x800)))),IKFAST_ATAN2_MAGTHRESH); |
| 11431 | if(!x801.valid){ |
| 11432 | continue; |
| 11433 | } |
| 11434 | CheckValue<IkReal> x802=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 11435 | if(!x802.valid){ |
| 11436 | continue; |
| 11437 | } |
| 11438 | j0array[0]=((-1.5707963267949)+(x801.value)+(((1.5707963267949)*(x802.value)))); |
| 11439 | sj0array[0]=IKsin(j0array[0]); |
| 11440 | cj0array[0]=IKcos(j0array[0]); |
| 11441 | if( j0array[0] > IKPI ) |
| 11442 | { |
| 11443 | j0array[0]-=IK2PI; |
| 11444 | } |
| 11445 | else if( j0array[0] < -IKPI ) |
| 11446 | { j0array[0]+=IK2PI; |
| 11447 | } |
| 11448 | j0valid[0] = true; |
| 11449 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11450 | { |
| 11451 | if( !j0valid[ij0] ) |
| 11452 | { |
| 11453 | continue; |
| 11454 | } |
| 11455 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11456 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11457 | { |
| 11458 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11459 | { |
| 11460 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11461 | } |
| 11462 | } |
| 11463 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11464 | { |
| 11465 | IkReal evalcond[8]; |
| 11466 | IkReal x803=IKsin(j0); |
| 11467 | IkReal x804=IKcos(j0); |
| 11468 | IkReal x805=(gconst23*x804); |
| 11469 | IkReal x806=(gconst24*x803); |
| 11470 | IkReal x807=((1.0)*x804); |
| 11471 | IkReal x808=((1.0)*x803); |
| 11472 | IkReal x809=(x805+x806); |
| 11473 | evalcond[0]=(gconst23+((new_r00*x804))+((new_r10*x803))); |
| 11474 | evalcond[1]=(gconst24+((new_r11*x803))+((new_r01*x804))); |
| 11475 | evalcond[2]=(new_r00+x809); |
| 11476 | evalcond[3]=(new_r11+x809); |
| 11477 | evalcond[4]=((((-1.0)*new_r01*x808))+gconst23+((new_r11*x804))); |
| 11478 | evalcond[5]=(gconst24+((new_r00*x803))+(((-1.0)*new_r10*x807))); |
| 11479 | evalcond[6]=(new_r01+(((-1.0)*gconst23*x808))+((gconst24*x804))); |
| 11480 | evalcond[7]=((((-1.0)*gconst24*x807))+((gconst23*x803))+new_r10); |
| 11481 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11482 | { |
| 11483 | continue; |
| 11484 | } |
| 11485 | } |
| 11486 | |
| 11487 | { |
| 11488 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11489 | vinfos[0].jointtype = 1; |
| 11490 | vinfos[0].foffset = j0; |
| 11491 | vinfos[0].indices[0] = _ij0[0]; |
| 11492 | vinfos[0].indices[1] = _ij0[1]; |
| 11493 | vinfos[0].maxsolutions = _nj0; |
| 11494 | vinfos[1].jointtype = 1; |
| 11495 | vinfos[1].foffset = j1; |
| 11496 | vinfos[1].indices[0] = _ij1[0]; |
| 11497 | vinfos[1].indices[1] = _ij1[1]; |
| 11498 | vinfos[1].maxsolutions = _nj1; |
| 11499 | vinfos[2].jointtype = 1; |
| 11500 | vinfos[2].foffset = j2; |
| 11501 | vinfos[2].indices[0] = _ij2[0]; |
| 11502 | vinfos[2].indices[1] = _ij2[1]; |
| 11503 | vinfos[2].maxsolutions = _nj2; |
| 11504 | vinfos[3].jointtype = 1; |
| 11505 | vinfos[3].foffset = j3; |
| 11506 | vinfos[3].indices[0] = _ij3[0]; |
| 11507 | vinfos[3].indices[1] = _ij3[1]; |
| 11508 | vinfos[3].maxsolutions = _nj3; |
| 11509 | vinfos[4].jointtype = 1; |
| 11510 | vinfos[4].foffset = j4; |
| 11511 | vinfos[4].indices[0] = _ij4[0]; |
| 11512 | vinfos[4].indices[1] = _ij4[1]; |
| 11513 | vinfos[4].maxsolutions = _nj4; |
| 11514 | vinfos[5].jointtype = 1; |
| 11515 | vinfos[5].foffset = j5; |
| 11516 | vinfos[5].indices[0] = _ij5[0]; |
| 11517 | vinfos[5].indices[1] = _ij5[1]; |
| 11518 | vinfos[5].maxsolutions = _nj5; |
| 11519 | std::vector<int> vfree(0); |
| 11520 | solutions.AddSolution(vinfos,vfree); |
| 11521 | } |
| 11522 | } |
| 11523 | } |
| 11524 | |
| 11525 | } |
| 11526 | |
| 11527 | } |
| 11528 | |
| 11529 | } else |
| 11530 | { |
| 11531 | { |
| 11532 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11533 | bool j0valid[1]={false}; |
| 11534 | _nj0 = 1; |
| 11535 | CheckValue<IkReal> x810 = IKatan2WithCheck(IkReal((((gconst23*new_r01))+(((-1.0)*gconst24*new_r00)))),IkReal(((((-1.0)*gconst23*new_r11))+((gconst24*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| 11536 | if(!x810.valid){ |
| 11537 | continue; |
| 11538 | } |
| 11539 | CheckValue<IkReal> x811=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| 11540 | if(!x811.valid){ |
| 11541 | continue; |
| 11542 | } |
| 11543 | j0array[0]=((-1.5707963267949)+(x810.value)+(((1.5707963267949)*(x811.value)))); |
| 11544 | sj0array[0]=IKsin(j0array[0]); |
| 11545 | cj0array[0]=IKcos(j0array[0]); |
| 11546 | if( j0array[0] > IKPI ) |
| 11547 | { |
| 11548 | j0array[0]-=IK2PI; |
| 11549 | } |
| 11550 | else if( j0array[0] < -IKPI ) |
| 11551 | { j0array[0]+=IK2PI; |
| 11552 | } |
| 11553 | j0valid[0] = true; |
| 11554 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11555 | { |
| 11556 | if( !j0valid[ij0] ) |
| 11557 | { |
| 11558 | continue; |
| 11559 | } |
| 11560 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11561 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11562 | { |
| 11563 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11564 | { |
| 11565 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11566 | } |
| 11567 | } |
| 11568 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11569 | { |
| 11570 | IkReal evalcond[8]; |
| 11571 | IkReal x812=IKsin(j0); |
| 11572 | IkReal x813=IKcos(j0); |
| 11573 | IkReal x814=(gconst23*x813); |
| 11574 | IkReal x815=(gconst24*x812); |
| 11575 | IkReal x816=((1.0)*x813); |
| 11576 | IkReal x817=((1.0)*x812); |
| 11577 | IkReal x818=(x814+x815); |
| 11578 | evalcond[0]=(((new_r00*x813))+((new_r10*x812))+gconst23); |
| 11579 | evalcond[1]=(((new_r11*x812))+((new_r01*x813))+gconst24); |
| 11580 | evalcond[2]=(new_r00+x818); |
| 11581 | evalcond[3]=(new_r11+x818); |
| 11582 | evalcond[4]=(((new_r11*x813))+gconst23+(((-1.0)*new_r01*x817))); |
| 11583 | evalcond[5]=(((new_r00*x812))+gconst24+(((-1.0)*new_r10*x816))); |
| 11584 | evalcond[6]=((((-1.0)*gconst23*x817))+((gconst24*x813))+new_r01); |
| 11585 | evalcond[7]=(((gconst23*x812))+(((-1.0)*gconst24*x816))+new_r10); |
| 11586 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11587 | { |
| 11588 | continue; |
| 11589 | } |
| 11590 | } |
| 11591 | |
| 11592 | { |
| 11593 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11594 | vinfos[0].jointtype = 1; |
| 11595 | vinfos[0].foffset = j0; |
| 11596 | vinfos[0].indices[0] = _ij0[0]; |
| 11597 | vinfos[0].indices[1] = _ij0[1]; |
| 11598 | vinfos[0].maxsolutions = _nj0; |
| 11599 | vinfos[1].jointtype = 1; |
| 11600 | vinfos[1].foffset = j1; |
| 11601 | vinfos[1].indices[0] = _ij1[0]; |
| 11602 | vinfos[1].indices[1] = _ij1[1]; |
| 11603 | vinfos[1].maxsolutions = _nj1; |
| 11604 | vinfos[2].jointtype = 1; |
| 11605 | vinfos[2].foffset = j2; |
| 11606 | vinfos[2].indices[0] = _ij2[0]; |
| 11607 | vinfos[2].indices[1] = _ij2[1]; |
| 11608 | vinfos[2].maxsolutions = _nj2; |
| 11609 | vinfos[3].jointtype = 1; |
| 11610 | vinfos[3].foffset = j3; |
| 11611 | vinfos[3].indices[0] = _ij3[0]; |
| 11612 | vinfos[3].indices[1] = _ij3[1]; |
| 11613 | vinfos[3].maxsolutions = _nj3; |
| 11614 | vinfos[4].jointtype = 1; |
| 11615 | vinfos[4].foffset = j4; |
| 11616 | vinfos[4].indices[0] = _ij4[0]; |
| 11617 | vinfos[4].indices[1] = _ij4[1]; |
| 11618 | vinfos[4].maxsolutions = _nj4; |
| 11619 | vinfos[5].jointtype = 1; |
| 11620 | vinfos[5].foffset = j5; |
| 11621 | vinfos[5].indices[0] = _ij5[0]; |
| 11622 | vinfos[5].indices[1] = _ij5[1]; |
| 11623 | vinfos[5].maxsolutions = _nj5; |
| 11624 | std::vector<int> vfree(0); |
| 11625 | solutions.AddSolution(vinfos,vfree); |
| 11626 | } |
| 11627 | } |
| 11628 | } |
| 11629 | |
| 11630 | } |
| 11631 | |
| 11632 | } |
| 11633 | |
| 11634 | } |
| 11635 | } while(0); |
| 11636 | if( bgotonextstatement ) |
| 11637 | { |
| 11638 | bool bgotonextstatement = true; |
| 11639 | do |
| 11640 | { |
| 11641 | IkReal x821 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| 11642 | if(IKabs(x821)==0){ |
| 11643 | continue; |
| 11644 | } |
| 11645 | IkReal x819=pow(x821,-0.5); |
| 11646 | IkReal x820=((1.0)*x819); |
| 11647 | CheckValue<IkReal> x822 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 11648 | if(!x822.valid){ |
| 11649 | continue; |
| 11650 | } |
| 11651 | IkReal gconst25=((3.14159265358979)+(((-1.0)*(x822.value)))); |
| 11652 | IkReal gconst26=(new_r01*x820); |
| 11653 | IkReal gconst27=(new_r11*x820); |
| 11654 | CheckValue<IkReal> x823 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 11655 | if(!x823.valid){ |
| 11656 | continue; |
| 11657 | } |
| 11658 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x823.value)+j2)))), 6.28318530717959))); |
| 11659 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 11660 | { |
| 11661 | bgotonextstatement=false; |
| 11662 | { |
| 11663 | IkReal j0eval[3]; |
| 11664 | CheckValue<IkReal> x827 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 11665 | if(!x827.valid){ |
| 11666 | continue; |
| 11667 | } |
| 11668 | IkReal x824=((1.0)*(x827.value)); |
| 11669 | IkReal x825=x819; |
| 11670 | IkReal x826=((1.0)*x825); |
| 11671 | sj1=1.0; |
| 11672 | cj1=0; |
| 11673 | j1=1.5707963267949; |
| 11674 | sj2=gconst26; |
| 11675 | cj2=gconst27; |
| 11676 | j2=((3.14159265)+(((-1.0)*x824))); |
| 11677 | IkReal gconst25=((3.14159265358979)+(((-1.0)*x824))); |
| 11678 | IkReal gconst26=(new_r01*x826); |
| 11679 | IkReal gconst27=(new_r11*x826); |
| 11680 | IkReal x828=new_r01*new_r01; |
| 11681 | IkReal x829=((1.0)*new_r01); |
| 11682 | IkReal x830=((((-1.0)*new_r10*x829))+((new_r00*new_r11))); |
| 11683 | IkReal x831=x819; |
| 11684 | IkReal x832=(new_r11*x831); |
| 11685 | j0eval[0]=x830; |
| 11686 | j0eval[1]=((IKabs(((((-1.0)*new_r00*x832))+((x828*x831)))))+(IKabs(((((-1.0)*x829*x832))+((new_r10*x832)))))); |
| 11687 | j0eval[2]=IKsign(x830); |
| 11688 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 11689 | { |
| 11690 | { |
| 11691 | IkReal j0eval[3]; |
| 11692 | CheckValue<IkReal> x836 = IKatan2WithCheck(IkReal(new_r01),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 11693 | if(!x836.valid){ |
| 11694 | continue; |
| 11695 | } |
| 11696 | IkReal x833=((1.0)*(x836.value)); |
| 11697 | IkReal x834=x819; |
| 11698 | IkReal x835=((1.0)*x834); |
| 11699 | sj1=1.0; |
| 11700 | cj1=0; |
| 11701 | j1=1.5707963267949; |
| 11702 | sj2=gconst26; |
| 11703 | cj2=gconst27; |
| 11704 | j2=((3.14159265)+(((-1.0)*x833))); |
| 11705 | IkReal gconst25=((3.14159265358979)+(((-1.0)*x833))); |
| 11706 | IkReal gconst26=(new_r01*x835); |
| 11707 | IkReal gconst27=(new_r11*x835); |
| 11708 | IkReal x837=new_r01*new_r01; |
| 11709 | IkReal x838=(new_r00*new_r01); |
| 11710 | IkReal x839=(((new_r10*new_r11))+x838); |
| 11711 | IkReal x840=x819; |
| 11712 | IkReal x841=((1.0)*new_r01*x840); |
| 11713 | j0eval[0]=x839; |
| 11714 | j0eval[1]=((IKabs((((x838*x840))+(((-1.0)*new_r11*x841)))))+(IKabs(((((-1.0)*new_r10*x841))+(((-1.0)*x837*x840)))))); |
| 11715 | j0eval[2]=IKsign(x839); |
| 11716 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 11717 | { |
| 11718 | { |
| 11719 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11720 | bool j0valid[1]={false}; |
| 11721 | _nj0 = 1; |
| 11722 | IkReal x842=((1.0)*new_r00); |
| 11723 | CheckValue<IkReal> x843 = IKatan2WithCheck(IkReal(((((-1.0)*(gconst26*gconst26)))+(new_r00*new_r00))),IkReal(((((-1.0)*new_r10*x842))+((gconst26*gconst27)))),IKFAST_ATAN2_MAGTHRESH); |
| 11724 | if(!x843.valid){ |
| 11725 | continue; |
| 11726 | } |
| 11727 | CheckValue<IkReal> x844=IKPowWithIntegerCheck(IKsign((((gconst26*new_r10))+(((-1.0)*gconst27*x842)))),-1); |
| 11728 | if(!x844.valid){ |
| 11729 | continue; |
| 11730 | } |
| 11731 | j0array[0]=((-1.5707963267949)+(x843.value)+(((1.5707963267949)*(x844.value)))); |
| 11732 | sj0array[0]=IKsin(j0array[0]); |
| 11733 | cj0array[0]=IKcos(j0array[0]); |
| 11734 | if( j0array[0] > IKPI ) |
| 11735 | { |
| 11736 | j0array[0]-=IK2PI; |
| 11737 | } |
| 11738 | else if( j0array[0] < -IKPI ) |
| 11739 | { j0array[0]+=IK2PI; |
| 11740 | } |
| 11741 | j0valid[0] = true; |
| 11742 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11743 | { |
| 11744 | if( !j0valid[ij0] ) |
| 11745 | { |
| 11746 | continue; |
| 11747 | } |
| 11748 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11749 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11750 | { |
| 11751 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11752 | { |
| 11753 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11754 | } |
| 11755 | } |
| 11756 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11757 | { |
| 11758 | IkReal evalcond[8]; |
| 11759 | IkReal x845=IKsin(j0); |
| 11760 | IkReal x846=IKcos(j0); |
| 11761 | IkReal x847=(gconst26*x846); |
| 11762 | IkReal x848=(gconst27*x845); |
| 11763 | IkReal x849=(gconst27*x846); |
| 11764 | IkReal x850=(gconst26*x845); |
| 11765 | IkReal x851=(x847+x848); |
| 11766 | evalcond[0]=(((new_r10*x845))+((new_r00*x846))+gconst26); |
| 11767 | evalcond[1]=(gconst27+((new_r01*x846))+((new_r11*x845))); |
| 11768 | evalcond[2]=(new_r00+x851); |
| 11769 | evalcond[3]=(new_r11+x851); |
| 11770 | evalcond[4]=((((-1.0)*new_r01*x845))+gconst26+((new_r11*x846))); |
| 11771 | evalcond[5]=(((new_r00*x845))+gconst27+(((-1.0)*new_r10*x846))); |
| 11772 | evalcond[6]=((((-1.0)*x850))+new_r01+x849); |
| 11773 | evalcond[7]=((((-1.0)*x849))+new_r10+x850); |
| 11774 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11775 | { |
| 11776 | continue; |
| 11777 | } |
| 11778 | } |
| 11779 | |
| 11780 | { |
| 11781 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11782 | vinfos[0].jointtype = 1; |
| 11783 | vinfos[0].foffset = j0; |
| 11784 | vinfos[0].indices[0] = _ij0[0]; |
| 11785 | vinfos[0].indices[1] = _ij0[1]; |
| 11786 | vinfos[0].maxsolutions = _nj0; |
| 11787 | vinfos[1].jointtype = 1; |
| 11788 | vinfos[1].foffset = j1; |
| 11789 | vinfos[1].indices[0] = _ij1[0]; |
| 11790 | vinfos[1].indices[1] = _ij1[1]; |
| 11791 | vinfos[1].maxsolutions = _nj1; |
| 11792 | vinfos[2].jointtype = 1; |
| 11793 | vinfos[2].foffset = j2; |
| 11794 | vinfos[2].indices[0] = _ij2[0]; |
| 11795 | vinfos[2].indices[1] = _ij2[1]; |
| 11796 | vinfos[2].maxsolutions = _nj2; |
| 11797 | vinfos[3].jointtype = 1; |
| 11798 | vinfos[3].foffset = j3; |
| 11799 | vinfos[3].indices[0] = _ij3[0]; |
| 11800 | vinfos[3].indices[1] = _ij3[1]; |
| 11801 | vinfos[3].maxsolutions = _nj3; |
| 11802 | vinfos[4].jointtype = 1; |
| 11803 | vinfos[4].foffset = j4; |
| 11804 | vinfos[4].indices[0] = _ij4[0]; |
| 11805 | vinfos[4].indices[1] = _ij4[1]; |
| 11806 | vinfos[4].maxsolutions = _nj4; |
| 11807 | vinfos[5].jointtype = 1; |
| 11808 | vinfos[5].foffset = j5; |
| 11809 | vinfos[5].indices[0] = _ij5[0]; |
| 11810 | vinfos[5].indices[1] = _ij5[1]; |
| 11811 | vinfos[5].maxsolutions = _nj5; |
| 11812 | std::vector<int> vfree(0); |
| 11813 | solutions.AddSolution(vinfos,vfree); |
| 11814 | } |
| 11815 | } |
| 11816 | } |
| 11817 | |
| 11818 | } else |
| 11819 | { |
| 11820 | { |
| 11821 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11822 | bool j0valid[1]={false}; |
| 11823 | _nj0 = 1; |
| 11824 | IkReal x852=((1.0)*gconst26); |
| 11825 | CheckValue<IkReal> x853 = IKatan2WithCheck(IkReal((((gconst26*new_r00))+(((-1.0)*new_r11*x852)))),IkReal(((((-1.0)*new_r01*x852))+(((-1.0)*new_r10*x852)))),IKFAST_ATAN2_MAGTHRESH); |
| 11826 | if(!x853.valid){ |
| 11827 | continue; |
| 11828 | } |
| 11829 | CheckValue<IkReal> x854=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 11830 | if(!x854.valid){ |
| 11831 | continue; |
| 11832 | } |
| 11833 | j0array[0]=((-1.5707963267949)+(x853.value)+(((1.5707963267949)*(x854.value)))); |
| 11834 | sj0array[0]=IKsin(j0array[0]); |
| 11835 | cj0array[0]=IKcos(j0array[0]); |
| 11836 | if( j0array[0] > IKPI ) |
| 11837 | { |
| 11838 | j0array[0]-=IK2PI; |
| 11839 | } |
| 11840 | else if( j0array[0] < -IKPI ) |
| 11841 | { j0array[0]+=IK2PI; |
| 11842 | } |
| 11843 | j0valid[0] = true; |
| 11844 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11845 | { |
| 11846 | if( !j0valid[ij0] ) |
| 11847 | { |
| 11848 | continue; |
| 11849 | } |
| 11850 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11851 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11852 | { |
| 11853 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11854 | { |
| 11855 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11856 | } |
| 11857 | } |
| 11858 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11859 | { |
| 11860 | IkReal evalcond[8]; |
| 11861 | IkReal x855=IKsin(j0); |
| 11862 | IkReal x856=IKcos(j0); |
| 11863 | IkReal x857=(gconst26*x856); |
| 11864 | IkReal x858=(gconst27*x855); |
| 11865 | IkReal x859=(gconst27*x856); |
| 11866 | IkReal x860=(gconst26*x855); |
| 11867 | IkReal x861=(x857+x858); |
| 11868 | evalcond[0]=(gconst26+((new_r10*x855))+((new_r00*x856))); |
| 11869 | evalcond[1]=(gconst27+((new_r11*x855))+((new_r01*x856))); |
| 11870 | evalcond[2]=(new_r00+x861); |
| 11871 | evalcond[3]=(new_r11+x861); |
| 11872 | evalcond[4]=(gconst26+((new_r11*x856))+(((-1.0)*new_r01*x855))); |
| 11873 | evalcond[5]=(gconst27+(((-1.0)*new_r10*x856))+((new_r00*x855))); |
| 11874 | evalcond[6]=((((-1.0)*x860))+new_r01+x859); |
| 11875 | evalcond[7]=((((-1.0)*x859))+new_r10+x860); |
| 11876 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11877 | { |
| 11878 | continue; |
| 11879 | } |
| 11880 | } |
| 11881 | |
| 11882 | { |
| 11883 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11884 | vinfos[0].jointtype = 1; |
| 11885 | vinfos[0].foffset = j0; |
| 11886 | vinfos[0].indices[0] = _ij0[0]; |
| 11887 | vinfos[0].indices[1] = _ij0[1]; |
| 11888 | vinfos[0].maxsolutions = _nj0; |
| 11889 | vinfos[1].jointtype = 1; |
| 11890 | vinfos[1].foffset = j1; |
| 11891 | vinfos[1].indices[0] = _ij1[0]; |
| 11892 | vinfos[1].indices[1] = _ij1[1]; |
| 11893 | vinfos[1].maxsolutions = _nj1; |
| 11894 | vinfos[2].jointtype = 1; |
| 11895 | vinfos[2].foffset = j2; |
| 11896 | vinfos[2].indices[0] = _ij2[0]; |
| 11897 | vinfos[2].indices[1] = _ij2[1]; |
| 11898 | vinfos[2].maxsolutions = _nj2; |
| 11899 | vinfos[3].jointtype = 1; |
| 11900 | vinfos[3].foffset = j3; |
| 11901 | vinfos[3].indices[0] = _ij3[0]; |
| 11902 | vinfos[3].indices[1] = _ij3[1]; |
| 11903 | vinfos[3].maxsolutions = _nj3; |
| 11904 | vinfos[4].jointtype = 1; |
| 11905 | vinfos[4].foffset = j4; |
| 11906 | vinfos[4].indices[0] = _ij4[0]; |
| 11907 | vinfos[4].indices[1] = _ij4[1]; |
| 11908 | vinfos[4].maxsolutions = _nj4; |
| 11909 | vinfos[5].jointtype = 1; |
| 11910 | vinfos[5].foffset = j5; |
| 11911 | vinfos[5].indices[0] = _ij5[0]; |
| 11912 | vinfos[5].indices[1] = _ij5[1]; |
| 11913 | vinfos[5].maxsolutions = _nj5; |
| 11914 | std::vector<int> vfree(0); |
| 11915 | solutions.AddSolution(vinfos,vfree); |
| 11916 | } |
| 11917 | } |
| 11918 | } |
| 11919 | |
| 11920 | } |
| 11921 | |
| 11922 | } |
| 11923 | |
| 11924 | } else |
| 11925 | { |
| 11926 | { |
| 11927 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 11928 | bool j0valid[1]={false}; |
| 11929 | _nj0 = 1; |
| 11930 | CheckValue<IkReal> x862=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| 11931 | if(!x862.valid){ |
| 11932 | continue; |
| 11933 | } |
| 11934 | CheckValue<IkReal> x863 = IKatan2WithCheck(IkReal((((gconst26*new_r01))+(((-1.0)*gconst27*new_r00)))),IkReal(((((-1.0)*gconst26*new_r11))+((gconst27*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| 11935 | if(!x863.valid){ |
| 11936 | continue; |
| 11937 | } |
| 11938 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x862.value)))+(x863.value)); |
| 11939 | sj0array[0]=IKsin(j0array[0]); |
| 11940 | cj0array[0]=IKcos(j0array[0]); |
| 11941 | if( j0array[0] > IKPI ) |
| 11942 | { |
| 11943 | j0array[0]-=IK2PI; |
| 11944 | } |
| 11945 | else if( j0array[0] < -IKPI ) |
| 11946 | { j0array[0]+=IK2PI; |
| 11947 | } |
| 11948 | j0valid[0] = true; |
| 11949 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 11950 | { |
| 11951 | if( !j0valid[ij0] ) |
| 11952 | { |
| 11953 | continue; |
| 11954 | } |
| 11955 | _ij0[0] = ij0; _ij0[1] = -1; |
| 11956 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 11957 | { |
| 11958 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 11959 | { |
| 11960 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 11961 | } |
| 11962 | } |
| 11963 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 11964 | { |
| 11965 | IkReal evalcond[8]; |
| 11966 | IkReal x864=IKsin(j0); |
| 11967 | IkReal x865=IKcos(j0); |
| 11968 | IkReal x866=(gconst26*x865); |
| 11969 | IkReal x867=(gconst27*x864); |
| 11970 | IkReal x868=(gconst27*x865); |
| 11971 | IkReal x869=(gconst26*x864); |
| 11972 | IkReal x870=(x867+x866); |
| 11973 | evalcond[0]=(((new_r00*x865))+gconst26+((new_r10*x864))); |
| 11974 | evalcond[1]=(((new_r01*x865))+gconst27+((new_r11*x864))); |
| 11975 | evalcond[2]=(new_r00+x870); |
| 11976 | evalcond[3]=(new_r11+x870); |
| 11977 | evalcond[4]=(gconst26+((new_r11*x865))+(((-1.0)*new_r01*x864))); |
| 11978 | evalcond[5]=(((new_r00*x864))+(((-1.0)*new_r10*x865))+gconst27); |
| 11979 | evalcond[6]=((((-1.0)*x869))+new_r01+x868); |
| 11980 | evalcond[7]=((((-1.0)*x868))+new_r10+x869); |
| 11981 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 11982 | { |
| 11983 | continue; |
| 11984 | } |
| 11985 | } |
| 11986 | |
| 11987 | { |
| 11988 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 11989 | vinfos[0].jointtype = 1; |
| 11990 | vinfos[0].foffset = j0; |
| 11991 | vinfos[0].indices[0] = _ij0[0]; |
| 11992 | vinfos[0].indices[1] = _ij0[1]; |
| 11993 | vinfos[0].maxsolutions = _nj0; |
| 11994 | vinfos[1].jointtype = 1; |
| 11995 | vinfos[1].foffset = j1; |
| 11996 | vinfos[1].indices[0] = _ij1[0]; |
| 11997 | vinfos[1].indices[1] = _ij1[1]; |
| 11998 | vinfos[1].maxsolutions = _nj1; |
| 11999 | vinfos[2].jointtype = 1; |
| 12000 | vinfos[2].foffset = j2; |
| 12001 | vinfos[2].indices[0] = _ij2[0]; |
| 12002 | vinfos[2].indices[1] = _ij2[1]; |
| 12003 | vinfos[2].maxsolutions = _nj2; |
| 12004 | vinfos[3].jointtype = 1; |
| 12005 | vinfos[3].foffset = j3; |
| 12006 | vinfos[3].indices[0] = _ij3[0]; |
| 12007 | vinfos[3].indices[1] = _ij3[1]; |
| 12008 | vinfos[3].maxsolutions = _nj3; |
| 12009 | vinfos[4].jointtype = 1; |
| 12010 | vinfos[4].foffset = j4; |
| 12011 | vinfos[4].indices[0] = _ij4[0]; |
| 12012 | vinfos[4].indices[1] = _ij4[1]; |
| 12013 | vinfos[4].maxsolutions = _nj4; |
| 12014 | vinfos[5].jointtype = 1; |
| 12015 | vinfos[5].foffset = j5; |
| 12016 | vinfos[5].indices[0] = _ij5[0]; |
| 12017 | vinfos[5].indices[1] = _ij5[1]; |
| 12018 | vinfos[5].maxsolutions = _nj5; |
| 12019 | std::vector<int> vfree(0); |
| 12020 | solutions.AddSolution(vinfos,vfree); |
| 12021 | } |
| 12022 | } |
| 12023 | } |
| 12024 | |
| 12025 | } |
| 12026 | |
| 12027 | } |
| 12028 | |
| 12029 | } |
| 12030 | } while(0); |
| 12031 | if( bgotonextstatement ) |
| 12032 | { |
| 12033 | bool bgotonextstatement = true; |
| 12034 | do |
| 12035 | { |
| 12036 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 12037 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 12038 | { |
| 12039 | bgotonextstatement=false; |
| 12040 | { |
| 12041 | IkReal j0eval[1]; |
| 12042 | sj1=1.0; |
| 12043 | cj1=0; |
| 12044 | j1=1.5707963267949; |
| 12045 | new_r11=0; |
| 12046 | new_r01=0; |
| 12047 | new_r22=0; |
| 12048 | new_r20=0; |
| 12049 | j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 12050 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 12051 | { |
| 12052 | continue; // no branches [j0] |
| 12053 | |
| 12054 | } else |
| 12055 | { |
| 12056 | { |
| 12057 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 12058 | bool j0valid[2]={false}; |
| 12059 | _nj0 = 2; |
| 12060 | CheckValue<IkReal> x872 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 12061 | if(!x872.valid){ |
| 12062 | continue; |
| 12063 | } |
| 12064 | IkReal x871=x872.value; |
| 12065 | j0array[0]=((-1.0)*x871); |
| 12066 | sj0array[0]=IKsin(j0array[0]); |
| 12067 | cj0array[0]=IKcos(j0array[0]); |
| 12068 | j0array[1]=((3.14159265358979)+(((-1.0)*x871))); |
| 12069 | sj0array[1]=IKsin(j0array[1]); |
| 12070 | cj0array[1]=IKcos(j0array[1]); |
| 12071 | if( j0array[0] > IKPI ) |
| 12072 | { |
| 12073 | j0array[0]-=IK2PI; |
| 12074 | } |
| 12075 | else if( j0array[0] < -IKPI ) |
| 12076 | { j0array[0]+=IK2PI; |
| 12077 | } |
| 12078 | j0valid[0] = true; |
| 12079 | if( j0array[1] > IKPI ) |
| 12080 | { |
| 12081 | j0array[1]-=IK2PI; |
| 12082 | } |
| 12083 | else if( j0array[1] < -IKPI ) |
| 12084 | { j0array[1]+=IK2PI; |
| 12085 | } |
| 12086 | j0valid[1] = true; |
| 12087 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 12088 | { |
| 12089 | if( !j0valid[ij0] ) |
| 12090 | { |
| 12091 | continue; |
| 12092 | } |
| 12093 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12094 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 12095 | { |
| 12096 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12097 | { |
| 12098 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12099 | } |
| 12100 | } |
| 12101 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12102 | { |
| 12103 | IkReal evalcond[1]; |
| 12104 | evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0))))); |
| 12105 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| 12106 | { |
| 12107 | continue; |
| 12108 | } |
| 12109 | } |
| 12110 | |
| 12111 | { |
| 12112 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12113 | vinfos[0].jointtype = 1; |
| 12114 | vinfos[0].foffset = j0; |
| 12115 | vinfos[0].indices[0] = _ij0[0]; |
| 12116 | vinfos[0].indices[1] = _ij0[1]; |
| 12117 | vinfos[0].maxsolutions = _nj0; |
| 12118 | vinfos[1].jointtype = 1; |
| 12119 | vinfos[1].foffset = j1; |
| 12120 | vinfos[1].indices[0] = _ij1[0]; |
| 12121 | vinfos[1].indices[1] = _ij1[1]; |
| 12122 | vinfos[1].maxsolutions = _nj1; |
| 12123 | vinfos[2].jointtype = 1; |
| 12124 | vinfos[2].foffset = j2; |
| 12125 | vinfos[2].indices[0] = _ij2[0]; |
| 12126 | vinfos[2].indices[1] = _ij2[1]; |
| 12127 | vinfos[2].maxsolutions = _nj2; |
| 12128 | vinfos[3].jointtype = 1; |
| 12129 | vinfos[3].foffset = j3; |
| 12130 | vinfos[3].indices[0] = _ij3[0]; |
| 12131 | vinfos[3].indices[1] = _ij3[1]; |
| 12132 | vinfos[3].maxsolutions = _nj3; |
| 12133 | vinfos[4].jointtype = 1; |
| 12134 | vinfos[4].foffset = j4; |
| 12135 | vinfos[4].indices[0] = _ij4[0]; |
| 12136 | vinfos[4].indices[1] = _ij4[1]; |
| 12137 | vinfos[4].maxsolutions = _nj4; |
| 12138 | vinfos[5].jointtype = 1; |
| 12139 | vinfos[5].foffset = j5; |
| 12140 | vinfos[5].indices[0] = _ij5[0]; |
| 12141 | vinfos[5].indices[1] = _ij5[1]; |
| 12142 | vinfos[5].maxsolutions = _nj5; |
| 12143 | std::vector<int> vfree(0); |
| 12144 | solutions.AddSolution(vinfos,vfree); |
| 12145 | } |
| 12146 | } |
| 12147 | } |
| 12148 | |
| 12149 | } |
| 12150 | |
| 12151 | } |
| 12152 | |
| 12153 | } |
| 12154 | } while(0); |
| 12155 | if( bgotonextstatement ) |
| 12156 | { |
| 12157 | bool bgotonextstatement = true; |
| 12158 | do |
| 12159 | { |
| 12160 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 12161 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 12162 | { |
| 12163 | bgotonextstatement=false; |
| 12164 | { |
| 12165 | IkReal j0eval[3]; |
| 12166 | sj1=1.0; |
| 12167 | cj1=0; |
| 12168 | j1=1.5707963267949; |
| 12169 | new_r11=0; |
| 12170 | new_r10=0; |
| 12171 | new_r22=0; |
| 12172 | new_r02=0; |
| 12173 | j0eval[0]=new_r01; |
| 12174 | j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| 12175 | j0eval[2]=IKsign(new_r01); |
| 12176 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 12177 | { |
| 12178 | { |
| 12179 | IkReal j0eval[3]; |
| 12180 | sj1=1.0; |
| 12181 | cj1=0; |
| 12182 | j1=1.5707963267949; |
| 12183 | new_r11=0; |
| 12184 | new_r10=0; |
| 12185 | new_r22=0; |
| 12186 | new_r02=0; |
| 12187 | j0eval[0]=new_r00; |
| 12188 | j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| 12189 | j0eval[2]=IKsign(new_r00); |
| 12190 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 12191 | { |
| 12192 | { |
| 12193 | IkReal j0eval[2]; |
| 12194 | sj1=1.0; |
| 12195 | cj1=0; |
| 12196 | j1=1.5707963267949; |
| 12197 | new_r11=0; |
| 12198 | new_r10=0; |
| 12199 | new_r22=0; |
| 12200 | new_r02=0; |
| 12201 | j0eval[0]=new_r01; |
| 12202 | j0eval[1]=new_r00; |
| 12203 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 12204 | { |
| 12205 | continue; // no branches [j0] |
| 12206 | |
| 12207 | } else |
| 12208 | { |
| 12209 | { |
| 12210 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12211 | bool j0valid[1]={false}; |
| 12212 | _nj0 = 1; |
| 12213 | CheckValue<IkReal> x873=IKPowWithIntegerCheck(new_r01,-1); |
| 12214 | if(!x873.valid){ |
| 12215 | continue; |
| 12216 | } |
| 12217 | CheckValue<IkReal> x874=IKPowWithIntegerCheck(new_r00,-1); |
| 12218 | if(!x874.valid){ |
| 12219 | continue; |
| 12220 | } |
| 12221 | if( IKabs((sj2*(x873.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj2*(x874.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x873.value)))+IKsqr(((-1.0)*sj2*(x874.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 12222 | continue; |
| 12223 | j0array[0]=IKatan2((sj2*(x873.value)), ((-1.0)*sj2*(x874.value))); |
| 12224 | sj0array[0]=IKsin(j0array[0]); |
| 12225 | cj0array[0]=IKcos(j0array[0]); |
| 12226 | if( j0array[0] > IKPI ) |
| 12227 | { |
| 12228 | j0array[0]-=IK2PI; |
| 12229 | } |
| 12230 | else if( j0array[0] < -IKPI ) |
| 12231 | { j0array[0]+=IK2PI; |
| 12232 | } |
| 12233 | j0valid[0] = true; |
| 12234 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12235 | { |
| 12236 | if( !j0valid[ij0] ) |
| 12237 | { |
| 12238 | continue; |
| 12239 | } |
| 12240 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12241 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12242 | { |
| 12243 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12244 | { |
| 12245 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12246 | } |
| 12247 | } |
| 12248 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12249 | { |
| 12250 | IkReal evalcond[8]; |
| 12251 | IkReal x875=IKcos(j0); |
| 12252 | IkReal x876=IKsin(j0); |
| 12253 | IkReal x877=(sj2*x875); |
| 12254 | IkReal x878=(cj2*x876); |
| 12255 | IkReal x879=(sj2*x876); |
| 12256 | IkReal x880=(cj2*x875); |
| 12257 | IkReal x881=(x878+x877); |
| 12258 | evalcond[0]=(((new_r00*x876))+cj2); |
| 12259 | evalcond[1]=(((new_r00*x875))+sj2); |
| 12260 | evalcond[2]=(((new_r01*x875))+cj2); |
| 12261 | evalcond[3]=(sj2+(((-1.0)*new_r01*x876))); |
| 12262 | evalcond[4]=x881; |
| 12263 | evalcond[5]=(new_r00+x881); |
| 12264 | evalcond[6]=((((-1.0)*x880))+x879); |
| 12265 | evalcond[7]=((((-1.0)*x879))+new_r01+x880); |
| 12266 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12267 | { |
| 12268 | continue; |
| 12269 | } |
| 12270 | } |
| 12271 | |
| 12272 | { |
| 12273 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12274 | vinfos[0].jointtype = 1; |
| 12275 | vinfos[0].foffset = j0; |
| 12276 | vinfos[0].indices[0] = _ij0[0]; |
| 12277 | vinfos[0].indices[1] = _ij0[1]; |
| 12278 | vinfos[0].maxsolutions = _nj0; |
| 12279 | vinfos[1].jointtype = 1; |
| 12280 | vinfos[1].foffset = j1; |
| 12281 | vinfos[1].indices[0] = _ij1[0]; |
| 12282 | vinfos[1].indices[1] = _ij1[1]; |
| 12283 | vinfos[1].maxsolutions = _nj1; |
| 12284 | vinfos[2].jointtype = 1; |
| 12285 | vinfos[2].foffset = j2; |
| 12286 | vinfos[2].indices[0] = _ij2[0]; |
| 12287 | vinfos[2].indices[1] = _ij2[1]; |
| 12288 | vinfos[2].maxsolutions = _nj2; |
| 12289 | vinfos[3].jointtype = 1; |
| 12290 | vinfos[3].foffset = j3; |
| 12291 | vinfos[3].indices[0] = _ij3[0]; |
| 12292 | vinfos[3].indices[1] = _ij3[1]; |
| 12293 | vinfos[3].maxsolutions = _nj3; |
| 12294 | vinfos[4].jointtype = 1; |
| 12295 | vinfos[4].foffset = j4; |
| 12296 | vinfos[4].indices[0] = _ij4[0]; |
| 12297 | vinfos[4].indices[1] = _ij4[1]; |
| 12298 | vinfos[4].maxsolutions = _nj4; |
| 12299 | vinfos[5].jointtype = 1; |
| 12300 | vinfos[5].foffset = j5; |
| 12301 | vinfos[5].indices[0] = _ij5[0]; |
| 12302 | vinfos[5].indices[1] = _ij5[1]; |
| 12303 | vinfos[5].maxsolutions = _nj5; |
| 12304 | std::vector<int> vfree(0); |
| 12305 | solutions.AddSolution(vinfos,vfree); |
| 12306 | } |
| 12307 | } |
| 12308 | } |
| 12309 | |
| 12310 | } |
| 12311 | |
| 12312 | } |
| 12313 | |
| 12314 | } else |
| 12315 | { |
| 12316 | { |
| 12317 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12318 | bool j0valid[1]={false}; |
| 12319 | _nj0 = 1; |
| 12320 | CheckValue<IkReal> x882 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| 12321 | if(!x882.valid){ |
| 12322 | continue; |
| 12323 | } |
| 12324 | CheckValue<IkReal> x883=IKPowWithIntegerCheck(IKsign(new_r00),-1); |
| 12325 | if(!x883.valid){ |
| 12326 | continue; |
| 12327 | } |
| 12328 | j0array[0]=((-1.5707963267949)+(x882.value)+(((1.5707963267949)*(x883.value)))); |
| 12329 | sj0array[0]=IKsin(j0array[0]); |
| 12330 | cj0array[0]=IKcos(j0array[0]); |
| 12331 | if( j0array[0] > IKPI ) |
| 12332 | { |
| 12333 | j0array[0]-=IK2PI; |
| 12334 | } |
| 12335 | else if( j0array[0] < -IKPI ) |
| 12336 | { j0array[0]+=IK2PI; |
| 12337 | } |
| 12338 | j0valid[0] = true; |
| 12339 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12340 | { |
| 12341 | if( !j0valid[ij0] ) |
| 12342 | { |
| 12343 | continue; |
| 12344 | } |
| 12345 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12346 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12347 | { |
| 12348 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12349 | { |
| 12350 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12351 | } |
| 12352 | } |
| 12353 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12354 | { |
| 12355 | IkReal evalcond[8]; |
| 12356 | IkReal x884=IKcos(j0); |
| 12357 | IkReal x885=IKsin(j0); |
| 12358 | IkReal x886=(sj2*x884); |
| 12359 | IkReal x887=(cj2*x885); |
| 12360 | IkReal x888=(sj2*x885); |
| 12361 | IkReal x889=(cj2*x884); |
| 12362 | IkReal x890=(x887+x886); |
| 12363 | evalcond[0]=(cj2+((new_r00*x885))); |
| 12364 | evalcond[1]=(sj2+((new_r00*x884))); |
| 12365 | evalcond[2]=(cj2+((new_r01*x884))); |
| 12366 | evalcond[3]=(sj2+(((-1.0)*new_r01*x885))); |
| 12367 | evalcond[4]=x890; |
| 12368 | evalcond[5]=(new_r00+x890); |
| 12369 | evalcond[6]=((((-1.0)*x889))+x888); |
| 12370 | evalcond[7]=((((-1.0)*x888))+new_r01+x889); |
| 12371 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12372 | { |
| 12373 | continue; |
| 12374 | } |
| 12375 | } |
| 12376 | |
| 12377 | { |
| 12378 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12379 | vinfos[0].jointtype = 1; |
| 12380 | vinfos[0].foffset = j0; |
| 12381 | vinfos[0].indices[0] = _ij0[0]; |
| 12382 | vinfos[0].indices[1] = _ij0[1]; |
| 12383 | vinfos[0].maxsolutions = _nj0; |
| 12384 | vinfos[1].jointtype = 1; |
| 12385 | vinfos[1].foffset = j1; |
| 12386 | vinfos[1].indices[0] = _ij1[0]; |
| 12387 | vinfos[1].indices[1] = _ij1[1]; |
| 12388 | vinfos[1].maxsolutions = _nj1; |
| 12389 | vinfos[2].jointtype = 1; |
| 12390 | vinfos[2].foffset = j2; |
| 12391 | vinfos[2].indices[0] = _ij2[0]; |
| 12392 | vinfos[2].indices[1] = _ij2[1]; |
| 12393 | vinfos[2].maxsolutions = _nj2; |
| 12394 | vinfos[3].jointtype = 1; |
| 12395 | vinfos[3].foffset = j3; |
| 12396 | vinfos[3].indices[0] = _ij3[0]; |
| 12397 | vinfos[3].indices[1] = _ij3[1]; |
| 12398 | vinfos[3].maxsolutions = _nj3; |
| 12399 | vinfos[4].jointtype = 1; |
| 12400 | vinfos[4].foffset = j4; |
| 12401 | vinfos[4].indices[0] = _ij4[0]; |
| 12402 | vinfos[4].indices[1] = _ij4[1]; |
| 12403 | vinfos[4].maxsolutions = _nj4; |
| 12404 | vinfos[5].jointtype = 1; |
| 12405 | vinfos[5].foffset = j5; |
| 12406 | vinfos[5].indices[0] = _ij5[0]; |
| 12407 | vinfos[5].indices[1] = _ij5[1]; |
| 12408 | vinfos[5].maxsolutions = _nj5; |
| 12409 | std::vector<int> vfree(0); |
| 12410 | solutions.AddSolution(vinfos,vfree); |
| 12411 | } |
| 12412 | } |
| 12413 | } |
| 12414 | |
| 12415 | } |
| 12416 | |
| 12417 | } |
| 12418 | |
| 12419 | } else |
| 12420 | { |
| 12421 | { |
| 12422 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12423 | bool j0valid[1]={false}; |
| 12424 | _nj0 = 1; |
| 12425 | CheckValue<IkReal> x891=IKPowWithIntegerCheck(IKsign(new_r01),-1); |
| 12426 | if(!x891.valid){ |
| 12427 | continue; |
| 12428 | } |
| 12429 | CheckValue<IkReal> x892 = IKatan2WithCheck(IkReal(sj2),IkReal(((-1.0)*cj2)),IKFAST_ATAN2_MAGTHRESH); |
| 12430 | if(!x892.valid){ |
| 12431 | continue; |
| 12432 | } |
| 12433 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x891.value)))+(x892.value)); |
| 12434 | sj0array[0]=IKsin(j0array[0]); |
| 12435 | cj0array[0]=IKcos(j0array[0]); |
| 12436 | if( j0array[0] > IKPI ) |
| 12437 | { |
| 12438 | j0array[0]-=IK2PI; |
| 12439 | } |
| 12440 | else if( j0array[0] < -IKPI ) |
| 12441 | { j0array[0]+=IK2PI; |
| 12442 | } |
| 12443 | j0valid[0] = true; |
| 12444 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12445 | { |
| 12446 | if( !j0valid[ij0] ) |
| 12447 | { |
| 12448 | continue; |
| 12449 | } |
| 12450 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12451 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12452 | { |
| 12453 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12454 | { |
| 12455 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12456 | } |
| 12457 | } |
| 12458 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12459 | { |
| 12460 | IkReal evalcond[8]; |
| 12461 | IkReal x893=IKcos(j0); |
| 12462 | IkReal x894=IKsin(j0); |
| 12463 | IkReal x895=(sj2*x893); |
| 12464 | IkReal x896=(cj2*x894); |
| 12465 | IkReal x897=(sj2*x894); |
| 12466 | IkReal x898=(cj2*x893); |
| 12467 | IkReal x899=(x896+x895); |
| 12468 | evalcond[0]=(cj2+((new_r00*x894))); |
| 12469 | evalcond[1]=(sj2+((new_r00*x893))); |
| 12470 | evalcond[2]=(cj2+((new_r01*x893))); |
| 12471 | evalcond[3]=(sj2+(((-1.0)*new_r01*x894))); |
| 12472 | evalcond[4]=x899; |
| 12473 | evalcond[5]=(new_r00+x899); |
| 12474 | evalcond[6]=((((-1.0)*x898))+x897); |
| 12475 | evalcond[7]=((((-1.0)*x897))+new_r01+x898); |
| 12476 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12477 | { |
| 12478 | continue; |
| 12479 | } |
| 12480 | } |
| 12481 | |
| 12482 | { |
| 12483 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12484 | vinfos[0].jointtype = 1; |
| 12485 | vinfos[0].foffset = j0; |
| 12486 | vinfos[0].indices[0] = _ij0[0]; |
| 12487 | vinfos[0].indices[1] = _ij0[1]; |
| 12488 | vinfos[0].maxsolutions = _nj0; |
| 12489 | vinfos[1].jointtype = 1; |
| 12490 | vinfos[1].foffset = j1; |
| 12491 | vinfos[1].indices[0] = _ij1[0]; |
| 12492 | vinfos[1].indices[1] = _ij1[1]; |
| 12493 | vinfos[1].maxsolutions = _nj1; |
| 12494 | vinfos[2].jointtype = 1; |
| 12495 | vinfos[2].foffset = j2; |
| 12496 | vinfos[2].indices[0] = _ij2[0]; |
| 12497 | vinfos[2].indices[1] = _ij2[1]; |
| 12498 | vinfos[2].maxsolutions = _nj2; |
| 12499 | vinfos[3].jointtype = 1; |
| 12500 | vinfos[3].foffset = j3; |
| 12501 | vinfos[3].indices[0] = _ij3[0]; |
| 12502 | vinfos[3].indices[1] = _ij3[1]; |
| 12503 | vinfos[3].maxsolutions = _nj3; |
| 12504 | vinfos[4].jointtype = 1; |
| 12505 | vinfos[4].foffset = j4; |
| 12506 | vinfos[4].indices[0] = _ij4[0]; |
| 12507 | vinfos[4].indices[1] = _ij4[1]; |
| 12508 | vinfos[4].maxsolutions = _nj4; |
| 12509 | vinfos[5].jointtype = 1; |
| 12510 | vinfos[5].foffset = j5; |
| 12511 | vinfos[5].indices[0] = _ij5[0]; |
| 12512 | vinfos[5].indices[1] = _ij5[1]; |
| 12513 | vinfos[5].maxsolutions = _nj5; |
| 12514 | std::vector<int> vfree(0); |
| 12515 | solutions.AddSolution(vinfos,vfree); |
| 12516 | } |
| 12517 | } |
| 12518 | } |
| 12519 | |
| 12520 | } |
| 12521 | |
| 12522 | } |
| 12523 | |
| 12524 | } |
| 12525 | } while(0); |
| 12526 | if( bgotonextstatement ) |
| 12527 | { |
| 12528 | bool bgotonextstatement = true; |
| 12529 | do |
| 12530 | { |
| 12531 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 12532 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 12533 | { |
| 12534 | bgotonextstatement=false; |
| 12535 | { |
| 12536 | IkReal j0eval[3]; |
| 12537 | sj1=1.0; |
| 12538 | cj1=0; |
| 12539 | j1=1.5707963267949; |
| 12540 | new_r00=0; |
| 12541 | new_r01=0; |
| 12542 | new_r12=0; |
| 12543 | new_r22=0; |
| 12544 | j0eval[0]=new_r10; |
| 12545 | j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| 12546 | j0eval[2]=IKsign(new_r10); |
| 12547 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 12548 | { |
| 12549 | { |
| 12550 | IkReal j0eval[3]; |
| 12551 | sj1=1.0; |
| 12552 | cj1=0; |
| 12553 | j1=1.5707963267949; |
| 12554 | new_r00=0; |
| 12555 | new_r01=0; |
| 12556 | new_r12=0; |
| 12557 | new_r22=0; |
| 12558 | j0eval[0]=new_r11; |
| 12559 | j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| 12560 | j0eval[2]=IKsign(new_r11); |
| 12561 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 12562 | { |
| 12563 | { |
| 12564 | IkReal j0eval[2]; |
| 12565 | sj1=1.0; |
| 12566 | cj1=0; |
| 12567 | j1=1.5707963267949; |
| 12568 | new_r00=0; |
| 12569 | new_r01=0; |
| 12570 | new_r12=0; |
| 12571 | new_r22=0; |
| 12572 | j0eval[0]=new_r11; |
| 12573 | j0eval[1]=new_r10; |
| 12574 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 12575 | { |
| 12576 | continue; // no branches [j0] |
| 12577 | |
| 12578 | } else |
| 12579 | { |
| 12580 | { |
| 12581 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12582 | bool j0valid[1]={false}; |
| 12583 | _nj0 = 1; |
| 12584 | CheckValue<IkReal> x900=IKPowWithIntegerCheck(new_r11,-1); |
| 12585 | if(!x900.valid){ |
| 12586 | continue; |
| 12587 | } |
| 12588 | CheckValue<IkReal> x901=IKPowWithIntegerCheck(new_r10,-1); |
| 12589 | if(!x901.valid){ |
| 12590 | continue; |
| 12591 | } |
| 12592 | if( IKabs(((-1.0)*cj2*(x900.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((cj2*(x901.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*cj2*(x900.value)))+IKsqr((cj2*(x901.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 12593 | continue; |
| 12594 | j0array[0]=IKatan2(((-1.0)*cj2*(x900.value)), (cj2*(x901.value))); |
| 12595 | sj0array[0]=IKsin(j0array[0]); |
| 12596 | cj0array[0]=IKcos(j0array[0]); |
| 12597 | if( j0array[0] > IKPI ) |
| 12598 | { |
| 12599 | j0array[0]-=IK2PI; |
| 12600 | } |
| 12601 | else if( j0array[0] < -IKPI ) |
| 12602 | { j0array[0]+=IK2PI; |
| 12603 | } |
| 12604 | j0valid[0] = true; |
| 12605 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12606 | { |
| 12607 | if( !j0valid[ij0] ) |
| 12608 | { |
| 12609 | continue; |
| 12610 | } |
| 12611 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12612 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12613 | { |
| 12614 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12615 | { |
| 12616 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12617 | } |
| 12618 | } |
| 12619 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12620 | { |
| 12621 | IkReal evalcond[8]; |
| 12622 | IkReal x902=IKsin(j0); |
| 12623 | IkReal x903=IKcos(j0); |
| 12624 | IkReal x904=(sj2*x903); |
| 12625 | IkReal x905=(cj2*x902); |
| 12626 | IkReal x906=(sj2*x902); |
| 12627 | IkReal x907=((1.0)*x903); |
| 12628 | IkReal x908=(x904+x905); |
| 12629 | evalcond[0]=(sj2+((new_r11*x903))); |
| 12630 | evalcond[1]=(sj2+((new_r10*x902))); |
| 12631 | evalcond[2]=(cj2+((new_r11*x902))); |
| 12632 | evalcond[3]=(cj2+(((-1.0)*new_r10*x907))); |
| 12633 | evalcond[4]=x908; |
| 12634 | evalcond[5]=(new_r11+x908); |
| 12635 | evalcond[6]=(((cj2*x903))+(((-1.0)*x906))); |
| 12636 | evalcond[7]=(new_r10+x906+(((-1.0)*cj2*x907))); |
| 12637 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12638 | { |
| 12639 | continue; |
| 12640 | } |
| 12641 | } |
| 12642 | |
| 12643 | { |
| 12644 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12645 | vinfos[0].jointtype = 1; |
| 12646 | vinfos[0].foffset = j0; |
| 12647 | vinfos[0].indices[0] = _ij0[0]; |
| 12648 | vinfos[0].indices[1] = _ij0[1]; |
| 12649 | vinfos[0].maxsolutions = _nj0; |
| 12650 | vinfos[1].jointtype = 1; |
| 12651 | vinfos[1].foffset = j1; |
| 12652 | vinfos[1].indices[0] = _ij1[0]; |
| 12653 | vinfos[1].indices[1] = _ij1[1]; |
| 12654 | vinfos[1].maxsolutions = _nj1; |
| 12655 | vinfos[2].jointtype = 1; |
| 12656 | vinfos[2].foffset = j2; |
| 12657 | vinfos[2].indices[0] = _ij2[0]; |
| 12658 | vinfos[2].indices[1] = _ij2[1]; |
| 12659 | vinfos[2].maxsolutions = _nj2; |
| 12660 | vinfos[3].jointtype = 1; |
| 12661 | vinfos[3].foffset = j3; |
| 12662 | vinfos[3].indices[0] = _ij3[0]; |
| 12663 | vinfos[3].indices[1] = _ij3[1]; |
| 12664 | vinfos[3].maxsolutions = _nj3; |
| 12665 | vinfos[4].jointtype = 1; |
| 12666 | vinfos[4].foffset = j4; |
| 12667 | vinfos[4].indices[0] = _ij4[0]; |
| 12668 | vinfos[4].indices[1] = _ij4[1]; |
| 12669 | vinfos[4].maxsolutions = _nj4; |
| 12670 | vinfos[5].jointtype = 1; |
| 12671 | vinfos[5].foffset = j5; |
| 12672 | vinfos[5].indices[0] = _ij5[0]; |
| 12673 | vinfos[5].indices[1] = _ij5[1]; |
| 12674 | vinfos[5].maxsolutions = _nj5; |
| 12675 | std::vector<int> vfree(0); |
| 12676 | solutions.AddSolution(vinfos,vfree); |
| 12677 | } |
| 12678 | } |
| 12679 | } |
| 12680 | |
| 12681 | } |
| 12682 | |
| 12683 | } |
| 12684 | |
| 12685 | } else |
| 12686 | { |
| 12687 | { |
| 12688 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12689 | bool j0valid[1]={false}; |
| 12690 | _nj0 = 1; |
| 12691 | CheckValue<IkReal> x909=IKPowWithIntegerCheck(IKsign(new_r11),-1); |
| 12692 | if(!x909.valid){ |
| 12693 | continue; |
| 12694 | } |
| 12695 | CheckValue<IkReal> x910 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| 12696 | if(!x910.valid){ |
| 12697 | continue; |
| 12698 | } |
| 12699 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x909.value)))+(x910.value)); |
| 12700 | sj0array[0]=IKsin(j0array[0]); |
| 12701 | cj0array[0]=IKcos(j0array[0]); |
| 12702 | if( j0array[0] > IKPI ) |
| 12703 | { |
| 12704 | j0array[0]-=IK2PI; |
| 12705 | } |
| 12706 | else if( j0array[0] < -IKPI ) |
| 12707 | { j0array[0]+=IK2PI; |
| 12708 | } |
| 12709 | j0valid[0] = true; |
| 12710 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12711 | { |
| 12712 | if( !j0valid[ij0] ) |
| 12713 | { |
| 12714 | continue; |
| 12715 | } |
| 12716 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12717 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12718 | { |
| 12719 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12720 | { |
| 12721 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12722 | } |
| 12723 | } |
| 12724 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12725 | { |
| 12726 | IkReal evalcond[8]; |
| 12727 | IkReal x911=IKsin(j0); |
| 12728 | IkReal x912=IKcos(j0); |
| 12729 | IkReal x913=(sj2*x912); |
| 12730 | IkReal x914=(cj2*x911); |
| 12731 | IkReal x915=(sj2*x911); |
| 12732 | IkReal x916=((1.0)*x912); |
| 12733 | IkReal x917=(x913+x914); |
| 12734 | evalcond[0]=(sj2+((new_r11*x912))); |
| 12735 | evalcond[1]=(sj2+((new_r10*x911))); |
| 12736 | evalcond[2]=(cj2+((new_r11*x911))); |
| 12737 | evalcond[3]=(cj2+(((-1.0)*new_r10*x916))); |
| 12738 | evalcond[4]=x917; |
| 12739 | evalcond[5]=(new_r11+x917); |
| 12740 | evalcond[6]=(((cj2*x912))+(((-1.0)*x915))); |
| 12741 | evalcond[7]=(new_r10+x915+(((-1.0)*cj2*x916))); |
| 12742 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12743 | { |
| 12744 | continue; |
| 12745 | } |
| 12746 | } |
| 12747 | |
| 12748 | { |
| 12749 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12750 | vinfos[0].jointtype = 1; |
| 12751 | vinfos[0].foffset = j0; |
| 12752 | vinfos[0].indices[0] = _ij0[0]; |
| 12753 | vinfos[0].indices[1] = _ij0[1]; |
| 12754 | vinfos[0].maxsolutions = _nj0; |
| 12755 | vinfos[1].jointtype = 1; |
| 12756 | vinfos[1].foffset = j1; |
| 12757 | vinfos[1].indices[0] = _ij1[0]; |
| 12758 | vinfos[1].indices[1] = _ij1[1]; |
| 12759 | vinfos[1].maxsolutions = _nj1; |
| 12760 | vinfos[2].jointtype = 1; |
| 12761 | vinfos[2].foffset = j2; |
| 12762 | vinfos[2].indices[0] = _ij2[0]; |
| 12763 | vinfos[2].indices[1] = _ij2[1]; |
| 12764 | vinfos[2].maxsolutions = _nj2; |
| 12765 | vinfos[3].jointtype = 1; |
| 12766 | vinfos[3].foffset = j3; |
| 12767 | vinfos[3].indices[0] = _ij3[0]; |
| 12768 | vinfos[3].indices[1] = _ij3[1]; |
| 12769 | vinfos[3].maxsolutions = _nj3; |
| 12770 | vinfos[4].jointtype = 1; |
| 12771 | vinfos[4].foffset = j4; |
| 12772 | vinfos[4].indices[0] = _ij4[0]; |
| 12773 | vinfos[4].indices[1] = _ij4[1]; |
| 12774 | vinfos[4].maxsolutions = _nj4; |
| 12775 | vinfos[5].jointtype = 1; |
| 12776 | vinfos[5].foffset = j5; |
| 12777 | vinfos[5].indices[0] = _ij5[0]; |
| 12778 | vinfos[5].indices[1] = _ij5[1]; |
| 12779 | vinfos[5].maxsolutions = _nj5; |
| 12780 | std::vector<int> vfree(0); |
| 12781 | solutions.AddSolution(vinfos,vfree); |
| 12782 | } |
| 12783 | } |
| 12784 | } |
| 12785 | |
| 12786 | } |
| 12787 | |
| 12788 | } |
| 12789 | |
| 12790 | } else |
| 12791 | { |
| 12792 | { |
| 12793 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 12794 | bool j0valid[1]={false}; |
| 12795 | _nj0 = 1; |
| 12796 | CheckValue<IkReal> x918=IKPowWithIntegerCheck(IKsign(new_r10),-1); |
| 12797 | if(!x918.valid){ |
| 12798 | continue; |
| 12799 | } |
| 12800 | CheckValue<IkReal> x919 = IKatan2WithCheck(IkReal(((-1.0)*sj2)),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH); |
| 12801 | if(!x919.valid){ |
| 12802 | continue; |
| 12803 | } |
| 12804 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x918.value)))+(x919.value)); |
| 12805 | sj0array[0]=IKsin(j0array[0]); |
| 12806 | cj0array[0]=IKcos(j0array[0]); |
| 12807 | if( j0array[0] > IKPI ) |
| 12808 | { |
| 12809 | j0array[0]-=IK2PI; |
| 12810 | } |
| 12811 | else if( j0array[0] < -IKPI ) |
| 12812 | { j0array[0]+=IK2PI; |
| 12813 | } |
| 12814 | j0valid[0] = true; |
| 12815 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 12816 | { |
| 12817 | if( !j0valid[ij0] ) |
| 12818 | { |
| 12819 | continue; |
| 12820 | } |
| 12821 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12822 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 12823 | { |
| 12824 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12825 | { |
| 12826 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12827 | } |
| 12828 | } |
| 12829 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12830 | { |
| 12831 | IkReal evalcond[8]; |
| 12832 | IkReal x920=IKsin(j0); |
| 12833 | IkReal x921=IKcos(j0); |
| 12834 | IkReal x922=(sj2*x921); |
| 12835 | IkReal x923=(cj2*x920); |
| 12836 | IkReal x924=(sj2*x920); |
| 12837 | IkReal x925=((1.0)*x921); |
| 12838 | IkReal x926=(x922+x923); |
| 12839 | evalcond[0]=(sj2+((new_r11*x921))); |
| 12840 | evalcond[1]=(sj2+((new_r10*x920))); |
| 12841 | evalcond[2]=(cj2+((new_r11*x920))); |
| 12842 | evalcond[3]=(cj2+(((-1.0)*new_r10*x925))); |
| 12843 | evalcond[4]=x926; |
| 12844 | evalcond[5]=(new_r11+x926); |
| 12845 | evalcond[6]=((((-1.0)*x924))+((cj2*x921))); |
| 12846 | evalcond[7]=((((-1.0)*cj2*x925))+new_r10+x924); |
| 12847 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 12848 | { |
| 12849 | continue; |
| 12850 | } |
| 12851 | } |
| 12852 | |
| 12853 | { |
| 12854 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12855 | vinfos[0].jointtype = 1; |
| 12856 | vinfos[0].foffset = j0; |
| 12857 | vinfos[0].indices[0] = _ij0[0]; |
| 12858 | vinfos[0].indices[1] = _ij0[1]; |
| 12859 | vinfos[0].maxsolutions = _nj0; |
| 12860 | vinfos[1].jointtype = 1; |
| 12861 | vinfos[1].foffset = j1; |
| 12862 | vinfos[1].indices[0] = _ij1[0]; |
| 12863 | vinfos[1].indices[1] = _ij1[1]; |
| 12864 | vinfos[1].maxsolutions = _nj1; |
| 12865 | vinfos[2].jointtype = 1; |
| 12866 | vinfos[2].foffset = j2; |
| 12867 | vinfos[2].indices[0] = _ij2[0]; |
| 12868 | vinfos[2].indices[1] = _ij2[1]; |
| 12869 | vinfos[2].maxsolutions = _nj2; |
| 12870 | vinfos[3].jointtype = 1; |
| 12871 | vinfos[3].foffset = j3; |
| 12872 | vinfos[3].indices[0] = _ij3[0]; |
| 12873 | vinfos[3].indices[1] = _ij3[1]; |
| 12874 | vinfos[3].maxsolutions = _nj3; |
| 12875 | vinfos[4].jointtype = 1; |
| 12876 | vinfos[4].foffset = j4; |
| 12877 | vinfos[4].indices[0] = _ij4[0]; |
| 12878 | vinfos[4].indices[1] = _ij4[1]; |
| 12879 | vinfos[4].maxsolutions = _nj4; |
| 12880 | vinfos[5].jointtype = 1; |
| 12881 | vinfos[5].foffset = j5; |
| 12882 | vinfos[5].indices[0] = _ij5[0]; |
| 12883 | vinfos[5].indices[1] = _ij5[1]; |
| 12884 | vinfos[5].maxsolutions = _nj5; |
| 12885 | std::vector<int> vfree(0); |
| 12886 | solutions.AddSolution(vinfos,vfree); |
| 12887 | } |
| 12888 | } |
| 12889 | } |
| 12890 | |
| 12891 | } |
| 12892 | |
| 12893 | } |
| 12894 | |
| 12895 | } |
| 12896 | } while(0); |
| 12897 | if( bgotonextstatement ) |
| 12898 | { |
| 12899 | bool bgotonextstatement = true; |
| 12900 | do |
| 12901 | { |
| 12902 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 12903 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 12904 | { |
| 12905 | bgotonextstatement=false; |
| 12906 | { |
| 12907 | IkReal j0eval[1]; |
| 12908 | sj1=1.0; |
| 12909 | cj1=0; |
| 12910 | j1=1.5707963267949; |
| 12911 | new_r00=0; |
| 12912 | new_r10=0; |
| 12913 | new_r21=0; |
| 12914 | new_r22=0; |
| 12915 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 12916 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 12917 | { |
| 12918 | continue; // no branches [j0] |
| 12919 | |
| 12920 | } else |
| 12921 | { |
| 12922 | { |
| 12923 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 12924 | bool j0valid[2]={false}; |
| 12925 | _nj0 = 2; |
| 12926 | CheckValue<IkReal> x928 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| 12927 | if(!x928.valid){ |
| 12928 | continue; |
| 12929 | } |
| 12930 | IkReal x927=x928.value; |
| 12931 | j0array[0]=((-1.0)*x927); |
| 12932 | sj0array[0]=IKsin(j0array[0]); |
| 12933 | cj0array[0]=IKcos(j0array[0]); |
| 12934 | j0array[1]=((3.14159265358979)+(((-1.0)*x927))); |
| 12935 | sj0array[1]=IKsin(j0array[1]); |
| 12936 | cj0array[1]=IKcos(j0array[1]); |
| 12937 | if( j0array[0] > IKPI ) |
| 12938 | { |
| 12939 | j0array[0]-=IK2PI; |
| 12940 | } |
| 12941 | else if( j0array[0] < -IKPI ) |
| 12942 | { j0array[0]+=IK2PI; |
| 12943 | } |
| 12944 | j0valid[0] = true; |
| 12945 | if( j0array[1] > IKPI ) |
| 12946 | { |
| 12947 | j0array[1]-=IK2PI; |
| 12948 | } |
| 12949 | else if( j0array[1] < -IKPI ) |
| 12950 | { j0array[1]+=IK2PI; |
| 12951 | } |
| 12952 | j0valid[1] = true; |
| 12953 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 12954 | { |
| 12955 | if( !j0valid[ij0] ) |
| 12956 | { |
| 12957 | continue; |
| 12958 | } |
| 12959 | _ij0[0] = ij0; _ij0[1] = -1; |
| 12960 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 12961 | { |
| 12962 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 12963 | { |
| 12964 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 12965 | } |
| 12966 | } |
| 12967 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 12968 | { |
| 12969 | IkReal evalcond[1]; |
| 12970 | evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0))))); |
| 12971 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| 12972 | { |
| 12973 | continue; |
| 12974 | } |
| 12975 | } |
| 12976 | |
| 12977 | { |
| 12978 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 12979 | vinfos[0].jointtype = 1; |
| 12980 | vinfos[0].foffset = j0; |
| 12981 | vinfos[0].indices[0] = _ij0[0]; |
| 12982 | vinfos[0].indices[1] = _ij0[1]; |
| 12983 | vinfos[0].maxsolutions = _nj0; |
| 12984 | vinfos[1].jointtype = 1; |
| 12985 | vinfos[1].foffset = j1; |
| 12986 | vinfos[1].indices[0] = _ij1[0]; |
| 12987 | vinfos[1].indices[1] = _ij1[1]; |
| 12988 | vinfos[1].maxsolutions = _nj1; |
| 12989 | vinfos[2].jointtype = 1; |
| 12990 | vinfos[2].foffset = j2; |
| 12991 | vinfos[2].indices[0] = _ij2[0]; |
| 12992 | vinfos[2].indices[1] = _ij2[1]; |
| 12993 | vinfos[2].maxsolutions = _nj2; |
| 12994 | vinfos[3].jointtype = 1; |
| 12995 | vinfos[3].foffset = j3; |
| 12996 | vinfos[3].indices[0] = _ij3[0]; |
| 12997 | vinfos[3].indices[1] = _ij3[1]; |
| 12998 | vinfos[3].maxsolutions = _nj3; |
| 12999 | vinfos[4].jointtype = 1; |
| 13000 | vinfos[4].foffset = j4; |
| 13001 | vinfos[4].indices[0] = _ij4[0]; |
| 13002 | vinfos[4].indices[1] = _ij4[1]; |
| 13003 | vinfos[4].maxsolutions = _nj4; |
| 13004 | vinfos[5].jointtype = 1; |
| 13005 | vinfos[5].foffset = j5; |
| 13006 | vinfos[5].indices[0] = _ij5[0]; |
| 13007 | vinfos[5].indices[1] = _ij5[1]; |
| 13008 | vinfos[5].maxsolutions = _nj5; |
| 13009 | std::vector<int> vfree(0); |
| 13010 | solutions.AddSolution(vinfos,vfree); |
| 13011 | } |
| 13012 | } |
| 13013 | } |
| 13014 | |
| 13015 | } |
| 13016 | |
| 13017 | } |
| 13018 | |
| 13019 | } |
| 13020 | } while(0); |
| 13021 | if( bgotonextstatement ) |
| 13022 | { |
| 13023 | bool bgotonextstatement = true; |
| 13024 | do |
| 13025 | { |
| 13026 | if( 1 ) |
| 13027 | { |
| 13028 | bgotonextstatement=false; |
| 13029 | continue; // branch miss [j0] |
| 13030 | |
| 13031 | } |
| 13032 | } while(0); |
| 13033 | if( bgotonextstatement ) |
| 13034 | { |
| 13035 | } |
| 13036 | } |
| 13037 | } |
| 13038 | } |
| 13039 | } |
| 13040 | } |
| 13041 | } |
| 13042 | } |
| 13043 | } |
| 13044 | } |
| 13045 | |
| 13046 | } else |
| 13047 | { |
| 13048 | { |
| 13049 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 13050 | bool j0valid[1]={false}; |
| 13051 | _nj0 = 1; |
| 13052 | IkReal x929=((1.0)*sj2); |
| 13053 | CheckValue<IkReal> x930=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x929))+((cj2*new_r00)))),-1); |
| 13054 | if(!x930.valid){ |
| 13055 | continue; |
| 13056 | } |
| 13057 | CheckValue<IkReal> x931 = IKatan2WithCheck(IkReal(((1.0)+(((-1.0)*(cj2*cj2)))+(((-1.0)*new_r00*new_r11)))),IkReal(((((-1.0)*cj2*x929))+((new_r10*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 13058 | if(!x931.valid){ |
| 13059 | continue; |
| 13060 | } |
| 13061 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x930.value)))+(x931.value)); |
| 13062 | sj0array[0]=IKsin(j0array[0]); |
| 13063 | cj0array[0]=IKcos(j0array[0]); |
| 13064 | if( j0array[0] > IKPI ) |
| 13065 | { |
| 13066 | j0array[0]-=IK2PI; |
| 13067 | } |
| 13068 | else if( j0array[0] < -IKPI ) |
| 13069 | { j0array[0]+=IK2PI; |
| 13070 | } |
| 13071 | j0valid[0] = true; |
| 13072 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 13073 | { |
| 13074 | if( !j0valid[ij0] ) |
| 13075 | { |
| 13076 | continue; |
| 13077 | } |
| 13078 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13079 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 13080 | { |
| 13081 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13082 | { |
| 13083 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13084 | } |
| 13085 | } |
| 13086 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13087 | { |
| 13088 | IkReal evalcond[8]; |
| 13089 | IkReal x932=IKsin(j0); |
| 13090 | IkReal x933=IKcos(j0); |
| 13091 | IkReal x934=(sj2*x933); |
| 13092 | IkReal x935=(cj2*x932); |
| 13093 | IkReal x936=(sj2*x932); |
| 13094 | IkReal x937=((1.0)*x933); |
| 13095 | IkReal x938=(x935+x934); |
| 13096 | evalcond[0]=(sj2+((new_r00*x933))+((new_r10*x932))); |
| 13097 | evalcond[1]=(cj2+((new_r01*x933))+((new_r11*x932))); |
| 13098 | evalcond[2]=(new_r00+x938); |
| 13099 | evalcond[3]=(new_r11+x938); |
| 13100 | evalcond[4]=(sj2+(((-1.0)*new_r01*x932))+((new_r11*x933))); |
| 13101 | evalcond[5]=(cj2+(((-1.0)*new_r10*x937))+((new_r00*x932))); |
| 13102 | evalcond[6]=(((cj2*x933))+(((-1.0)*x936))+new_r01); |
| 13103 | evalcond[7]=((((-1.0)*cj2*x937))+new_r10+x936); |
| 13104 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 13105 | { |
| 13106 | continue; |
| 13107 | } |
| 13108 | } |
| 13109 | |
| 13110 | { |
| 13111 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13112 | vinfos[0].jointtype = 1; |
| 13113 | vinfos[0].foffset = j0; |
| 13114 | vinfos[0].indices[0] = _ij0[0]; |
| 13115 | vinfos[0].indices[1] = _ij0[1]; |
| 13116 | vinfos[0].maxsolutions = _nj0; |
| 13117 | vinfos[1].jointtype = 1; |
| 13118 | vinfos[1].foffset = j1; |
| 13119 | vinfos[1].indices[0] = _ij1[0]; |
| 13120 | vinfos[1].indices[1] = _ij1[1]; |
| 13121 | vinfos[1].maxsolutions = _nj1; |
| 13122 | vinfos[2].jointtype = 1; |
| 13123 | vinfos[2].foffset = j2; |
| 13124 | vinfos[2].indices[0] = _ij2[0]; |
| 13125 | vinfos[2].indices[1] = _ij2[1]; |
| 13126 | vinfos[2].maxsolutions = _nj2; |
| 13127 | vinfos[3].jointtype = 1; |
| 13128 | vinfos[3].foffset = j3; |
| 13129 | vinfos[3].indices[0] = _ij3[0]; |
| 13130 | vinfos[3].indices[1] = _ij3[1]; |
| 13131 | vinfos[3].maxsolutions = _nj3; |
| 13132 | vinfos[4].jointtype = 1; |
| 13133 | vinfos[4].foffset = j4; |
| 13134 | vinfos[4].indices[0] = _ij4[0]; |
| 13135 | vinfos[4].indices[1] = _ij4[1]; |
| 13136 | vinfos[4].maxsolutions = _nj4; |
| 13137 | vinfos[5].jointtype = 1; |
| 13138 | vinfos[5].foffset = j5; |
| 13139 | vinfos[5].indices[0] = _ij5[0]; |
| 13140 | vinfos[5].indices[1] = _ij5[1]; |
| 13141 | vinfos[5].maxsolutions = _nj5; |
| 13142 | std::vector<int> vfree(0); |
| 13143 | solutions.AddSolution(vinfos,vfree); |
| 13144 | } |
| 13145 | } |
| 13146 | } |
| 13147 | |
| 13148 | } |
| 13149 | |
| 13150 | } |
| 13151 | |
| 13152 | } else |
| 13153 | { |
| 13154 | { |
| 13155 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 13156 | bool j0valid[1]={false}; |
| 13157 | _nj0 = 1; |
| 13158 | CheckValue<IkReal> x939=IKPowWithIntegerCheck(IKsign((((cj2*new_r01))+(((-1.0)*new_r11*sj2)))),-1); |
| 13159 | if(!x939.valid){ |
| 13160 | continue; |
| 13161 | } |
| 13162 | CheckValue<IkReal> x940 = IKatan2WithCheck(IkReal((((cj2*sj2))+(((-1.0)*new_r00*new_r01)))),IkReal(((((-1.0)*(cj2*cj2)))+((new_r00*new_r11)))),IKFAST_ATAN2_MAGTHRESH); |
| 13163 | if(!x940.valid){ |
| 13164 | continue; |
| 13165 | } |
| 13166 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x939.value)))+(x940.value)); |
| 13167 | sj0array[0]=IKsin(j0array[0]); |
| 13168 | cj0array[0]=IKcos(j0array[0]); |
| 13169 | if( j0array[0] > IKPI ) |
| 13170 | { |
| 13171 | j0array[0]-=IK2PI; |
| 13172 | } |
| 13173 | else if( j0array[0] < -IKPI ) |
| 13174 | { j0array[0]+=IK2PI; |
| 13175 | } |
| 13176 | j0valid[0] = true; |
| 13177 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 13178 | { |
| 13179 | if( !j0valid[ij0] ) |
| 13180 | { |
| 13181 | continue; |
| 13182 | } |
| 13183 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13184 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 13185 | { |
| 13186 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13187 | { |
| 13188 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13189 | } |
| 13190 | } |
| 13191 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13192 | { |
| 13193 | IkReal evalcond[8]; |
| 13194 | IkReal x941=IKsin(j0); |
| 13195 | IkReal x942=IKcos(j0); |
| 13196 | IkReal x943=(sj2*x942); |
| 13197 | IkReal x944=(cj2*x941); |
| 13198 | IkReal x945=(sj2*x941); |
| 13199 | IkReal x946=((1.0)*x942); |
| 13200 | IkReal x947=(x943+x944); |
| 13201 | evalcond[0]=(sj2+((new_r00*x942))+((new_r10*x941))); |
| 13202 | evalcond[1]=(cj2+((new_r01*x942))+((new_r11*x941))); |
| 13203 | evalcond[2]=(new_r00+x947); |
| 13204 | evalcond[3]=(new_r11+x947); |
| 13205 | evalcond[4]=((((-1.0)*new_r01*x941))+sj2+((new_r11*x942))); |
| 13206 | evalcond[5]=(((new_r00*x941))+cj2+(((-1.0)*new_r10*x946))); |
| 13207 | evalcond[6]=(((cj2*x942))+(((-1.0)*x945))+new_r01); |
| 13208 | evalcond[7]=((((-1.0)*cj2*x946))+new_r10+x945); |
| 13209 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 13210 | { |
| 13211 | continue; |
| 13212 | } |
| 13213 | } |
| 13214 | |
| 13215 | { |
| 13216 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13217 | vinfos[0].jointtype = 1; |
| 13218 | vinfos[0].foffset = j0; |
| 13219 | vinfos[0].indices[0] = _ij0[0]; |
| 13220 | vinfos[0].indices[1] = _ij0[1]; |
| 13221 | vinfos[0].maxsolutions = _nj0; |
| 13222 | vinfos[1].jointtype = 1; |
| 13223 | vinfos[1].foffset = j1; |
| 13224 | vinfos[1].indices[0] = _ij1[0]; |
| 13225 | vinfos[1].indices[1] = _ij1[1]; |
| 13226 | vinfos[1].maxsolutions = _nj1; |
| 13227 | vinfos[2].jointtype = 1; |
| 13228 | vinfos[2].foffset = j2; |
| 13229 | vinfos[2].indices[0] = _ij2[0]; |
| 13230 | vinfos[2].indices[1] = _ij2[1]; |
| 13231 | vinfos[2].maxsolutions = _nj2; |
| 13232 | vinfos[3].jointtype = 1; |
| 13233 | vinfos[3].foffset = j3; |
| 13234 | vinfos[3].indices[0] = _ij3[0]; |
| 13235 | vinfos[3].indices[1] = _ij3[1]; |
| 13236 | vinfos[3].maxsolutions = _nj3; |
| 13237 | vinfos[4].jointtype = 1; |
| 13238 | vinfos[4].foffset = j4; |
| 13239 | vinfos[4].indices[0] = _ij4[0]; |
| 13240 | vinfos[4].indices[1] = _ij4[1]; |
| 13241 | vinfos[4].maxsolutions = _nj4; |
| 13242 | vinfos[5].jointtype = 1; |
| 13243 | vinfos[5].foffset = j5; |
| 13244 | vinfos[5].indices[0] = _ij5[0]; |
| 13245 | vinfos[5].indices[1] = _ij5[1]; |
| 13246 | vinfos[5].maxsolutions = _nj5; |
| 13247 | std::vector<int> vfree(0); |
| 13248 | solutions.AddSolution(vinfos,vfree); |
| 13249 | } |
| 13250 | } |
| 13251 | } |
| 13252 | |
| 13253 | } |
| 13254 | |
| 13255 | } |
| 13256 | |
| 13257 | } else |
| 13258 | { |
| 13259 | { |
| 13260 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 13261 | bool j0valid[1]={false}; |
| 13262 | _nj0 = 1; |
| 13263 | CheckValue<IkReal> x948 = IKatan2WithCheck(IkReal((((new_r01*sj2))+(((-1.0)*cj2*new_r00)))),IkReal((((cj2*new_r10))+(((-1.0)*new_r11*sj2)))),IKFAST_ATAN2_MAGTHRESH); |
| 13264 | if(!x948.valid){ |
| 13265 | continue; |
| 13266 | } |
| 13267 | CheckValue<IkReal> x949=IKPowWithIntegerCheck(IKsign((((new_r00*new_r11))+(((-1.0)*new_r01*new_r10)))),-1); |
| 13268 | if(!x949.valid){ |
| 13269 | continue; |
| 13270 | } |
| 13271 | j0array[0]=((-1.5707963267949)+(x948.value)+(((1.5707963267949)*(x949.value)))); |
| 13272 | sj0array[0]=IKsin(j0array[0]); |
| 13273 | cj0array[0]=IKcos(j0array[0]); |
| 13274 | if( j0array[0] > IKPI ) |
| 13275 | { |
| 13276 | j0array[0]-=IK2PI; |
| 13277 | } |
| 13278 | else if( j0array[0] < -IKPI ) |
| 13279 | { j0array[0]+=IK2PI; |
| 13280 | } |
| 13281 | j0valid[0] = true; |
| 13282 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 13283 | { |
| 13284 | if( !j0valid[ij0] ) |
| 13285 | { |
| 13286 | continue; |
| 13287 | } |
| 13288 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13289 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 13290 | { |
| 13291 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13292 | { |
| 13293 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13294 | } |
| 13295 | } |
| 13296 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13297 | { |
| 13298 | IkReal evalcond[8]; |
| 13299 | IkReal x950=IKsin(j0); |
| 13300 | IkReal x951=IKcos(j0); |
| 13301 | IkReal x952=(sj2*x951); |
| 13302 | IkReal x953=(cj2*x950); |
| 13303 | IkReal x954=(sj2*x950); |
| 13304 | IkReal x955=((1.0)*x951); |
| 13305 | IkReal x956=(x953+x952); |
| 13306 | evalcond[0]=(((new_r10*x950))+((new_r00*x951))+sj2); |
| 13307 | evalcond[1]=(((new_r01*x951))+cj2+((new_r11*x950))); |
| 13308 | evalcond[2]=(new_r00+x956); |
| 13309 | evalcond[3]=(new_r11+x956); |
| 13310 | evalcond[4]=(sj2+(((-1.0)*new_r01*x950))+((new_r11*x951))); |
| 13311 | evalcond[5]=(((new_r00*x950))+cj2+(((-1.0)*new_r10*x955))); |
| 13312 | evalcond[6]=((((-1.0)*x954))+((cj2*x951))+new_r01); |
| 13313 | evalcond[7]=((((-1.0)*cj2*x955))+new_r10+x954); |
| 13314 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 13315 | { |
| 13316 | continue; |
| 13317 | } |
| 13318 | } |
| 13319 | |
| 13320 | { |
| 13321 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13322 | vinfos[0].jointtype = 1; |
| 13323 | vinfos[0].foffset = j0; |
| 13324 | vinfos[0].indices[0] = _ij0[0]; |
| 13325 | vinfos[0].indices[1] = _ij0[1]; |
| 13326 | vinfos[0].maxsolutions = _nj0; |
| 13327 | vinfos[1].jointtype = 1; |
| 13328 | vinfos[1].foffset = j1; |
| 13329 | vinfos[1].indices[0] = _ij1[0]; |
| 13330 | vinfos[1].indices[1] = _ij1[1]; |
| 13331 | vinfos[1].maxsolutions = _nj1; |
| 13332 | vinfos[2].jointtype = 1; |
| 13333 | vinfos[2].foffset = j2; |
| 13334 | vinfos[2].indices[0] = _ij2[0]; |
| 13335 | vinfos[2].indices[1] = _ij2[1]; |
| 13336 | vinfos[2].maxsolutions = _nj2; |
| 13337 | vinfos[3].jointtype = 1; |
| 13338 | vinfos[3].foffset = j3; |
| 13339 | vinfos[3].indices[0] = _ij3[0]; |
| 13340 | vinfos[3].indices[1] = _ij3[1]; |
| 13341 | vinfos[3].maxsolutions = _nj3; |
| 13342 | vinfos[4].jointtype = 1; |
| 13343 | vinfos[4].foffset = j4; |
| 13344 | vinfos[4].indices[0] = _ij4[0]; |
| 13345 | vinfos[4].indices[1] = _ij4[1]; |
| 13346 | vinfos[4].maxsolutions = _nj4; |
| 13347 | vinfos[5].jointtype = 1; |
| 13348 | vinfos[5].foffset = j5; |
| 13349 | vinfos[5].indices[0] = _ij5[0]; |
| 13350 | vinfos[5].indices[1] = _ij5[1]; |
| 13351 | vinfos[5].maxsolutions = _nj5; |
| 13352 | std::vector<int> vfree(0); |
| 13353 | solutions.AddSolution(vinfos,vfree); |
| 13354 | } |
| 13355 | } |
| 13356 | } |
| 13357 | |
| 13358 | } |
| 13359 | |
| 13360 | } |
| 13361 | |
| 13362 | } |
| 13363 | } while(0); |
| 13364 | if( bgotonextstatement ) |
| 13365 | { |
| 13366 | bool bgotonextstatement = true; |
| 13367 | do |
| 13368 | { |
| 13369 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| 13370 | evalcond[1]=new_r02; |
| 13371 | evalcond[2]=new_r12; |
| 13372 | evalcond[3]=new_r20; |
| 13373 | evalcond[4]=new_r21; |
| 13374 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 13375 | { |
| 13376 | bgotonextstatement=false; |
| 13377 | { |
| 13378 | IkReal j0eval[3]; |
| 13379 | sj1=-1.0; |
| 13380 | cj1=0; |
| 13381 | j1=-1.5707963267949; |
| 13382 | IkReal x957=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| 13383 | j0eval[0]=x957; |
| 13384 | j0eval[1]=IKsign(x957); |
| 13385 | j0eval[2]=((IKabs((((new_r10*sj2))+((cj2*new_r11)))))+(IKabs((((new_r00*sj2))+((cj2*new_r01)))))); |
| 13386 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13387 | { |
| 13388 | { |
| 13389 | IkReal j0eval[3]; |
| 13390 | sj1=-1.0; |
| 13391 | cj1=0; |
| 13392 | j1=-1.5707963267949; |
| 13393 | IkReal x958=((1.0)*sj2); |
| 13394 | IkReal x959=((((-1.0)*new_r01*x958))+((cj2*new_r11))); |
| 13395 | j0eval[0]=x959; |
| 13396 | j0eval[1]=((IKabs(((-1.0)+(cj2*cj2)+(new_r11*new_r11))))+(IKabs(((((-1.0)*cj2*x958))+((new_r01*new_r11)))))); |
| 13397 | j0eval[2]=IKsign(x959); |
| 13398 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13399 | { |
| 13400 | { |
| 13401 | IkReal j0eval[3]; |
| 13402 | sj1=-1.0; |
| 13403 | cj1=0; |
| 13404 | j1=-1.5707963267949; |
| 13405 | IkReal x960=((1.0)*new_r00); |
| 13406 | IkReal x961=((((-1.0)*sj2*x960))+((cj2*new_r10))); |
| 13407 | j0eval[0]=x961; |
| 13408 | j0eval[1]=IKsign(x961); |
| 13409 | j0eval[2]=((IKabs(((cj2*cj2)+(((-1.0)*new_r00*x960)))))+(IKabs((((cj2*sj2))+(((-1.0)*new_r10*x960)))))); |
| 13410 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13411 | { |
| 13412 | { |
| 13413 | IkReal evalcond[1]; |
| 13414 | bool bgotonextstatement = true; |
| 13415 | do |
| 13416 | { |
| 13417 | IkReal x962=((-1.0)*new_r00); |
| 13418 | IkReal x964 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| 13419 | if(IKabs(x964)==0){ |
| 13420 | continue; |
| 13421 | } |
| 13422 | IkReal x963=pow(x964,-0.5); |
| 13423 | CheckValue<IkReal> x965 = IKatan2WithCheck(IkReal(new_r10),IkReal(x962),IKFAST_ATAN2_MAGTHRESH); |
| 13424 | if(!x965.valid){ |
| 13425 | continue; |
| 13426 | } |
| 13427 | IkReal gconst28=((-1.0)*(x965.value)); |
| 13428 | IkReal gconst29=((-1.0)*new_r10*x963); |
| 13429 | IkReal gconst30=(x962*x963); |
| 13430 | CheckValue<IkReal> x966 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 13431 | if(!x966.valid){ |
| 13432 | continue; |
| 13433 | } |
| 13434 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs((j2+(x966.value))))), 6.28318530717959))); |
| 13435 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 13436 | { |
| 13437 | bgotonextstatement=false; |
| 13438 | { |
| 13439 | IkReal j0eval[3]; |
| 13440 | IkReal x967=((-1.0)*new_r00); |
| 13441 | CheckValue<IkReal> x970 = IKatan2WithCheck(IkReal(new_r10),IkReal(x967),IKFAST_ATAN2_MAGTHRESH); |
| 13442 | if(!x970.valid){ |
| 13443 | continue; |
| 13444 | } |
| 13445 | IkReal x968=((-1.0)*(x970.value)); |
| 13446 | IkReal x969=x963; |
| 13447 | sj1=-1.0; |
| 13448 | cj1=0; |
| 13449 | j1=-1.5707963267949; |
| 13450 | sj2=gconst29; |
| 13451 | cj2=gconst30; |
| 13452 | j2=x968; |
| 13453 | IkReal gconst28=x968; |
| 13454 | IkReal gconst29=((-1.0)*new_r10*x969); |
| 13455 | IkReal gconst30=(x967*x969); |
| 13456 | IkReal x971=new_r10*new_r10; |
| 13457 | IkReal x972=(new_r00*new_r11); |
| 13458 | IkReal x973=((((-1.0)*x972))+((new_r01*new_r10))); |
| 13459 | IkReal x974=x963; |
| 13460 | IkReal x975=((1.0)*new_r00*x974); |
| 13461 | j0eval[0]=x973; |
| 13462 | j0eval[1]=IKsign(x973); |
| 13463 | j0eval[2]=((IKabs(((((-1.0)*new_r01*x975))+(((-1.0)*new_r10*x975)))))+(IKabs((((x971*x974))+((x972*x974)))))); |
| 13464 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13465 | { |
| 13466 | { |
| 13467 | IkReal j0eval[1]; |
| 13468 | IkReal x976=((-1.0)*new_r00); |
| 13469 | CheckValue<IkReal> x979 = IKatan2WithCheck(IkReal(new_r10),IkReal(x976),IKFAST_ATAN2_MAGTHRESH); |
| 13470 | if(!x979.valid){ |
| 13471 | continue; |
| 13472 | } |
| 13473 | IkReal x977=((-1.0)*(x979.value)); |
| 13474 | IkReal x978=x963; |
| 13475 | sj1=-1.0; |
| 13476 | cj1=0; |
| 13477 | j1=-1.5707963267949; |
| 13478 | sj2=gconst29; |
| 13479 | cj2=gconst30; |
| 13480 | j2=x977; |
| 13481 | IkReal gconst28=x977; |
| 13482 | IkReal gconst29=((-1.0)*new_r10*x978); |
| 13483 | IkReal gconst30=(x976*x978); |
| 13484 | IkReal x980=new_r10*new_r10; |
| 13485 | CheckValue<IkReal> x983=IKPowWithIntegerCheck((x980+(new_r00*new_r00)),-1); |
| 13486 | if(!x983.valid){ |
| 13487 | continue; |
| 13488 | } |
| 13489 | IkReal x981=x983.value; |
| 13490 | IkReal x982=(new_r00*x981); |
| 13491 | j0eval[0]=((IKabs((((new_r00*new_r11))+((x980*x981)))))+(IKabs((((new_r01*x982*(new_r00*new_r00)))+((new_r10*x982))+((new_r01*x980*x982)))))); |
| 13492 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 13493 | { |
| 13494 | { |
| 13495 | IkReal j0eval[3]; |
| 13496 | IkReal x984=((-1.0)*new_r00); |
| 13497 | CheckValue<IkReal> x987 = IKatan2WithCheck(IkReal(new_r10),IkReal(x984),IKFAST_ATAN2_MAGTHRESH); |
| 13498 | if(!x987.valid){ |
| 13499 | continue; |
| 13500 | } |
| 13501 | IkReal x985=((-1.0)*(x987.value)); |
| 13502 | IkReal x986=x963; |
| 13503 | sj1=-1.0; |
| 13504 | cj1=0; |
| 13505 | j1=-1.5707963267949; |
| 13506 | sj2=gconst29; |
| 13507 | cj2=gconst30; |
| 13508 | j2=x985; |
| 13509 | IkReal gconst28=x985; |
| 13510 | IkReal gconst29=((-1.0)*new_r10*x986); |
| 13511 | IkReal gconst30=(x984*x986); |
| 13512 | IkReal x988=new_r10*new_r10; |
| 13513 | IkReal x989=(((new_r10*new_r11))+((new_r00*new_r01))); |
| 13514 | IkReal x990=x963; |
| 13515 | IkReal x991=((1.0)*new_r10*x990); |
| 13516 | j0eval[0]=x989; |
| 13517 | j0eval[1]=IKsign(x989); |
| 13518 | j0eval[2]=((IKabs(((((-1.0)*new_r11*x991))+(((-1.0)*new_r00*x991)))))+(IKabs((((x988*x990))+(((-1.0)*new_r01*x991)))))); |
| 13519 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13520 | { |
| 13521 | { |
| 13522 | IkReal evalcond[2]; |
| 13523 | bool bgotonextstatement = true; |
| 13524 | do |
| 13525 | { |
| 13526 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| 13527 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 13528 | { |
| 13529 | bgotonextstatement=false; |
| 13530 | { |
| 13531 | IkReal j0eval[1]; |
| 13532 | CheckValue<IkReal> x993 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 13533 | if(!x993.valid){ |
| 13534 | continue; |
| 13535 | } |
| 13536 | IkReal x992=((-1.0)*(x993.value)); |
| 13537 | sj1=-1.0; |
| 13538 | cj1=0; |
| 13539 | j1=-1.5707963267949; |
| 13540 | sj2=gconst29; |
| 13541 | cj2=gconst30; |
| 13542 | j2=x992; |
| 13543 | new_r11=0; |
| 13544 | new_r00=0; |
| 13545 | IkReal gconst28=x992; |
| 13546 | IkReal x994 = new_r10*new_r10; |
| 13547 | if(IKabs(x994)==0){ |
| 13548 | continue; |
| 13549 | } |
| 13550 | IkReal gconst29=((-1.0)*new_r10*(pow(x994,-0.5))); |
| 13551 | IkReal gconst30=0; |
| 13552 | j0eval[0]=new_r01; |
| 13553 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 13554 | { |
| 13555 | { |
| 13556 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 13557 | bool j0valid[2]={false}; |
| 13558 | _nj0 = 2; |
| 13559 | CheckValue<IkReal> x995=IKPowWithIntegerCheck(gconst29,-1); |
| 13560 | if(!x995.valid){ |
| 13561 | continue; |
| 13562 | } |
| 13563 | sj0array[0]=(new_r01*(x995.value)); |
| 13564 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 13565 | { |
| 13566 | j0valid[0] = j0valid[1] = true; |
| 13567 | j0array[0] = IKasin(sj0array[0]); |
| 13568 | cj0array[0] = IKcos(j0array[0]); |
| 13569 | sj0array[1] = sj0array[0]; |
| 13570 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 13571 | cj0array[1] = -cj0array[0]; |
| 13572 | } |
| 13573 | else if( isnan(sj0array[0]) ) |
| 13574 | { |
| 13575 | // probably any value will work |
| 13576 | j0valid[0] = true; |
| 13577 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 13578 | } |
| 13579 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 13580 | { |
| 13581 | if( !j0valid[ij0] ) |
| 13582 | { |
| 13583 | continue; |
| 13584 | } |
| 13585 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13586 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 13587 | { |
| 13588 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13589 | { |
| 13590 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13591 | } |
| 13592 | } |
| 13593 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13594 | { |
| 13595 | IkReal evalcond[6]; |
| 13596 | IkReal x996=IKcos(j0); |
| 13597 | IkReal x997=IKsin(j0); |
| 13598 | IkReal x998=((1.0)*gconst29); |
| 13599 | IkReal x999=((-1.0)*x996); |
| 13600 | evalcond[0]=(new_r01*x996); |
| 13601 | evalcond[1]=(new_r10*x999); |
| 13602 | evalcond[2]=(gconst29*x999); |
| 13603 | evalcond[3]=(gconst29+(((-1.0)*new_r01*x997))); |
| 13604 | evalcond[4]=((((-1.0)*x997*x998))+new_r10); |
| 13605 | evalcond[5]=(((new_r10*x997))+(((-1.0)*x998))); |
| 13606 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 13607 | { |
| 13608 | continue; |
| 13609 | } |
| 13610 | } |
| 13611 | |
| 13612 | { |
| 13613 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13614 | vinfos[0].jointtype = 1; |
| 13615 | vinfos[0].foffset = j0; |
| 13616 | vinfos[0].indices[0] = _ij0[0]; |
| 13617 | vinfos[0].indices[1] = _ij0[1]; |
| 13618 | vinfos[0].maxsolutions = _nj0; |
| 13619 | vinfos[1].jointtype = 1; |
| 13620 | vinfos[1].foffset = j1; |
| 13621 | vinfos[1].indices[0] = _ij1[0]; |
| 13622 | vinfos[1].indices[1] = _ij1[1]; |
| 13623 | vinfos[1].maxsolutions = _nj1; |
| 13624 | vinfos[2].jointtype = 1; |
| 13625 | vinfos[2].foffset = j2; |
| 13626 | vinfos[2].indices[0] = _ij2[0]; |
| 13627 | vinfos[2].indices[1] = _ij2[1]; |
| 13628 | vinfos[2].maxsolutions = _nj2; |
| 13629 | vinfos[3].jointtype = 1; |
| 13630 | vinfos[3].foffset = j3; |
| 13631 | vinfos[3].indices[0] = _ij3[0]; |
| 13632 | vinfos[3].indices[1] = _ij3[1]; |
| 13633 | vinfos[3].maxsolutions = _nj3; |
| 13634 | vinfos[4].jointtype = 1; |
| 13635 | vinfos[4].foffset = j4; |
| 13636 | vinfos[4].indices[0] = _ij4[0]; |
| 13637 | vinfos[4].indices[1] = _ij4[1]; |
| 13638 | vinfos[4].maxsolutions = _nj4; |
| 13639 | vinfos[5].jointtype = 1; |
| 13640 | vinfos[5].foffset = j5; |
| 13641 | vinfos[5].indices[0] = _ij5[0]; |
| 13642 | vinfos[5].indices[1] = _ij5[1]; |
| 13643 | vinfos[5].maxsolutions = _nj5; |
| 13644 | std::vector<int> vfree(0); |
| 13645 | solutions.AddSolution(vinfos,vfree); |
| 13646 | } |
| 13647 | } |
| 13648 | } |
| 13649 | |
| 13650 | } else |
| 13651 | { |
| 13652 | { |
| 13653 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 13654 | bool j0valid[2]={false}; |
| 13655 | _nj0 = 2; |
| 13656 | CheckValue<IkReal> x1000=IKPowWithIntegerCheck(new_r01,-1); |
| 13657 | if(!x1000.valid){ |
| 13658 | continue; |
| 13659 | } |
| 13660 | sj0array[0]=(gconst29*(x1000.value)); |
| 13661 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 13662 | { |
| 13663 | j0valid[0] = j0valid[1] = true; |
| 13664 | j0array[0] = IKasin(sj0array[0]); |
| 13665 | cj0array[0] = IKcos(j0array[0]); |
| 13666 | sj0array[1] = sj0array[0]; |
| 13667 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 13668 | cj0array[1] = -cj0array[0]; |
| 13669 | } |
| 13670 | else if( isnan(sj0array[0]) ) |
| 13671 | { |
| 13672 | // probably any value will work |
| 13673 | j0valid[0] = true; |
| 13674 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 13675 | } |
| 13676 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 13677 | { |
| 13678 | if( !j0valid[ij0] ) |
| 13679 | { |
| 13680 | continue; |
| 13681 | } |
| 13682 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13683 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 13684 | { |
| 13685 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13686 | { |
| 13687 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13688 | } |
| 13689 | } |
| 13690 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13691 | { |
| 13692 | IkReal evalcond[6]; |
| 13693 | IkReal x1001=IKcos(j0); |
| 13694 | IkReal x1002=IKsin(j0); |
| 13695 | IkReal x1003=((1.0)*gconst29); |
| 13696 | IkReal x1004=(x1002*x1003); |
| 13697 | IkReal x1005=((-1.0)*x1001); |
| 13698 | evalcond[0]=(new_r01*x1001); |
| 13699 | evalcond[1]=(new_r10*x1005); |
| 13700 | evalcond[2]=(gconst29*x1005); |
| 13701 | evalcond[3]=((((-1.0)*x1004))+new_r01); |
| 13702 | evalcond[4]=((((-1.0)*x1004))+new_r10); |
| 13703 | evalcond[5]=((((-1.0)*x1003))+((new_r10*x1002))); |
| 13704 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 13705 | { |
| 13706 | continue; |
| 13707 | } |
| 13708 | } |
| 13709 | |
| 13710 | { |
| 13711 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13712 | vinfos[0].jointtype = 1; |
| 13713 | vinfos[0].foffset = j0; |
| 13714 | vinfos[0].indices[0] = _ij0[0]; |
| 13715 | vinfos[0].indices[1] = _ij0[1]; |
| 13716 | vinfos[0].maxsolutions = _nj0; |
| 13717 | vinfos[1].jointtype = 1; |
| 13718 | vinfos[1].foffset = j1; |
| 13719 | vinfos[1].indices[0] = _ij1[0]; |
| 13720 | vinfos[1].indices[1] = _ij1[1]; |
| 13721 | vinfos[1].maxsolutions = _nj1; |
| 13722 | vinfos[2].jointtype = 1; |
| 13723 | vinfos[2].foffset = j2; |
| 13724 | vinfos[2].indices[0] = _ij2[0]; |
| 13725 | vinfos[2].indices[1] = _ij2[1]; |
| 13726 | vinfos[2].maxsolutions = _nj2; |
| 13727 | vinfos[3].jointtype = 1; |
| 13728 | vinfos[3].foffset = j3; |
| 13729 | vinfos[3].indices[0] = _ij3[0]; |
| 13730 | vinfos[3].indices[1] = _ij3[1]; |
| 13731 | vinfos[3].maxsolutions = _nj3; |
| 13732 | vinfos[4].jointtype = 1; |
| 13733 | vinfos[4].foffset = j4; |
| 13734 | vinfos[4].indices[0] = _ij4[0]; |
| 13735 | vinfos[4].indices[1] = _ij4[1]; |
| 13736 | vinfos[4].maxsolutions = _nj4; |
| 13737 | vinfos[5].jointtype = 1; |
| 13738 | vinfos[5].foffset = j5; |
| 13739 | vinfos[5].indices[0] = _ij5[0]; |
| 13740 | vinfos[5].indices[1] = _ij5[1]; |
| 13741 | vinfos[5].maxsolutions = _nj5; |
| 13742 | std::vector<int> vfree(0); |
| 13743 | solutions.AddSolution(vinfos,vfree); |
| 13744 | } |
| 13745 | } |
| 13746 | } |
| 13747 | |
| 13748 | } |
| 13749 | |
| 13750 | } |
| 13751 | |
| 13752 | } |
| 13753 | } while(0); |
| 13754 | if( bgotonextstatement ) |
| 13755 | { |
| 13756 | bool bgotonextstatement = true; |
| 13757 | do |
| 13758 | { |
| 13759 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 13760 | evalcond[1]=gconst29; |
| 13761 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 13762 | { |
| 13763 | bgotonextstatement=false; |
| 13764 | { |
| 13765 | IkReal j0eval[3]; |
| 13766 | IkReal x1006=((-1.0)*new_r00); |
| 13767 | CheckValue<IkReal> x1008 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1006),IKFAST_ATAN2_MAGTHRESH); |
| 13768 | if(!x1008.valid){ |
| 13769 | continue; |
| 13770 | } |
| 13771 | IkReal x1007=((-1.0)*(x1008.value)); |
| 13772 | sj1=-1.0; |
| 13773 | cj1=0; |
| 13774 | j1=-1.5707963267949; |
| 13775 | sj2=gconst29; |
| 13776 | cj2=gconst30; |
| 13777 | j2=x1007; |
| 13778 | new_r11=0; |
| 13779 | new_r01=0; |
| 13780 | new_r22=0; |
| 13781 | new_r20=0; |
| 13782 | IkReal gconst28=x1007; |
| 13783 | IkReal gconst29=((-1.0)*new_r10); |
| 13784 | IkReal gconst30=x1006; |
| 13785 | j0eval[0]=-1.0; |
| 13786 | j0eval[1]=-1.0; |
| 13787 | j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| 13788 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13789 | { |
| 13790 | { |
| 13791 | IkReal j0eval[3]; |
| 13792 | IkReal x1009=((-1.0)*new_r00); |
| 13793 | CheckValue<IkReal> x1011 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1009),IKFAST_ATAN2_MAGTHRESH); |
| 13794 | if(!x1011.valid){ |
| 13795 | continue; |
| 13796 | } |
| 13797 | IkReal x1010=((-1.0)*(x1011.value)); |
| 13798 | sj1=-1.0; |
| 13799 | cj1=0; |
| 13800 | j1=-1.5707963267949; |
| 13801 | sj2=gconst29; |
| 13802 | cj2=gconst30; |
| 13803 | j2=x1010; |
| 13804 | new_r11=0; |
| 13805 | new_r01=0; |
| 13806 | new_r22=0; |
| 13807 | new_r20=0; |
| 13808 | IkReal gconst28=x1010; |
| 13809 | IkReal gconst29=((-1.0)*new_r10); |
| 13810 | IkReal gconst30=x1009; |
| 13811 | j0eval[0]=1.0; |
| 13812 | j0eval[1]=1.0; |
| 13813 | j0eval[2]=((IKabs(new_r10*new_r10))+(IKabs((new_r00*new_r10)))); |
| 13814 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13815 | { |
| 13816 | { |
| 13817 | IkReal j0eval[3]; |
| 13818 | IkReal x1012=((-1.0)*new_r00); |
| 13819 | CheckValue<IkReal> x1014 = IKatan2WithCheck(IkReal(new_r10),IkReal(x1012),IKFAST_ATAN2_MAGTHRESH); |
| 13820 | if(!x1014.valid){ |
| 13821 | continue; |
| 13822 | } |
| 13823 | IkReal x1013=((-1.0)*(x1014.value)); |
| 13824 | sj1=-1.0; |
| 13825 | cj1=0; |
| 13826 | j1=-1.5707963267949; |
| 13827 | sj2=gconst29; |
| 13828 | cj2=gconst30; |
| 13829 | j2=x1013; |
| 13830 | new_r11=0; |
| 13831 | new_r01=0; |
| 13832 | new_r22=0; |
| 13833 | new_r20=0; |
| 13834 | IkReal gconst28=x1013; |
| 13835 | IkReal gconst29=((-1.0)*new_r10); |
| 13836 | IkReal gconst30=x1012; |
| 13837 | j0eval[0]=1.0; |
| 13838 | j0eval[1]=1.0; |
| 13839 | j0eval[2]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs((new_r00*new_r10)))); |
| 13840 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 13841 | { |
| 13842 | continue; // 3 cases reached |
| 13843 | |
| 13844 | } else |
| 13845 | { |
| 13846 | { |
| 13847 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 13848 | bool j0valid[1]={false}; |
| 13849 | _nj0 = 1; |
| 13850 | CheckValue<IkReal> x1015=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst29*new_r10))+(((-1.0)*gconst30*new_r00)))),-1); |
| 13851 | if(!x1015.valid){ |
| 13852 | continue; |
| 13853 | } |
| 13854 | CheckValue<IkReal> x1016 = IKatan2WithCheck(IkReal(gconst30*gconst30),IkReal(((-1.0)*gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH); |
| 13855 | if(!x1016.valid){ |
| 13856 | continue; |
| 13857 | } |
| 13858 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1015.value)))+(x1016.value)); |
| 13859 | sj0array[0]=IKsin(j0array[0]); |
| 13860 | cj0array[0]=IKcos(j0array[0]); |
| 13861 | if( j0array[0] > IKPI ) |
| 13862 | { |
| 13863 | j0array[0]-=IK2PI; |
| 13864 | } |
| 13865 | else if( j0array[0] < -IKPI ) |
| 13866 | { j0array[0]+=IK2PI; |
| 13867 | } |
| 13868 | j0valid[0] = true; |
| 13869 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 13870 | { |
| 13871 | if( !j0valid[ij0] ) |
| 13872 | { |
| 13873 | continue; |
| 13874 | } |
| 13875 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13876 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 13877 | { |
| 13878 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13879 | { |
| 13880 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13881 | } |
| 13882 | } |
| 13883 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13884 | { |
| 13885 | IkReal evalcond[6]; |
| 13886 | IkReal x1017=IKsin(j0); |
| 13887 | IkReal x1018=IKcos(j0); |
| 13888 | IkReal x1019=((1.0)*x1017); |
| 13889 | IkReal x1020=(gconst29*x1018); |
| 13890 | IkReal x1021=((1.0)*x1018); |
| 13891 | IkReal x1022=(((gconst30*x1021))+((gconst29*x1019))); |
| 13892 | evalcond[0]=(x1020+(((-1.0)*gconst30*x1019))); |
| 13893 | evalcond[1]=(gconst30+(((-1.0)*new_r10*x1021))+((new_r00*x1017))); |
| 13894 | evalcond[2]=((((-1.0)*x1020))+((gconst30*x1017))+new_r00); |
| 13895 | evalcond[3]=((-1.0)*x1022); |
| 13896 | evalcond[4]=(((new_r10*x1017))+((new_r00*x1018))+(((-1.0)*gconst29))); |
| 13897 | evalcond[5]=((((-1.0)*x1022))+new_r10); |
| 13898 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 13899 | { |
| 13900 | continue; |
| 13901 | } |
| 13902 | } |
| 13903 | |
| 13904 | { |
| 13905 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 13906 | vinfos[0].jointtype = 1; |
| 13907 | vinfos[0].foffset = j0; |
| 13908 | vinfos[0].indices[0] = _ij0[0]; |
| 13909 | vinfos[0].indices[1] = _ij0[1]; |
| 13910 | vinfos[0].maxsolutions = _nj0; |
| 13911 | vinfos[1].jointtype = 1; |
| 13912 | vinfos[1].foffset = j1; |
| 13913 | vinfos[1].indices[0] = _ij1[0]; |
| 13914 | vinfos[1].indices[1] = _ij1[1]; |
| 13915 | vinfos[1].maxsolutions = _nj1; |
| 13916 | vinfos[2].jointtype = 1; |
| 13917 | vinfos[2].foffset = j2; |
| 13918 | vinfos[2].indices[0] = _ij2[0]; |
| 13919 | vinfos[2].indices[1] = _ij2[1]; |
| 13920 | vinfos[2].maxsolutions = _nj2; |
| 13921 | vinfos[3].jointtype = 1; |
| 13922 | vinfos[3].foffset = j3; |
| 13923 | vinfos[3].indices[0] = _ij3[0]; |
| 13924 | vinfos[3].indices[1] = _ij3[1]; |
| 13925 | vinfos[3].maxsolutions = _nj3; |
| 13926 | vinfos[4].jointtype = 1; |
| 13927 | vinfos[4].foffset = j4; |
| 13928 | vinfos[4].indices[0] = _ij4[0]; |
| 13929 | vinfos[4].indices[1] = _ij4[1]; |
| 13930 | vinfos[4].maxsolutions = _nj4; |
| 13931 | vinfos[5].jointtype = 1; |
| 13932 | vinfos[5].foffset = j5; |
| 13933 | vinfos[5].indices[0] = _ij5[0]; |
| 13934 | vinfos[5].indices[1] = _ij5[1]; |
| 13935 | vinfos[5].maxsolutions = _nj5; |
| 13936 | std::vector<int> vfree(0); |
| 13937 | solutions.AddSolution(vinfos,vfree); |
| 13938 | } |
| 13939 | } |
| 13940 | } |
| 13941 | |
| 13942 | } |
| 13943 | |
| 13944 | } |
| 13945 | |
| 13946 | } else |
| 13947 | { |
| 13948 | { |
| 13949 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 13950 | bool j0valid[1]={false}; |
| 13951 | _nj0 = 1; |
| 13952 | CheckValue<IkReal> x1023=IKPowWithIntegerCheck(IKsign(((gconst29*gconst29)+(gconst30*gconst30))),-1); |
| 13953 | if(!x1023.valid){ |
| 13954 | continue; |
| 13955 | } |
| 13956 | CheckValue<IkReal> x1024 = IKatan2WithCheck(IkReal((gconst29*new_r10)),IkReal((gconst30*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 13957 | if(!x1024.valid){ |
| 13958 | continue; |
| 13959 | } |
| 13960 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1023.value)))+(x1024.value)); |
| 13961 | sj0array[0]=IKsin(j0array[0]); |
| 13962 | cj0array[0]=IKcos(j0array[0]); |
| 13963 | if( j0array[0] > IKPI ) |
| 13964 | { |
| 13965 | j0array[0]-=IK2PI; |
| 13966 | } |
| 13967 | else if( j0array[0] < -IKPI ) |
| 13968 | { j0array[0]+=IK2PI; |
| 13969 | } |
| 13970 | j0valid[0] = true; |
| 13971 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 13972 | { |
| 13973 | if( !j0valid[ij0] ) |
| 13974 | { |
| 13975 | continue; |
| 13976 | } |
| 13977 | _ij0[0] = ij0; _ij0[1] = -1; |
| 13978 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 13979 | { |
| 13980 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 13981 | { |
| 13982 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 13983 | } |
| 13984 | } |
| 13985 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 13986 | { |
| 13987 | IkReal evalcond[6]; |
| 13988 | IkReal x1025=IKsin(j0); |
| 13989 | IkReal x1026=IKcos(j0); |
| 13990 | IkReal x1027=((1.0)*x1025); |
| 13991 | IkReal x1028=(gconst29*x1026); |
| 13992 | IkReal x1029=((1.0)*x1026); |
| 13993 | IkReal x1030=(((gconst30*x1029))+((gconst29*x1027))); |
| 13994 | evalcond[0]=(x1028+(((-1.0)*gconst30*x1027))); |
| 13995 | evalcond[1]=(gconst30+(((-1.0)*new_r10*x1029))+((new_r00*x1025))); |
| 13996 | evalcond[2]=((((-1.0)*x1028))+((gconst30*x1025))+new_r00); |
| 13997 | evalcond[3]=((-1.0)*x1030); |
| 13998 | evalcond[4]=(((new_r10*x1025))+(((-1.0)*gconst29))+((new_r00*x1026))); |
| 13999 | evalcond[5]=((((-1.0)*x1030))+new_r10); |
| 14000 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 14001 | { |
| 14002 | continue; |
| 14003 | } |
| 14004 | } |
| 14005 | |
| 14006 | { |
| 14007 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14008 | vinfos[0].jointtype = 1; |
| 14009 | vinfos[0].foffset = j0; |
| 14010 | vinfos[0].indices[0] = _ij0[0]; |
| 14011 | vinfos[0].indices[1] = _ij0[1]; |
| 14012 | vinfos[0].maxsolutions = _nj0; |
| 14013 | vinfos[1].jointtype = 1; |
| 14014 | vinfos[1].foffset = j1; |
| 14015 | vinfos[1].indices[0] = _ij1[0]; |
| 14016 | vinfos[1].indices[1] = _ij1[1]; |
| 14017 | vinfos[1].maxsolutions = _nj1; |
| 14018 | vinfos[2].jointtype = 1; |
| 14019 | vinfos[2].foffset = j2; |
| 14020 | vinfos[2].indices[0] = _ij2[0]; |
| 14021 | vinfos[2].indices[1] = _ij2[1]; |
| 14022 | vinfos[2].maxsolutions = _nj2; |
| 14023 | vinfos[3].jointtype = 1; |
| 14024 | vinfos[3].foffset = j3; |
| 14025 | vinfos[3].indices[0] = _ij3[0]; |
| 14026 | vinfos[3].indices[1] = _ij3[1]; |
| 14027 | vinfos[3].maxsolutions = _nj3; |
| 14028 | vinfos[4].jointtype = 1; |
| 14029 | vinfos[4].foffset = j4; |
| 14030 | vinfos[4].indices[0] = _ij4[0]; |
| 14031 | vinfos[4].indices[1] = _ij4[1]; |
| 14032 | vinfos[4].maxsolutions = _nj4; |
| 14033 | vinfos[5].jointtype = 1; |
| 14034 | vinfos[5].foffset = j5; |
| 14035 | vinfos[5].indices[0] = _ij5[0]; |
| 14036 | vinfos[5].indices[1] = _ij5[1]; |
| 14037 | vinfos[5].maxsolutions = _nj5; |
| 14038 | std::vector<int> vfree(0); |
| 14039 | solutions.AddSolution(vinfos,vfree); |
| 14040 | } |
| 14041 | } |
| 14042 | } |
| 14043 | |
| 14044 | } |
| 14045 | |
| 14046 | } |
| 14047 | |
| 14048 | } else |
| 14049 | { |
| 14050 | { |
| 14051 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14052 | bool j0valid[1]={false}; |
| 14053 | _nj0 = 1; |
| 14054 | CheckValue<IkReal> x1031=IKPowWithIntegerCheck(IKsign((((gconst29*new_r10))+((gconst30*new_r00)))),-1); |
| 14055 | if(!x1031.valid){ |
| 14056 | continue; |
| 14057 | } |
| 14058 | CheckValue<IkReal> x1032 = IKatan2WithCheck(IkReal(gconst29*gconst29),IkReal((gconst29*gconst30)),IKFAST_ATAN2_MAGTHRESH); |
| 14059 | if(!x1032.valid){ |
| 14060 | continue; |
| 14061 | } |
| 14062 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1031.value)))+(x1032.value)); |
| 14063 | sj0array[0]=IKsin(j0array[0]); |
| 14064 | cj0array[0]=IKcos(j0array[0]); |
| 14065 | if( j0array[0] > IKPI ) |
| 14066 | { |
| 14067 | j0array[0]-=IK2PI; |
| 14068 | } |
| 14069 | else if( j0array[0] < -IKPI ) |
| 14070 | { j0array[0]+=IK2PI; |
| 14071 | } |
| 14072 | j0valid[0] = true; |
| 14073 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14074 | { |
| 14075 | if( !j0valid[ij0] ) |
| 14076 | { |
| 14077 | continue; |
| 14078 | } |
| 14079 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14080 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14081 | { |
| 14082 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14083 | { |
| 14084 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14085 | } |
| 14086 | } |
| 14087 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14088 | { |
| 14089 | IkReal evalcond[6]; |
| 14090 | IkReal x1033=IKsin(j0); |
| 14091 | IkReal x1034=IKcos(j0); |
| 14092 | IkReal x1035=((1.0)*x1033); |
| 14093 | IkReal x1036=(gconst29*x1034); |
| 14094 | IkReal x1037=((1.0)*x1034); |
| 14095 | IkReal x1038=(((gconst30*x1037))+((gconst29*x1035))); |
| 14096 | evalcond[0]=(x1036+(((-1.0)*gconst30*x1035))); |
| 14097 | evalcond[1]=(gconst30+(((-1.0)*new_r10*x1037))+((new_r00*x1033))); |
| 14098 | evalcond[2]=((((-1.0)*x1036))+((gconst30*x1033))+new_r00); |
| 14099 | evalcond[3]=((-1.0)*x1038); |
| 14100 | evalcond[4]=(((new_r10*x1033))+(((-1.0)*gconst29))+((new_r00*x1034))); |
| 14101 | evalcond[5]=((((-1.0)*x1038))+new_r10); |
| 14102 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 14103 | { |
| 14104 | continue; |
| 14105 | } |
| 14106 | } |
| 14107 | |
| 14108 | { |
| 14109 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14110 | vinfos[0].jointtype = 1; |
| 14111 | vinfos[0].foffset = j0; |
| 14112 | vinfos[0].indices[0] = _ij0[0]; |
| 14113 | vinfos[0].indices[1] = _ij0[1]; |
| 14114 | vinfos[0].maxsolutions = _nj0; |
| 14115 | vinfos[1].jointtype = 1; |
| 14116 | vinfos[1].foffset = j1; |
| 14117 | vinfos[1].indices[0] = _ij1[0]; |
| 14118 | vinfos[1].indices[1] = _ij1[1]; |
| 14119 | vinfos[1].maxsolutions = _nj1; |
| 14120 | vinfos[2].jointtype = 1; |
| 14121 | vinfos[2].foffset = j2; |
| 14122 | vinfos[2].indices[0] = _ij2[0]; |
| 14123 | vinfos[2].indices[1] = _ij2[1]; |
| 14124 | vinfos[2].maxsolutions = _nj2; |
| 14125 | vinfos[3].jointtype = 1; |
| 14126 | vinfos[3].foffset = j3; |
| 14127 | vinfos[3].indices[0] = _ij3[0]; |
| 14128 | vinfos[3].indices[1] = _ij3[1]; |
| 14129 | vinfos[3].maxsolutions = _nj3; |
| 14130 | vinfos[4].jointtype = 1; |
| 14131 | vinfos[4].foffset = j4; |
| 14132 | vinfos[4].indices[0] = _ij4[0]; |
| 14133 | vinfos[4].indices[1] = _ij4[1]; |
| 14134 | vinfos[4].maxsolutions = _nj4; |
| 14135 | vinfos[5].jointtype = 1; |
| 14136 | vinfos[5].foffset = j5; |
| 14137 | vinfos[5].indices[0] = _ij5[0]; |
| 14138 | vinfos[5].indices[1] = _ij5[1]; |
| 14139 | vinfos[5].maxsolutions = _nj5; |
| 14140 | std::vector<int> vfree(0); |
| 14141 | solutions.AddSolution(vinfos,vfree); |
| 14142 | } |
| 14143 | } |
| 14144 | } |
| 14145 | |
| 14146 | } |
| 14147 | |
| 14148 | } |
| 14149 | |
| 14150 | } |
| 14151 | } while(0); |
| 14152 | if( bgotonextstatement ) |
| 14153 | { |
| 14154 | bool bgotonextstatement = true; |
| 14155 | do |
| 14156 | { |
| 14157 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| 14158 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 14159 | { |
| 14160 | bgotonextstatement=false; |
| 14161 | { |
| 14162 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 14163 | bool j0valid[2]={false}; |
| 14164 | _nj0 = 2; |
| 14165 | CheckValue<IkReal> x1039=IKPowWithIntegerCheck(gconst30,-1); |
| 14166 | if(!x1039.valid){ |
| 14167 | continue; |
| 14168 | } |
| 14169 | sj0array[0]=(new_r11*(x1039.value)); |
| 14170 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 14171 | { |
| 14172 | j0valid[0] = j0valid[1] = true; |
| 14173 | j0array[0] = IKasin(sj0array[0]); |
| 14174 | cj0array[0] = IKcos(j0array[0]); |
| 14175 | sj0array[1] = sj0array[0]; |
| 14176 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 14177 | cj0array[1] = -cj0array[0]; |
| 14178 | } |
| 14179 | else if( isnan(sj0array[0]) ) |
| 14180 | { |
| 14181 | // probably any value will work |
| 14182 | j0valid[0] = true; |
| 14183 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 14184 | } |
| 14185 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 14186 | { |
| 14187 | if( !j0valid[ij0] ) |
| 14188 | { |
| 14189 | continue; |
| 14190 | } |
| 14191 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14192 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 14193 | { |
| 14194 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14195 | { |
| 14196 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14197 | } |
| 14198 | } |
| 14199 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14200 | { |
| 14201 | IkReal evalcond[6]; |
| 14202 | IkReal x1040=IKcos(j0); |
| 14203 | IkReal x1041=IKsin(j0); |
| 14204 | evalcond[0]=(new_r11*x1040); |
| 14205 | evalcond[1]=(new_r00*x1040); |
| 14206 | evalcond[2]=((-1.0)*gconst30*x1040); |
| 14207 | evalcond[3]=(gconst30+((new_r00*x1041))); |
| 14208 | evalcond[4]=(new_r00+((gconst30*x1041))); |
| 14209 | evalcond[5]=(((new_r11*x1041))+(((-1.0)*gconst30))); |
| 14210 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 14211 | { |
| 14212 | continue; |
| 14213 | } |
| 14214 | } |
| 14215 | |
| 14216 | { |
| 14217 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14218 | vinfos[0].jointtype = 1; |
| 14219 | vinfos[0].foffset = j0; |
| 14220 | vinfos[0].indices[0] = _ij0[0]; |
| 14221 | vinfos[0].indices[1] = _ij0[1]; |
| 14222 | vinfos[0].maxsolutions = _nj0; |
| 14223 | vinfos[1].jointtype = 1; |
| 14224 | vinfos[1].foffset = j1; |
| 14225 | vinfos[1].indices[0] = _ij1[0]; |
| 14226 | vinfos[1].indices[1] = _ij1[1]; |
| 14227 | vinfos[1].maxsolutions = _nj1; |
| 14228 | vinfos[2].jointtype = 1; |
| 14229 | vinfos[2].foffset = j2; |
| 14230 | vinfos[2].indices[0] = _ij2[0]; |
| 14231 | vinfos[2].indices[1] = _ij2[1]; |
| 14232 | vinfos[2].maxsolutions = _nj2; |
| 14233 | vinfos[3].jointtype = 1; |
| 14234 | vinfos[3].foffset = j3; |
| 14235 | vinfos[3].indices[0] = _ij3[0]; |
| 14236 | vinfos[3].indices[1] = _ij3[1]; |
| 14237 | vinfos[3].maxsolutions = _nj3; |
| 14238 | vinfos[4].jointtype = 1; |
| 14239 | vinfos[4].foffset = j4; |
| 14240 | vinfos[4].indices[0] = _ij4[0]; |
| 14241 | vinfos[4].indices[1] = _ij4[1]; |
| 14242 | vinfos[4].maxsolutions = _nj4; |
| 14243 | vinfos[5].jointtype = 1; |
| 14244 | vinfos[5].foffset = j5; |
| 14245 | vinfos[5].indices[0] = _ij5[0]; |
| 14246 | vinfos[5].indices[1] = _ij5[1]; |
| 14247 | vinfos[5].maxsolutions = _nj5; |
| 14248 | std::vector<int> vfree(0); |
| 14249 | solutions.AddSolution(vinfos,vfree); |
| 14250 | } |
| 14251 | } |
| 14252 | } |
| 14253 | |
| 14254 | } |
| 14255 | } while(0); |
| 14256 | if( bgotonextstatement ) |
| 14257 | { |
| 14258 | bool bgotonextstatement = true; |
| 14259 | do |
| 14260 | { |
| 14261 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 14262 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 14263 | { |
| 14264 | bgotonextstatement=false; |
| 14265 | { |
| 14266 | IkReal j0eval[1]; |
| 14267 | IkReal x1042=((-1.0)*new_r00); |
| 14268 | CheckValue<IkReal> x1044 = IKatan2WithCheck(IkReal(0),IkReal(x1042),IKFAST_ATAN2_MAGTHRESH); |
| 14269 | if(!x1044.valid){ |
| 14270 | continue; |
| 14271 | } |
| 14272 | IkReal x1043=((-1.0)*(x1044.value)); |
| 14273 | sj1=-1.0; |
| 14274 | cj1=0; |
| 14275 | j1=-1.5707963267949; |
| 14276 | sj2=gconst29; |
| 14277 | cj2=gconst30; |
| 14278 | j2=x1043; |
| 14279 | new_r11=0; |
| 14280 | new_r10=0; |
| 14281 | new_r22=0; |
| 14282 | new_r02=0; |
| 14283 | IkReal gconst28=x1043; |
| 14284 | IkReal gconst29=0; |
| 14285 | IkReal x1045 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 14286 | if(IKabs(x1045)==0){ |
| 14287 | continue; |
| 14288 | } |
| 14289 | IkReal gconst30=(x1042*(pow(x1045,-0.5))); |
| 14290 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 14291 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 14292 | { |
| 14293 | { |
| 14294 | IkReal j0eval[1]; |
| 14295 | IkReal x1046=((-1.0)*new_r00); |
| 14296 | CheckValue<IkReal> x1048 = IKatan2WithCheck(IkReal(0),IkReal(x1046),IKFAST_ATAN2_MAGTHRESH); |
| 14297 | if(!x1048.valid){ |
| 14298 | continue; |
| 14299 | } |
| 14300 | IkReal x1047=((-1.0)*(x1048.value)); |
| 14301 | sj1=-1.0; |
| 14302 | cj1=0; |
| 14303 | j1=-1.5707963267949; |
| 14304 | sj2=gconst29; |
| 14305 | cj2=gconst30; |
| 14306 | j2=x1047; |
| 14307 | new_r11=0; |
| 14308 | new_r10=0; |
| 14309 | new_r22=0; |
| 14310 | new_r02=0; |
| 14311 | IkReal gconst28=x1047; |
| 14312 | IkReal gconst29=0; |
| 14313 | IkReal x1049 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 14314 | if(IKabs(x1049)==0){ |
| 14315 | continue; |
| 14316 | } |
| 14317 | IkReal gconst30=(x1046*(pow(x1049,-0.5))); |
| 14318 | j0eval[0]=new_r00; |
| 14319 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 14320 | { |
| 14321 | { |
| 14322 | IkReal j0eval[2]; |
| 14323 | IkReal x1050=((-1.0)*new_r00); |
| 14324 | CheckValue<IkReal> x1052 = IKatan2WithCheck(IkReal(0),IkReal(x1050),IKFAST_ATAN2_MAGTHRESH); |
| 14325 | if(!x1052.valid){ |
| 14326 | continue; |
| 14327 | } |
| 14328 | IkReal x1051=((-1.0)*(x1052.value)); |
| 14329 | sj1=-1.0; |
| 14330 | cj1=0; |
| 14331 | j1=-1.5707963267949; |
| 14332 | sj2=gconst29; |
| 14333 | cj2=gconst30; |
| 14334 | j2=x1051; |
| 14335 | new_r11=0; |
| 14336 | new_r10=0; |
| 14337 | new_r22=0; |
| 14338 | new_r02=0; |
| 14339 | IkReal gconst28=x1051; |
| 14340 | IkReal gconst29=0; |
| 14341 | IkReal x1053 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 14342 | if(IKabs(x1053)==0){ |
| 14343 | continue; |
| 14344 | } |
| 14345 | IkReal gconst30=(x1050*(pow(x1053,-0.5))); |
| 14346 | j0eval[0]=new_r00; |
| 14347 | j0eval[1]=new_r01; |
| 14348 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 14349 | { |
| 14350 | continue; // 3 cases reached |
| 14351 | |
| 14352 | } else |
| 14353 | { |
| 14354 | { |
| 14355 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14356 | bool j0valid[1]={false}; |
| 14357 | _nj0 = 1; |
| 14358 | CheckValue<IkReal> x1054=IKPowWithIntegerCheck(new_r00,-1); |
| 14359 | if(!x1054.valid){ |
| 14360 | continue; |
| 14361 | } |
| 14362 | CheckValue<IkReal> x1055=IKPowWithIntegerCheck(new_r01,-1); |
| 14363 | if(!x1055.valid){ |
| 14364 | continue; |
| 14365 | } |
| 14366 | if( IKabs(((-1.0)*gconst30*(x1054.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst30*(x1055.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1054.value)))+IKsqr((gconst30*(x1055.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 14367 | continue; |
| 14368 | j0array[0]=IKatan2(((-1.0)*gconst30*(x1054.value)), (gconst30*(x1055.value))); |
| 14369 | sj0array[0]=IKsin(j0array[0]); |
| 14370 | cj0array[0]=IKcos(j0array[0]); |
| 14371 | if( j0array[0] > IKPI ) |
| 14372 | { |
| 14373 | j0array[0]-=IK2PI; |
| 14374 | } |
| 14375 | else if( j0array[0] < -IKPI ) |
| 14376 | { j0array[0]+=IK2PI; |
| 14377 | } |
| 14378 | j0valid[0] = true; |
| 14379 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14380 | { |
| 14381 | if( !j0valid[ij0] ) |
| 14382 | { |
| 14383 | continue; |
| 14384 | } |
| 14385 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14386 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14387 | { |
| 14388 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14389 | { |
| 14390 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14391 | } |
| 14392 | } |
| 14393 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14394 | { |
| 14395 | IkReal evalcond[8]; |
| 14396 | IkReal x1056=IKsin(j0); |
| 14397 | IkReal x1057=IKcos(j0); |
| 14398 | IkReal x1058=((1.0)*gconst30); |
| 14399 | IkReal x1059=((-1.0)*gconst30); |
| 14400 | evalcond[0]=(new_r00*x1057); |
| 14401 | evalcond[1]=((-1.0)*new_r01*x1056); |
| 14402 | evalcond[2]=(x1056*x1059); |
| 14403 | evalcond[3]=(x1057*x1059); |
| 14404 | evalcond[4]=(gconst30+((new_r00*x1056))); |
| 14405 | evalcond[5]=(((gconst30*x1056))+new_r00); |
| 14406 | evalcond[6]=((((-1.0)*x1057*x1058))+new_r01); |
| 14407 | evalcond[7]=((((-1.0)*x1058))+((new_r01*x1057))); |
| 14408 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 14409 | { |
| 14410 | continue; |
| 14411 | } |
| 14412 | } |
| 14413 | |
| 14414 | { |
| 14415 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14416 | vinfos[0].jointtype = 1; |
| 14417 | vinfos[0].foffset = j0; |
| 14418 | vinfos[0].indices[0] = _ij0[0]; |
| 14419 | vinfos[0].indices[1] = _ij0[1]; |
| 14420 | vinfos[0].maxsolutions = _nj0; |
| 14421 | vinfos[1].jointtype = 1; |
| 14422 | vinfos[1].foffset = j1; |
| 14423 | vinfos[1].indices[0] = _ij1[0]; |
| 14424 | vinfos[1].indices[1] = _ij1[1]; |
| 14425 | vinfos[1].maxsolutions = _nj1; |
| 14426 | vinfos[2].jointtype = 1; |
| 14427 | vinfos[2].foffset = j2; |
| 14428 | vinfos[2].indices[0] = _ij2[0]; |
| 14429 | vinfos[2].indices[1] = _ij2[1]; |
| 14430 | vinfos[2].maxsolutions = _nj2; |
| 14431 | vinfos[3].jointtype = 1; |
| 14432 | vinfos[3].foffset = j3; |
| 14433 | vinfos[3].indices[0] = _ij3[0]; |
| 14434 | vinfos[3].indices[1] = _ij3[1]; |
| 14435 | vinfos[3].maxsolutions = _nj3; |
| 14436 | vinfos[4].jointtype = 1; |
| 14437 | vinfos[4].foffset = j4; |
| 14438 | vinfos[4].indices[0] = _ij4[0]; |
| 14439 | vinfos[4].indices[1] = _ij4[1]; |
| 14440 | vinfos[4].maxsolutions = _nj4; |
| 14441 | vinfos[5].jointtype = 1; |
| 14442 | vinfos[5].foffset = j5; |
| 14443 | vinfos[5].indices[0] = _ij5[0]; |
| 14444 | vinfos[5].indices[1] = _ij5[1]; |
| 14445 | vinfos[5].maxsolutions = _nj5; |
| 14446 | std::vector<int> vfree(0); |
| 14447 | solutions.AddSolution(vinfos,vfree); |
| 14448 | } |
| 14449 | } |
| 14450 | } |
| 14451 | |
| 14452 | } |
| 14453 | |
| 14454 | } |
| 14455 | |
| 14456 | } else |
| 14457 | { |
| 14458 | { |
| 14459 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14460 | bool j0valid[1]={false}; |
| 14461 | _nj0 = 1; |
| 14462 | CheckValue<IkReal> x1060=IKPowWithIntegerCheck(new_r00,-1); |
| 14463 | if(!x1060.valid){ |
| 14464 | continue; |
| 14465 | } |
| 14466 | CheckValue<IkReal> x1061=IKPowWithIntegerCheck(gconst30,-1); |
| 14467 | if(!x1061.valid){ |
| 14468 | continue; |
| 14469 | } |
| 14470 | if( IKabs(((-1.0)*gconst30*(x1060.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1061.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1060.value)))+IKsqr((new_r01*(x1061.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 14471 | continue; |
| 14472 | j0array[0]=IKatan2(((-1.0)*gconst30*(x1060.value)), (new_r01*(x1061.value))); |
| 14473 | sj0array[0]=IKsin(j0array[0]); |
| 14474 | cj0array[0]=IKcos(j0array[0]); |
| 14475 | if( j0array[0] > IKPI ) |
| 14476 | { |
| 14477 | j0array[0]-=IK2PI; |
| 14478 | } |
| 14479 | else if( j0array[0] < -IKPI ) |
| 14480 | { j0array[0]+=IK2PI; |
| 14481 | } |
| 14482 | j0valid[0] = true; |
| 14483 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14484 | { |
| 14485 | if( !j0valid[ij0] ) |
| 14486 | { |
| 14487 | continue; |
| 14488 | } |
| 14489 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14490 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14491 | { |
| 14492 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14493 | { |
| 14494 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14495 | } |
| 14496 | } |
| 14497 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14498 | { |
| 14499 | IkReal evalcond[8]; |
| 14500 | IkReal x1062=IKsin(j0); |
| 14501 | IkReal x1063=IKcos(j0); |
| 14502 | IkReal x1064=((1.0)*gconst30); |
| 14503 | IkReal x1065=((-1.0)*gconst30); |
| 14504 | evalcond[0]=(new_r00*x1063); |
| 14505 | evalcond[1]=((-1.0)*new_r01*x1062); |
| 14506 | evalcond[2]=(x1062*x1065); |
| 14507 | evalcond[3]=(x1063*x1065); |
| 14508 | evalcond[4]=(gconst30+((new_r00*x1062))); |
| 14509 | evalcond[5]=(((gconst30*x1062))+new_r00); |
| 14510 | evalcond[6]=((((-1.0)*x1063*x1064))+new_r01); |
| 14511 | evalcond[7]=(((new_r01*x1063))+(((-1.0)*x1064))); |
| 14512 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 14513 | { |
| 14514 | continue; |
| 14515 | } |
| 14516 | } |
| 14517 | |
| 14518 | { |
| 14519 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14520 | vinfos[0].jointtype = 1; |
| 14521 | vinfos[0].foffset = j0; |
| 14522 | vinfos[0].indices[0] = _ij0[0]; |
| 14523 | vinfos[0].indices[1] = _ij0[1]; |
| 14524 | vinfos[0].maxsolutions = _nj0; |
| 14525 | vinfos[1].jointtype = 1; |
| 14526 | vinfos[1].foffset = j1; |
| 14527 | vinfos[1].indices[0] = _ij1[0]; |
| 14528 | vinfos[1].indices[1] = _ij1[1]; |
| 14529 | vinfos[1].maxsolutions = _nj1; |
| 14530 | vinfos[2].jointtype = 1; |
| 14531 | vinfos[2].foffset = j2; |
| 14532 | vinfos[2].indices[0] = _ij2[0]; |
| 14533 | vinfos[2].indices[1] = _ij2[1]; |
| 14534 | vinfos[2].maxsolutions = _nj2; |
| 14535 | vinfos[3].jointtype = 1; |
| 14536 | vinfos[3].foffset = j3; |
| 14537 | vinfos[3].indices[0] = _ij3[0]; |
| 14538 | vinfos[3].indices[1] = _ij3[1]; |
| 14539 | vinfos[3].maxsolutions = _nj3; |
| 14540 | vinfos[4].jointtype = 1; |
| 14541 | vinfos[4].foffset = j4; |
| 14542 | vinfos[4].indices[0] = _ij4[0]; |
| 14543 | vinfos[4].indices[1] = _ij4[1]; |
| 14544 | vinfos[4].maxsolutions = _nj4; |
| 14545 | vinfos[5].jointtype = 1; |
| 14546 | vinfos[5].foffset = j5; |
| 14547 | vinfos[5].indices[0] = _ij5[0]; |
| 14548 | vinfos[5].indices[1] = _ij5[1]; |
| 14549 | vinfos[5].maxsolutions = _nj5; |
| 14550 | std::vector<int> vfree(0); |
| 14551 | solutions.AddSolution(vinfos,vfree); |
| 14552 | } |
| 14553 | } |
| 14554 | } |
| 14555 | |
| 14556 | } |
| 14557 | |
| 14558 | } |
| 14559 | |
| 14560 | } else |
| 14561 | { |
| 14562 | { |
| 14563 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14564 | bool j0valid[1]={false}; |
| 14565 | _nj0 = 1; |
| 14566 | CheckValue<IkReal> x1066=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| 14567 | if(!x1066.valid){ |
| 14568 | continue; |
| 14569 | } |
| 14570 | CheckValue<IkReal> x1067 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 14571 | if(!x1067.valid){ |
| 14572 | continue; |
| 14573 | } |
| 14574 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1066.value)))+(x1067.value)); |
| 14575 | sj0array[0]=IKsin(j0array[0]); |
| 14576 | cj0array[0]=IKcos(j0array[0]); |
| 14577 | if( j0array[0] > IKPI ) |
| 14578 | { |
| 14579 | j0array[0]-=IK2PI; |
| 14580 | } |
| 14581 | else if( j0array[0] < -IKPI ) |
| 14582 | { j0array[0]+=IK2PI; |
| 14583 | } |
| 14584 | j0valid[0] = true; |
| 14585 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14586 | { |
| 14587 | if( !j0valid[ij0] ) |
| 14588 | { |
| 14589 | continue; |
| 14590 | } |
| 14591 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14592 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14593 | { |
| 14594 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14595 | { |
| 14596 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14597 | } |
| 14598 | } |
| 14599 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14600 | { |
| 14601 | IkReal evalcond[8]; |
| 14602 | IkReal x1068=IKsin(j0); |
| 14603 | IkReal x1069=IKcos(j0); |
| 14604 | IkReal x1070=((1.0)*gconst30); |
| 14605 | IkReal x1071=((-1.0)*gconst30); |
| 14606 | evalcond[0]=(new_r00*x1069); |
| 14607 | evalcond[1]=((-1.0)*new_r01*x1068); |
| 14608 | evalcond[2]=(x1068*x1071); |
| 14609 | evalcond[3]=(x1069*x1071); |
| 14610 | evalcond[4]=(gconst30+((new_r00*x1068))); |
| 14611 | evalcond[5]=(((gconst30*x1068))+new_r00); |
| 14612 | evalcond[6]=(new_r01+(((-1.0)*x1069*x1070))); |
| 14613 | evalcond[7]=(((new_r01*x1069))+(((-1.0)*x1070))); |
| 14614 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 14615 | { |
| 14616 | continue; |
| 14617 | } |
| 14618 | } |
| 14619 | |
| 14620 | { |
| 14621 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14622 | vinfos[0].jointtype = 1; |
| 14623 | vinfos[0].foffset = j0; |
| 14624 | vinfos[0].indices[0] = _ij0[0]; |
| 14625 | vinfos[0].indices[1] = _ij0[1]; |
| 14626 | vinfos[0].maxsolutions = _nj0; |
| 14627 | vinfos[1].jointtype = 1; |
| 14628 | vinfos[1].foffset = j1; |
| 14629 | vinfos[1].indices[0] = _ij1[0]; |
| 14630 | vinfos[1].indices[1] = _ij1[1]; |
| 14631 | vinfos[1].maxsolutions = _nj1; |
| 14632 | vinfos[2].jointtype = 1; |
| 14633 | vinfos[2].foffset = j2; |
| 14634 | vinfos[2].indices[0] = _ij2[0]; |
| 14635 | vinfos[2].indices[1] = _ij2[1]; |
| 14636 | vinfos[2].maxsolutions = _nj2; |
| 14637 | vinfos[3].jointtype = 1; |
| 14638 | vinfos[3].foffset = j3; |
| 14639 | vinfos[3].indices[0] = _ij3[0]; |
| 14640 | vinfos[3].indices[1] = _ij3[1]; |
| 14641 | vinfos[3].maxsolutions = _nj3; |
| 14642 | vinfos[4].jointtype = 1; |
| 14643 | vinfos[4].foffset = j4; |
| 14644 | vinfos[4].indices[0] = _ij4[0]; |
| 14645 | vinfos[4].indices[1] = _ij4[1]; |
| 14646 | vinfos[4].maxsolutions = _nj4; |
| 14647 | vinfos[5].jointtype = 1; |
| 14648 | vinfos[5].foffset = j5; |
| 14649 | vinfos[5].indices[0] = _ij5[0]; |
| 14650 | vinfos[5].indices[1] = _ij5[1]; |
| 14651 | vinfos[5].maxsolutions = _nj5; |
| 14652 | std::vector<int> vfree(0); |
| 14653 | solutions.AddSolution(vinfos,vfree); |
| 14654 | } |
| 14655 | } |
| 14656 | } |
| 14657 | |
| 14658 | } |
| 14659 | |
| 14660 | } |
| 14661 | |
| 14662 | } |
| 14663 | } while(0); |
| 14664 | if( bgotonextstatement ) |
| 14665 | { |
| 14666 | bool bgotonextstatement = true; |
| 14667 | do |
| 14668 | { |
| 14669 | evalcond[0]=IKabs(new_r10); |
| 14670 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 14671 | { |
| 14672 | bgotonextstatement=false; |
| 14673 | { |
| 14674 | IkReal j0eval[1]; |
| 14675 | IkReal x1072=((-1.0)*new_r00); |
| 14676 | CheckValue<IkReal> x1074 = IKatan2WithCheck(IkReal(0),IkReal(x1072),IKFAST_ATAN2_MAGTHRESH); |
| 14677 | if(!x1074.valid){ |
| 14678 | continue; |
| 14679 | } |
| 14680 | IkReal x1073=((-1.0)*(x1074.value)); |
| 14681 | sj1=-1.0; |
| 14682 | cj1=0; |
| 14683 | j1=-1.5707963267949; |
| 14684 | sj2=gconst29; |
| 14685 | cj2=gconst30; |
| 14686 | j2=x1073; |
| 14687 | new_r10=0; |
| 14688 | IkReal gconst28=x1073; |
| 14689 | IkReal gconst29=0; |
| 14690 | IkReal x1075 = new_r00*new_r00; |
| 14691 | if(IKabs(x1075)==0){ |
| 14692 | continue; |
| 14693 | } |
| 14694 | IkReal gconst30=(x1072*(pow(x1075,-0.5))); |
| 14695 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 14696 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 14697 | { |
| 14698 | { |
| 14699 | IkReal j0eval[1]; |
| 14700 | IkReal x1076=((-1.0)*new_r00); |
| 14701 | CheckValue<IkReal> x1078 = IKatan2WithCheck(IkReal(0),IkReal(x1076),IKFAST_ATAN2_MAGTHRESH); |
| 14702 | if(!x1078.valid){ |
| 14703 | continue; |
| 14704 | } |
| 14705 | IkReal x1077=((-1.0)*(x1078.value)); |
| 14706 | sj1=-1.0; |
| 14707 | cj1=0; |
| 14708 | j1=-1.5707963267949; |
| 14709 | sj2=gconst29; |
| 14710 | cj2=gconst30; |
| 14711 | j2=x1077; |
| 14712 | new_r10=0; |
| 14713 | IkReal gconst28=x1077; |
| 14714 | IkReal gconst29=0; |
| 14715 | IkReal x1079 = new_r00*new_r00; |
| 14716 | if(IKabs(x1079)==0){ |
| 14717 | continue; |
| 14718 | } |
| 14719 | IkReal gconst30=(x1076*(pow(x1079,-0.5))); |
| 14720 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 14721 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 14722 | { |
| 14723 | { |
| 14724 | IkReal j0eval[1]; |
| 14725 | IkReal x1080=((-1.0)*new_r00); |
| 14726 | CheckValue<IkReal> x1082 = IKatan2WithCheck(IkReal(0),IkReal(x1080),IKFAST_ATAN2_MAGTHRESH); |
| 14727 | if(!x1082.valid){ |
| 14728 | continue; |
| 14729 | } |
| 14730 | IkReal x1081=((-1.0)*(x1082.value)); |
| 14731 | sj1=-1.0; |
| 14732 | cj1=0; |
| 14733 | j1=-1.5707963267949; |
| 14734 | sj2=gconst29; |
| 14735 | cj2=gconst30; |
| 14736 | j2=x1081; |
| 14737 | new_r10=0; |
| 14738 | IkReal gconst28=x1081; |
| 14739 | IkReal gconst29=0; |
| 14740 | IkReal x1083 = new_r00*new_r00; |
| 14741 | if(IKabs(x1083)==0){ |
| 14742 | continue; |
| 14743 | } |
| 14744 | IkReal gconst30=(x1080*(pow(x1083,-0.5))); |
| 14745 | j0eval[0]=new_r00; |
| 14746 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 14747 | { |
| 14748 | continue; // 3 cases reached |
| 14749 | |
| 14750 | } else |
| 14751 | { |
| 14752 | { |
| 14753 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14754 | bool j0valid[1]={false}; |
| 14755 | _nj0 = 1; |
| 14756 | CheckValue<IkReal> x1084=IKPowWithIntegerCheck(new_r00,-1); |
| 14757 | if(!x1084.valid){ |
| 14758 | continue; |
| 14759 | } |
| 14760 | CheckValue<IkReal> x1085=IKPowWithIntegerCheck(gconst30,-1); |
| 14761 | if(!x1085.valid){ |
| 14762 | continue; |
| 14763 | } |
| 14764 | if( IKabs(((-1.0)*gconst30*(x1084.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1085.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst30*(x1084.value)))+IKsqr((new_r01*(x1085.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 14765 | continue; |
| 14766 | j0array[0]=IKatan2(((-1.0)*gconst30*(x1084.value)), (new_r01*(x1085.value))); |
| 14767 | sj0array[0]=IKsin(j0array[0]); |
| 14768 | cj0array[0]=IKcos(j0array[0]); |
| 14769 | if( j0array[0] > IKPI ) |
| 14770 | { |
| 14771 | j0array[0]-=IK2PI; |
| 14772 | } |
| 14773 | else if( j0array[0] < -IKPI ) |
| 14774 | { j0array[0]+=IK2PI; |
| 14775 | } |
| 14776 | j0valid[0] = true; |
| 14777 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14778 | { |
| 14779 | if( !j0valid[ij0] ) |
| 14780 | { |
| 14781 | continue; |
| 14782 | } |
| 14783 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14784 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14785 | { |
| 14786 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14787 | { |
| 14788 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14789 | } |
| 14790 | } |
| 14791 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14792 | { |
| 14793 | IkReal evalcond[8]; |
| 14794 | IkReal x1086=IKcos(j0); |
| 14795 | IkReal x1087=IKsin(j0); |
| 14796 | IkReal x1088=((1.0)*gconst30); |
| 14797 | evalcond[0]=(new_r00*x1086); |
| 14798 | evalcond[1]=((-1.0)*gconst30*x1086); |
| 14799 | evalcond[2]=(((new_r00*x1087))+gconst30); |
| 14800 | evalcond[3]=(((gconst30*x1087))+new_r00); |
| 14801 | evalcond[4]=((((-1.0)*x1087*x1088))+new_r11); |
| 14802 | evalcond[5]=(new_r01+(((-1.0)*x1086*x1088))); |
| 14803 | evalcond[6]=((((-1.0)*new_r01*x1087))+((new_r11*x1086))); |
| 14804 | evalcond[7]=(((new_r01*x1086))+((new_r11*x1087))+(((-1.0)*x1088))); |
| 14805 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 14806 | { |
| 14807 | continue; |
| 14808 | } |
| 14809 | } |
| 14810 | |
| 14811 | { |
| 14812 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14813 | vinfos[0].jointtype = 1; |
| 14814 | vinfos[0].foffset = j0; |
| 14815 | vinfos[0].indices[0] = _ij0[0]; |
| 14816 | vinfos[0].indices[1] = _ij0[1]; |
| 14817 | vinfos[0].maxsolutions = _nj0; |
| 14818 | vinfos[1].jointtype = 1; |
| 14819 | vinfos[1].foffset = j1; |
| 14820 | vinfos[1].indices[0] = _ij1[0]; |
| 14821 | vinfos[1].indices[1] = _ij1[1]; |
| 14822 | vinfos[1].maxsolutions = _nj1; |
| 14823 | vinfos[2].jointtype = 1; |
| 14824 | vinfos[2].foffset = j2; |
| 14825 | vinfos[2].indices[0] = _ij2[0]; |
| 14826 | vinfos[2].indices[1] = _ij2[1]; |
| 14827 | vinfos[2].maxsolutions = _nj2; |
| 14828 | vinfos[3].jointtype = 1; |
| 14829 | vinfos[3].foffset = j3; |
| 14830 | vinfos[3].indices[0] = _ij3[0]; |
| 14831 | vinfos[3].indices[1] = _ij3[1]; |
| 14832 | vinfos[3].maxsolutions = _nj3; |
| 14833 | vinfos[4].jointtype = 1; |
| 14834 | vinfos[4].foffset = j4; |
| 14835 | vinfos[4].indices[0] = _ij4[0]; |
| 14836 | vinfos[4].indices[1] = _ij4[1]; |
| 14837 | vinfos[4].maxsolutions = _nj4; |
| 14838 | vinfos[5].jointtype = 1; |
| 14839 | vinfos[5].foffset = j5; |
| 14840 | vinfos[5].indices[0] = _ij5[0]; |
| 14841 | vinfos[5].indices[1] = _ij5[1]; |
| 14842 | vinfos[5].maxsolutions = _nj5; |
| 14843 | std::vector<int> vfree(0); |
| 14844 | solutions.AddSolution(vinfos,vfree); |
| 14845 | } |
| 14846 | } |
| 14847 | } |
| 14848 | |
| 14849 | } |
| 14850 | |
| 14851 | } |
| 14852 | |
| 14853 | } else |
| 14854 | { |
| 14855 | { |
| 14856 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14857 | bool j0valid[1]={false}; |
| 14858 | _nj0 = 1; |
| 14859 | CheckValue<IkReal> x1089=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| 14860 | if(!x1089.valid){ |
| 14861 | continue; |
| 14862 | } |
| 14863 | CheckValue<IkReal> x1090 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 14864 | if(!x1090.valid){ |
| 14865 | continue; |
| 14866 | } |
| 14867 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1089.value)))+(x1090.value)); |
| 14868 | sj0array[0]=IKsin(j0array[0]); |
| 14869 | cj0array[0]=IKcos(j0array[0]); |
| 14870 | if( j0array[0] > IKPI ) |
| 14871 | { |
| 14872 | j0array[0]-=IK2PI; |
| 14873 | } |
| 14874 | else if( j0array[0] < -IKPI ) |
| 14875 | { j0array[0]+=IK2PI; |
| 14876 | } |
| 14877 | j0valid[0] = true; |
| 14878 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14879 | { |
| 14880 | if( !j0valid[ij0] ) |
| 14881 | { |
| 14882 | continue; |
| 14883 | } |
| 14884 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14885 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14886 | { |
| 14887 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14888 | { |
| 14889 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14890 | } |
| 14891 | } |
| 14892 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14893 | { |
| 14894 | IkReal evalcond[8]; |
| 14895 | IkReal x1091=IKcos(j0); |
| 14896 | IkReal x1092=IKsin(j0); |
| 14897 | IkReal x1093=((1.0)*gconst30); |
| 14898 | evalcond[0]=(new_r00*x1091); |
| 14899 | evalcond[1]=((-1.0)*gconst30*x1091); |
| 14900 | evalcond[2]=(((new_r00*x1092))+gconst30); |
| 14901 | evalcond[3]=(((gconst30*x1092))+new_r00); |
| 14902 | evalcond[4]=((((-1.0)*x1092*x1093))+new_r11); |
| 14903 | evalcond[5]=((((-1.0)*x1091*x1093))+new_r01); |
| 14904 | evalcond[6]=(((new_r11*x1091))+(((-1.0)*new_r01*x1092))); |
| 14905 | evalcond[7]=(((new_r11*x1092))+((new_r01*x1091))+(((-1.0)*x1093))); |
| 14906 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 14907 | { |
| 14908 | continue; |
| 14909 | } |
| 14910 | } |
| 14911 | |
| 14912 | { |
| 14913 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 14914 | vinfos[0].jointtype = 1; |
| 14915 | vinfos[0].foffset = j0; |
| 14916 | vinfos[0].indices[0] = _ij0[0]; |
| 14917 | vinfos[0].indices[1] = _ij0[1]; |
| 14918 | vinfos[0].maxsolutions = _nj0; |
| 14919 | vinfos[1].jointtype = 1; |
| 14920 | vinfos[1].foffset = j1; |
| 14921 | vinfos[1].indices[0] = _ij1[0]; |
| 14922 | vinfos[1].indices[1] = _ij1[1]; |
| 14923 | vinfos[1].maxsolutions = _nj1; |
| 14924 | vinfos[2].jointtype = 1; |
| 14925 | vinfos[2].foffset = j2; |
| 14926 | vinfos[2].indices[0] = _ij2[0]; |
| 14927 | vinfos[2].indices[1] = _ij2[1]; |
| 14928 | vinfos[2].maxsolutions = _nj2; |
| 14929 | vinfos[3].jointtype = 1; |
| 14930 | vinfos[3].foffset = j3; |
| 14931 | vinfos[3].indices[0] = _ij3[0]; |
| 14932 | vinfos[3].indices[1] = _ij3[1]; |
| 14933 | vinfos[3].maxsolutions = _nj3; |
| 14934 | vinfos[4].jointtype = 1; |
| 14935 | vinfos[4].foffset = j4; |
| 14936 | vinfos[4].indices[0] = _ij4[0]; |
| 14937 | vinfos[4].indices[1] = _ij4[1]; |
| 14938 | vinfos[4].maxsolutions = _nj4; |
| 14939 | vinfos[5].jointtype = 1; |
| 14940 | vinfos[5].foffset = j5; |
| 14941 | vinfos[5].indices[0] = _ij5[0]; |
| 14942 | vinfos[5].indices[1] = _ij5[1]; |
| 14943 | vinfos[5].maxsolutions = _nj5; |
| 14944 | std::vector<int> vfree(0); |
| 14945 | solutions.AddSolution(vinfos,vfree); |
| 14946 | } |
| 14947 | } |
| 14948 | } |
| 14949 | |
| 14950 | } |
| 14951 | |
| 14952 | } |
| 14953 | |
| 14954 | } else |
| 14955 | { |
| 14956 | { |
| 14957 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 14958 | bool j0valid[1]={false}; |
| 14959 | _nj0 = 1; |
| 14960 | CheckValue<IkReal> x1094=IKPowWithIntegerCheck(IKsign(gconst30),-1); |
| 14961 | if(!x1094.valid){ |
| 14962 | continue; |
| 14963 | } |
| 14964 | CheckValue<IkReal> x1095 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 14965 | if(!x1095.valid){ |
| 14966 | continue; |
| 14967 | } |
| 14968 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1094.value)))+(x1095.value)); |
| 14969 | sj0array[0]=IKsin(j0array[0]); |
| 14970 | cj0array[0]=IKcos(j0array[0]); |
| 14971 | if( j0array[0] > IKPI ) |
| 14972 | { |
| 14973 | j0array[0]-=IK2PI; |
| 14974 | } |
| 14975 | else if( j0array[0] < -IKPI ) |
| 14976 | { j0array[0]+=IK2PI; |
| 14977 | } |
| 14978 | j0valid[0] = true; |
| 14979 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 14980 | { |
| 14981 | if( !j0valid[ij0] ) |
| 14982 | { |
| 14983 | continue; |
| 14984 | } |
| 14985 | _ij0[0] = ij0; _ij0[1] = -1; |
| 14986 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 14987 | { |
| 14988 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 14989 | { |
| 14990 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 14991 | } |
| 14992 | } |
| 14993 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 14994 | { |
| 14995 | IkReal evalcond[8]; |
| 14996 | IkReal x1096=IKcos(j0); |
| 14997 | IkReal x1097=IKsin(j0); |
| 14998 | IkReal x1098=((1.0)*gconst30); |
| 14999 | evalcond[0]=(new_r00*x1096); |
| 15000 | evalcond[1]=((-1.0)*gconst30*x1096); |
| 15001 | evalcond[2]=(((new_r00*x1097))+gconst30); |
| 15002 | evalcond[3]=(((gconst30*x1097))+new_r00); |
| 15003 | evalcond[4]=((((-1.0)*x1097*x1098))+new_r11); |
| 15004 | evalcond[5]=((((-1.0)*x1096*x1098))+new_r01); |
| 15005 | evalcond[6]=(((new_r11*x1096))+(((-1.0)*new_r01*x1097))); |
| 15006 | evalcond[7]=(((new_r11*x1097))+((new_r01*x1096))+(((-1.0)*x1098))); |
| 15007 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15008 | { |
| 15009 | continue; |
| 15010 | } |
| 15011 | } |
| 15012 | |
| 15013 | { |
| 15014 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15015 | vinfos[0].jointtype = 1; |
| 15016 | vinfos[0].foffset = j0; |
| 15017 | vinfos[0].indices[0] = _ij0[0]; |
| 15018 | vinfos[0].indices[1] = _ij0[1]; |
| 15019 | vinfos[0].maxsolutions = _nj0; |
| 15020 | vinfos[1].jointtype = 1; |
| 15021 | vinfos[1].foffset = j1; |
| 15022 | vinfos[1].indices[0] = _ij1[0]; |
| 15023 | vinfos[1].indices[1] = _ij1[1]; |
| 15024 | vinfos[1].maxsolutions = _nj1; |
| 15025 | vinfos[2].jointtype = 1; |
| 15026 | vinfos[2].foffset = j2; |
| 15027 | vinfos[2].indices[0] = _ij2[0]; |
| 15028 | vinfos[2].indices[1] = _ij2[1]; |
| 15029 | vinfos[2].maxsolutions = _nj2; |
| 15030 | vinfos[3].jointtype = 1; |
| 15031 | vinfos[3].foffset = j3; |
| 15032 | vinfos[3].indices[0] = _ij3[0]; |
| 15033 | vinfos[3].indices[1] = _ij3[1]; |
| 15034 | vinfos[3].maxsolutions = _nj3; |
| 15035 | vinfos[4].jointtype = 1; |
| 15036 | vinfos[4].foffset = j4; |
| 15037 | vinfos[4].indices[0] = _ij4[0]; |
| 15038 | vinfos[4].indices[1] = _ij4[1]; |
| 15039 | vinfos[4].maxsolutions = _nj4; |
| 15040 | vinfos[5].jointtype = 1; |
| 15041 | vinfos[5].foffset = j5; |
| 15042 | vinfos[5].indices[0] = _ij5[0]; |
| 15043 | vinfos[5].indices[1] = _ij5[1]; |
| 15044 | vinfos[5].maxsolutions = _nj5; |
| 15045 | std::vector<int> vfree(0); |
| 15046 | solutions.AddSolution(vinfos,vfree); |
| 15047 | } |
| 15048 | } |
| 15049 | } |
| 15050 | |
| 15051 | } |
| 15052 | |
| 15053 | } |
| 15054 | |
| 15055 | } |
| 15056 | } while(0); |
| 15057 | if( bgotonextstatement ) |
| 15058 | { |
| 15059 | bool bgotonextstatement = true; |
| 15060 | do |
| 15061 | { |
| 15062 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 15063 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 15064 | { |
| 15065 | bgotonextstatement=false; |
| 15066 | { |
| 15067 | IkReal j0eval[1]; |
| 15068 | CheckValue<IkReal> x1100 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 15069 | if(!x1100.valid){ |
| 15070 | continue; |
| 15071 | } |
| 15072 | IkReal x1099=((-1.0)*(x1100.value)); |
| 15073 | sj1=-1.0; |
| 15074 | cj1=0; |
| 15075 | j1=-1.5707963267949; |
| 15076 | sj2=gconst29; |
| 15077 | cj2=gconst30; |
| 15078 | j2=x1099; |
| 15079 | new_r00=0; |
| 15080 | new_r01=0; |
| 15081 | new_r12=0; |
| 15082 | new_r22=0; |
| 15083 | IkReal gconst28=x1099; |
| 15084 | IkReal x1101 = new_r10*new_r10; |
| 15085 | if(IKabs(x1101)==0){ |
| 15086 | continue; |
| 15087 | } |
| 15088 | IkReal gconst29=((-1.0)*new_r10*(pow(x1101,-0.5))); |
| 15089 | IkReal gconst30=0; |
| 15090 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 15091 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 15092 | { |
| 15093 | { |
| 15094 | IkReal j0eval[1]; |
| 15095 | CheckValue<IkReal> x1103 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 15096 | if(!x1103.valid){ |
| 15097 | continue; |
| 15098 | } |
| 15099 | IkReal x1102=((-1.0)*(x1103.value)); |
| 15100 | sj1=-1.0; |
| 15101 | cj1=0; |
| 15102 | j1=-1.5707963267949; |
| 15103 | sj2=gconst29; |
| 15104 | cj2=gconst30; |
| 15105 | j2=x1102; |
| 15106 | new_r00=0; |
| 15107 | new_r01=0; |
| 15108 | new_r12=0; |
| 15109 | new_r22=0; |
| 15110 | IkReal gconst28=x1102; |
| 15111 | IkReal x1104 = new_r10*new_r10; |
| 15112 | if(IKabs(x1104)==0){ |
| 15113 | continue; |
| 15114 | } |
| 15115 | IkReal gconst29=((-1.0)*new_r10*(pow(x1104,-0.5))); |
| 15116 | IkReal gconst30=0; |
| 15117 | j0eval[0]=new_r11; |
| 15118 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 15119 | { |
| 15120 | { |
| 15121 | IkReal j0eval[2]; |
| 15122 | CheckValue<IkReal> x1106 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 15123 | if(!x1106.valid){ |
| 15124 | continue; |
| 15125 | } |
| 15126 | IkReal x1105=((-1.0)*(x1106.value)); |
| 15127 | sj1=-1.0; |
| 15128 | cj1=0; |
| 15129 | j1=-1.5707963267949; |
| 15130 | sj2=gconst29; |
| 15131 | cj2=gconst30; |
| 15132 | j2=x1105; |
| 15133 | new_r00=0; |
| 15134 | new_r01=0; |
| 15135 | new_r12=0; |
| 15136 | new_r22=0; |
| 15137 | IkReal gconst28=x1105; |
| 15138 | IkReal x1107 = new_r10*new_r10; |
| 15139 | if(IKabs(x1107)==0){ |
| 15140 | continue; |
| 15141 | } |
| 15142 | IkReal gconst29=((-1.0)*new_r10*(pow(x1107,-0.5))); |
| 15143 | IkReal gconst30=0; |
| 15144 | j0eval[0]=new_r10; |
| 15145 | j0eval[1]=new_r11; |
| 15146 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 15147 | { |
| 15148 | continue; // 3 cases reached |
| 15149 | |
| 15150 | } else |
| 15151 | { |
| 15152 | { |
| 15153 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15154 | bool j0valid[1]={false}; |
| 15155 | _nj0 = 1; |
| 15156 | CheckValue<IkReal> x1108=IKPowWithIntegerCheck(new_r10,-1); |
| 15157 | if(!x1108.valid){ |
| 15158 | continue; |
| 15159 | } |
| 15160 | CheckValue<IkReal> x1109=IKPowWithIntegerCheck(new_r11,-1); |
| 15161 | if(!x1109.valid){ |
| 15162 | continue; |
| 15163 | } |
| 15164 | if( IKabs((gconst29*(x1108.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst29*(x1109.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst29*(x1108.value)))+IKsqr(((-1.0)*gconst29*(x1109.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 15165 | continue; |
| 15166 | j0array[0]=IKatan2((gconst29*(x1108.value)), ((-1.0)*gconst29*(x1109.value))); |
| 15167 | sj0array[0]=IKsin(j0array[0]); |
| 15168 | cj0array[0]=IKcos(j0array[0]); |
| 15169 | if( j0array[0] > IKPI ) |
| 15170 | { |
| 15171 | j0array[0]-=IK2PI; |
| 15172 | } |
| 15173 | else if( j0array[0] < -IKPI ) |
| 15174 | { j0array[0]+=IK2PI; |
| 15175 | } |
| 15176 | j0valid[0] = true; |
| 15177 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15178 | { |
| 15179 | if( !j0valid[ij0] ) |
| 15180 | { |
| 15181 | continue; |
| 15182 | } |
| 15183 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15184 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15185 | { |
| 15186 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15187 | { |
| 15188 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15189 | } |
| 15190 | } |
| 15191 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15192 | { |
| 15193 | IkReal evalcond[8]; |
| 15194 | IkReal x1110=IKcos(j0); |
| 15195 | IkReal x1111=IKsin(j0); |
| 15196 | IkReal x1112=((1.0)*gconst29); |
| 15197 | IkReal x1113=(gconst29*x1110); |
| 15198 | evalcond[0]=(new_r11*x1111); |
| 15199 | evalcond[1]=((-1.0)*new_r10*x1110); |
| 15200 | evalcond[2]=((-1.0)*x1113); |
| 15201 | evalcond[3]=((-1.0)*gconst29*x1111); |
| 15202 | evalcond[4]=(gconst29+((new_r11*x1110))); |
| 15203 | evalcond[5]=(x1113+new_r11); |
| 15204 | evalcond[6]=(new_r10+(((-1.0)*x1111*x1112))); |
| 15205 | evalcond[7]=(((new_r10*x1111))+(((-1.0)*x1112))); |
| 15206 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15207 | { |
| 15208 | continue; |
| 15209 | } |
| 15210 | } |
| 15211 | |
| 15212 | { |
| 15213 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15214 | vinfos[0].jointtype = 1; |
| 15215 | vinfos[0].foffset = j0; |
| 15216 | vinfos[0].indices[0] = _ij0[0]; |
| 15217 | vinfos[0].indices[1] = _ij0[1]; |
| 15218 | vinfos[0].maxsolutions = _nj0; |
| 15219 | vinfos[1].jointtype = 1; |
| 15220 | vinfos[1].foffset = j1; |
| 15221 | vinfos[1].indices[0] = _ij1[0]; |
| 15222 | vinfos[1].indices[1] = _ij1[1]; |
| 15223 | vinfos[1].maxsolutions = _nj1; |
| 15224 | vinfos[2].jointtype = 1; |
| 15225 | vinfos[2].foffset = j2; |
| 15226 | vinfos[2].indices[0] = _ij2[0]; |
| 15227 | vinfos[2].indices[1] = _ij2[1]; |
| 15228 | vinfos[2].maxsolutions = _nj2; |
| 15229 | vinfos[3].jointtype = 1; |
| 15230 | vinfos[3].foffset = j3; |
| 15231 | vinfos[3].indices[0] = _ij3[0]; |
| 15232 | vinfos[3].indices[1] = _ij3[1]; |
| 15233 | vinfos[3].maxsolutions = _nj3; |
| 15234 | vinfos[4].jointtype = 1; |
| 15235 | vinfos[4].foffset = j4; |
| 15236 | vinfos[4].indices[0] = _ij4[0]; |
| 15237 | vinfos[4].indices[1] = _ij4[1]; |
| 15238 | vinfos[4].maxsolutions = _nj4; |
| 15239 | vinfos[5].jointtype = 1; |
| 15240 | vinfos[5].foffset = j5; |
| 15241 | vinfos[5].indices[0] = _ij5[0]; |
| 15242 | vinfos[5].indices[1] = _ij5[1]; |
| 15243 | vinfos[5].maxsolutions = _nj5; |
| 15244 | std::vector<int> vfree(0); |
| 15245 | solutions.AddSolution(vinfos,vfree); |
| 15246 | } |
| 15247 | } |
| 15248 | } |
| 15249 | |
| 15250 | } |
| 15251 | |
| 15252 | } |
| 15253 | |
| 15254 | } else |
| 15255 | { |
| 15256 | { |
| 15257 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15258 | bool j0valid[1]={false}; |
| 15259 | _nj0 = 1; |
| 15260 | CheckValue<IkReal> x1114=IKPowWithIntegerCheck(gconst29,-1); |
| 15261 | if(!x1114.valid){ |
| 15262 | continue; |
| 15263 | } |
| 15264 | CheckValue<IkReal> x1115=IKPowWithIntegerCheck(new_r11,-1); |
| 15265 | if(!x1115.valid){ |
| 15266 | continue; |
| 15267 | } |
| 15268 | if( IKabs((new_r10*(x1114.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst29*(x1115.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1114.value)))+IKsqr(((-1.0)*gconst29*(x1115.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 15269 | continue; |
| 15270 | j0array[0]=IKatan2((new_r10*(x1114.value)), ((-1.0)*gconst29*(x1115.value))); |
| 15271 | sj0array[0]=IKsin(j0array[0]); |
| 15272 | cj0array[0]=IKcos(j0array[0]); |
| 15273 | if( j0array[0] > IKPI ) |
| 15274 | { |
| 15275 | j0array[0]-=IK2PI; |
| 15276 | } |
| 15277 | else if( j0array[0] < -IKPI ) |
| 15278 | { j0array[0]+=IK2PI; |
| 15279 | } |
| 15280 | j0valid[0] = true; |
| 15281 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15282 | { |
| 15283 | if( !j0valid[ij0] ) |
| 15284 | { |
| 15285 | continue; |
| 15286 | } |
| 15287 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15288 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15289 | { |
| 15290 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15291 | { |
| 15292 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15293 | } |
| 15294 | } |
| 15295 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15296 | { |
| 15297 | IkReal evalcond[8]; |
| 15298 | IkReal x1116=IKcos(j0); |
| 15299 | IkReal x1117=IKsin(j0); |
| 15300 | IkReal x1118=((1.0)*gconst29); |
| 15301 | IkReal x1119=(gconst29*x1116); |
| 15302 | evalcond[0]=(new_r11*x1117); |
| 15303 | evalcond[1]=((-1.0)*new_r10*x1116); |
| 15304 | evalcond[2]=((-1.0)*x1119); |
| 15305 | evalcond[3]=((-1.0)*gconst29*x1117); |
| 15306 | evalcond[4]=(gconst29+((new_r11*x1116))); |
| 15307 | evalcond[5]=(x1119+new_r11); |
| 15308 | evalcond[6]=(new_r10+(((-1.0)*x1117*x1118))); |
| 15309 | evalcond[7]=(((new_r10*x1117))+(((-1.0)*x1118))); |
| 15310 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15311 | { |
| 15312 | continue; |
| 15313 | } |
| 15314 | } |
| 15315 | |
| 15316 | { |
| 15317 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15318 | vinfos[0].jointtype = 1; |
| 15319 | vinfos[0].foffset = j0; |
| 15320 | vinfos[0].indices[0] = _ij0[0]; |
| 15321 | vinfos[0].indices[1] = _ij0[1]; |
| 15322 | vinfos[0].maxsolutions = _nj0; |
| 15323 | vinfos[1].jointtype = 1; |
| 15324 | vinfos[1].foffset = j1; |
| 15325 | vinfos[1].indices[0] = _ij1[0]; |
| 15326 | vinfos[1].indices[1] = _ij1[1]; |
| 15327 | vinfos[1].maxsolutions = _nj1; |
| 15328 | vinfos[2].jointtype = 1; |
| 15329 | vinfos[2].foffset = j2; |
| 15330 | vinfos[2].indices[0] = _ij2[0]; |
| 15331 | vinfos[2].indices[1] = _ij2[1]; |
| 15332 | vinfos[2].maxsolutions = _nj2; |
| 15333 | vinfos[3].jointtype = 1; |
| 15334 | vinfos[3].foffset = j3; |
| 15335 | vinfos[3].indices[0] = _ij3[0]; |
| 15336 | vinfos[3].indices[1] = _ij3[1]; |
| 15337 | vinfos[3].maxsolutions = _nj3; |
| 15338 | vinfos[4].jointtype = 1; |
| 15339 | vinfos[4].foffset = j4; |
| 15340 | vinfos[4].indices[0] = _ij4[0]; |
| 15341 | vinfos[4].indices[1] = _ij4[1]; |
| 15342 | vinfos[4].maxsolutions = _nj4; |
| 15343 | vinfos[5].jointtype = 1; |
| 15344 | vinfos[5].foffset = j5; |
| 15345 | vinfos[5].indices[0] = _ij5[0]; |
| 15346 | vinfos[5].indices[1] = _ij5[1]; |
| 15347 | vinfos[5].maxsolutions = _nj5; |
| 15348 | std::vector<int> vfree(0); |
| 15349 | solutions.AddSolution(vinfos,vfree); |
| 15350 | } |
| 15351 | } |
| 15352 | } |
| 15353 | |
| 15354 | } |
| 15355 | |
| 15356 | } |
| 15357 | |
| 15358 | } else |
| 15359 | { |
| 15360 | { |
| 15361 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15362 | bool j0valid[1]={false}; |
| 15363 | _nj0 = 1; |
| 15364 | CheckValue<IkReal> x1120 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 15365 | if(!x1120.valid){ |
| 15366 | continue; |
| 15367 | } |
| 15368 | CheckValue<IkReal> x1121=IKPowWithIntegerCheck(IKsign(gconst29),-1); |
| 15369 | if(!x1121.valid){ |
| 15370 | continue; |
| 15371 | } |
| 15372 | j0array[0]=((-1.5707963267949)+(x1120.value)+(((1.5707963267949)*(x1121.value)))); |
| 15373 | sj0array[0]=IKsin(j0array[0]); |
| 15374 | cj0array[0]=IKcos(j0array[0]); |
| 15375 | if( j0array[0] > IKPI ) |
| 15376 | { |
| 15377 | j0array[0]-=IK2PI; |
| 15378 | } |
| 15379 | else if( j0array[0] < -IKPI ) |
| 15380 | { j0array[0]+=IK2PI; |
| 15381 | } |
| 15382 | j0valid[0] = true; |
| 15383 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15384 | { |
| 15385 | if( !j0valid[ij0] ) |
| 15386 | { |
| 15387 | continue; |
| 15388 | } |
| 15389 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15390 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15391 | { |
| 15392 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15393 | { |
| 15394 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15395 | } |
| 15396 | } |
| 15397 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15398 | { |
| 15399 | IkReal evalcond[8]; |
| 15400 | IkReal x1122=IKcos(j0); |
| 15401 | IkReal x1123=IKsin(j0); |
| 15402 | IkReal x1124=((1.0)*gconst29); |
| 15403 | IkReal x1125=(gconst29*x1122); |
| 15404 | evalcond[0]=(new_r11*x1123); |
| 15405 | evalcond[1]=((-1.0)*new_r10*x1122); |
| 15406 | evalcond[2]=((-1.0)*x1125); |
| 15407 | evalcond[3]=((-1.0)*gconst29*x1123); |
| 15408 | evalcond[4]=(gconst29+((new_r11*x1122))); |
| 15409 | evalcond[5]=(x1125+new_r11); |
| 15410 | evalcond[6]=((((-1.0)*x1123*x1124))+new_r10); |
| 15411 | evalcond[7]=(((new_r10*x1123))+(((-1.0)*x1124))); |
| 15412 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15413 | { |
| 15414 | continue; |
| 15415 | } |
| 15416 | } |
| 15417 | |
| 15418 | { |
| 15419 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15420 | vinfos[0].jointtype = 1; |
| 15421 | vinfos[0].foffset = j0; |
| 15422 | vinfos[0].indices[0] = _ij0[0]; |
| 15423 | vinfos[0].indices[1] = _ij0[1]; |
| 15424 | vinfos[0].maxsolutions = _nj0; |
| 15425 | vinfos[1].jointtype = 1; |
| 15426 | vinfos[1].foffset = j1; |
| 15427 | vinfos[1].indices[0] = _ij1[0]; |
| 15428 | vinfos[1].indices[1] = _ij1[1]; |
| 15429 | vinfos[1].maxsolutions = _nj1; |
| 15430 | vinfos[2].jointtype = 1; |
| 15431 | vinfos[2].foffset = j2; |
| 15432 | vinfos[2].indices[0] = _ij2[0]; |
| 15433 | vinfos[2].indices[1] = _ij2[1]; |
| 15434 | vinfos[2].maxsolutions = _nj2; |
| 15435 | vinfos[3].jointtype = 1; |
| 15436 | vinfos[3].foffset = j3; |
| 15437 | vinfos[3].indices[0] = _ij3[0]; |
| 15438 | vinfos[3].indices[1] = _ij3[1]; |
| 15439 | vinfos[3].maxsolutions = _nj3; |
| 15440 | vinfos[4].jointtype = 1; |
| 15441 | vinfos[4].foffset = j4; |
| 15442 | vinfos[4].indices[0] = _ij4[0]; |
| 15443 | vinfos[4].indices[1] = _ij4[1]; |
| 15444 | vinfos[4].maxsolutions = _nj4; |
| 15445 | vinfos[5].jointtype = 1; |
| 15446 | vinfos[5].foffset = j5; |
| 15447 | vinfos[5].indices[0] = _ij5[0]; |
| 15448 | vinfos[5].indices[1] = _ij5[1]; |
| 15449 | vinfos[5].maxsolutions = _nj5; |
| 15450 | std::vector<int> vfree(0); |
| 15451 | solutions.AddSolution(vinfos,vfree); |
| 15452 | } |
| 15453 | } |
| 15454 | } |
| 15455 | |
| 15456 | } |
| 15457 | |
| 15458 | } |
| 15459 | |
| 15460 | } |
| 15461 | } while(0); |
| 15462 | if( bgotonextstatement ) |
| 15463 | { |
| 15464 | bool bgotonextstatement = true; |
| 15465 | do |
| 15466 | { |
| 15467 | if( 1 ) |
| 15468 | { |
| 15469 | bgotonextstatement=false; |
| 15470 | continue; // branch miss [j0] |
| 15471 | |
| 15472 | } |
| 15473 | } while(0); |
| 15474 | if( bgotonextstatement ) |
| 15475 | { |
| 15476 | } |
| 15477 | } |
| 15478 | } |
| 15479 | } |
| 15480 | } |
| 15481 | } |
| 15482 | } |
| 15483 | } |
| 15484 | |
| 15485 | } else |
| 15486 | { |
| 15487 | { |
| 15488 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15489 | bool j0valid[1]={false}; |
| 15490 | _nj0 = 1; |
| 15491 | CheckValue<IkReal> x1126 = IKatan2WithCheck(IkReal((((gconst29*new_r11))+((gconst29*new_r00)))),IkReal((((gconst29*new_r01))+(((-1.0)*gconst29*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| 15492 | if(!x1126.valid){ |
| 15493 | continue; |
| 15494 | } |
| 15495 | CheckValue<IkReal> x1127=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 15496 | if(!x1127.valid){ |
| 15497 | continue; |
| 15498 | } |
| 15499 | j0array[0]=((-1.5707963267949)+(x1126.value)+(((1.5707963267949)*(x1127.value)))); |
| 15500 | sj0array[0]=IKsin(j0array[0]); |
| 15501 | cj0array[0]=IKcos(j0array[0]); |
| 15502 | if( j0array[0] > IKPI ) |
| 15503 | { |
| 15504 | j0array[0]-=IK2PI; |
| 15505 | } |
| 15506 | else if( j0array[0] < -IKPI ) |
| 15507 | { j0array[0]+=IK2PI; |
| 15508 | } |
| 15509 | j0valid[0] = true; |
| 15510 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15511 | { |
| 15512 | if( !j0valid[ij0] ) |
| 15513 | { |
| 15514 | continue; |
| 15515 | } |
| 15516 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15517 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15518 | { |
| 15519 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15520 | { |
| 15521 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15522 | } |
| 15523 | } |
| 15524 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15525 | { |
| 15526 | IkReal evalcond[8]; |
| 15527 | IkReal x1128=IKsin(j0); |
| 15528 | IkReal x1129=IKcos(j0); |
| 15529 | IkReal x1130=((1.0)*gconst30); |
| 15530 | IkReal x1131=((1.0)*gconst29); |
| 15531 | IkReal x1132=(gconst29*x1129); |
| 15532 | IkReal x1133=(((x1129*x1130))+((x1128*x1131))); |
| 15533 | evalcond[0]=((((-1.0)*new_r01*x1128))+gconst29+((new_r11*x1129))); |
| 15534 | evalcond[1]=(gconst30+((new_r00*x1128))+(((-1.0)*new_r10*x1129))); |
| 15535 | evalcond[2]=(((gconst30*x1128))+new_r00+(((-1.0)*x1129*x1131))); |
| 15536 | evalcond[3]=(x1132+(((-1.0)*x1128*x1130))+new_r11); |
| 15537 | evalcond[4]=(((new_r10*x1128))+(((-1.0)*x1131))+((new_r00*x1129))); |
| 15538 | evalcond[5]=((((-1.0)*x1130))+((new_r01*x1129))+((new_r11*x1128))); |
| 15539 | evalcond[6]=((((-1.0)*x1133))+new_r01); |
| 15540 | evalcond[7]=((((-1.0)*x1133))+new_r10); |
| 15541 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15542 | { |
| 15543 | continue; |
| 15544 | } |
| 15545 | } |
| 15546 | |
| 15547 | { |
| 15548 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15549 | vinfos[0].jointtype = 1; |
| 15550 | vinfos[0].foffset = j0; |
| 15551 | vinfos[0].indices[0] = _ij0[0]; |
| 15552 | vinfos[0].indices[1] = _ij0[1]; |
| 15553 | vinfos[0].maxsolutions = _nj0; |
| 15554 | vinfos[1].jointtype = 1; |
| 15555 | vinfos[1].foffset = j1; |
| 15556 | vinfos[1].indices[0] = _ij1[0]; |
| 15557 | vinfos[1].indices[1] = _ij1[1]; |
| 15558 | vinfos[1].maxsolutions = _nj1; |
| 15559 | vinfos[2].jointtype = 1; |
| 15560 | vinfos[2].foffset = j2; |
| 15561 | vinfos[2].indices[0] = _ij2[0]; |
| 15562 | vinfos[2].indices[1] = _ij2[1]; |
| 15563 | vinfos[2].maxsolutions = _nj2; |
| 15564 | vinfos[3].jointtype = 1; |
| 15565 | vinfos[3].foffset = j3; |
| 15566 | vinfos[3].indices[0] = _ij3[0]; |
| 15567 | vinfos[3].indices[1] = _ij3[1]; |
| 15568 | vinfos[3].maxsolutions = _nj3; |
| 15569 | vinfos[4].jointtype = 1; |
| 15570 | vinfos[4].foffset = j4; |
| 15571 | vinfos[4].indices[0] = _ij4[0]; |
| 15572 | vinfos[4].indices[1] = _ij4[1]; |
| 15573 | vinfos[4].maxsolutions = _nj4; |
| 15574 | vinfos[5].jointtype = 1; |
| 15575 | vinfos[5].foffset = j5; |
| 15576 | vinfos[5].indices[0] = _ij5[0]; |
| 15577 | vinfos[5].indices[1] = _ij5[1]; |
| 15578 | vinfos[5].maxsolutions = _nj5; |
| 15579 | std::vector<int> vfree(0); |
| 15580 | solutions.AddSolution(vinfos,vfree); |
| 15581 | } |
| 15582 | } |
| 15583 | } |
| 15584 | |
| 15585 | } |
| 15586 | |
| 15587 | } |
| 15588 | |
| 15589 | } else |
| 15590 | { |
| 15591 | { |
| 15592 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15593 | bool j0valid[1]={false}; |
| 15594 | _nj0 = 1; |
| 15595 | CheckValue<IkReal> x1134 = IKatan2WithCheck(IkReal(((gconst29*gconst29)+((new_r00*new_r11)))),IkReal((((new_r00*new_r01))+((gconst29*gconst30)))),IKFAST_ATAN2_MAGTHRESH); |
| 15596 | if(!x1134.valid){ |
| 15597 | continue; |
| 15598 | } |
| 15599 | CheckValue<IkReal> x1135=IKPowWithIntegerCheck(IKsign((((gconst29*new_r01))+(((-1.0)*gconst30*new_r11)))),-1); |
| 15600 | if(!x1135.valid){ |
| 15601 | continue; |
| 15602 | } |
| 15603 | j0array[0]=((-1.5707963267949)+(x1134.value)+(((1.5707963267949)*(x1135.value)))); |
| 15604 | sj0array[0]=IKsin(j0array[0]); |
| 15605 | cj0array[0]=IKcos(j0array[0]); |
| 15606 | if( j0array[0] > IKPI ) |
| 15607 | { |
| 15608 | j0array[0]-=IK2PI; |
| 15609 | } |
| 15610 | else if( j0array[0] < -IKPI ) |
| 15611 | { j0array[0]+=IK2PI; |
| 15612 | } |
| 15613 | j0valid[0] = true; |
| 15614 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15615 | { |
| 15616 | if( !j0valid[ij0] ) |
| 15617 | { |
| 15618 | continue; |
| 15619 | } |
| 15620 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15621 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15622 | { |
| 15623 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15624 | { |
| 15625 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15626 | } |
| 15627 | } |
| 15628 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15629 | { |
| 15630 | IkReal evalcond[8]; |
| 15631 | IkReal x1136=IKsin(j0); |
| 15632 | IkReal x1137=IKcos(j0); |
| 15633 | IkReal x1138=((1.0)*gconst30); |
| 15634 | IkReal x1139=((1.0)*gconst29); |
| 15635 | IkReal x1140=(gconst29*x1137); |
| 15636 | IkReal x1141=(((x1136*x1139))+((x1137*x1138))); |
| 15637 | evalcond[0]=((((-1.0)*new_r01*x1136))+gconst29+((new_r11*x1137))); |
| 15638 | evalcond[1]=(gconst30+((new_r00*x1136))+(((-1.0)*new_r10*x1137))); |
| 15639 | evalcond[2]=(((gconst30*x1136))+new_r00+(((-1.0)*x1137*x1139))); |
| 15640 | evalcond[3]=(x1140+(((-1.0)*x1136*x1138))+new_r11); |
| 15641 | evalcond[4]=((((-1.0)*x1139))+((new_r00*x1137))+((new_r10*x1136))); |
| 15642 | evalcond[5]=((((-1.0)*x1138))+((new_r11*x1136))+((new_r01*x1137))); |
| 15643 | evalcond[6]=((((-1.0)*x1141))+new_r01); |
| 15644 | evalcond[7]=((((-1.0)*x1141))+new_r10); |
| 15645 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15646 | { |
| 15647 | continue; |
| 15648 | } |
| 15649 | } |
| 15650 | |
| 15651 | { |
| 15652 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15653 | vinfos[0].jointtype = 1; |
| 15654 | vinfos[0].foffset = j0; |
| 15655 | vinfos[0].indices[0] = _ij0[0]; |
| 15656 | vinfos[0].indices[1] = _ij0[1]; |
| 15657 | vinfos[0].maxsolutions = _nj0; |
| 15658 | vinfos[1].jointtype = 1; |
| 15659 | vinfos[1].foffset = j1; |
| 15660 | vinfos[1].indices[0] = _ij1[0]; |
| 15661 | vinfos[1].indices[1] = _ij1[1]; |
| 15662 | vinfos[1].maxsolutions = _nj1; |
| 15663 | vinfos[2].jointtype = 1; |
| 15664 | vinfos[2].foffset = j2; |
| 15665 | vinfos[2].indices[0] = _ij2[0]; |
| 15666 | vinfos[2].indices[1] = _ij2[1]; |
| 15667 | vinfos[2].maxsolutions = _nj2; |
| 15668 | vinfos[3].jointtype = 1; |
| 15669 | vinfos[3].foffset = j3; |
| 15670 | vinfos[3].indices[0] = _ij3[0]; |
| 15671 | vinfos[3].indices[1] = _ij3[1]; |
| 15672 | vinfos[3].maxsolutions = _nj3; |
| 15673 | vinfos[4].jointtype = 1; |
| 15674 | vinfos[4].foffset = j4; |
| 15675 | vinfos[4].indices[0] = _ij4[0]; |
| 15676 | vinfos[4].indices[1] = _ij4[1]; |
| 15677 | vinfos[4].maxsolutions = _nj4; |
| 15678 | vinfos[5].jointtype = 1; |
| 15679 | vinfos[5].foffset = j5; |
| 15680 | vinfos[5].indices[0] = _ij5[0]; |
| 15681 | vinfos[5].indices[1] = _ij5[1]; |
| 15682 | vinfos[5].maxsolutions = _nj5; |
| 15683 | std::vector<int> vfree(0); |
| 15684 | solutions.AddSolution(vinfos,vfree); |
| 15685 | } |
| 15686 | } |
| 15687 | } |
| 15688 | |
| 15689 | } |
| 15690 | |
| 15691 | } |
| 15692 | |
| 15693 | } else |
| 15694 | { |
| 15695 | { |
| 15696 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 15697 | bool j0valid[1]={false}; |
| 15698 | _nj0 = 1; |
| 15699 | CheckValue<IkReal> x1142 = IKatan2WithCheck(IkReal((((gconst29*new_r10))+((gconst30*new_r11)))),IkReal((((gconst29*new_r00))+((gconst30*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 15700 | if(!x1142.valid){ |
| 15701 | continue; |
| 15702 | } |
| 15703 | CheckValue<IkReal> x1143=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| 15704 | if(!x1143.valid){ |
| 15705 | continue; |
| 15706 | } |
| 15707 | j0array[0]=((-1.5707963267949)+(x1142.value)+(((1.5707963267949)*(x1143.value)))); |
| 15708 | sj0array[0]=IKsin(j0array[0]); |
| 15709 | cj0array[0]=IKcos(j0array[0]); |
| 15710 | if( j0array[0] > IKPI ) |
| 15711 | { |
| 15712 | j0array[0]-=IK2PI; |
| 15713 | } |
| 15714 | else if( j0array[0] < -IKPI ) |
| 15715 | { j0array[0]+=IK2PI; |
| 15716 | } |
| 15717 | j0valid[0] = true; |
| 15718 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 15719 | { |
| 15720 | if( !j0valid[ij0] ) |
| 15721 | { |
| 15722 | continue; |
| 15723 | } |
| 15724 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15725 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 15726 | { |
| 15727 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15728 | { |
| 15729 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15730 | } |
| 15731 | } |
| 15732 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15733 | { |
| 15734 | IkReal evalcond[8]; |
| 15735 | IkReal x1144=IKsin(j0); |
| 15736 | IkReal x1145=IKcos(j0); |
| 15737 | IkReal x1146=((1.0)*gconst30); |
| 15738 | IkReal x1147=((1.0)*gconst29); |
| 15739 | IkReal x1148=(gconst29*x1145); |
| 15740 | IkReal x1149=(((x1145*x1146))+((x1144*x1147))); |
| 15741 | evalcond[0]=(gconst29+(((-1.0)*new_r01*x1144))+((new_r11*x1145))); |
| 15742 | evalcond[1]=((((-1.0)*new_r10*x1145))+((new_r00*x1144))+gconst30); |
| 15743 | evalcond[2]=((((-1.0)*x1145*x1147))+((gconst30*x1144))+new_r00); |
| 15744 | evalcond[3]=(x1148+new_r11+(((-1.0)*x1144*x1146))); |
| 15745 | evalcond[4]=(((new_r00*x1145))+(((-1.0)*x1147))+((new_r10*x1144))); |
| 15746 | evalcond[5]=((((-1.0)*x1146))+((new_r01*x1145))+((new_r11*x1144))); |
| 15747 | evalcond[6]=((((-1.0)*x1149))+new_r01); |
| 15748 | evalcond[7]=((((-1.0)*x1149))+new_r10); |
| 15749 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 15750 | { |
| 15751 | continue; |
| 15752 | } |
| 15753 | } |
| 15754 | |
| 15755 | { |
| 15756 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 15757 | vinfos[0].jointtype = 1; |
| 15758 | vinfos[0].foffset = j0; |
| 15759 | vinfos[0].indices[0] = _ij0[0]; |
| 15760 | vinfos[0].indices[1] = _ij0[1]; |
| 15761 | vinfos[0].maxsolutions = _nj0; |
| 15762 | vinfos[1].jointtype = 1; |
| 15763 | vinfos[1].foffset = j1; |
| 15764 | vinfos[1].indices[0] = _ij1[0]; |
| 15765 | vinfos[1].indices[1] = _ij1[1]; |
| 15766 | vinfos[1].maxsolutions = _nj1; |
| 15767 | vinfos[2].jointtype = 1; |
| 15768 | vinfos[2].foffset = j2; |
| 15769 | vinfos[2].indices[0] = _ij2[0]; |
| 15770 | vinfos[2].indices[1] = _ij2[1]; |
| 15771 | vinfos[2].maxsolutions = _nj2; |
| 15772 | vinfos[3].jointtype = 1; |
| 15773 | vinfos[3].foffset = j3; |
| 15774 | vinfos[3].indices[0] = _ij3[0]; |
| 15775 | vinfos[3].indices[1] = _ij3[1]; |
| 15776 | vinfos[3].maxsolutions = _nj3; |
| 15777 | vinfos[4].jointtype = 1; |
| 15778 | vinfos[4].foffset = j4; |
| 15779 | vinfos[4].indices[0] = _ij4[0]; |
| 15780 | vinfos[4].indices[1] = _ij4[1]; |
| 15781 | vinfos[4].maxsolutions = _nj4; |
| 15782 | vinfos[5].jointtype = 1; |
| 15783 | vinfos[5].foffset = j5; |
| 15784 | vinfos[5].indices[0] = _ij5[0]; |
| 15785 | vinfos[5].indices[1] = _ij5[1]; |
| 15786 | vinfos[5].maxsolutions = _nj5; |
| 15787 | std::vector<int> vfree(0); |
| 15788 | solutions.AddSolution(vinfos,vfree); |
| 15789 | } |
| 15790 | } |
| 15791 | } |
| 15792 | |
| 15793 | } |
| 15794 | |
| 15795 | } |
| 15796 | |
| 15797 | } |
| 15798 | } while(0); |
| 15799 | if( bgotonextstatement ) |
| 15800 | { |
| 15801 | bool bgotonextstatement = true; |
| 15802 | do |
| 15803 | { |
| 15804 | IkReal x1152 = ((new_r10*new_r10)+(new_r00*new_r00)); |
| 15805 | if(IKabs(x1152)==0){ |
| 15806 | continue; |
| 15807 | } |
| 15808 | IkReal x1150=pow(x1152,-0.5); |
| 15809 | IkReal x1151=((1.0)*x1150); |
| 15810 | CheckValue<IkReal> x1153 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 15811 | if(!x1153.valid){ |
| 15812 | continue; |
| 15813 | } |
| 15814 | IkReal gconst31=((3.14159265358979)+(((-1.0)*(x1153.value)))); |
| 15815 | IkReal gconst32=(new_r10*x1151); |
| 15816 | IkReal gconst33=(new_r00*x1151); |
| 15817 | CheckValue<IkReal> x1154 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 15818 | if(!x1154.valid){ |
| 15819 | continue; |
| 15820 | } |
| 15821 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2+(x1154.value))))), 6.28318530717959))); |
| 15822 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 15823 | { |
| 15824 | bgotonextstatement=false; |
| 15825 | { |
| 15826 | IkReal j0eval[3]; |
| 15827 | CheckValue<IkReal> x1158 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 15828 | if(!x1158.valid){ |
| 15829 | continue; |
| 15830 | } |
| 15831 | IkReal x1155=((1.0)*(x1158.value)); |
| 15832 | IkReal x1156=x1150; |
| 15833 | IkReal x1157=((1.0)*x1156); |
| 15834 | sj1=-1.0; |
| 15835 | cj1=0; |
| 15836 | j1=-1.5707963267949; |
| 15837 | sj2=gconst32; |
| 15838 | cj2=gconst33; |
| 15839 | j2=((3.14159265)+(((-1.0)*x1155))); |
| 15840 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1155))); |
| 15841 | IkReal gconst32=(new_r10*x1157); |
| 15842 | IkReal gconst33=(new_r00*x1157); |
| 15843 | IkReal x1159=new_r10*new_r10; |
| 15844 | IkReal x1160=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| 15845 | IkReal x1161=x1150; |
| 15846 | IkReal x1162=(new_r00*x1161); |
| 15847 | j0eval[0]=x1160; |
| 15848 | j0eval[1]=IKsign(x1160); |
| 15849 | j0eval[2]=((IKabs((((new_r10*x1162))+((new_r01*x1162)))))+(IKabs((((x1159*x1161))+((new_r11*x1162)))))); |
| 15850 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 15851 | { |
| 15852 | { |
| 15853 | IkReal j0eval[1]; |
| 15854 | CheckValue<IkReal> x1166 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 15855 | if(!x1166.valid){ |
| 15856 | continue; |
| 15857 | } |
| 15858 | IkReal x1163=((1.0)*(x1166.value)); |
| 15859 | IkReal x1164=x1150; |
| 15860 | IkReal x1165=((1.0)*x1164); |
| 15861 | sj1=-1.0; |
| 15862 | cj1=0; |
| 15863 | j1=-1.5707963267949; |
| 15864 | sj2=gconst32; |
| 15865 | cj2=gconst33; |
| 15866 | j2=((3.14159265)+(((-1.0)*x1163))); |
| 15867 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1163))); |
| 15868 | IkReal gconst32=(new_r10*x1165); |
| 15869 | IkReal gconst33=(new_r00*x1165); |
| 15870 | IkReal x1167=new_r10*new_r10; |
| 15871 | IkReal x1168=new_r00*new_r00*new_r00; |
| 15872 | CheckValue<IkReal> x1172=IKPowWithIntegerCheck((x1167+(new_r00*new_r00)),-1); |
| 15873 | if(!x1172.valid){ |
| 15874 | continue; |
| 15875 | } |
| 15876 | IkReal x1169=x1172.value; |
| 15877 | IkReal x1170=(x1167*x1169); |
| 15878 | IkReal x1171=(x1168*x1169); |
| 15879 | j0eval[0]=((IKabs((((new_r00*new_r11*x1170))+x1170+((new_r11*x1171)))))+(IKabs((((new_r00*new_r10*x1169))+((new_r00*new_r01*x1170))+((new_r01*x1171)))))); |
| 15880 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 15881 | { |
| 15882 | { |
| 15883 | IkReal j0eval[3]; |
| 15884 | CheckValue<IkReal> x1176 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 15885 | if(!x1176.valid){ |
| 15886 | continue; |
| 15887 | } |
| 15888 | IkReal x1173=((1.0)*(x1176.value)); |
| 15889 | IkReal x1174=x1150; |
| 15890 | IkReal x1175=((1.0)*x1174); |
| 15891 | sj1=-1.0; |
| 15892 | cj1=0; |
| 15893 | j1=-1.5707963267949; |
| 15894 | sj2=gconst32; |
| 15895 | cj2=gconst33; |
| 15896 | j2=((3.14159265)+(((-1.0)*x1173))); |
| 15897 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1173))); |
| 15898 | IkReal gconst32=(new_r10*x1175); |
| 15899 | IkReal gconst33=(new_r00*x1175); |
| 15900 | IkReal x1177=new_r10*new_r10; |
| 15901 | IkReal x1178=(((new_r10*new_r11))+((new_r00*new_r01))); |
| 15902 | IkReal x1179=x1150; |
| 15903 | IkReal x1180=(new_r10*x1179); |
| 15904 | j0eval[0]=x1178; |
| 15905 | j0eval[1]=IKsign(x1178); |
| 15906 | j0eval[2]=((IKabs((((new_r11*x1180))+((new_r00*x1180)))))+(IKabs(((((-1.0)*x1177*x1179))+((new_r01*x1180)))))); |
| 15907 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 15908 | { |
| 15909 | { |
| 15910 | IkReal evalcond[2]; |
| 15911 | bool bgotonextstatement = true; |
| 15912 | do |
| 15913 | { |
| 15914 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| 15915 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 15916 | { |
| 15917 | bgotonextstatement=false; |
| 15918 | { |
| 15919 | IkReal j0eval[1]; |
| 15920 | CheckValue<IkReal> x1182 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 15921 | if(!x1182.valid){ |
| 15922 | continue; |
| 15923 | } |
| 15924 | IkReal x1181=((1.0)*(x1182.value)); |
| 15925 | sj1=-1.0; |
| 15926 | cj1=0; |
| 15927 | j1=-1.5707963267949; |
| 15928 | sj2=gconst32; |
| 15929 | cj2=gconst33; |
| 15930 | j2=((3.14159265)+(((-1.0)*x1181))); |
| 15931 | new_r11=0; |
| 15932 | new_r00=0; |
| 15933 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1181))); |
| 15934 | IkReal x1183 = new_r10*new_r10; |
| 15935 | if(IKabs(x1183)==0){ |
| 15936 | continue; |
| 15937 | } |
| 15938 | IkReal gconst32=((1.0)*new_r10*(pow(x1183,-0.5))); |
| 15939 | IkReal gconst33=0; |
| 15940 | j0eval[0]=new_r01; |
| 15941 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 15942 | { |
| 15943 | { |
| 15944 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 15945 | bool j0valid[2]={false}; |
| 15946 | _nj0 = 2; |
| 15947 | CheckValue<IkReal> x1184=IKPowWithIntegerCheck(gconst32,-1); |
| 15948 | if(!x1184.valid){ |
| 15949 | continue; |
| 15950 | } |
| 15951 | sj0array[0]=(new_r01*(x1184.value)); |
| 15952 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 15953 | { |
| 15954 | j0valid[0] = j0valid[1] = true; |
| 15955 | j0array[0] = IKasin(sj0array[0]); |
| 15956 | cj0array[0] = IKcos(j0array[0]); |
| 15957 | sj0array[1] = sj0array[0]; |
| 15958 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 15959 | cj0array[1] = -cj0array[0]; |
| 15960 | } |
| 15961 | else if( isnan(sj0array[0]) ) |
| 15962 | { |
| 15963 | // probably any value will work |
| 15964 | j0valid[0] = true; |
| 15965 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 15966 | } |
| 15967 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 15968 | { |
| 15969 | if( !j0valid[ij0] ) |
| 15970 | { |
| 15971 | continue; |
| 15972 | } |
| 15973 | _ij0[0] = ij0; _ij0[1] = -1; |
| 15974 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 15975 | { |
| 15976 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 15977 | { |
| 15978 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 15979 | } |
| 15980 | } |
| 15981 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 15982 | { |
| 15983 | IkReal evalcond[6]; |
| 15984 | IkReal x1185=IKcos(j0); |
| 15985 | IkReal x1186=IKsin(j0); |
| 15986 | IkReal x1187=((1.0)*gconst32); |
| 15987 | IkReal x1188=((-1.0)*x1185); |
| 15988 | evalcond[0]=(new_r01*x1185); |
| 15989 | evalcond[1]=(new_r10*x1188); |
| 15990 | evalcond[2]=(gconst32*x1188); |
| 15991 | evalcond[3]=((((-1.0)*new_r01*x1186))+gconst32); |
| 15992 | evalcond[4]=((((-1.0)*x1186*x1187))+new_r10); |
| 15993 | evalcond[5]=((((-1.0)*x1187))+((new_r10*x1186))); |
| 15994 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 15995 | { |
| 15996 | continue; |
| 15997 | } |
| 15998 | } |
| 15999 | |
| 16000 | { |
| 16001 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16002 | vinfos[0].jointtype = 1; |
| 16003 | vinfos[0].foffset = j0; |
| 16004 | vinfos[0].indices[0] = _ij0[0]; |
| 16005 | vinfos[0].indices[1] = _ij0[1]; |
| 16006 | vinfos[0].maxsolutions = _nj0; |
| 16007 | vinfos[1].jointtype = 1; |
| 16008 | vinfos[1].foffset = j1; |
| 16009 | vinfos[1].indices[0] = _ij1[0]; |
| 16010 | vinfos[1].indices[1] = _ij1[1]; |
| 16011 | vinfos[1].maxsolutions = _nj1; |
| 16012 | vinfos[2].jointtype = 1; |
| 16013 | vinfos[2].foffset = j2; |
| 16014 | vinfos[2].indices[0] = _ij2[0]; |
| 16015 | vinfos[2].indices[1] = _ij2[1]; |
| 16016 | vinfos[2].maxsolutions = _nj2; |
| 16017 | vinfos[3].jointtype = 1; |
| 16018 | vinfos[3].foffset = j3; |
| 16019 | vinfos[3].indices[0] = _ij3[0]; |
| 16020 | vinfos[3].indices[1] = _ij3[1]; |
| 16021 | vinfos[3].maxsolutions = _nj3; |
| 16022 | vinfos[4].jointtype = 1; |
| 16023 | vinfos[4].foffset = j4; |
| 16024 | vinfos[4].indices[0] = _ij4[0]; |
| 16025 | vinfos[4].indices[1] = _ij4[1]; |
| 16026 | vinfos[4].maxsolutions = _nj4; |
| 16027 | vinfos[5].jointtype = 1; |
| 16028 | vinfos[5].foffset = j5; |
| 16029 | vinfos[5].indices[0] = _ij5[0]; |
| 16030 | vinfos[5].indices[1] = _ij5[1]; |
| 16031 | vinfos[5].maxsolutions = _nj5; |
| 16032 | std::vector<int> vfree(0); |
| 16033 | solutions.AddSolution(vinfos,vfree); |
| 16034 | } |
| 16035 | } |
| 16036 | } |
| 16037 | |
| 16038 | } else |
| 16039 | { |
| 16040 | { |
| 16041 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 16042 | bool j0valid[2]={false}; |
| 16043 | _nj0 = 2; |
| 16044 | CheckValue<IkReal> x1189=IKPowWithIntegerCheck(new_r01,-1); |
| 16045 | if(!x1189.valid){ |
| 16046 | continue; |
| 16047 | } |
| 16048 | sj0array[0]=(gconst32*(x1189.value)); |
| 16049 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 16050 | { |
| 16051 | j0valid[0] = j0valid[1] = true; |
| 16052 | j0array[0] = IKasin(sj0array[0]); |
| 16053 | cj0array[0] = IKcos(j0array[0]); |
| 16054 | sj0array[1] = sj0array[0]; |
| 16055 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 16056 | cj0array[1] = -cj0array[0]; |
| 16057 | } |
| 16058 | else if( isnan(sj0array[0]) ) |
| 16059 | { |
| 16060 | // probably any value will work |
| 16061 | j0valid[0] = true; |
| 16062 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 16063 | } |
| 16064 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 16065 | { |
| 16066 | if( !j0valid[ij0] ) |
| 16067 | { |
| 16068 | continue; |
| 16069 | } |
| 16070 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16071 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 16072 | { |
| 16073 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16074 | { |
| 16075 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16076 | } |
| 16077 | } |
| 16078 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16079 | { |
| 16080 | IkReal evalcond[6]; |
| 16081 | IkReal x1190=IKcos(j0); |
| 16082 | IkReal x1191=IKsin(j0); |
| 16083 | IkReal x1192=((1.0)*gconst32); |
| 16084 | IkReal x1193=(x1191*x1192); |
| 16085 | IkReal x1194=((-1.0)*x1190); |
| 16086 | evalcond[0]=(new_r01*x1190); |
| 16087 | evalcond[1]=(new_r10*x1194); |
| 16088 | evalcond[2]=(gconst32*x1194); |
| 16089 | evalcond[3]=((((-1.0)*x1193))+new_r01); |
| 16090 | evalcond[4]=((((-1.0)*x1193))+new_r10); |
| 16091 | evalcond[5]=((((-1.0)*x1192))+((new_r10*x1191))); |
| 16092 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 16093 | { |
| 16094 | continue; |
| 16095 | } |
| 16096 | } |
| 16097 | |
| 16098 | { |
| 16099 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16100 | vinfos[0].jointtype = 1; |
| 16101 | vinfos[0].foffset = j0; |
| 16102 | vinfos[0].indices[0] = _ij0[0]; |
| 16103 | vinfos[0].indices[1] = _ij0[1]; |
| 16104 | vinfos[0].maxsolutions = _nj0; |
| 16105 | vinfos[1].jointtype = 1; |
| 16106 | vinfos[1].foffset = j1; |
| 16107 | vinfos[1].indices[0] = _ij1[0]; |
| 16108 | vinfos[1].indices[1] = _ij1[1]; |
| 16109 | vinfos[1].maxsolutions = _nj1; |
| 16110 | vinfos[2].jointtype = 1; |
| 16111 | vinfos[2].foffset = j2; |
| 16112 | vinfos[2].indices[0] = _ij2[0]; |
| 16113 | vinfos[2].indices[1] = _ij2[1]; |
| 16114 | vinfos[2].maxsolutions = _nj2; |
| 16115 | vinfos[3].jointtype = 1; |
| 16116 | vinfos[3].foffset = j3; |
| 16117 | vinfos[3].indices[0] = _ij3[0]; |
| 16118 | vinfos[3].indices[1] = _ij3[1]; |
| 16119 | vinfos[3].maxsolutions = _nj3; |
| 16120 | vinfos[4].jointtype = 1; |
| 16121 | vinfos[4].foffset = j4; |
| 16122 | vinfos[4].indices[0] = _ij4[0]; |
| 16123 | vinfos[4].indices[1] = _ij4[1]; |
| 16124 | vinfos[4].maxsolutions = _nj4; |
| 16125 | vinfos[5].jointtype = 1; |
| 16126 | vinfos[5].foffset = j5; |
| 16127 | vinfos[5].indices[0] = _ij5[0]; |
| 16128 | vinfos[5].indices[1] = _ij5[1]; |
| 16129 | vinfos[5].maxsolutions = _nj5; |
| 16130 | std::vector<int> vfree(0); |
| 16131 | solutions.AddSolution(vinfos,vfree); |
| 16132 | } |
| 16133 | } |
| 16134 | } |
| 16135 | |
| 16136 | } |
| 16137 | |
| 16138 | } |
| 16139 | |
| 16140 | } |
| 16141 | } while(0); |
| 16142 | if( bgotonextstatement ) |
| 16143 | { |
| 16144 | bool bgotonextstatement = true; |
| 16145 | do |
| 16146 | { |
| 16147 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 16148 | evalcond[1]=gconst32; |
| 16149 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 16150 | { |
| 16151 | bgotonextstatement=false; |
| 16152 | { |
| 16153 | IkReal j0eval[4]; |
| 16154 | CheckValue<IkReal> x1196 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16155 | if(!x1196.valid){ |
| 16156 | continue; |
| 16157 | } |
| 16158 | IkReal x1195=((1.0)*(x1196.value)); |
| 16159 | sj1=-1.0; |
| 16160 | cj1=0; |
| 16161 | j1=-1.5707963267949; |
| 16162 | sj2=gconst32; |
| 16163 | cj2=gconst33; |
| 16164 | j2=((3.14159265)+(((-1.0)*x1195))); |
| 16165 | new_r11=0; |
| 16166 | new_r01=0; |
| 16167 | new_r22=0; |
| 16168 | new_r20=0; |
| 16169 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1195))); |
| 16170 | IkReal gconst32=((1.0)*new_r10); |
| 16171 | IkReal gconst33=((1.0)*new_r00); |
| 16172 | j0eval[0]=1.0; |
| 16173 | j0eval[1]=new_r10; |
| 16174 | j0eval[2]=1.0; |
| 16175 | j0eval[3]=1.0; |
| 16176 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| 16177 | { |
| 16178 | { |
| 16179 | IkReal j0eval[4]; |
| 16180 | CheckValue<IkReal> x1198 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16181 | if(!x1198.valid){ |
| 16182 | continue; |
| 16183 | } |
| 16184 | IkReal x1197=((1.0)*(x1198.value)); |
| 16185 | sj1=-1.0; |
| 16186 | cj1=0; |
| 16187 | j1=-1.5707963267949; |
| 16188 | sj2=gconst32; |
| 16189 | cj2=gconst33; |
| 16190 | j2=((3.14159265)+(((-1.0)*x1197))); |
| 16191 | new_r11=0; |
| 16192 | new_r01=0; |
| 16193 | new_r22=0; |
| 16194 | new_r20=0; |
| 16195 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1197))); |
| 16196 | IkReal gconst32=((1.0)*new_r10); |
| 16197 | IkReal gconst33=((1.0)*new_r00); |
| 16198 | j0eval[0]=1.0; |
| 16199 | j0eval[1]=new_r10; |
| 16200 | j0eval[2]=1.0; |
| 16201 | j0eval[3]=1.0; |
| 16202 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| 16203 | { |
| 16204 | { |
| 16205 | IkReal j0eval[3]; |
| 16206 | CheckValue<IkReal> x1200 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16207 | if(!x1200.valid){ |
| 16208 | continue; |
| 16209 | } |
| 16210 | IkReal x1199=((1.0)*(x1200.value)); |
| 16211 | sj1=-1.0; |
| 16212 | cj1=0; |
| 16213 | j1=-1.5707963267949; |
| 16214 | sj2=gconst32; |
| 16215 | cj2=gconst33; |
| 16216 | j2=((3.14159265)+(((-1.0)*x1199))); |
| 16217 | new_r11=0; |
| 16218 | new_r01=0; |
| 16219 | new_r22=0; |
| 16220 | new_r20=0; |
| 16221 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1199))); |
| 16222 | IkReal gconst32=((1.0)*new_r10); |
| 16223 | IkReal gconst33=((1.0)*new_r00); |
| 16224 | j0eval[0]=-1.0; |
| 16225 | j0eval[1]=((IKabs(((1.0)+(((-1.0)*(new_r10*new_r10))))))+(IKabs(((1.0)*new_r00*new_r10)))); |
| 16226 | j0eval[2]=-1.0; |
| 16227 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 16228 | { |
| 16229 | continue; // 3 cases reached |
| 16230 | |
| 16231 | } else |
| 16232 | { |
| 16233 | { |
| 16234 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16235 | bool j0valid[1]={false}; |
| 16236 | _nj0 = 1; |
| 16237 | CheckValue<IkReal> x1201=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r00))+(((-1.0)*gconst32*new_r10)))),-1); |
| 16238 | if(!x1201.valid){ |
| 16239 | continue; |
| 16240 | } |
| 16241 | CheckValue<IkReal> x1202 = IKatan2WithCheck(IkReal(gconst33*gconst33),IkReal(((-1.0)*gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH); |
| 16242 | if(!x1202.valid){ |
| 16243 | continue; |
| 16244 | } |
| 16245 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1201.value)))+(x1202.value)); |
| 16246 | sj0array[0]=IKsin(j0array[0]); |
| 16247 | cj0array[0]=IKcos(j0array[0]); |
| 16248 | if( j0array[0] > IKPI ) |
| 16249 | { |
| 16250 | j0array[0]-=IK2PI; |
| 16251 | } |
| 16252 | else if( j0array[0] < -IKPI ) |
| 16253 | { j0array[0]+=IK2PI; |
| 16254 | } |
| 16255 | j0valid[0] = true; |
| 16256 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16257 | { |
| 16258 | if( !j0valid[ij0] ) |
| 16259 | { |
| 16260 | continue; |
| 16261 | } |
| 16262 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16263 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16264 | { |
| 16265 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16266 | { |
| 16267 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16268 | } |
| 16269 | } |
| 16270 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16271 | { |
| 16272 | IkReal evalcond[6]; |
| 16273 | IkReal x1203=IKsin(j0); |
| 16274 | IkReal x1204=IKcos(j0); |
| 16275 | IkReal x1205=((1.0)*gconst32); |
| 16276 | IkReal x1206=(gconst33*x1203); |
| 16277 | IkReal x1207=((1.0)*x1204); |
| 16278 | IkReal x1208=(((gconst33*x1207))+((x1203*x1205))); |
| 16279 | evalcond[0]=((((-1.0)*x1206))+((gconst32*x1204))); |
| 16280 | evalcond[1]=(((new_r00*x1203))+gconst33+(((-1.0)*new_r10*x1207))); |
| 16281 | evalcond[2]=((((-1.0)*x1204*x1205))+x1206+new_r00); |
| 16282 | evalcond[3]=((-1.0)*x1208); |
| 16283 | evalcond[4]=(((new_r00*x1204))+((new_r10*x1203))+(((-1.0)*x1205))); |
| 16284 | evalcond[5]=(new_r10+(((-1.0)*x1208))); |
| 16285 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 16286 | { |
| 16287 | continue; |
| 16288 | } |
| 16289 | } |
| 16290 | |
| 16291 | { |
| 16292 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16293 | vinfos[0].jointtype = 1; |
| 16294 | vinfos[0].foffset = j0; |
| 16295 | vinfos[0].indices[0] = _ij0[0]; |
| 16296 | vinfos[0].indices[1] = _ij0[1]; |
| 16297 | vinfos[0].maxsolutions = _nj0; |
| 16298 | vinfos[1].jointtype = 1; |
| 16299 | vinfos[1].foffset = j1; |
| 16300 | vinfos[1].indices[0] = _ij1[0]; |
| 16301 | vinfos[1].indices[1] = _ij1[1]; |
| 16302 | vinfos[1].maxsolutions = _nj1; |
| 16303 | vinfos[2].jointtype = 1; |
| 16304 | vinfos[2].foffset = j2; |
| 16305 | vinfos[2].indices[0] = _ij2[0]; |
| 16306 | vinfos[2].indices[1] = _ij2[1]; |
| 16307 | vinfos[2].maxsolutions = _nj2; |
| 16308 | vinfos[3].jointtype = 1; |
| 16309 | vinfos[3].foffset = j3; |
| 16310 | vinfos[3].indices[0] = _ij3[0]; |
| 16311 | vinfos[3].indices[1] = _ij3[1]; |
| 16312 | vinfos[3].maxsolutions = _nj3; |
| 16313 | vinfos[4].jointtype = 1; |
| 16314 | vinfos[4].foffset = j4; |
| 16315 | vinfos[4].indices[0] = _ij4[0]; |
| 16316 | vinfos[4].indices[1] = _ij4[1]; |
| 16317 | vinfos[4].maxsolutions = _nj4; |
| 16318 | vinfos[5].jointtype = 1; |
| 16319 | vinfos[5].foffset = j5; |
| 16320 | vinfos[5].indices[0] = _ij5[0]; |
| 16321 | vinfos[5].indices[1] = _ij5[1]; |
| 16322 | vinfos[5].maxsolutions = _nj5; |
| 16323 | std::vector<int> vfree(0); |
| 16324 | solutions.AddSolution(vinfos,vfree); |
| 16325 | } |
| 16326 | } |
| 16327 | } |
| 16328 | |
| 16329 | } |
| 16330 | |
| 16331 | } |
| 16332 | |
| 16333 | } else |
| 16334 | { |
| 16335 | { |
| 16336 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16337 | bool j0valid[1]={false}; |
| 16338 | _nj0 = 1; |
| 16339 | CheckValue<IkReal> x1209=IKPowWithIntegerCheck(IKsign(((gconst32*gconst32)+(gconst33*gconst33))),-1); |
| 16340 | if(!x1209.valid){ |
| 16341 | continue; |
| 16342 | } |
| 16343 | CheckValue<IkReal> x1210 = IKatan2WithCheck(IkReal((gconst32*new_r10)),IkReal((gconst33*new_r10)),IKFAST_ATAN2_MAGTHRESH); |
| 16344 | if(!x1210.valid){ |
| 16345 | continue; |
| 16346 | } |
| 16347 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1209.value)))+(x1210.value)); |
| 16348 | sj0array[0]=IKsin(j0array[0]); |
| 16349 | cj0array[0]=IKcos(j0array[0]); |
| 16350 | if( j0array[0] > IKPI ) |
| 16351 | { |
| 16352 | j0array[0]-=IK2PI; |
| 16353 | } |
| 16354 | else if( j0array[0] < -IKPI ) |
| 16355 | { j0array[0]+=IK2PI; |
| 16356 | } |
| 16357 | j0valid[0] = true; |
| 16358 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16359 | { |
| 16360 | if( !j0valid[ij0] ) |
| 16361 | { |
| 16362 | continue; |
| 16363 | } |
| 16364 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16365 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16366 | { |
| 16367 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16368 | { |
| 16369 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16370 | } |
| 16371 | } |
| 16372 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16373 | { |
| 16374 | IkReal evalcond[6]; |
| 16375 | IkReal x1211=IKsin(j0); |
| 16376 | IkReal x1212=IKcos(j0); |
| 16377 | IkReal x1213=((1.0)*gconst32); |
| 16378 | IkReal x1214=(gconst33*x1211); |
| 16379 | IkReal x1215=((1.0)*x1212); |
| 16380 | IkReal x1216=(((gconst33*x1215))+((x1211*x1213))); |
| 16381 | evalcond[0]=(((gconst32*x1212))+(((-1.0)*x1214))); |
| 16382 | evalcond[1]=(gconst33+((new_r00*x1211))+(((-1.0)*new_r10*x1215))); |
| 16383 | evalcond[2]=(x1214+(((-1.0)*x1212*x1213))+new_r00); |
| 16384 | evalcond[3]=((-1.0)*x1216); |
| 16385 | evalcond[4]=(((new_r10*x1211))+((new_r00*x1212))+(((-1.0)*x1213))); |
| 16386 | evalcond[5]=(new_r10+(((-1.0)*x1216))); |
| 16387 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 16388 | { |
| 16389 | continue; |
| 16390 | } |
| 16391 | } |
| 16392 | |
| 16393 | { |
| 16394 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16395 | vinfos[0].jointtype = 1; |
| 16396 | vinfos[0].foffset = j0; |
| 16397 | vinfos[0].indices[0] = _ij0[0]; |
| 16398 | vinfos[0].indices[1] = _ij0[1]; |
| 16399 | vinfos[0].maxsolutions = _nj0; |
| 16400 | vinfos[1].jointtype = 1; |
| 16401 | vinfos[1].foffset = j1; |
| 16402 | vinfos[1].indices[0] = _ij1[0]; |
| 16403 | vinfos[1].indices[1] = _ij1[1]; |
| 16404 | vinfos[1].maxsolutions = _nj1; |
| 16405 | vinfos[2].jointtype = 1; |
| 16406 | vinfos[2].foffset = j2; |
| 16407 | vinfos[2].indices[0] = _ij2[0]; |
| 16408 | vinfos[2].indices[1] = _ij2[1]; |
| 16409 | vinfos[2].maxsolutions = _nj2; |
| 16410 | vinfos[3].jointtype = 1; |
| 16411 | vinfos[3].foffset = j3; |
| 16412 | vinfos[3].indices[0] = _ij3[0]; |
| 16413 | vinfos[3].indices[1] = _ij3[1]; |
| 16414 | vinfos[3].maxsolutions = _nj3; |
| 16415 | vinfos[4].jointtype = 1; |
| 16416 | vinfos[4].foffset = j4; |
| 16417 | vinfos[4].indices[0] = _ij4[0]; |
| 16418 | vinfos[4].indices[1] = _ij4[1]; |
| 16419 | vinfos[4].maxsolutions = _nj4; |
| 16420 | vinfos[5].jointtype = 1; |
| 16421 | vinfos[5].foffset = j5; |
| 16422 | vinfos[5].indices[0] = _ij5[0]; |
| 16423 | vinfos[5].indices[1] = _ij5[1]; |
| 16424 | vinfos[5].maxsolutions = _nj5; |
| 16425 | std::vector<int> vfree(0); |
| 16426 | solutions.AddSolution(vinfos,vfree); |
| 16427 | } |
| 16428 | } |
| 16429 | } |
| 16430 | |
| 16431 | } |
| 16432 | |
| 16433 | } |
| 16434 | |
| 16435 | } else |
| 16436 | { |
| 16437 | { |
| 16438 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16439 | bool j0valid[1]={false}; |
| 16440 | _nj0 = 1; |
| 16441 | CheckValue<IkReal> x1217=IKPowWithIntegerCheck(IKsign((((gconst33*new_r00))+((gconst32*new_r10)))),-1); |
| 16442 | if(!x1217.valid){ |
| 16443 | continue; |
| 16444 | } |
| 16445 | CheckValue<IkReal> x1218 = IKatan2WithCheck(IkReal(gconst32*gconst32),IkReal((gconst32*gconst33)),IKFAST_ATAN2_MAGTHRESH); |
| 16446 | if(!x1218.valid){ |
| 16447 | continue; |
| 16448 | } |
| 16449 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1217.value)))+(x1218.value)); |
| 16450 | sj0array[0]=IKsin(j0array[0]); |
| 16451 | cj0array[0]=IKcos(j0array[0]); |
| 16452 | if( j0array[0] > IKPI ) |
| 16453 | { |
| 16454 | j0array[0]-=IK2PI; |
| 16455 | } |
| 16456 | else if( j0array[0] < -IKPI ) |
| 16457 | { j0array[0]+=IK2PI; |
| 16458 | } |
| 16459 | j0valid[0] = true; |
| 16460 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16461 | { |
| 16462 | if( !j0valid[ij0] ) |
| 16463 | { |
| 16464 | continue; |
| 16465 | } |
| 16466 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16467 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16468 | { |
| 16469 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16470 | { |
| 16471 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16472 | } |
| 16473 | } |
| 16474 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16475 | { |
| 16476 | IkReal evalcond[6]; |
| 16477 | IkReal x1219=IKsin(j0); |
| 16478 | IkReal x1220=IKcos(j0); |
| 16479 | IkReal x1221=((1.0)*gconst32); |
| 16480 | IkReal x1222=(gconst33*x1219); |
| 16481 | IkReal x1223=((1.0)*x1220); |
| 16482 | IkReal x1224=(((x1219*x1221))+((gconst33*x1223))); |
| 16483 | evalcond[0]=((((-1.0)*x1222))+((gconst32*x1220))); |
| 16484 | evalcond[1]=(gconst33+((new_r00*x1219))+(((-1.0)*new_r10*x1223))); |
| 16485 | evalcond[2]=(x1222+(((-1.0)*x1220*x1221))+new_r00); |
| 16486 | evalcond[3]=((-1.0)*x1224); |
| 16487 | evalcond[4]=(((new_r10*x1219))+(((-1.0)*x1221))+((new_r00*x1220))); |
| 16488 | evalcond[5]=((((-1.0)*x1224))+new_r10); |
| 16489 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 16490 | { |
| 16491 | continue; |
| 16492 | } |
| 16493 | } |
| 16494 | |
| 16495 | { |
| 16496 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16497 | vinfos[0].jointtype = 1; |
| 16498 | vinfos[0].foffset = j0; |
| 16499 | vinfos[0].indices[0] = _ij0[0]; |
| 16500 | vinfos[0].indices[1] = _ij0[1]; |
| 16501 | vinfos[0].maxsolutions = _nj0; |
| 16502 | vinfos[1].jointtype = 1; |
| 16503 | vinfos[1].foffset = j1; |
| 16504 | vinfos[1].indices[0] = _ij1[0]; |
| 16505 | vinfos[1].indices[1] = _ij1[1]; |
| 16506 | vinfos[1].maxsolutions = _nj1; |
| 16507 | vinfos[2].jointtype = 1; |
| 16508 | vinfos[2].foffset = j2; |
| 16509 | vinfos[2].indices[0] = _ij2[0]; |
| 16510 | vinfos[2].indices[1] = _ij2[1]; |
| 16511 | vinfos[2].maxsolutions = _nj2; |
| 16512 | vinfos[3].jointtype = 1; |
| 16513 | vinfos[3].foffset = j3; |
| 16514 | vinfos[3].indices[0] = _ij3[0]; |
| 16515 | vinfos[3].indices[1] = _ij3[1]; |
| 16516 | vinfos[3].maxsolutions = _nj3; |
| 16517 | vinfos[4].jointtype = 1; |
| 16518 | vinfos[4].foffset = j4; |
| 16519 | vinfos[4].indices[0] = _ij4[0]; |
| 16520 | vinfos[4].indices[1] = _ij4[1]; |
| 16521 | vinfos[4].maxsolutions = _nj4; |
| 16522 | vinfos[5].jointtype = 1; |
| 16523 | vinfos[5].foffset = j5; |
| 16524 | vinfos[5].indices[0] = _ij5[0]; |
| 16525 | vinfos[5].indices[1] = _ij5[1]; |
| 16526 | vinfos[5].maxsolutions = _nj5; |
| 16527 | std::vector<int> vfree(0); |
| 16528 | solutions.AddSolution(vinfos,vfree); |
| 16529 | } |
| 16530 | } |
| 16531 | } |
| 16532 | |
| 16533 | } |
| 16534 | |
| 16535 | } |
| 16536 | |
| 16537 | } |
| 16538 | } while(0); |
| 16539 | if( bgotonextstatement ) |
| 16540 | { |
| 16541 | bool bgotonextstatement = true; |
| 16542 | do |
| 16543 | { |
| 16544 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| 16545 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 16546 | { |
| 16547 | bgotonextstatement=false; |
| 16548 | { |
| 16549 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 16550 | bool j0valid[2]={false}; |
| 16551 | _nj0 = 2; |
| 16552 | CheckValue<IkReal> x1225=IKPowWithIntegerCheck(gconst33,-1); |
| 16553 | if(!x1225.valid){ |
| 16554 | continue; |
| 16555 | } |
| 16556 | sj0array[0]=(new_r11*(x1225.value)); |
| 16557 | if( sj0array[0] >= -1-IKFAST_SINCOS_THRESH && sj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 16558 | { |
| 16559 | j0valid[0] = j0valid[1] = true; |
| 16560 | j0array[0] = IKasin(sj0array[0]); |
| 16561 | cj0array[0] = IKcos(j0array[0]); |
| 16562 | sj0array[1] = sj0array[0]; |
| 16563 | j0array[1] = j0array[0] > 0 ? (IKPI-j0array[0]) : (-IKPI-j0array[0]); |
| 16564 | cj0array[1] = -cj0array[0]; |
| 16565 | } |
| 16566 | else if( isnan(sj0array[0]) ) |
| 16567 | { |
| 16568 | // probably any value will work |
| 16569 | j0valid[0] = true; |
| 16570 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 16571 | } |
| 16572 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 16573 | { |
| 16574 | if( !j0valid[ij0] ) |
| 16575 | { |
| 16576 | continue; |
| 16577 | } |
| 16578 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16579 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 16580 | { |
| 16581 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16582 | { |
| 16583 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16584 | } |
| 16585 | } |
| 16586 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16587 | { |
| 16588 | IkReal evalcond[6]; |
| 16589 | IkReal x1226=IKcos(j0); |
| 16590 | IkReal x1227=IKsin(j0); |
| 16591 | evalcond[0]=(new_r11*x1226); |
| 16592 | evalcond[1]=(new_r00*x1226); |
| 16593 | evalcond[2]=((-1.0)*gconst33*x1226); |
| 16594 | evalcond[3]=(gconst33+((new_r00*x1227))); |
| 16595 | evalcond[4]=(((gconst33*x1227))+new_r00); |
| 16596 | evalcond[5]=(((new_r11*x1227))+(((-1.0)*gconst33))); |
| 16597 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 16598 | { |
| 16599 | continue; |
| 16600 | } |
| 16601 | } |
| 16602 | |
| 16603 | { |
| 16604 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16605 | vinfos[0].jointtype = 1; |
| 16606 | vinfos[0].foffset = j0; |
| 16607 | vinfos[0].indices[0] = _ij0[0]; |
| 16608 | vinfos[0].indices[1] = _ij0[1]; |
| 16609 | vinfos[0].maxsolutions = _nj0; |
| 16610 | vinfos[1].jointtype = 1; |
| 16611 | vinfos[1].foffset = j1; |
| 16612 | vinfos[1].indices[0] = _ij1[0]; |
| 16613 | vinfos[1].indices[1] = _ij1[1]; |
| 16614 | vinfos[1].maxsolutions = _nj1; |
| 16615 | vinfos[2].jointtype = 1; |
| 16616 | vinfos[2].foffset = j2; |
| 16617 | vinfos[2].indices[0] = _ij2[0]; |
| 16618 | vinfos[2].indices[1] = _ij2[1]; |
| 16619 | vinfos[2].maxsolutions = _nj2; |
| 16620 | vinfos[3].jointtype = 1; |
| 16621 | vinfos[3].foffset = j3; |
| 16622 | vinfos[3].indices[0] = _ij3[0]; |
| 16623 | vinfos[3].indices[1] = _ij3[1]; |
| 16624 | vinfos[3].maxsolutions = _nj3; |
| 16625 | vinfos[4].jointtype = 1; |
| 16626 | vinfos[4].foffset = j4; |
| 16627 | vinfos[4].indices[0] = _ij4[0]; |
| 16628 | vinfos[4].indices[1] = _ij4[1]; |
| 16629 | vinfos[4].maxsolutions = _nj4; |
| 16630 | vinfos[5].jointtype = 1; |
| 16631 | vinfos[5].foffset = j5; |
| 16632 | vinfos[5].indices[0] = _ij5[0]; |
| 16633 | vinfos[5].indices[1] = _ij5[1]; |
| 16634 | vinfos[5].maxsolutions = _nj5; |
| 16635 | std::vector<int> vfree(0); |
| 16636 | solutions.AddSolution(vinfos,vfree); |
| 16637 | } |
| 16638 | } |
| 16639 | } |
| 16640 | |
| 16641 | } |
| 16642 | } while(0); |
| 16643 | if( bgotonextstatement ) |
| 16644 | { |
| 16645 | bool bgotonextstatement = true; |
| 16646 | do |
| 16647 | { |
| 16648 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 16649 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 16650 | { |
| 16651 | bgotonextstatement=false; |
| 16652 | { |
| 16653 | IkReal j0eval[1]; |
| 16654 | CheckValue<IkReal> x1229 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16655 | if(!x1229.valid){ |
| 16656 | continue; |
| 16657 | } |
| 16658 | IkReal x1228=((1.0)*(x1229.value)); |
| 16659 | sj1=-1.0; |
| 16660 | cj1=0; |
| 16661 | j1=-1.5707963267949; |
| 16662 | sj2=gconst32; |
| 16663 | cj2=gconst33; |
| 16664 | j2=((3.14159265)+(((-1.0)*x1228))); |
| 16665 | new_r11=0; |
| 16666 | new_r10=0; |
| 16667 | new_r22=0; |
| 16668 | new_r02=0; |
| 16669 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1228))); |
| 16670 | IkReal gconst32=0; |
| 16671 | IkReal x1230 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 16672 | if(IKabs(x1230)==0){ |
| 16673 | continue; |
| 16674 | } |
| 16675 | IkReal gconst33=((1.0)*new_r00*(pow(x1230,-0.5))); |
| 16676 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 16677 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 16678 | { |
| 16679 | { |
| 16680 | IkReal j0eval[1]; |
| 16681 | CheckValue<IkReal> x1232 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16682 | if(!x1232.valid){ |
| 16683 | continue; |
| 16684 | } |
| 16685 | IkReal x1231=((1.0)*(x1232.value)); |
| 16686 | sj1=-1.0; |
| 16687 | cj1=0; |
| 16688 | j1=-1.5707963267949; |
| 16689 | sj2=gconst32; |
| 16690 | cj2=gconst33; |
| 16691 | j2=((3.14159265)+(((-1.0)*x1231))); |
| 16692 | new_r11=0; |
| 16693 | new_r10=0; |
| 16694 | new_r22=0; |
| 16695 | new_r02=0; |
| 16696 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1231))); |
| 16697 | IkReal gconst32=0; |
| 16698 | IkReal x1233 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 16699 | if(IKabs(x1233)==0){ |
| 16700 | continue; |
| 16701 | } |
| 16702 | IkReal gconst33=((1.0)*new_r00*(pow(x1233,-0.5))); |
| 16703 | j0eval[0]=new_r00; |
| 16704 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 16705 | { |
| 16706 | { |
| 16707 | IkReal j0eval[2]; |
| 16708 | CheckValue<IkReal> x1235 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 16709 | if(!x1235.valid){ |
| 16710 | continue; |
| 16711 | } |
| 16712 | IkReal x1234=((1.0)*(x1235.value)); |
| 16713 | sj1=-1.0; |
| 16714 | cj1=0; |
| 16715 | j1=-1.5707963267949; |
| 16716 | sj2=gconst32; |
| 16717 | cj2=gconst33; |
| 16718 | j2=((3.14159265)+(((-1.0)*x1234))); |
| 16719 | new_r11=0; |
| 16720 | new_r10=0; |
| 16721 | new_r22=0; |
| 16722 | new_r02=0; |
| 16723 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1234))); |
| 16724 | IkReal gconst32=0; |
| 16725 | IkReal x1236 = ((1.0)+(((-1.0)*(new_r01*new_r01)))); |
| 16726 | if(IKabs(x1236)==0){ |
| 16727 | continue; |
| 16728 | } |
| 16729 | IkReal gconst33=((1.0)*new_r00*(pow(x1236,-0.5))); |
| 16730 | j0eval[0]=new_r00; |
| 16731 | j0eval[1]=new_r01; |
| 16732 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 16733 | { |
| 16734 | continue; // 3 cases reached |
| 16735 | |
| 16736 | } else |
| 16737 | { |
| 16738 | { |
| 16739 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16740 | bool j0valid[1]={false}; |
| 16741 | _nj0 = 1; |
| 16742 | CheckValue<IkReal> x1237=IKPowWithIntegerCheck(new_r00,-1); |
| 16743 | if(!x1237.valid){ |
| 16744 | continue; |
| 16745 | } |
| 16746 | CheckValue<IkReal> x1238=IKPowWithIntegerCheck(new_r01,-1); |
| 16747 | if(!x1238.valid){ |
| 16748 | continue; |
| 16749 | } |
| 16750 | if( IKabs(((-1.0)*gconst33*(x1237.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst33*(x1238.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1237.value)))+IKsqr((gconst33*(x1238.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 16751 | continue; |
| 16752 | j0array[0]=IKatan2(((-1.0)*gconst33*(x1237.value)), (gconst33*(x1238.value))); |
| 16753 | sj0array[0]=IKsin(j0array[0]); |
| 16754 | cj0array[0]=IKcos(j0array[0]); |
| 16755 | if( j0array[0] > IKPI ) |
| 16756 | { |
| 16757 | j0array[0]-=IK2PI; |
| 16758 | } |
| 16759 | else if( j0array[0] < -IKPI ) |
| 16760 | { j0array[0]+=IK2PI; |
| 16761 | } |
| 16762 | j0valid[0] = true; |
| 16763 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16764 | { |
| 16765 | if( !j0valid[ij0] ) |
| 16766 | { |
| 16767 | continue; |
| 16768 | } |
| 16769 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16770 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16771 | { |
| 16772 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16773 | { |
| 16774 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16775 | } |
| 16776 | } |
| 16777 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16778 | { |
| 16779 | IkReal evalcond[8]; |
| 16780 | IkReal x1239=IKsin(j0); |
| 16781 | IkReal x1240=IKcos(j0); |
| 16782 | IkReal x1241=((1.0)*gconst33); |
| 16783 | IkReal x1242=(gconst33*x1239); |
| 16784 | evalcond[0]=(new_r00*x1240); |
| 16785 | evalcond[1]=((-1.0)*new_r01*x1239); |
| 16786 | evalcond[2]=((-1.0)*x1242); |
| 16787 | evalcond[3]=((-1.0)*gconst33*x1240); |
| 16788 | evalcond[4]=(gconst33+((new_r00*x1239))); |
| 16789 | evalcond[5]=(x1242+new_r00); |
| 16790 | evalcond[6]=((((-1.0)*x1240*x1241))+new_r01); |
| 16791 | evalcond[7]=((((-1.0)*x1241))+((new_r01*x1240))); |
| 16792 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 16793 | { |
| 16794 | continue; |
| 16795 | } |
| 16796 | } |
| 16797 | |
| 16798 | { |
| 16799 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16800 | vinfos[0].jointtype = 1; |
| 16801 | vinfos[0].foffset = j0; |
| 16802 | vinfos[0].indices[0] = _ij0[0]; |
| 16803 | vinfos[0].indices[1] = _ij0[1]; |
| 16804 | vinfos[0].maxsolutions = _nj0; |
| 16805 | vinfos[1].jointtype = 1; |
| 16806 | vinfos[1].foffset = j1; |
| 16807 | vinfos[1].indices[0] = _ij1[0]; |
| 16808 | vinfos[1].indices[1] = _ij1[1]; |
| 16809 | vinfos[1].maxsolutions = _nj1; |
| 16810 | vinfos[2].jointtype = 1; |
| 16811 | vinfos[2].foffset = j2; |
| 16812 | vinfos[2].indices[0] = _ij2[0]; |
| 16813 | vinfos[2].indices[1] = _ij2[1]; |
| 16814 | vinfos[2].maxsolutions = _nj2; |
| 16815 | vinfos[3].jointtype = 1; |
| 16816 | vinfos[3].foffset = j3; |
| 16817 | vinfos[3].indices[0] = _ij3[0]; |
| 16818 | vinfos[3].indices[1] = _ij3[1]; |
| 16819 | vinfos[3].maxsolutions = _nj3; |
| 16820 | vinfos[4].jointtype = 1; |
| 16821 | vinfos[4].foffset = j4; |
| 16822 | vinfos[4].indices[0] = _ij4[0]; |
| 16823 | vinfos[4].indices[1] = _ij4[1]; |
| 16824 | vinfos[4].maxsolutions = _nj4; |
| 16825 | vinfos[5].jointtype = 1; |
| 16826 | vinfos[5].foffset = j5; |
| 16827 | vinfos[5].indices[0] = _ij5[0]; |
| 16828 | vinfos[5].indices[1] = _ij5[1]; |
| 16829 | vinfos[5].maxsolutions = _nj5; |
| 16830 | std::vector<int> vfree(0); |
| 16831 | solutions.AddSolution(vinfos,vfree); |
| 16832 | } |
| 16833 | } |
| 16834 | } |
| 16835 | |
| 16836 | } |
| 16837 | |
| 16838 | } |
| 16839 | |
| 16840 | } else |
| 16841 | { |
| 16842 | { |
| 16843 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16844 | bool j0valid[1]={false}; |
| 16845 | _nj0 = 1; |
| 16846 | CheckValue<IkReal> x1243=IKPowWithIntegerCheck(new_r00,-1); |
| 16847 | if(!x1243.valid){ |
| 16848 | continue; |
| 16849 | } |
| 16850 | CheckValue<IkReal> x1244=IKPowWithIntegerCheck(gconst33,-1); |
| 16851 | if(!x1244.valid){ |
| 16852 | continue; |
| 16853 | } |
| 16854 | if( IKabs(((-1.0)*gconst33*(x1243.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1244.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1243.value)))+IKsqr((new_r01*(x1244.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 16855 | continue; |
| 16856 | j0array[0]=IKatan2(((-1.0)*gconst33*(x1243.value)), (new_r01*(x1244.value))); |
| 16857 | sj0array[0]=IKsin(j0array[0]); |
| 16858 | cj0array[0]=IKcos(j0array[0]); |
| 16859 | if( j0array[0] > IKPI ) |
| 16860 | { |
| 16861 | j0array[0]-=IK2PI; |
| 16862 | } |
| 16863 | else if( j0array[0] < -IKPI ) |
| 16864 | { j0array[0]+=IK2PI; |
| 16865 | } |
| 16866 | j0valid[0] = true; |
| 16867 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16868 | { |
| 16869 | if( !j0valid[ij0] ) |
| 16870 | { |
| 16871 | continue; |
| 16872 | } |
| 16873 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16874 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16875 | { |
| 16876 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16877 | { |
| 16878 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16879 | } |
| 16880 | } |
| 16881 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16882 | { |
| 16883 | IkReal evalcond[8]; |
| 16884 | IkReal x1245=IKsin(j0); |
| 16885 | IkReal x1246=IKcos(j0); |
| 16886 | IkReal x1247=((1.0)*gconst33); |
| 16887 | IkReal x1248=(gconst33*x1245); |
| 16888 | evalcond[0]=(new_r00*x1246); |
| 16889 | evalcond[1]=((-1.0)*new_r01*x1245); |
| 16890 | evalcond[2]=((-1.0)*x1248); |
| 16891 | evalcond[3]=((-1.0)*gconst33*x1246); |
| 16892 | evalcond[4]=(gconst33+((new_r00*x1245))); |
| 16893 | evalcond[5]=(x1248+new_r00); |
| 16894 | evalcond[6]=(new_r01+(((-1.0)*x1246*x1247))); |
| 16895 | evalcond[7]=((((-1.0)*x1247))+((new_r01*x1246))); |
| 16896 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 16897 | { |
| 16898 | continue; |
| 16899 | } |
| 16900 | } |
| 16901 | |
| 16902 | { |
| 16903 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 16904 | vinfos[0].jointtype = 1; |
| 16905 | vinfos[0].foffset = j0; |
| 16906 | vinfos[0].indices[0] = _ij0[0]; |
| 16907 | vinfos[0].indices[1] = _ij0[1]; |
| 16908 | vinfos[0].maxsolutions = _nj0; |
| 16909 | vinfos[1].jointtype = 1; |
| 16910 | vinfos[1].foffset = j1; |
| 16911 | vinfos[1].indices[0] = _ij1[0]; |
| 16912 | vinfos[1].indices[1] = _ij1[1]; |
| 16913 | vinfos[1].maxsolutions = _nj1; |
| 16914 | vinfos[2].jointtype = 1; |
| 16915 | vinfos[2].foffset = j2; |
| 16916 | vinfos[2].indices[0] = _ij2[0]; |
| 16917 | vinfos[2].indices[1] = _ij2[1]; |
| 16918 | vinfos[2].maxsolutions = _nj2; |
| 16919 | vinfos[3].jointtype = 1; |
| 16920 | vinfos[3].foffset = j3; |
| 16921 | vinfos[3].indices[0] = _ij3[0]; |
| 16922 | vinfos[3].indices[1] = _ij3[1]; |
| 16923 | vinfos[3].maxsolutions = _nj3; |
| 16924 | vinfos[4].jointtype = 1; |
| 16925 | vinfos[4].foffset = j4; |
| 16926 | vinfos[4].indices[0] = _ij4[0]; |
| 16927 | vinfos[4].indices[1] = _ij4[1]; |
| 16928 | vinfos[4].maxsolutions = _nj4; |
| 16929 | vinfos[5].jointtype = 1; |
| 16930 | vinfos[5].foffset = j5; |
| 16931 | vinfos[5].indices[0] = _ij5[0]; |
| 16932 | vinfos[5].indices[1] = _ij5[1]; |
| 16933 | vinfos[5].maxsolutions = _nj5; |
| 16934 | std::vector<int> vfree(0); |
| 16935 | solutions.AddSolution(vinfos,vfree); |
| 16936 | } |
| 16937 | } |
| 16938 | } |
| 16939 | |
| 16940 | } |
| 16941 | |
| 16942 | } |
| 16943 | |
| 16944 | } else |
| 16945 | { |
| 16946 | { |
| 16947 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 16948 | bool j0valid[1]={false}; |
| 16949 | _nj0 = 1; |
| 16950 | CheckValue<IkReal> x1249 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 16951 | if(!x1249.valid){ |
| 16952 | continue; |
| 16953 | } |
| 16954 | CheckValue<IkReal> x1250=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| 16955 | if(!x1250.valid){ |
| 16956 | continue; |
| 16957 | } |
| 16958 | j0array[0]=((-1.5707963267949)+(x1249.value)+(((1.5707963267949)*(x1250.value)))); |
| 16959 | sj0array[0]=IKsin(j0array[0]); |
| 16960 | cj0array[0]=IKcos(j0array[0]); |
| 16961 | if( j0array[0] > IKPI ) |
| 16962 | { |
| 16963 | j0array[0]-=IK2PI; |
| 16964 | } |
| 16965 | else if( j0array[0] < -IKPI ) |
| 16966 | { j0array[0]+=IK2PI; |
| 16967 | } |
| 16968 | j0valid[0] = true; |
| 16969 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 16970 | { |
| 16971 | if( !j0valid[ij0] ) |
| 16972 | { |
| 16973 | continue; |
| 16974 | } |
| 16975 | _ij0[0] = ij0; _ij0[1] = -1; |
| 16976 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 16977 | { |
| 16978 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 16979 | { |
| 16980 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 16981 | } |
| 16982 | } |
| 16983 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 16984 | { |
| 16985 | IkReal evalcond[8]; |
| 16986 | IkReal x1251=IKsin(j0); |
| 16987 | IkReal x1252=IKcos(j0); |
| 16988 | IkReal x1253=((1.0)*gconst33); |
| 16989 | IkReal x1254=(gconst33*x1251); |
| 16990 | evalcond[0]=(new_r00*x1252); |
| 16991 | evalcond[1]=((-1.0)*new_r01*x1251); |
| 16992 | evalcond[2]=((-1.0)*x1254); |
| 16993 | evalcond[3]=((-1.0)*gconst33*x1252); |
| 16994 | evalcond[4]=(((new_r00*x1251))+gconst33); |
| 16995 | evalcond[5]=(x1254+new_r00); |
| 16996 | evalcond[6]=((((-1.0)*x1252*x1253))+new_r01); |
| 16997 | evalcond[7]=((((-1.0)*x1253))+((new_r01*x1252))); |
| 16998 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 16999 | { |
| 17000 | continue; |
| 17001 | } |
| 17002 | } |
| 17003 | |
| 17004 | { |
| 17005 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17006 | vinfos[0].jointtype = 1; |
| 17007 | vinfos[0].foffset = j0; |
| 17008 | vinfos[0].indices[0] = _ij0[0]; |
| 17009 | vinfos[0].indices[1] = _ij0[1]; |
| 17010 | vinfos[0].maxsolutions = _nj0; |
| 17011 | vinfos[1].jointtype = 1; |
| 17012 | vinfos[1].foffset = j1; |
| 17013 | vinfos[1].indices[0] = _ij1[0]; |
| 17014 | vinfos[1].indices[1] = _ij1[1]; |
| 17015 | vinfos[1].maxsolutions = _nj1; |
| 17016 | vinfos[2].jointtype = 1; |
| 17017 | vinfos[2].foffset = j2; |
| 17018 | vinfos[2].indices[0] = _ij2[0]; |
| 17019 | vinfos[2].indices[1] = _ij2[1]; |
| 17020 | vinfos[2].maxsolutions = _nj2; |
| 17021 | vinfos[3].jointtype = 1; |
| 17022 | vinfos[3].foffset = j3; |
| 17023 | vinfos[3].indices[0] = _ij3[0]; |
| 17024 | vinfos[3].indices[1] = _ij3[1]; |
| 17025 | vinfos[3].maxsolutions = _nj3; |
| 17026 | vinfos[4].jointtype = 1; |
| 17027 | vinfos[4].foffset = j4; |
| 17028 | vinfos[4].indices[0] = _ij4[0]; |
| 17029 | vinfos[4].indices[1] = _ij4[1]; |
| 17030 | vinfos[4].maxsolutions = _nj4; |
| 17031 | vinfos[5].jointtype = 1; |
| 17032 | vinfos[5].foffset = j5; |
| 17033 | vinfos[5].indices[0] = _ij5[0]; |
| 17034 | vinfos[5].indices[1] = _ij5[1]; |
| 17035 | vinfos[5].maxsolutions = _nj5; |
| 17036 | std::vector<int> vfree(0); |
| 17037 | solutions.AddSolution(vinfos,vfree); |
| 17038 | } |
| 17039 | } |
| 17040 | } |
| 17041 | |
| 17042 | } |
| 17043 | |
| 17044 | } |
| 17045 | |
| 17046 | } |
| 17047 | } while(0); |
| 17048 | if( bgotonextstatement ) |
| 17049 | { |
| 17050 | bool bgotonextstatement = true; |
| 17051 | do |
| 17052 | { |
| 17053 | evalcond[0]=IKabs(new_r10); |
| 17054 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 17055 | { |
| 17056 | bgotonextstatement=false; |
| 17057 | { |
| 17058 | IkReal j0eval[1]; |
| 17059 | CheckValue<IkReal> x1256 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 17060 | if(!x1256.valid){ |
| 17061 | continue; |
| 17062 | } |
| 17063 | IkReal x1255=((1.0)*(x1256.value)); |
| 17064 | sj1=-1.0; |
| 17065 | cj1=0; |
| 17066 | j1=-1.5707963267949; |
| 17067 | sj2=gconst32; |
| 17068 | cj2=gconst33; |
| 17069 | j2=((3.14159265)+(((-1.0)*x1255))); |
| 17070 | new_r10=0; |
| 17071 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1255))); |
| 17072 | IkReal gconst32=0; |
| 17073 | IkReal x1257 = new_r00*new_r00; |
| 17074 | if(IKabs(x1257)==0){ |
| 17075 | continue; |
| 17076 | } |
| 17077 | IkReal gconst33=((1.0)*new_r00*(pow(x1257,-0.5))); |
| 17078 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 17079 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 17080 | { |
| 17081 | { |
| 17082 | IkReal j0eval[1]; |
| 17083 | CheckValue<IkReal> x1259 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 17084 | if(!x1259.valid){ |
| 17085 | continue; |
| 17086 | } |
| 17087 | IkReal x1258=((1.0)*(x1259.value)); |
| 17088 | sj1=-1.0; |
| 17089 | cj1=0; |
| 17090 | j1=-1.5707963267949; |
| 17091 | sj2=gconst32; |
| 17092 | cj2=gconst33; |
| 17093 | j2=((3.14159265)+(((-1.0)*x1258))); |
| 17094 | new_r10=0; |
| 17095 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1258))); |
| 17096 | IkReal gconst32=0; |
| 17097 | IkReal x1260 = new_r00*new_r00; |
| 17098 | if(IKabs(x1260)==0){ |
| 17099 | continue; |
| 17100 | } |
| 17101 | IkReal gconst33=((1.0)*new_r00*(pow(x1260,-0.5))); |
| 17102 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 17103 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 17104 | { |
| 17105 | { |
| 17106 | IkReal j0eval[1]; |
| 17107 | CheckValue<IkReal> x1262 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r00)),IKFAST_ATAN2_MAGTHRESH); |
| 17108 | if(!x1262.valid){ |
| 17109 | continue; |
| 17110 | } |
| 17111 | IkReal x1261=((1.0)*(x1262.value)); |
| 17112 | sj1=-1.0; |
| 17113 | cj1=0; |
| 17114 | j1=-1.5707963267949; |
| 17115 | sj2=gconst32; |
| 17116 | cj2=gconst33; |
| 17117 | j2=((3.14159265)+(((-1.0)*x1261))); |
| 17118 | new_r10=0; |
| 17119 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1261))); |
| 17120 | IkReal gconst32=0; |
| 17121 | IkReal x1263 = new_r00*new_r00; |
| 17122 | if(IKabs(x1263)==0){ |
| 17123 | continue; |
| 17124 | } |
| 17125 | IkReal gconst33=((1.0)*new_r00*(pow(x1263,-0.5))); |
| 17126 | j0eval[0]=new_r00; |
| 17127 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 17128 | { |
| 17129 | continue; // 3 cases reached |
| 17130 | |
| 17131 | } else |
| 17132 | { |
| 17133 | { |
| 17134 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17135 | bool j0valid[1]={false}; |
| 17136 | _nj0 = 1; |
| 17137 | CheckValue<IkReal> x1264=IKPowWithIntegerCheck(new_r00,-1); |
| 17138 | if(!x1264.valid){ |
| 17139 | continue; |
| 17140 | } |
| 17141 | CheckValue<IkReal> x1265=IKPowWithIntegerCheck(gconst33,-1); |
| 17142 | if(!x1265.valid){ |
| 17143 | continue; |
| 17144 | } |
| 17145 | if( IKabs(((-1.0)*gconst33*(x1264.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1265.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst33*(x1264.value)))+IKsqr((new_r01*(x1265.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 17146 | continue; |
| 17147 | j0array[0]=IKatan2(((-1.0)*gconst33*(x1264.value)), (new_r01*(x1265.value))); |
| 17148 | sj0array[0]=IKsin(j0array[0]); |
| 17149 | cj0array[0]=IKcos(j0array[0]); |
| 17150 | if( j0array[0] > IKPI ) |
| 17151 | { |
| 17152 | j0array[0]-=IK2PI; |
| 17153 | } |
| 17154 | else if( j0array[0] < -IKPI ) |
| 17155 | { j0array[0]+=IK2PI; |
| 17156 | } |
| 17157 | j0valid[0] = true; |
| 17158 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17159 | { |
| 17160 | if( !j0valid[ij0] ) |
| 17161 | { |
| 17162 | continue; |
| 17163 | } |
| 17164 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17165 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17166 | { |
| 17167 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17168 | { |
| 17169 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17170 | } |
| 17171 | } |
| 17172 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17173 | { |
| 17174 | IkReal evalcond[8]; |
| 17175 | IkReal x1266=IKcos(j0); |
| 17176 | IkReal x1267=IKsin(j0); |
| 17177 | IkReal x1268=((1.0)*gconst33); |
| 17178 | evalcond[0]=(new_r00*x1266); |
| 17179 | evalcond[1]=((-1.0)*gconst33*x1266); |
| 17180 | evalcond[2]=(gconst33+((new_r00*x1267))); |
| 17181 | evalcond[3]=(((gconst33*x1267))+new_r00); |
| 17182 | evalcond[4]=((((-1.0)*x1267*x1268))+new_r11); |
| 17183 | evalcond[5]=((((-1.0)*x1266*x1268))+new_r01); |
| 17184 | evalcond[6]=((((-1.0)*new_r01*x1267))+((new_r11*x1266))); |
| 17185 | evalcond[7]=(((new_r01*x1266))+((new_r11*x1267))+(((-1.0)*x1268))); |
| 17186 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17187 | { |
| 17188 | continue; |
| 17189 | } |
| 17190 | } |
| 17191 | |
| 17192 | { |
| 17193 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17194 | vinfos[0].jointtype = 1; |
| 17195 | vinfos[0].foffset = j0; |
| 17196 | vinfos[0].indices[0] = _ij0[0]; |
| 17197 | vinfos[0].indices[1] = _ij0[1]; |
| 17198 | vinfos[0].maxsolutions = _nj0; |
| 17199 | vinfos[1].jointtype = 1; |
| 17200 | vinfos[1].foffset = j1; |
| 17201 | vinfos[1].indices[0] = _ij1[0]; |
| 17202 | vinfos[1].indices[1] = _ij1[1]; |
| 17203 | vinfos[1].maxsolutions = _nj1; |
| 17204 | vinfos[2].jointtype = 1; |
| 17205 | vinfos[2].foffset = j2; |
| 17206 | vinfos[2].indices[0] = _ij2[0]; |
| 17207 | vinfos[2].indices[1] = _ij2[1]; |
| 17208 | vinfos[2].maxsolutions = _nj2; |
| 17209 | vinfos[3].jointtype = 1; |
| 17210 | vinfos[3].foffset = j3; |
| 17211 | vinfos[3].indices[0] = _ij3[0]; |
| 17212 | vinfos[3].indices[1] = _ij3[1]; |
| 17213 | vinfos[3].maxsolutions = _nj3; |
| 17214 | vinfos[4].jointtype = 1; |
| 17215 | vinfos[4].foffset = j4; |
| 17216 | vinfos[4].indices[0] = _ij4[0]; |
| 17217 | vinfos[4].indices[1] = _ij4[1]; |
| 17218 | vinfos[4].maxsolutions = _nj4; |
| 17219 | vinfos[5].jointtype = 1; |
| 17220 | vinfos[5].foffset = j5; |
| 17221 | vinfos[5].indices[0] = _ij5[0]; |
| 17222 | vinfos[5].indices[1] = _ij5[1]; |
| 17223 | vinfos[5].maxsolutions = _nj5; |
| 17224 | std::vector<int> vfree(0); |
| 17225 | solutions.AddSolution(vinfos,vfree); |
| 17226 | } |
| 17227 | } |
| 17228 | } |
| 17229 | |
| 17230 | } |
| 17231 | |
| 17232 | } |
| 17233 | |
| 17234 | } else |
| 17235 | { |
| 17236 | { |
| 17237 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17238 | bool j0valid[1]={false}; |
| 17239 | _nj0 = 1; |
| 17240 | CheckValue<IkReal> x1269 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 17241 | if(!x1269.valid){ |
| 17242 | continue; |
| 17243 | } |
| 17244 | CheckValue<IkReal> x1270=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| 17245 | if(!x1270.valid){ |
| 17246 | continue; |
| 17247 | } |
| 17248 | j0array[0]=((-1.5707963267949)+(x1269.value)+(((1.5707963267949)*(x1270.value)))); |
| 17249 | sj0array[0]=IKsin(j0array[0]); |
| 17250 | cj0array[0]=IKcos(j0array[0]); |
| 17251 | if( j0array[0] > IKPI ) |
| 17252 | { |
| 17253 | j0array[0]-=IK2PI; |
| 17254 | } |
| 17255 | else if( j0array[0] < -IKPI ) |
| 17256 | { j0array[0]+=IK2PI; |
| 17257 | } |
| 17258 | j0valid[0] = true; |
| 17259 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17260 | { |
| 17261 | if( !j0valid[ij0] ) |
| 17262 | { |
| 17263 | continue; |
| 17264 | } |
| 17265 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17266 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17267 | { |
| 17268 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17269 | { |
| 17270 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17271 | } |
| 17272 | } |
| 17273 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17274 | { |
| 17275 | IkReal evalcond[8]; |
| 17276 | IkReal x1271=IKcos(j0); |
| 17277 | IkReal x1272=IKsin(j0); |
| 17278 | IkReal x1273=((1.0)*gconst33); |
| 17279 | evalcond[0]=(new_r00*x1271); |
| 17280 | evalcond[1]=((-1.0)*gconst33*x1271); |
| 17281 | evalcond[2]=(((new_r00*x1272))+gconst33); |
| 17282 | evalcond[3]=(((gconst33*x1272))+new_r00); |
| 17283 | evalcond[4]=((((-1.0)*x1272*x1273))+new_r11); |
| 17284 | evalcond[5]=((((-1.0)*x1271*x1273))+new_r01); |
| 17285 | evalcond[6]=((((-1.0)*new_r01*x1272))+((new_r11*x1271))); |
| 17286 | evalcond[7]=(((new_r01*x1271))+(((-1.0)*x1273))+((new_r11*x1272))); |
| 17287 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17288 | { |
| 17289 | continue; |
| 17290 | } |
| 17291 | } |
| 17292 | |
| 17293 | { |
| 17294 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17295 | vinfos[0].jointtype = 1; |
| 17296 | vinfos[0].foffset = j0; |
| 17297 | vinfos[0].indices[0] = _ij0[0]; |
| 17298 | vinfos[0].indices[1] = _ij0[1]; |
| 17299 | vinfos[0].maxsolutions = _nj0; |
| 17300 | vinfos[1].jointtype = 1; |
| 17301 | vinfos[1].foffset = j1; |
| 17302 | vinfos[1].indices[0] = _ij1[0]; |
| 17303 | vinfos[1].indices[1] = _ij1[1]; |
| 17304 | vinfos[1].maxsolutions = _nj1; |
| 17305 | vinfos[2].jointtype = 1; |
| 17306 | vinfos[2].foffset = j2; |
| 17307 | vinfos[2].indices[0] = _ij2[0]; |
| 17308 | vinfos[2].indices[1] = _ij2[1]; |
| 17309 | vinfos[2].maxsolutions = _nj2; |
| 17310 | vinfos[3].jointtype = 1; |
| 17311 | vinfos[3].foffset = j3; |
| 17312 | vinfos[3].indices[0] = _ij3[0]; |
| 17313 | vinfos[3].indices[1] = _ij3[1]; |
| 17314 | vinfos[3].maxsolutions = _nj3; |
| 17315 | vinfos[4].jointtype = 1; |
| 17316 | vinfos[4].foffset = j4; |
| 17317 | vinfos[4].indices[0] = _ij4[0]; |
| 17318 | vinfos[4].indices[1] = _ij4[1]; |
| 17319 | vinfos[4].maxsolutions = _nj4; |
| 17320 | vinfos[5].jointtype = 1; |
| 17321 | vinfos[5].foffset = j5; |
| 17322 | vinfos[5].indices[0] = _ij5[0]; |
| 17323 | vinfos[5].indices[1] = _ij5[1]; |
| 17324 | vinfos[5].maxsolutions = _nj5; |
| 17325 | std::vector<int> vfree(0); |
| 17326 | solutions.AddSolution(vinfos,vfree); |
| 17327 | } |
| 17328 | } |
| 17329 | } |
| 17330 | |
| 17331 | } |
| 17332 | |
| 17333 | } |
| 17334 | |
| 17335 | } else |
| 17336 | { |
| 17337 | { |
| 17338 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17339 | bool j0valid[1]={false}; |
| 17340 | _nj0 = 1; |
| 17341 | CheckValue<IkReal> x1274 = IKatan2WithCheck(IkReal(new_r11),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 17342 | if(!x1274.valid){ |
| 17343 | continue; |
| 17344 | } |
| 17345 | CheckValue<IkReal> x1275=IKPowWithIntegerCheck(IKsign(gconst33),-1); |
| 17346 | if(!x1275.valid){ |
| 17347 | continue; |
| 17348 | } |
| 17349 | j0array[0]=((-1.5707963267949)+(x1274.value)+(((1.5707963267949)*(x1275.value)))); |
| 17350 | sj0array[0]=IKsin(j0array[0]); |
| 17351 | cj0array[0]=IKcos(j0array[0]); |
| 17352 | if( j0array[0] > IKPI ) |
| 17353 | { |
| 17354 | j0array[0]-=IK2PI; |
| 17355 | } |
| 17356 | else if( j0array[0] < -IKPI ) |
| 17357 | { j0array[0]+=IK2PI; |
| 17358 | } |
| 17359 | j0valid[0] = true; |
| 17360 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17361 | { |
| 17362 | if( !j0valid[ij0] ) |
| 17363 | { |
| 17364 | continue; |
| 17365 | } |
| 17366 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17367 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17368 | { |
| 17369 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17370 | { |
| 17371 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17372 | } |
| 17373 | } |
| 17374 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17375 | { |
| 17376 | IkReal evalcond[8]; |
| 17377 | IkReal x1276=IKcos(j0); |
| 17378 | IkReal x1277=IKsin(j0); |
| 17379 | IkReal x1278=((1.0)*gconst33); |
| 17380 | evalcond[0]=(new_r00*x1276); |
| 17381 | evalcond[1]=((-1.0)*gconst33*x1276); |
| 17382 | evalcond[2]=(((new_r00*x1277))+gconst33); |
| 17383 | evalcond[3]=(((gconst33*x1277))+new_r00); |
| 17384 | evalcond[4]=((((-1.0)*x1277*x1278))+new_r11); |
| 17385 | evalcond[5]=((((-1.0)*x1276*x1278))+new_r01); |
| 17386 | evalcond[6]=((((-1.0)*new_r01*x1277))+((new_r11*x1276))); |
| 17387 | evalcond[7]=(((new_r01*x1276))+(((-1.0)*x1278))+((new_r11*x1277))); |
| 17388 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17389 | { |
| 17390 | continue; |
| 17391 | } |
| 17392 | } |
| 17393 | |
| 17394 | { |
| 17395 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17396 | vinfos[0].jointtype = 1; |
| 17397 | vinfos[0].foffset = j0; |
| 17398 | vinfos[0].indices[0] = _ij0[0]; |
| 17399 | vinfos[0].indices[1] = _ij0[1]; |
| 17400 | vinfos[0].maxsolutions = _nj0; |
| 17401 | vinfos[1].jointtype = 1; |
| 17402 | vinfos[1].foffset = j1; |
| 17403 | vinfos[1].indices[0] = _ij1[0]; |
| 17404 | vinfos[1].indices[1] = _ij1[1]; |
| 17405 | vinfos[1].maxsolutions = _nj1; |
| 17406 | vinfos[2].jointtype = 1; |
| 17407 | vinfos[2].foffset = j2; |
| 17408 | vinfos[2].indices[0] = _ij2[0]; |
| 17409 | vinfos[2].indices[1] = _ij2[1]; |
| 17410 | vinfos[2].maxsolutions = _nj2; |
| 17411 | vinfos[3].jointtype = 1; |
| 17412 | vinfos[3].foffset = j3; |
| 17413 | vinfos[3].indices[0] = _ij3[0]; |
| 17414 | vinfos[3].indices[1] = _ij3[1]; |
| 17415 | vinfos[3].maxsolutions = _nj3; |
| 17416 | vinfos[4].jointtype = 1; |
| 17417 | vinfos[4].foffset = j4; |
| 17418 | vinfos[4].indices[0] = _ij4[0]; |
| 17419 | vinfos[4].indices[1] = _ij4[1]; |
| 17420 | vinfos[4].maxsolutions = _nj4; |
| 17421 | vinfos[5].jointtype = 1; |
| 17422 | vinfos[5].foffset = j5; |
| 17423 | vinfos[5].indices[0] = _ij5[0]; |
| 17424 | vinfos[5].indices[1] = _ij5[1]; |
| 17425 | vinfos[5].maxsolutions = _nj5; |
| 17426 | std::vector<int> vfree(0); |
| 17427 | solutions.AddSolution(vinfos,vfree); |
| 17428 | } |
| 17429 | } |
| 17430 | } |
| 17431 | |
| 17432 | } |
| 17433 | |
| 17434 | } |
| 17435 | |
| 17436 | } |
| 17437 | } while(0); |
| 17438 | if( bgotonextstatement ) |
| 17439 | { |
| 17440 | bool bgotonextstatement = true; |
| 17441 | do |
| 17442 | { |
| 17443 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 17444 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 17445 | { |
| 17446 | bgotonextstatement=false; |
| 17447 | { |
| 17448 | IkReal j0eval[1]; |
| 17449 | CheckValue<IkReal> x1280 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 17450 | if(!x1280.valid){ |
| 17451 | continue; |
| 17452 | } |
| 17453 | IkReal x1279=((1.0)*(x1280.value)); |
| 17454 | sj1=-1.0; |
| 17455 | cj1=0; |
| 17456 | j1=-1.5707963267949; |
| 17457 | sj2=gconst32; |
| 17458 | cj2=gconst33; |
| 17459 | j2=((3.14159265)+(((-1.0)*x1279))); |
| 17460 | new_r00=0; |
| 17461 | new_r01=0; |
| 17462 | new_r12=0; |
| 17463 | new_r22=0; |
| 17464 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1279))); |
| 17465 | IkReal x1281 = new_r10*new_r10; |
| 17466 | if(IKabs(x1281)==0){ |
| 17467 | continue; |
| 17468 | } |
| 17469 | IkReal gconst32=((1.0)*new_r10*(pow(x1281,-0.5))); |
| 17470 | IkReal gconst33=0; |
| 17471 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 17472 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 17473 | { |
| 17474 | { |
| 17475 | IkReal j0eval[1]; |
| 17476 | CheckValue<IkReal> x1283 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 17477 | if(!x1283.valid){ |
| 17478 | continue; |
| 17479 | } |
| 17480 | IkReal x1282=((1.0)*(x1283.value)); |
| 17481 | sj1=-1.0; |
| 17482 | cj1=0; |
| 17483 | j1=-1.5707963267949; |
| 17484 | sj2=gconst32; |
| 17485 | cj2=gconst33; |
| 17486 | j2=((3.14159265)+(((-1.0)*x1282))); |
| 17487 | new_r00=0; |
| 17488 | new_r01=0; |
| 17489 | new_r12=0; |
| 17490 | new_r22=0; |
| 17491 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1282))); |
| 17492 | IkReal x1284 = new_r10*new_r10; |
| 17493 | if(IKabs(x1284)==0){ |
| 17494 | continue; |
| 17495 | } |
| 17496 | IkReal gconst32=((1.0)*new_r10*(pow(x1284,-0.5))); |
| 17497 | IkReal gconst33=0; |
| 17498 | j0eval[0]=new_r11; |
| 17499 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 17500 | { |
| 17501 | { |
| 17502 | IkReal j0eval[2]; |
| 17503 | CheckValue<IkReal> x1286 = IKatan2WithCheck(IkReal(new_r10),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 17504 | if(!x1286.valid){ |
| 17505 | continue; |
| 17506 | } |
| 17507 | IkReal x1285=((1.0)*(x1286.value)); |
| 17508 | sj1=-1.0; |
| 17509 | cj1=0; |
| 17510 | j1=-1.5707963267949; |
| 17511 | sj2=gconst32; |
| 17512 | cj2=gconst33; |
| 17513 | j2=((3.14159265)+(((-1.0)*x1285))); |
| 17514 | new_r00=0; |
| 17515 | new_r01=0; |
| 17516 | new_r12=0; |
| 17517 | new_r22=0; |
| 17518 | IkReal gconst31=((3.14159265358979)+(((-1.0)*x1285))); |
| 17519 | IkReal x1287 = new_r10*new_r10; |
| 17520 | if(IKabs(x1287)==0){ |
| 17521 | continue; |
| 17522 | } |
| 17523 | IkReal gconst32=((1.0)*new_r10*(pow(x1287,-0.5))); |
| 17524 | IkReal gconst33=0; |
| 17525 | j0eval[0]=new_r10; |
| 17526 | j0eval[1]=new_r11; |
| 17527 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 17528 | { |
| 17529 | continue; // 3 cases reached |
| 17530 | |
| 17531 | } else |
| 17532 | { |
| 17533 | { |
| 17534 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17535 | bool j0valid[1]={false}; |
| 17536 | _nj0 = 1; |
| 17537 | CheckValue<IkReal> x1288=IKPowWithIntegerCheck(new_r10,-1); |
| 17538 | if(!x1288.valid){ |
| 17539 | continue; |
| 17540 | } |
| 17541 | CheckValue<IkReal> x1289=IKPowWithIntegerCheck(new_r11,-1); |
| 17542 | if(!x1289.valid){ |
| 17543 | continue; |
| 17544 | } |
| 17545 | if( IKabs((gconst32*(x1288.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst32*(x1289.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst32*(x1288.value)))+IKsqr(((-1.0)*gconst32*(x1289.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 17546 | continue; |
| 17547 | j0array[0]=IKatan2((gconst32*(x1288.value)), ((-1.0)*gconst32*(x1289.value))); |
| 17548 | sj0array[0]=IKsin(j0array[0]); |
| 17549 | cj0array[0]=IKcos(j0array[0]); |
| 17550 | if( j0array[0] > IKPI ) |
| 17551 | { |
| 17552 | j0array[0]-=IK2PI; |
| 17553 | } |
| 17554 | else if( j0array[0] < -IKPI ) |
| 17555 | { j0array[0]+=IK2PI; |
| 17556 | } |
| 17557 | j0valid[0] = true; |
| 17558 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17559 | { |
| 17560 | if( !j0valid[ij0] ) |
| 17561 | { |
| 17562 | continue; |
| 17563 | } |
| 17564 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17565 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17566 | { |
| 17567 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17568 | { |
| 17569 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17570 | } |
| 17571 | } |
| 17572 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17573 | { |
| 17574 | IkReal evalcond[8]; |
| 17575 | IkReal x1290=IKcos(j0); |
| 17576 | IkReal x1291=IKsin(j0); |
| 17577 | IkReal x1292=((1.0)*gconst32); |
| 17578 | IkReal x1293=(gconst32*x1290); |
| 17579 | evalcond[0]=(new_r11*x1291); |
| 17580 | evalcond[1]=((-1.0)*new_r10*x1290); |
| 17581 | evalcond[2]=((-1.0)*x1293); |
| 17582 | evalcond[3]=((-1.0)*gconst32*x1291); |
| 17583 | evalcond[4]=(gconst32+((new_r11*x1290))); |
| 17584 | evalcond[5]=(x1293+new_r11); |
| 17585 | evalcond[6]=(new_r10+(((-1.0)*x1291*x1292))); |
| 17586 | evalcond[7]=((((-1.0)*x1292))+((new_r10*x1291))); |
| 17587 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17588 | { |
| 17589 | continue; |
| 17590 | } |
| 17591 | } |
| 17592 | |
| 17593 | { |
| 17594 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17595 | vinfos[0].jointtype = 1; |
| 17596 | vinfos[0].foffset = j0; |
| 17597 | vinfos[0].indices[0] = _ij0[0]; |
| 17598 | vinfos[0].indices[1] = _ij0[1]; |
| 17599 | vinfos[0].maxsolutions = _nj0; |
| 17600 | vinfos[1].jointtype = 1; |
| 17601 | vinfos[1].foffset = j1; |
| 17602 | vinfos[1].indices[0] = _ij1[0]; |
| 17603 | vinfos[1].indices[1] = _ij1[1]; |
| 17604 | vinfos[1].maxsolutions = _nj1; |
| 17605 | vinfos[2].jointtype = 1; |
| 17606 | vinfos[2].foffset = j2; |
| 17607 | vinfos[2].indices[0] = _ij2[0]; |
| 17608 | vinfos[2].indices[1] = _ij2[1]; |
| 17609 | vinfos[2].maxsolutions = _nj2; |
| 17610 | vinfos[3].jointtype = 1; |
| 17611 | vinfos[3].foffset = j3; |
| 17612 | vinfos[3].indices[0] = _ij3[0]; |
| 17613 | vinfos[3].indices[1] = _ij3[1]; |
| 17614 | vinfos[3].maxsolutions = _nj3; |
| 17615 | vinfos[4].jointtype = 1; |
| 17616 | vinfos[4].foffset = j4; |
| 17617 | vinfos[4].indices[0] = _ij4[0]; |
| 17618 | vinfos[4].indices[1] = _ij4[1]; |
| 17619 | vinfos[4].maxsolutions = _nj4; |
| 17620 | vinfos[5].jointtype = 1; |
| 17621 | vinfos[5].foffset = j5; |
| 17622 | vinfos[5].indices[0] = _ij5[0]; |
| 17623 | vinfos[5].indices[1] = _ij5[1]; |
| 17624 | vinfos[5].maxsolutions = _nj5; |
| 17625 | std::vector<int> vfree(0); |
| 17626 | solutions.AddSolution(vinfos,vfree); |
| 17627 | } |
| 17628 | } |
| 17629 | } |
| 17630 | |
| 17631 | } |
| 17632 | |
| 17633 | } |
| 17634 | |
| 17635 | } else |
| 17636 | { |
| 17637 | { |
| 17638 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17639 | bool j0valid[1]={false}; |
| 17640 | _nj0 = 1; |
| 17641 | CheckValue<IkReal> x1294=IKPowWithIntegerCheck(gconst32,-1); |
| 17642 | if(!x1294.valid){ |
| 17643 | continue; |
| 17644 | } |
| 17645 | CheckValue<IkReal> x1295=IKPowWithIntegerCheck(new_r11,-1); |
| 17646 | if(!x1295.valid){ |
| 17647 | continue; |
| 17648 | } |
| 17649 | if( IKabs((new_r10*(x1294.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst32*(x1295.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1294.value)))+IKsqr(((-1.0)*gconst32*(x1295.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 17650 | continue; |
| 17651 | j0array[0]=IKatan2((new_r10*(x1294.value)), ((-1.0)*gconst32*(x1295.value))); |
| 17652 | sj0array[0]=IKsin(j0array[0]); |
| 17653 | cj0array[0]=IKcos(j0array[0]); |
| 17654 | if( j0array[0] > IKPI ) |
| 17655 | { |
| 17656 | j0array[0]-=IK2PI; |
| 17657 | } |
| 17658 | else if( j0array[0] < -IKPI ) |
| 17659 | { j0array[0]+=IK2PI; |
| 17660 | } |
| 17661 | j0valid[0] = true; |
| 17662 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17663 | { |
| 17664 | if( !j0valid[ij0] ) |
| 17665 | { |
| 17666 | continue; |
| 17667 | } |
| 17668 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17669 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17670 | { |
| 17671 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17672 | { |
| 17673 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17674 | } |
| 17675 | } |
| 17676 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17677 | { |
| 17678 | IkReal evalcond[8]; |
| 17679 | IkReal x1296=IKcos(j0); |
| 17680 | IkReal x1297=IKsin(j0); |
| 17681 | IkReal x1298=((1.0)*gconst32); |
| 17682 | IkReal x1299=(gconst32*x1296); |
| 17683 | evalcond[0]=(new_r11*x1297); |
| 17684 | evalcond[1]=((-1.0)*new_r10*x1296); |
| 17685 | evalcond[2]=((-1.0)*x1299); |
| 17686 | evalcond[3]=((-1.0)*gconst32*x1297); |
| 17687 | evalcond[4]=(gconst32+((new_r11*x1296))); |
| 17688 | evalcond[5]=(x1299+new_r11); |
| 17689 | evalcond[6]=((((-1.0)*x1297*x1298))+new_r10); |
| 17690 | evalcond[7]=((((-1.0)*x1298))+((new_r10*x1297))); |
| 17691 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17692 | { |
| 17693 | continue; |
| 17694 | } |
| 17695 | } |
| 17696 | |
| 17697 | { |
| 17698 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17699 | vinfos[0].jointtype = 1; |
| 17700 | vinfos[0].foffset = j0; |
| 17701 | vinfos[0].indices[0] = _ij0[0]; |
| 17702 | vinfos[0].indices[1] = _ij0[1]; |
| 17703 | vinfos[0].maxsolutions = _nj0; |
| 17704 | vinfos[1].jointtype = 1; |
| 17705 | vinfos[1].foffset = j1; |
| 17706 | vinfos[1].indices[0] = _ij1[0]; |
| 17707 | vinfos[1].indices[1] = _ij1[1]; |
| 17708 | vinfos[1].maxsolutions = _nj1; |
| 17709 | vinfos[2].jointtype = 1; |
| 17710 | vinfos[2].foffset = j2; |
| 17711 | vinfos[2].indices[0] = _ij2[0]; |
| 17712 | vinfos[2].indices[1] = _ij2[1]; |
| 17713 | vinfos[2].maxsolutions = _nj2; |
| 17714 | vinfos[3].jointtype = 1; |
| 17715 | vinfos[3].foffset = j3; |
| 17716 | vinfos[3].indices[0] = _ij3[0]; |
| 17717 | vinfos[3].indices[1] = _ij3[1]; |
| 17718 | vinfos[3].maxsolutions = _nj3; |
| 17719 | vinfos[4].jointtype = 1; |
| 17720 | vinfos[4].foffset = j4; |
| 17721 | vinfos[4].indices[0] = _ij4[0]; |
| 17722 | vinfos[4].indices[1] = _ij4[1]; |
| 17723 | vinfos[4].maxsolutions = _nj4; |
| 17724 | vinfos[5].jointtype = 1; |
| 17725 | vinfos[5].foffset = j5; |
| 17726 | vinfos[5].indices[0] = _ij5[0]; |
| 17727 | vinfos[5].indices[1] = _ij5[1]; |
| 17728 | vinfos[5].maxsolutions = _nj5; |
| 17729 | std::vector<int> vfree(0); |
| 17730 | solutions.AddSolution(vinfos,vfree); |
| 17731 | } |
| 17732 | } |
| 17733 | } |
| 17734 | |
| 17735 | } |
| 17736 | |
| 17737 | } |
| 17738 | |
| 17739 | } else |
| 17740 | { |
| 17741 | { |
| 17742 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17743 | bool j0valid[1]={false}; |
| 17744 | _nj0 = 1; |
| 17745 | CheckValue<IkReal> x1300 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 17746 | if(!x1300.valid){ |
| 17747 | continue; |
| 17748 | } |
| 17749 | CheckValue<IkReal> x1301=IKPowWithIntegerCheck(IKsign(gconst32),-1); |
| 17750 | if(!x1301.valid){ |
| 17751 | continue; |
| 17752 | } |
| 17753 | j0array[0]=((-1.5707963267949)+(x1300.value)+(((1.5707963267949)*(x1301.value)))); |
| 17754 | sj0array[0]=IKsin(j0array[0]); |
| 17755 | cj0array[0]=IKcos(j0array[0]); |
| 17756 | if( j0array[0] > IKPI ) |
| 17757 | { |
| 17758 | j0array[0]-=IK2PI; |
| 17759 | } |
| 17760 | else if( j0array[0] < -IKPI ) |
| 17761 | { j0array[0]+=IK2PI; |
| 17762 | } |
| 17763 | j0valid[0] = true; |
| 17764 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17765 | { |
| 17766 | if( !j0valid[ij0] ) |
| 17767 | { |
| 17768 | continue; |
| 17769 | } |
| 17770 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17771 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17772 | { |
| 17773 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17774 | { |
| 17775 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17776 | } |
| 17777 | } |
| 17778 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17779 | { |
| 17780 | IkReal evalcond[8]; |
| 17781 | IkReal x1302=IKcos(j0); |
| 17782 | IkReal x1303=IKsin(j0); |
| 17783 | IkReal x1304=((1.0)*gconst32); |
| 17784 | IkReal x1305=(gconst32*x1302); |
| 17785 | evalcond[0]=(new_r11*x1303); |
| 17786 | evalcond[1]=((-1.0)*new_r10*x1302); |
| 17787 | evalcond[2]=((-1.0)*x1305); |
| 17788 | evalcond[3]=((-1.0)*gconst32*x1303); |
| 17789 | evalcond[4]=(gconst32+((new_r11*x1302))); |
| 17790 | evalcond[5]=(x1305+new_r11); |
| 17791 | evalcond[6]=((((-1.0)*x1303*x1304))+new_r10); |
| 17792 | evalcond[7]=((((-1.0)*x1304))+((new_r10*x1303))); |
| 17793 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17794 | { |
| 17795 | continue; |
| 17796 | } |
| 17797 | } |
| 17798 | |
| 17799 | { |
| 17800 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17801 | vinfos[0].jointtype = 1; |
| 17802 | vinfos[0].foffset = j0; |
| 17803 | vinfos[0].indices[0] = _ij0[0]; |
| 17804 | vinfos[0].indices[1] = _ij0[1]; |
| 17805 | vinfos[0].maxsolutions = _nj0; |
| 17806 | vinfos[1].jointtype = 1; |
| 17807 | vinfos[1].foffset = j1; |
| 17808 | vinfos[1].indices[0] = _ij1[0]; |
| 17809 | vinfos[1].indices[1] = _ij1[1]; |
| 17810 | vinfos[1].maxsolutions = _nj1; |
| 17811 | vinfos[2].jointtype = 1; |
| 17812 | vinfos[2].foffset = j2; |
| 17813 | vinfos[2].indices[0] = _ij2[0]; |
| 17814 | vinfos[2].indices[1] = _ij2[1]; |
| 17815 | vinfos[2].maxsolutions = _nj2; |
| 17816 | vinfos[3].jointtype = 1; |
| 17817 | vinfos[3].foffset = j3; |
| 17818 | vinfos[3].indices[0] = _ij3[0]; |
| 17819 | vinfos[3].indices[1] = _ij3[1]; |
| 17820 | vinfos[3].maxsolutions = _nj3; |
| 17821 | vinfos[4].jointtype = 1; |
| 17822 | vinfos[4].foffset = j4; |
| 17823 | vinfos[4].indices[0] = _ij4[0]; |
| 17824 | vinfos[4].indices[1] = _ij4[1]; |
| 17825 | vinfos[4].maxsolutions = _nj4; |
| 17826 | vinfos[5].jointtype = 1; |
| 17827 | vinfos[5].foffset = j5; |
| 17828 | vinfos[5].indices[0] = _ij5[0]; |
| 17829 | vinfos[5].indices[1] = _ij5[1]; |
| 17830 | vinfos[5].maxsolutions = _nj5; |
| 17831 | std::vector<int> vfree(0); |
| 17832 | solutions.AddSolution(vinfos,vfree); |
| 17833 | } |
| 17834 | } |
| 17835 | } |
| 17836 | |
| 17837 | } |
| 17838 | |
| 17839 | } |
| 17840 | |
| 17841 | } |
| 17842 | } while(0); |
| 17843 | if( bgotonextstatement ) |
| 17844 | { |
| 17845 | bool bgotonextstatement = true; |
| 17846 | do |
| 17847 | { |
| 17848 | if( 1 ) |
| 17849 | { |
| 17850 | bgotonextstatement=false; |
| 17851 | continue; // branch miss [j0] |
| 17852 | |
| 17853 | } |
| 17854 | } while(0); |
| 17855 | if( bgotonextstatement ) |
| 17856 | { |
| 17857 | } |
| 17858 | } |
| 17859 | } |
| 17860 | } |
| 17861 | } |
| 17862 | } |
| 17863 | } |
| 17864 | } |
| 17865 | |
| 17866 | } else |
| 17867 | { |
| 17868 | { |
| 17869 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17870 | bool j0valid[1]={false}; |
| 17871 | _nj0 = 1; |
| 17872 | CheckValue<IkReal> x1306 = IKatan2WithCheck(IkReal((((gconst32*new_r11))+((gconst32*new_r00)))),IkReal(((((-1.0)*gconst32*new_r10))+((gconst32*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 17873 | if(!x1306.valid){ |
| 17874 | continue; |
| 17875 | } |
| 17876 | CheckValue<IkReal> x1307=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 17877 | if(!x1307.valid){ |
| 17878 | continue; |
| 17879 | } |
| 17880 | j0array[0]=((-1.5707963267949)+(x1306.value)+(((1.5707963267949)*(x1307.value)))); |
| 17881 | sj0array[0]=IKsin(j0array[0]); |
| 17882 | cj0array[0]=IKcos(j0array[0]); |
| 17883 | if( j0array[0] > IKPI ) |
| 17884 | { |
| 17885 | j0array[0]-=IK2PI; |
| 17886 | } |
| 17887 | else if( j0array[0] < -IKPI ) |
| 17888 | { j0array[0]+=IK2PI; |
| 17889 | } |
| 17890 | j0valid[0] = true; |
| 17891 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17892 | { |
| 17893 | if( !j0valid[ij0] ) |
| 17894 | { |
| 17895 | continue; |
| 17896 | } |
| 17897 | _ij0[0] = ij0; _ij0[1] = -1; |
| 17898 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 17899 | { |
| 17900 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 17901 | { |
| 17902 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 17903 | } |
| 17904 | } |
| 17905 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 17906 | { |
| 17907 | IkReal evalcond[8]; |
| 17908 | IkReal x1308=IKsin(j0); |
| 17909 | IkReal x1309=IKcos(j0); |
| 17910 | IkReal x1310=((1.0)*gconst32); |
| 17911 | IkReal x1311=(gconst33*x1308); |
| 17912 | IkReal x1312=((1.0)*x1309); |
| 17913 | IkReal x1313=(((gconst33*x1312))+((x1308*x1310))); |
| 17914 | evalcond[0]=(gconst32+((new_r11*x1309))+(((-1.0)*new_r01*x1308))); |
| 17915 | evalcond[1]=((((-1.0)*new_r10*x1312))+gconst33+((new_r00*x1308))); |
| 17916 | evalcond[2]=(x1311+new_r00+(((-1.0)*x1309*x1310))); |
| 17917 | evalcond[3]=((((-1.0)*x1311))+((gconst32*x1309))+new_r11); |
| 17918 | evalcond[4]=((((-1.0)*x1310))+((new_r10*x1308))+((new_r00*x1309))); |
| 17919 | evalcond[5]=(((new_r11*x1308))+(((-1.0)*gconst33))+((new_r01*x1309))); |
| 17920 | evalcond[6]=((((-1.0)*x1313))+new_r01); |
| 17921 | evalcond[7]=((((-1.0)*x1313))+new_r10); |
| 17922 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 17923 | { |
| 17924 | continue; |
| 17925 | } |
| 17926 | } |
| 17927 | |
| 17928 | { |
| 17929 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 17930 | vinfos[0].jointtype = 1; |
| 17931 | vinfos[0].foffset = j0; |
| 17932 | vinfos[0].indices[0] = _ij0[0]; |
| 17933 | vinfos[0].indices[1] = _ij0[1]; |
| 17934 | vinfos[0].maxsolutions = _nj0; |
| 17935 | vinfos[1].jointtype = 1; |
| 17936 | vinfos[1].foffset = j1; |
| 17937 | vinfos[1].indices[0] = _ij1[0]; |
| 17938 | vinfos[1].indices[1] = _ij1[1]; |
| 17939 | vinfos[1].maxsolutions = _nj1; |
| 17940 | vinfos[2].jointtype = 1; |
| 17941 | vinfos[2].foffset = j2; |
| 17942 | vinfos[2].indices[0] = _ij2[0]; |
| 17943 | vinfos[2].indices[1] = _ij2[1]; |
| 17944 | vinfos[2].maxsolutions = _nj2; |
| 17945 | vinfos[3].jointtype = 1; |
| 17946 | vinfos[3].foffset = j3; |
| 17947 | vinfos[3].indices[0] = _ij3[0]; |
| 17948 | vinfos[3].indices[1] = _ij3[1]; |
| 17949 | vinfos[3].maxsolutions = _nj3; |
| 17950 | vinfos[4].jointtype = 1; |
| 17951 | vinfos[4].foffset = j4; |
| 17952 | vinfos[4].indices[0] = _ij4[0]; |
| 17953 | vinfos[4].indices[1] = _ij4[1]; |
| 17954 | vinfos[4].maxsolutions = _nj4; |
| 17955 | vinfos[5].jointtype = 1; |
| 17956 | vinfos[5].foffset = j5; |
| 17957 | vinfos[5].indices[0] = _ij5[0]; |
| 17958 | vinfos[5].indices[1] = _ij5[1]; |
| 17959 | vinfos[5].maxsolutions = _nj5; |
| 17960 | std::vector<int> vfree(0); |
| 17961 | solutions.AddSolution(vinfos,vfree); |
| 17962 | } |
| 17963 | } |
| 17964 | } |
| 17965 | |
| 17966 | } |
| 17967 | |
| 17968 | } |
| 17969 | |
| 17970 | } else |
| 17971 | { |
| 17972 | { |
| 17973 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 17974 | bool j0valid[1]={false}; |
| 17975 | _nj0 = 1; |
| 17976 | CheckValue<IkReal> x1314=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst33*new_r11))+((gconst32*new_r01)))),-1); |
| 17977 | if(!x1314.valid){ |
| 17978 | continue; |
| 17979 | } |
| 17980 | CheckValue<IkReal> x1315 = IKatan2WithCheck(IkReal((((new_r00*new_r11))+(gconst32*gconst32))),IkReal((((gconst32*gconst33))+((new_r00*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 17981 | if(!x1315.valid){ |
| 17982 | continue; |
| 17983 | } |
| 17984 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1314.value)))+(x1315.value)); |
| 17985 | sj0array[0]=IKsin(j0array[0]); |
| 17986 | cj0array[0]=IKcos(j0array[0]); |
| 17987 | if( j0array[0] > IKPI ) |
| 17988 | { |
| 17989 | j0array[0]-=IK2PI; |
| 17990 | } |
| 17991 | else if( j0array[0] < -IKPI ) |
| 17992 | { j0array[0]+=IK2PI; |
| 17993 | } |
| 17994 | j0valid[0] = true; |
| 17995 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 17996 | { |
| 17997 | if( !j0valid[ij0] ) |
| 17998 | { |
| 17999 | continue; |
| 18000 | } |
| 18001 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18002 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18003 | { |
| 18004 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18005 | { |
| 18006 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18007 | } |
| 18008 | } |
| 18009 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18010 | { |
| 18011 | IkReal evalcond[8]; |
| 18012 | IkReal x1316=IKsin(j0); |
| 18013 | IkReal x1317=IKcos(j0); |
| 18014 | IkReal x1318=((1.0)*gconst32); |
| 18015 | IkReal x1319=(gconst33*x1316); |
| 18016 | IkReal x1320=((1.0)*x1317); |
| 18017 | IkReal x1321=(((gconst33*x1320))+((x1316*x1318))); |
| 18018 | evalcond[0]=(gconst32+((new_r11*x1317))+(((-1.0)*new_r01*x1316))); |
| 18019 | evalcond[1]=(((new_r00*x1316))+(((-1.0)*new_r10*x1320))+gconst33); |
| 18020 | evalcond[2]=(x1319+(((-1.0)*x1317*x1318))+new_r00); |
| 18021 | evalcond[3]=((((-1.0)*x1319))+((gconst32*x1317))+new_r11); |
| 18022 | evalcond[4]=(((new_r00*x1317))+(((-1.0)*x1318))+((new_r10*x1316))); |
| 18023 | evalcond[5]=(((new_r01*x1317))+((new_r11*x1316))+(((-1.0)*gconst33))); |
| 18024 | evalcond[6]=((((-1.0)*x1321))+new_r01); |
| 18025 | evalcond[7]=((((-1.0)*x1321))+new_r10); |
| 18026 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 18027 | { |
| 18028 | continue; |
| 18029 | } |
| 18030 | } |
| 18031 | |
| 18032 | { |
| 18033 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18034 | vinfos[0].jointtype = 1; |
| 18035 | vinfos[0].foffset = j0; |
| 18036 | vinfos[0].indices[0] = _ij0[0]; |
| 18037 | vinfos[0].indices[1] = _ij0[1]; |
| 18038 | vinfos[0].maxsolutions = _nj0; |
| 18039 | vinfos[1].jointtype = 1; |
| 18040 | vinfos[1].foffset = j1; |
| 18041 | vinfos[1].indices[0] = _ij1[0]; |
| 18042 | vinfos[1].indices[1] = _ij1[1]; |
| 18043 | vinfos[1].maxsolutions = _nj1; |
| 18044 | vinfos[2].jointtype = 1; |
| 18045 | vinfos[2].foffset = j2; |
| 18046 | vinfos[2].indices[0] = _ij2[0]; |
| 18047 | vinfos[2].indices[1] = _ij2[1]; |
| 18048 | vinfos[2].maxsolutions = _nj2; |
| 18049 | vinfos[3].jointtype = 1; |
| 18050 | vinfos[3].foffset = j3; |
| 18051 | vinfos[3].indices[0] = _ij3[0]; |
| 18052 | vinfos[3].indices[1] = _ij3[1]; |
| 18053 | vinfos[3].maxsolutions = _nj3; |
| 18054 | vinfos[4].jointtype = 1; |
| 18055 | vinfos[4].foffset = j4; |
| 18056 | vinfos[4].indices[0] = _ij4[0]; |
| 18057 | vinfos[4].indices[1] = _ij4[1]; |
| 18058 | vinfos[4].maxsolutions = _nj4; |
| 18059 | vinfos[5].jointtype = 1; |
| 18060 | vinfos[5].foffset = j5; |
| 18061 | vinfos[5].indices[0] = _ij5[0]; |
| 18062 | vinfos[5].indices[1] = _ij5[1]; |
| 18063 | vinfos[5].maxsolutions = _nj5; |
| 18064 | std::vector<int> vfree(0); |
| 18065 | solutions.AddSolution(vinfos,vfree); |
| 18066 | } |
| 18067 | } |
| 18068 | } |
| 18069 | |
| 18070 | } |
| 18071 | |
| 18072 | } |
| 18073 | |
| 18074 | } else |
| 18075 | { |
| 18076 | { |
| 18077 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18078 | bool j0valid[1]={false}; |
| 18079 | _nj0 = 1; |
| 18080 | CheckValue<IkReal> x1322=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| 18081 | if(!x1322.valid){ |
| 18082 | continue; |
| 18083 | } |
| 18084 | CheckValue<IkReal> x1323 = IKatan2WithCheck(IkReal((((gconst33*new_r11))+((gconst32*new_r10)))),IkReal((((gconst33*new_r01))+((gconst32*new_r00)))),IKFAST_ATAN2_MAGTHRESH); |
| 18085 | if(!x1323.valid){ |
| 18086 | continue; |
| 18087 | } |
| 18088 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1322.value)))+(x1323.value)); |
| 18089 | sj0array[0]=IKsin(j0array[0]); |
| 18090 | cj0array[0]=IKcos(j0array[0]); |
| 18091 | if( j0array[0] > IKPI ) |
| 18092 | { |
| 18093 | j0array[0]-=IK2PI; |
| 18094 | } |
| 18095 | else if( j0array[0] < -IKPI ) |
| 18096 | { j0array[0]+=IK2PI; |
| 18097 | } |
| 18098 | j0valid[0] = true; |
| 18099 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18100 | { |
| 18101 | if( !j0valid[ij0] ) |
| 18102 | { |
| 18103 | continue; |
| 18104 | } |
| 18105 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18106 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18107 | { |
| 18108 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18109 | { |
| 18110 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18111 | } |
| 18112 | } |
| 18113 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18114 | { |
| 18115 | IkReal evalcond[8]; |
| 18116 | IkReal x1324=IKsin(j0); |
| 18117 | IkReal x1325=IKcos(j0); |
| 18118 | IkReal x1326=((1.0)*gconst32); |
| 18119 | IkReal x1327=(gconst33*x1324); |
| 18120 | IkReal x1328=((1.0)*x1325); |
| 18121 | IkReal x1329=(((gconst33*x1328))+((x1324*x1326))); |
| 18122 | evalcond[0]=(gconst32+((new_r11*x1325))+(((-1.0)*new_r01*x1324))); |
| 18123 | evalcond[1]=(((new_r00*x1324))+(((-1.0)*new_r10*x1328))+gconst33); |
| 18124 | evalcond[2]=(x1327+(((-1.0)*x1325*x1326))+new_r00); |
| 18125 | evalcond[3]=((((-1.0)*x1327))+((gconst32*x1325))+new_r11); |
| 18126 | evalcond[4]=(((new_r00*x1325))+(((-1.0)*x1326))+((new_r10*x1324))); |
| 18127 | evalcond[5]=(((new_r01*x1325))+((new_r11*x1324))+(((-1.0)*gconst33))); |
| 18128 | evalcond[6]=((((-1.0)*x1329))+new_r01); |
| 18129 | evalcond[7]=((((-1.0)*x1329))+new_r10); |
| 18130 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 18131 | { |
| 18132 | continue; |
| 18133 | } |
| 18134 | } |
| 18135 | |
| 18136 | { |
| 18137 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18138 | vinfos[0].jointtype = 1; |
| 18139 | vinfos[0].foffset = j0; |
| 18140 | vinfos[0].indices[0] = _ij0[0]; |
| 18141 | vinfos[0].indices[1] = _ij0[1]; |
| 18142 | vinfos[0].maxsolutions = _nj0; |
| 18143 | vinfos[1].jointtype = 1; |
| 18144 | vinfos[1].foffset = j1; |
| 18145 | vinfos[1].indices[0] = _ij1[0]; |
| 18146 | vinfos[1].indices[1] = _ij1[1]; |
| 18147 | vinfos[1].maxsolutions = _nj1; |
| 18148 | vinfos[2].jointtype = 1; |
| 18149 | vinfos[2].foffset = j2; |
| 18150 | vinfos[2].indices[0] = _ij2[0]; |
| 18151 | vinfos[2].indices[1] = _ij2[1]; |
| 18152 | vinfos[2].maxsolutions = _nj2; |
| 18153 | vinfos[3].jointtype = 1; |
| 18154 | vinfos[3].foffset = j3; |
| 18155 | vinfos[3].indices[0] = _ij3[0]; |
| 18156 | vinfos[3].indices[1] = _ij3[1]; |
| 18157 | vinfos[3].maxsolutions = _nj3; |
| 18158 | vinfos[4].jointtype = 1; |
| 18159 | vinfos[4].foffset = j4; |
| 18160 | vinfos[4].indices[0] = _ij4[0]; |
| 18161 | vinfos[4].indices[1] = _ij4[1]; |
| 18162 | vinfos[4].maxsolutions = _nj4; |
| 18163 | vinfos[5].jointtype = 1; |
| 18164 | vinfos[5].foffset = j5; |
| 18165 | vinfos[5].indices[0] = _ij5[0]; |
| 18166 | vinfos[5].indices[1] = _ij5[1]; |
| 18167 | vinfos[5].maxsolutions = _nj5; |
| 18168 | std::vector<int> vfree(0); |
| 18169 | solutions.AddSolution(vinfos,vfree); |
| 18170 | } |
| 18171 | } |
| 18172 | } |
| 18173 | |
| 18174 | } |
| 18175 | |
| 18176 | } |
| 18177 | |
| 18178 | } |
| 18179 | } while(0); |
| 18180 | if( bgotonextstatement ) |
| 18181 | { |
| 18182 | bool bgotonextstatement = true; |
| 18183 | do |
| 18184 | { |
| 18185 | IkReal x1332 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| 18186 | if(IKabs(x1332)==0){ |
| 18187 | continue; |
| 18188 | } |
| 18189 | IkReal x1330=pow(x1332,-0.5); |
| 18190 | IkReal x1331=((-1.0)*x1330); |
| 18191 | CheckValue<IkReal> x1333 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18192 | if(!x1333.valid){ |
| 18193 | continue; |
| 18194 | } |
| 18195 | IkReal gconst34=((-1.0)*(x1333.value)); |
| 18196 | IkReal gconst35=(new_r11*x1331); |
| 18197 | IkReal gconst36=(new_r01*x1331); |
| 18198 | CheckValue<IkReal> x1334 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18199 | if(!x1334.valid){ |
| 18200 | continue; |
| 18201 | } |
| 18202 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((x1334.value)+j2)))), 6.28318530717959))); |
| 18203 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 18204 | { |
| 18205 | bgotonextstatement=false; |
| 18206 | { |
| 18207 | IkReal j0eval[3]; |
| 18208 | CheckValue<IkReal> x1338 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18209 | if(!x1338.valid){ |
| 18210 | continue; |
| 18211 | } |
| 18212 | IkReal x1335=((-1.0)*(x1338.value)); |
| 18213 | IkReal x1336=x1330; |
| 18214 | IkReal x1337=((-1.0)*x1336); |
| 18215 | sj1=-1.0; |
| 18216 | cj1=0; |
| 18217 | j1=-1.5707963267949; |
| 18218 | sj2=gconst35; |
| 18219 | cj2=gconst36; |
| 18220 | j2=x1335; |
| 18221 | IkReal gconst34=x1335; |
| 18222 | IkReal gconst35=(new_r11*x1337); |
| 18223 | IkReal gconst36=(new_r01*x1337); |
| 18224 | IkReal x1339=new_r01*new_r01; |
| 18225 | IkReal x1340=(new_r00*new_r11); |
| 18226 | IkReal x1341=(((new_r01*new_r10))+(((-1.0)*x1340))); |
| 18227 | IkReal x1342=x1330; |
| 18228 | IkReal x1343=((1.0)*new_r11*x1342); |
| 18229 | j0eval[0]=x1341; |
| 18230 | j0eval[1]=IKsign(x1341); |
| 18231 | j0eval[2]=((IKabs(((((-1.0)*new_r10*x1343))+(((-1.0)*new_r01*x1343)))))+(IKabs((((x1339*x1342))+((x1340*x1342)))))); |
| 18232 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 18233 | { |
| 18234 | { |
| 18235 | IkReal j0eval[3]; |
| 18236 | CheckValue<IkReal> x1347 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18237 | if(!x1347.valid){ |
| 18238 | continue; |
| 18239 | } |
| 18240 | IkReal x1344=((-1.0)*(x1347.value)); |
| 18241 | IkReal x1345=x1330; |
| 18242 | IkReal x1346=((-1.0)*x1345); |
| 18243 | sj1=-1.0; |
| 18244 | cj1=0; |
| 18245 | j1=-1.5707963267949; |
| 18246 | sj2=gconst35; |
| 18247 | cj2=gconst36; |
| 18248 | j2=x1344; |
| 18249 | IkReal gconst34=x1344; |
| 18250 | IkReal gconst35=(new_r11*x1346); |
| 18251 | IkReal gconst36=(new_r01*x1346); |
| 18252 | IkReal x1348=new_r11*new_r11; |
| 18253 | IkReal x1349=(((new_r10*new_r11))+((new_r00*new_r01))); |
| 18254 | IkReal x1350=x1330; |
| 18255 | IkReal x1351=(new_r11*x1350); |
| 18256 | j0eval[0]=x1349; |
| 18257 | j0eval[1]=IKsign(x1349); |
| 18258 | j0eval[2]=((IKabs((((new_r10*x1351))+(((-1.0)*new_r01*x1351)))))+(IKabs(((((-1.0)*x1348*x1350))+(((-1.0)*new_r00*x1351)))))); |
| 18259 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 18260 | { |
| 18261 | { |
| 18262 | IkReal j0eval[1]; |
| 18263 | CheckValue<IkReal> x1355 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18264 | if(!x1355.valid){ |
| 18265 | continue; |
| 18266 | } |
| 18267 | IkReal x1352=((-1.0)*(x1355.value)); |
| 18268 | IkReal x1353=x1330; |
| 18269 | IkReal x1354=((-1.0)*x1353); |
| 18270 | sj1=-1.0; |
| 18271 | cj1=0; |
| 18272 | j1=-1.5707963267949; |
| 18273 | sj2=gconst35; |
| 18274 | cj2=gconst36; |
| 18275 | j2=x1352; |
| 18276 | IkReal gconst34=x1352; |
| 18277 | IkReal gconst35=(new_r11*x1354); |
| 18278 | IkReal gconst36=(new_r01*x1354); |
| 18279 | IkReal x1356=new_r01*new_r01; |
| 18280 | CheckValue<IkReal> x1359=IKPowWithIntegerCheck((x1356+(new_r11*new_r11)),-1); |
| 18281 | if(!x1359.valid){ |
| 18282 | continue; |
| 18283 | } |
| 18284 | IkReal x1357=x1359.value; |
| 18285 | IkReal x1358=((1.0)*x1357); |
| 18286 | j0eval[0]=((IKabs(((((-1.0)*x1356*x1358))+(new_r00*new_r00))))+(IKabs((((new_r00*new_r10))+(((-1.0)*new_r01*new_r11*x1358)))))); |
| 18287 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 18288 | { |
| 18289 | { |
| 18290 | IkReal evalcond[2]; |
| 18291 | bool bgotonextstatement = true; |
| 18292 | do |
| 18293 | { |
| 18294 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 18295 | evalcond[1]=gconst36; |
| 18296 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 18297 | { |
| 18298 | bgotonextstatement=false; |
| 18299 | { |
| 18300 | IkReal j0eval[3]; |
| 18301 | IkReal x1360=((-1.0)*new_r01); |
| 18302 | CheckValue<IkReal> x1362 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1360),IKFAST_ATAN2_MAGTHRESH); |
| 18303 | if(!x1362.valid){ |
| 18304 | continue; |
| 18305 | } |
| 18306 | IkReal x1361=((-1.0)*(x1362.value)); |
| 18307 | sj1=-1.0; |
| 18308 | cj1=0; |
| 18309 | j1=-1.5707963267949; |
| 18310 | sj2=gconst35; |
| 18311 | cj2=gconst36; |
| 18312 | j2=x1361; |
| 18313 | new_r00=0; |
| 18314 | new_r10=0; |
| 18315 | new_r21=0; |
| 18316 | new_r22=0; |
| 18317 | IkReal gconst34=x1361; |
| 18318 | IkReal gconst35=((-1.0)*new_r11); |
| 18319 | IkReal gconst36=x1360; |
| 18320 | j0eval[0]=-1.0; |
| 18321 | j0eval[1]=-1.0; |
| 18322 | j0eval[2]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| 18323 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 18324 | { |
| 18325 | { |
| 18326 | IkReal j0eval[3]; |
| 18327 | IkReal x1363=((-1.0)*new_r01); |
| 18328 | CheckValue<IkReal> x1365 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1363),IKFAST_ATAN2_MAGTHRESH); |
| 18329 | if(!x1365.valid){ |
| 18330 | continue; |
| 18331 | } |
| 18332 | IkReal x1364=((-1.0)*(x1365.value)); |
| 18333 | sj1=-1.0; |
| 18334 | cj1=0; |
| 18335 | j1=-1.5707963267949; |
| 18336 | sj2=gconst35; |
| 18337 | cj2=gconst36; |
| 18338 | j2=x1364; |
| 18339 | new_r00=0; |
| 18340 | new_r10=0; |
| 18341 | new_r21=0; |
| 18342 | new_r22=0; |
| 18343 | IkReal gconst34=x1364; |
| 18344 | IkReal gconst35=((-1.0)*new_r11); |
| 18345 | IkReal gconst36=x1363; |
| 18346 | j0eval[0]=1.0; |
| 18347 | j0eval[1]=((IKabs(new_r01*new_r01))+(IKabs((new_r01*new_r11)))); |
| 18348 | j0eval[2]=1.0; |
| 18349 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 18350 | { |
| 18351 | { |
| 18352 | IkReal j0eval[3]; |
| 18353 | IkReal x1366=((-1.0)*new_r01); |
| 18354 | CheckValue<IkReal> x1368 = IKatan2WithCheck(IkReal(new_r11),IkReal(x1366),IKFAST_ATAN2_MAGTHRESH); |
| 18355 | if(!x1368.valid){ |
| 18356 | continue; |
| 18357 | } |
| 18358 | IkReal x1367=((-1.0)*(x1368.value)); |
| 18359 | sj1=-1.0; |
| 18360 | cj1=0; |
| 18361 | j1=-1.5707963267949; |
| 18362 | sj2=gconst35; |
| 18363 | cj2=gconst36; |
| 18364 | j2=x1367; |
| 18365 | new_r00=0; |
| 18366 | new_r10=0; |
| 18367 | new_r21=0; |
| 18368 | new_r22=0; |
| 18369 | IkReal gconst34=x1367; |
| 18370 | IkReal gconst35=((-1.0)*new_r11); |
| 18371 | IkReal gconst36=x1366; |
| 18372 | j0eval[0]=1.0; |
| 18373 | j0eval[1]=1.0; |
| 18374 | j0eval[2]=((IKabs((new_r01*new_r11)))+(IKabs(((1.0)+(((-1.0)*(new_r01*new_r01))))))); |
| 18375 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 18376 | { |
| 18377 | continue; // 3 cases reached |
| 18378 | |
| 18379 | } else |
| 18380 | { |
| 18381 | { |
| 18382 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18383 | bool j0valid[1]={false}; |
| 18384 | _nj0 = 1; |
| 18385 | CheckValue<IkReal> x1369=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1); |
| 18386 | if(!x1369.valid){ |
| 18387 | continue; |
| 18388 | } |
| 18389 | CheckValue<IkReal> x1370 = IKatan2WithCheck(IkReal((gconst36*new_r11)),IkReal(((-1.0)*gconst35*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 18390 | if(!x1370.valid){ |
| 18391 | continue; |
| 18392 | } |
| 18393 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1369.value)))+(x1370.value)); |
| 18394 | sj0array[0]=IKsin(j0array[0]); |
| 18395 | cj0array[0]=IKcos(j0array[0]); |
| 18396 | if( j0array[0] > IKPI ) |
| 18397 | { |
| 18398 | j0array[0]-=IK2PI; |
| 18399 | } |
| 18400 | else if( j0array[0] < -IKPI ) |
| 18401 | { j0array[0]+=IK2PI; |
| 18402 | } |
| 18403 | j0valid[0] = true; |
| 18404 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18405 | { |
| 18406 | if( !j0valid[ij0] ) |
| 18407 | { |
| 18408 | continue; |
| 18409 | } |
| 18410 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18411 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18412 | { |
| 18413 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18414 | { |
| 18415 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18416 | } |
| 18417 | } |
| 18418 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18419 | { |
| 18420 | IkReal evalcond[6]; |
| 18421 | IkReal x1371=IKcos(j0); |
| 18422 | IkReal x1372=IKsin(j0); |
| 18423 | IkReal x1373=((1.0)*gconst36); |
| 18424 | IkReal x1374=(gconst35*x1371); |
| 18425 | IkReal x1375=(gconst36*x1372); |
| 18426 | IkReal x1376=((1.0)*x1372); |
| 18427 | IkReal x1377=(((gconst35*x1376))+((x1371*x1373))); |
| 18428 | evalcond[0]=(x1375+(((-1.0)*x1374))); |
| 18429 | evalcond[1]=((((-1.0)*new_r01*x1376))+gconst35+((new_r11*x1371))); |
| 18430 | evalcond[2]=(x1374+(((-1.0)*x1372*x1373))+new_r11); |
| 18431 | evalcond[3]=((-1.0)*x1377); |
| 18432 | evalcond[4]=((((-1.0)*x1373))+((new_r11*x1372))+((new_r01*x1371))); |
| 18433 | evalcond[5]=((((-1.0)*x1377))+new_r01); |
| 18434 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 18435 | { |
| 18436 | continue; |
| 18437 | } |
| 18438 | } |
| 18439 | |
| 18440 | { |
| 18441 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18442 | vinfos[0].jointtype = 1; |
| 18443 | vinfos[0].foffset = j0; |
| 18444 | vinfos[0].indices[0] = _ij0[0]; |
| 18445 | vinfos[0].indices[1] = _ij0[1]; |
| 18446 | vinfos[0].maxsolutions = _nj0; |
| 18447 | vinfos[1].jointtype = 1; |
| 18448 | vinfos[1].foffset = j1; |
| 18449 | vinfos[1].indices[0] = _ij1[0]; |
| 18450 | vinfos[1].indices[1] = _ij1[1]; |
| 18451 | vinfos[1].maxsolutions = _nj1; |
| 18452 | vinfos[2].jointtype = 1; |
| 18453 | vinfos[2].foffset = j2; |
| 18454 | vinfos[2].indices[0] = _ij2[0]; |
| 18455 | vinfos[2].indices[1] = _ij2[1]; |
| 18456 | vinfos[2].maxsolutions = _nj2; |
| 18457 | vinfos[3].jointtype = 1; |
| 18458 | vinfos[3].foffset = j3; |
| 18459 | vinfos[3].indices[0] = _ij3[0]; |
| 18460 | vinfos[3].indices[1] = _ij3[1]; |
| 18461 | vinfos[3].maxsolutions = _nj3; |
| 18462 | vinfos[4].jointtype = 1; |
| 18463 | vinfos[4].foffset = j4; |
| 18464 | vinfos[4].indices[0] = _ij4[0]; |
| 18465 | vinfos[4].indices[1] = _ij4[1]; |
| 18466 | vinfos[4].maxsolutions = _nj4; |
| 18467 | vinfos[5].jointtype = 1; |
| 18468 | vinfos[5].foffset = j5; |
| 18469 | vinfos[5].indices[0] = _ij5[0]; |
| 18470 | vinfos[5].indices[1] = _ij5[1]; |
| 18471 | vinfos[5].maxsolutions = _nj5; |
| 18472 | std::vector<int> vfree(0); |
| 18473 | solutions.AddSolution(vinfos,vfree); |
| 18474 | } |
| 18475 | } |
| 18476 | } |
| 18477 | |
| 18478 | } |
| 18479 | |
| 18480 | } |
| 18481 | |
| 18482 | } else |
| 18483 | { |
| 18484 | { |
| 18485 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18486 | bool j0valid[1]={false}; |
| 18487 | _nj0 = 1; |
| 18488 | CheckValue<IkReal> x1378 = IKatan2WithCheck(IkReal((gconst35*new_r01)),IkReal((gconst36*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 18489 | if(!x1378.valid){ |
| 18490 | continue; |
| 18491 | } |
| 18492 | CheckValue<IkReal> x1379=IKPowWithIntegerCheck(IKsign(((gconst35*gconst35)+(gconst36*gconst36))),-1); |
| 18493 | if(!x1379.valid){ |
| 18494 | continue; |
| 18495 | } |
| 18496 | j0array[0]=((-1.5707963267949)+(x1378.value)+(((1.5707963267949)*(x1379.value)))); |
| 18497 | sj0array[0]=IKsin(j0array[0]); |
| 18498 | cj0array[0]=IKcos(j0array[0]); |
| 18499 | if( j0array[0] > IKPI ) |
| 18500 | { |
| 18501 | j0array[0]-=IK2PI; |
| 18502 | } |
| 18503 | else if( j0array[0] < -IKPI ) |
| 18504 | { j0array[0]+=IK2PI; |
| 18505 | } |
| 18506 | j0valid[0] = true; |
| 18507 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18508 | { |
| 18509 | if( !j0valid[ij0] ) |
| 18510 | { |
| 18511 | continue; |
| 18512 | } |
| 18513 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18514 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18515 | { |
| 18516 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18517 | { |
| 18518 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18519 | } |
| 18520 | } |
| 18521 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18522 | { |
| 18523 | IkReal evalcond[6]; |
| 18524 | IkReal x1380=IKcos(j0); |
| 18525 | IkReal x1381=IKsin(j0); |
| 18526 | IkReal x1382=((1.0)*gconst36); |
| 18527 | IkReal x1383=(gconst35*x1380); |
| 18528 | IkReal x1384=(gconst36*x1381); |
| 18529 | IkReal x1385=((1.0)*x1381); |
| 18530 | IkReal x1386=(((gconst35*x1385))+((x1380*x1382))); |
| 18531 | evalcond[0]=(x1384+(((-1.0)*x1383))); |
| 18532 | evalcond[1]=(((new_r11*x1380))+gconst35+(((-1.0)*new_r01*x1385))); |
| 18533 | evalcond[2]=(x1383+(((-1.0)*x1381*x1382))+new_r11); |
| 18534 | evalcond[3]=((-1.0)*x1386); |
| 18535 | evalcond[4]=((((-1.0)*x1382))+((new_r11*x1381))+((new_r01*x1380))); |
| 18536 | evalcond[5]=((((-1.0)*x1386))+new_r01); |
| 18537 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 18538 | { |
| 18539 | continue; |
| 18540 | } |
| 18541 | } |
| 18542 | |
| 18543 | { |
| 18544 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18545 | vinfos[0].jointtype = 1; |
| 18546 | vinfos[0].foffset = j0; |
| 18547 | vinfos[0].indices[0] = _ij0[0]; |
| 18548 | vinfos[0].indices[1] = _ij0[1]; |
| 18549 | vinfos[0].maxsolutions = _nj0; |
| 18550 | vinfos[1].jointtype = 1; |
| 18551 | vinfos[1].foffset = j1; |
| 18552 | vinfos[1].indices[0] = _ij1[0]; |
| 18553 | vinfos[1].indices[1] = _ij1[1]; |
| 18554 | vinfos[1].maxsolutions = _nj1; |
| 18555 | vinfos[2].jointtype = 1; |
| 18556 | vinfos[2].foffset = j2; |
| 18557 | vinfos[2].indices[0] = _ij2[0]; |
| 18558 | vinfos[2].indices[1] = _ij2[1]; |
| 18559 | vinfos[2].maxsolutions = _nj2; |
| 18560 | vinfos[3].jointtype = 1; |
| 18561 | vinfos[3].foffset = j3; |
| 18562 | vinfos[3].indices[0] = _ij3[0]; |
| 18563 | vinfos[3].indices[1] = _ij3[1]; |
| 18564 | vinfos[3].maxsolutions = _nj3; |
| 18565 | vinfos[4].jointtype = 1; |
| 18566 | vinfos[4].foffset = j4; |
| 18567 | vinfos[4].indices[0] = _ij4[0]; |
| 18568 | vinfos[4].indices[1] = _ij4[1]; |
| 18569 | vinfos[4].maxsolutions = _nj4; |
| 18570 | vinfos[5].jointtype = 1; |
| 18571 | vinfos[5].foffset = j5; |
| 18572 | vinfos[5].indices[0] = _ij5[0]; |
| 18573 | vinfos[5].indices[1] = _ij5[1]; |
| 18574 | vinfos[5].maxsolutions = _nj5; |
| 18575 | std::vector<int> vfree(0); |
| 18576 | solutions.AddSolution(vinfos,vfree); |
| 18577 | } |
| 18578 | } |
| 18579 | } |
| 18580 | |
| 18581 | } |
| 18582 | |
| 18583 | } |
| 18584 | |
| 18585 | } else |
| 18586 | { |
| 18587 | { |
| 18588 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18589 | bool j0valid[1]={false}; |
| 18590 | _nj0 = 1; |
| 18591 | CheckValue<IkReal> x1387=IKPowWithIntegerCheck(IKsign((((gconst36*new_r01))+((gconst35*new_r11)))),-1); |
| 18592 | if(!x1387.valid){ |
| 18593 | continue; |
| 18594 | } |
| 18595 | CheckValue<IkReal> x1388 = IKatan2WithCheck(IkReal((gconst35*gconst36)),IkReal(gconst36*gconst36),IKFAST_ATAN2_MAGTHRESH); |
| 18596 | if(!x1388.valid){ |
| 18597 | continue; |
| 18598 | } |
| 18599 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1387.value)))+(x1388.value)); |
| 18600 | sj0array[0]=IKsin(j0array[0]); |
| 18601 | cj0array[0]=IKcos(j0array[0]); |
| 18602 | if( j0array[0] > IKPI ) |
| 18603 | { |
| 18604 | j0array[0]-=IK2PI; |
| 18605 | } |
| 18606 | else if( j0array[0] < -IKPI ) |
| 18607 | { j0array[0]+=IK2PI; |
| 18608 | } |
| 18609 | j0valid[0] = true; |
| 18610 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18611 | { |
| 18612 | if( !j0valid[ij0] ) |
| 18613 | { |
| 18614 | continue; |
| 18615 | } |
| 18616 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18617 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18618 | { |
| 18619 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18620 | { |
| 18621 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18622 | } |
| 18623 | } |
| 18624 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18625 | { |
| 18626 | IkReal evalcond[6]; |
| 18627 | IkReal x1389=IKcos(j0); |
| 18628 | IkReal x1390=IKsin(j0); |
| 18629 | IkReal x1391=((1.0)*gconst36); |
| 18630 | IkReal x1392=(gconst35*x1389); |
| 18631 | IkReal x1393=(gconst36*x1390); |
| 18632 | IkReal x1394=((1.0)*x1390); |
| 18633 | IkReal x1395=(((gconst35*x1394))+((x1389*x1391))); |
| 18634 | evalcond[0]=(x1393+(((-1.0)*x1392))); |
| 18635 | evalcond[1]=(((new_r11*x1389))+gconst35+(((-1.0)*new_r01*x1394))); |
| 18636 | evalcond[2]=(x1392+(((-1.0)*x1390*x1391))+new_r11); |
| 18637 | evalcond[3]=((-1.0)*x1395); |
| 18638 | evalcond[4]=(((new_r11*x1390))+((new_r01*x1389))+(((-1.0)*x1391))); |
| 18639 | evalcond[5]=(new_r01+(((-1.0)*x1395))); |
| 18640 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 18641 | { |
| 18642 | continue; |
| 18643 | } |
| 18644 | } |
| 18645 | |
| 18646 | { |
| 18647 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18648 | vinfos[0].jointtype = 1; |
| 18649 | vinfos[0].foffset = j0; |
| 18650 | vinfos[0].indices[0] = _ij0[0]; |
| 18651 | vinfos[0].indices[1] = _ij0[1]; |
| 18652 | vinfos[0].maxsolutions = _nj0; |
| 18653 | vinfos[1].jointtype = 1; |
| 18654 | vinfos[1].foffset = j1; |
| 18655 | vinfos[1].indices[0] = _ij1[0]; |
| 18656 | vinfos[1].indices[1] = _ij1[1]; |
| 18657 | vinfos[1].maxsolutions = _nj1; |
| 18658 | vinfos[2].jointtype = 1; |
| 18659 | vinfos[2].foffset = j2; |
| 18660 | vinfos[2].indices[0] = _ij2[0]; |
| 18661 | vinfos[2].indices[1] = _ij2[1]; |
| 18662 | vinfos[2].maxsolutions = _nj2; |
| 18663 | vinfos[3].jointtype = 1; |
| 18664 | vinfos[3].foffset = j3; |
| 18665 | vinfos[3].indices[0] = _ij3[0]; |
| 18666 | vinfos[3].indices[1] = _ij3[1]; |
| 18667 | vinfos[3].maxsolutions = _nj3; |
| 18668 | vinfos[4].jointtype = 1; |
| 18669 | vinfos[4].foffset = j4; |
| 18670 | vinfos[4].indices[0] = _ij4[0]; |
| 18671 | vinfos[4].indices[1] = _ij4[1]; |
| 18672 | vinfos[4].maxsolutions = _nj4; |
| 18673 | vinfos[5].jointtype = 1; |
| 18674 | vinfos[5].foffset = j5; |
| 18675 | vinfos[5].indices[0] = _ij5[0]; |
| 18676 | vinfos[5].indices[1] = _ij5[1]; |
| 18677 | vinfos[5].maxsolutions = _nj5; |
| 18678 | std::vector<int> vfree(0); |
| 18679 | solutions.AddSolution(vinfos,vfree); |
| 18680 | } |
| 18681 | } |
| 18682 | } |
| 18683 | |
| 18684 | } |
| 18685 | |
| 18686 | } |
| 18687 | |
| 18688 | } |
| 18689 | } while(0); |
| 18690 | if( bgotonextstatement ) |
| 18691 | { |
| 18692 | bool bgotonextstatement = true; |
| 18693 | do |
| 18694 | { |
| 18695 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 18696 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 18697 | { |
| 18698 | bgotonextstatement=false; |
| 18699 | { |
| 18700 | IkReal j0eval[1]; |
| 18701 | CheckValue<IkReal> x1397 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 18702 | if(!x1397.valid){ |
| 18703 | continue; |
| 18704 | } |
| 18705 | IkReal x1396=((-1.0)*(x1397.value)); |
| 18706 | sj1=-1.0; |
| 18707 | cj1=0; |
| 18708 | j1=-1.5707963267949; |
| 18709 | sj2=gconst35; |
| 18710 | cj2=gconst36; |
| 18711 | j2=x1396; |
| 18712 | new_r00=0; |
| 18713 | new_r01=0; |
| 18714 | new_r12=0; |
| 18715 | new_r22=0; |
| 18716 | IkReal gconst34=x1396; |
| 18717 | IkReal x1398 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 18718 | if(IKabs(x1398)==0){ |
| 18719 | continue; |
| 18720 | } |
| 18721 | IkReal gconst35=((-1.0)*new_r11*(pow(x1398,-0.5))); |
| 18722 | IkReal gconst36=0; |
| 18723 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 18724 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 18725 | { |
| 18726 | { |
| 18727 | IkReal j0eval[1]; |
| 18728 | CheckValue<IkReal> x1400 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 18729 | if(!x1400.valid){ |
| 18730 | continue; |
| 18731 | } |
| 18732 | IkReal x1399=((-1.0)*(x1400.value)); |
| 18733 | sj1=-1.0; |
| 18734 | cj1=0; |
| 18735 | j1=-1.5707963267949; |
| 18736 | sj2=gconst35; |
| 18737 | cj2=gconst36; |
| 18738 | j2=x1399; |
| 18739 | new_r00=0; |
| 18740 | new_r01=0; |
| 18741 | new_r12=0; |
| 18742 | new_r22=0; |
| 18743 | IkReal gconst34=x1399; |
| 18744 | IkReal x1401 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 18745 | if(IKabs(x1401)==0){ |
| 18746 | continue; |
| 18747 | } |
| 18748 | IkReal gconst35=((-1.0)*new_r11*(pow(x1401,-0.5))); |
| 18749 | IkReal gconst36=0; |
| 18750 | j0eval[0]=new_r11; |
| 18751 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 18752 | { |
| 18753 | { |
| 18754 | IkReal j0eval[2]; |
| 18755 | CheckValue<IkReal> x1403 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 18756 | if(!x1403.valid){ |
| 18757 | continue; |
| 18758 | } |
| 18759 | IkReal x1402=((-1.0)*(x1403.value)); |
| 18760 | sj1=-1.0; |
| 18761 | cj1=0; |
| 18762 | j1=-1.5707963267949; |
| 18763 | sj2=gconst35; |
| 18764 | cj2=gconst36; |
| 18765 | j2=x1402; |
| 18766 | new_r00=0; |
| 18767 | new_r01=0; |
| 18768 | new_r12=0; |
| 18769 | new_r22=0; |
| 18770 | IkReal gconst34=x1402; |
| 18771 | IkReal x1404 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 18772 | if(IKabs(x1404)==0){ |
| 18773 | continue; |
| 18774 | } |
| 18775 | IkReal gconst35=((-1.0)*new_r11*(pow(x1404,-0.5))); |
| 18776 | IkReal gconst36=0; |
| 18777 | j0eval[0]=new_r10; |
| 18778 | j0eval[1]=new_r11; |
| 18779 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 18780 | { |
| 18781 | continue; // 3 cases reached |
| 18782 | |
| 18783 | } else |
| 18784 | { |
| 18785 | { |
| 18786 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18787 | bool j0valid[1]={false}; |
| 18788 | _nj0 = 1; |
| 18789 | CheckValue<IkReal> x1405=IKPowWithIntegerCheck(new_r10,-1); |
| 18790 | if(!x1405.valid){ |
| 18791 | continue; |
| 18792 | } |
| 18793 | CheckValue<IkReal> x1406=IKPowWithIntegerCheck(new_r11,-1); |
| 18794 | if(!x1406.valid){ |
| 18795 | continue; |
| 18796 | } |
| 18797 | if( IKabs((gconst35*(x1405.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst35*(x1406.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst35*(x1405.value)))+IKsqr(((-1.0)*gconst35*(x1406.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 18798 | continue; |
| 18799 | j0array[0]=IKatan2((gconst35*(x1405.value)), ((-1.0)*gconst35*(x1406.value))); |
| 18800 | sj0array[0]=IKsin(j0array[0]); |
| 18801 | cj0array[0]=IKcos(j0array[0]); |
| 18802 | if( j0array[0] > IKPI ) |
| 18803 | { |
| 18804 | j0array[0]-=IK2PI; |
| 18805 | } |
| 18806 | else if( j0array[0] < -IKPI ) |
| 18807 | { j0array[0]+=IK2PI; |
| 18808 | } |
| 18809 | j0valid[0] = true; |
| 18810 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18811 | { |
| 18812 | if( !j0valid[ij0] ) |
| 18813 | { |
| 18814 | continue; |
| 18815 | } |
| 18816 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18817 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18818 | { |
| 18819 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18820 | { |
| 18821 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18822 | } |
| 18823 | } |
| 18824 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18825 | { |
| 18826 | IkReal evalcond[8]; |
| 18827 | IkReal x1407=IKcos(j0); |
| 18828 | IkReal x1408=IKsin(j0); |
| 18829 | IkReal x1409=((1.0)*gconst35); |
| 18830 | IkReal x1410=((-1.0)*x1407); |
| 18831 | evalcond[0]=(new_r11*x1408); |
| 18832 | evalcond[1]=(new_r10*x1410); |
| 18833 | evalcond[2]=(gconst35*x1410); |
| 18834 | evalcond[3]=((-1.0)*gconst35*x1408); |
| 18835 | evalcond[4]=(gconst35+((new_r11*x1407))); |
| 18836 | evalcond[5]=(new_r11+((gconst35*x1407))); |
| 18837 | evalcond[6]=(new_r10+(((-1.0)*x1408*x1409))); |
| 18838 | evalcond[7]=(((new_r10*x1408))+(((-1.0)*x1409))); |
| 18839 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 18840 | { |
| 18841 | continue; |
| 18842 | } |
| 18843 | } |
| 18844 | |
| 18845 | { |
| 18846 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18847 | vinfos[0].jointtype = 1; |
| 18848 | vinfos[0].foffset = j0; |
| 18849 | vinfos[0].indices[0] = _ij0[0]; |
| 18850 | vinfos[0].indices[1] = _ij0[1]; |
| 18851 | vinfos[0].maxsolutions = _nj0; |
| 18852 | vinfos[1].jointtype = 1; |
| 18853 | vinfos[1].foffset = j1; |
| 18854 | vinfos[1].indices[0] = _ij1[0]; |
| 18855 | vinfos[1].indices[1] = _ij1[1]; |
| 18856 | vinfos[1].maxsolutions = _nj1; |
| 18857 | vinfos[2].jointtype = 1; |
| 18858 | vinfos[2].foffset = j2; |
| 18859 | vinfos[2].indices[0] = _ij2[0]; |
| 18860 | vinfos[2].indices[1] = _ij2[1]; |
| 18861 | vinfos[2].maxsolutions = _nj2; |
| 18862 | vinfos[3].jointtype = 1; |
| 18863 | vinfos[3].foffset = j3; |
| 18864 | vinfos[3].indices[0] = _ij3[0]; |
| 18865 | vinfos[3].indices[1] = _ij3[1]; |
| 18866 | vinfos[3].maxsolutions = _nj3; |
| 18867 | vinfos[4].jointtype = 1; |
| 18868 | vinfos[4].foffset = j4; |
| 18869 | vinfos[4].indices[0] = _ij4[0]; |
| 18870 | vinfos[4].indices[1] = _ij4[1]; |
| 18871 | vinfos[4].maxsolutions = _nj4; |
| 18872 | vinfos[5].jointtype = 1; |
| 18873 | vinfos[5].foffset = j5; |
| 18874 | vinfos[5].indices[0] = _ij5[0]; |
| 18875 | vinfos[5].indices[1] = _ij5[1]; |
| 18876 | vinfos[5].maxsolutions = _nj5; |
| 18877 | std::vector<int> vfree(0); |
| 18878 | solutions.AddSolution(vinfos,vfree); |
| 18879 | } |
| 18880 | } |
| 18881 | } |
| 18882 | |
| 18883 | } |
| 18884 | |
| 18885 | } |
| 18886 | |
| 18887 | } else |
| 18888 | { |
| 18889 | { |
| 18890 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18891 | bool j0valid[1]={false}; |
| 18892 | _nj0 = 1; |
| 18893 | CheckValue<IkReal> x1411=IKPowWithIntegerCheck(gconst35,-1); |
| 18894 | if(!x1411.valid){ |
| 18895 | continue; |
| 18896 | } |
| 18897 | CheckValue<IkReal> x1412=IKPowWithIntegerCheck(new_r11,-1); |
| 18898 | if(!x1412.valid){ |
| 18899 | continue; |
| 18900 | } |
| 18901 | if( IKabs((new_r10*(x1411.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst35*(x1412.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1411.value)))+IKsqr(((-1.0)*gconst35*(x1412.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 18902 | continue; |
| 18903 | j0array[0]=IKatan2((new_r10*(x1411.value)), ((-1.0)*gconst35*(x1412.value))); |
| 18904 | sj0array[0]=IKsin(j0array[0]); |
| 18905 | cj0array[0]=IKcos(j0array[0]); |
| 18906 | if( j0array[0] > IKPI ) |
| 18907 | { |
| 18908 | j0array[0]-=IK2PI; |
| 18909 | } |
| 18910 | else if( j0array[0] < -IKPI ) |
| 18911 | { j0array[0]+=IK2PI; |
| 18912 | } |
| 18913 | j0valid[0] = true; |
| 18914 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 18915 | { |
| 18916 | if( !j0valid[ij0] ) |
| 18917 | { |
| 18918 | continue; |
| 18919 | } |
| 18920 | _ij0[0] = ij0; _ij0[1] = -1; |
| 18921 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 18922 | { |
| 18923 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 18924 | { |
| 18925 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 18926 | } |
| 18927 | } |
| 18928 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 18929 | { |
| 18930 | IkReal evalcond[8]; |
| 18931 | IkReal x1413=IKcos(j0); |
| 18932 | IkReal x1414=IKsin(j0); |
| 18933 | IkReal x1415=((1.0)*gconst35); |
| 18934 | IkReal x1416=((-1.0)*x1413); |
| 18935 | evalcond[0]=(new_r11*x1414); |
| 18936 | evalcond[1]=(new_r10*x1416); |
| 18937 | evalcond[2]=(gconst35*x1416); |
| 18938 | evalcond[3]=((-1.0)*gconst35*x1414); |
| 18939 | evalcond[4]=(gconst35+((new_r11*x1413))); |
| 18940 | evalcond[5]=(((gconst35*x1413))+new_r11); |
| 18941 | evalcond[6]=((((-1.0)*x1414*x1415))+new_r10); |
| 18942 | evalcond[7]=((((-1.0)*x1415))+((new_r10*x1414))); |
| 18943 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 18944 | { |
| 18945 | continue; |
| 18946 | } |
| 18947 | } |
| 18948 | |
| 18949 | { |
| 18950 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 18951 | vinfos[0].jointtype = 1; |
| 18952 | vinfos[0].foffset = j0; |
| 18953 | vinfos[0].indices[0] = _ij0[0]; |
| 18954 | vinfos[0].indices[1] = _ij0[1]; |
| 18955 | vinfos[0].maxsolutions = _nj0; |
| 18956 | vinfos[1].jointtype = 1; |
| 18957 | vinfos[1].foffset = j1; |
| 18958 | vinfos[1].indices[0] = _ij1[0]; |
| 18959 | vinfos[1].indices[1] = _ij1[1]; |
| 18960 | vinfos[1].maxsolutions = _nj1; |
| 18961 | vinfos[2].jointtype = 1; |
| 18962 | vinfos[2].foffset = j2; |
| 18963 | vinfos[2].indices[0] = _ij2[0]; |
| 18964 | vinfos[2].indices[1] = _ij2[1]; |
| 18965 | vinfos[2].maxsolutions = _nj2; |
| 18966 | vinfos[3].jointtype = 1; |
| 18967 | vinfos[3].foffset = j3; |
| 18968 | vinfos[3].indices[0] = _ij3[0]; |
| 18969 | vinfos[3].indices[1] = _ij3[1]; |
| 18970 | vinfos[3].maxsolutions = _nj3; |
| 18971 | vinfos[4].jointtype = 1; |
| 18972 | vinfos[4].foffset = j4; |
| 18973 | vinfos[4].indices[0] = _ij4[0]; |
| 18974 | vinfos[4].indices[1] = _ij4[1]; |
| 18975 | vinfos[4].maxsolutions = _nj4; |
| 18976 | vinfos[5].jointtype = 1; |
| 18977 | vinfos[5].foffset = j5; |
| 18978 | vinfos[5].indices[0] = _ij5[0]; |
| 18979 | vinfos[5].indices[1] = _ij5[1]; |
| 18980 | vinfos[5].maxsolutions = _nj5; |
| 18981 | std::vector<int> vfree(0); |
| 18982 | solutions.AddSolution(vinfos,vfree); |
| 18983 | } |
| 18984 | } |
| 18985 | } |
| 18986 | |
| 18987 | } |
| 18988 | |
| 18989 | } |
| 18990 | |
| 18991 | } else |
| 18992 | { |
| 18993 | { |
| 18994 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 18995 | bool j0valid[1]={false}; |
| 18996 | _nj0 = 1; |
| 18997 | CheckValue<IkReal> x1417 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 18998 | if(!x1417.valid){ |
| 18999 | continue; |
| 19000 | } |
| 19001 | CheckValue<IkReal> x1418=IKPowWithIntegerCheck(IKsign(gconst35),-1); |
| 19002 | if(!x1418.valid){ |
| 19003 | continue; |
| 19004 | } |
| 19005 | j0array[0]=((-1.5707963267949)+(x1417.value)+(((1.5707963267949)*(x1418.value)))); |
| 19006 | sj0array[0]=IKsin(j0array[0]); |
| 19007 | cj0array[0]=IKcos(j0array[0]); |
| 19008 | if( j0array[0] > IKPI ) |
| 19009 | { |
| 19010 | j0array[0]-=IK2PI; |
| 19011 | } |
| 19012 | else if( j0array[0] < -IKPI ) |
| 19013 | { j0array[0]+=IK2PI; |
| 19014 | } |
| 19015 | j0valid[0] = true; |
| 19016 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19017 | { |
| 19018 | if( !j0valid[ij0] ) |
| 19019 | { |
| 19020 | continue; |
| 19021 | } |
| 19022 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19023 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19024 | { |
| 19025 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19026 | { |
| 19027 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19028 | } |
| 19029 | } |
| 19030 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19031 | { |
| 19032 | IkReal evalcond[8]; |
| 19033 | IkReal x1419=IKcos(j0); |
| 19034 | IkReal x1420=IKsin(j0); |
| 19035 | IkReal x1421=((1.0)*gconst35); |
| 19036 | IkReal x1422=((-1.0)*x1419); |
| 19037 | evalcond[0]=(new_r11*x1420); |
| 19038 | evalcond[1]=(new_r10*x1422); |
| 19039 | evalcond[2]=(gconst35*x1422); |
| 19040 | evalcond[3]=((-1.0)*gconst35*x1420); |
| 19041 | evalcond[4]=(gconst35+((new_r11*x1419))); |
| 19042 | evalcond[5]=(((gconst35*x1419))+new_r11); |
| 19043 | evalcond[6]=((((-1.0)*x1420*x1421))+new_r10); |
| 19044 | evalcond[7]=(((new_r10*x1420))+(((-1.0)*x1421))); |
| 19045 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19046 | { |
| 19047 | continue; |
| 19048 | } |
| 19049 | } |
| 19050 | |
| 19051 | { |
| 19052 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19053 | vinfos[0].jointtype = 1; |
| 19054 | vinfos[0].foffset = j0; |
| 19055 | vinfos[0].indices[0] = _ij0[0]; |
| 19056 | vinfos[0].indices[1] = _ij0[1]; |
| 19057 | vinfos[0].maxsolutions = _nj0; |
| 19058 | vinfos[1].jointtype = 1; |
| 19059 | vinfos[1].foffset = j1; |
| 19060 | vinfos[1].indices[0] = _ij1[0]; |
| 19061 | vinfos[1].indices[1] = _ij1[1]; |
| 19062 | vinfos[1].maxsolutions = _nj1; |
| 19063 | vinfos[2].jointtype = 1; |
| 19064 | vinfos[2].foffset = j2; |
| 19065 | vinfos[2].indices[0] = _ij2[0]; |
| 19066 | vinfos[2].indices[1] = _ij2[1]; |
| 19067 | vinfos[2].maxsolutions = _nj2; |
| 19068 | vinfos[3].jointtype = 1; |
| 19069 | vinfos[3].foffset = j3; |
| 19070 | vinfos[3].indices[0] = _ij3[0]; |
| 19071 | vinfos[3].indices[1] = _ij3[1]; |
| 19072 | vinfos[3].maxsolutions = _nj3; |
| 19073 | vinfos[4].jointtype = 1; |
| 19074 | vinfos[4].foffset = j4; |
| 19075 | vinfos[4].indices[0] = _ij4[0]; |
| 19076 | vinfos[4].indices[1] = _ij4[1]; |
| 19077 | vinfos[4].maxsolutions = _nj4; |
| 19078 | vinfos[5].jointtype = 1; |
| 19079 | vinfos[5].foffset = j5; |
| 19080 | vinfos[5].indices[0] = _ij5[0]; |
| 19081 | vinfos[5].indices[1] = _ij5[1]; |
| 19082 | vinfos[5].maxsolutions = _nj5; |
| 19083 | std::vector<int> vfree(0); |
| 19084 | solutions.AddSolution(vinfos,vfree); |
| 19085 | } |
| 19086 | } |
| 19087 | } |
| 19088 | |
| 19089 | } |
| 19090 | |
| 19091 | } |
| 19092 | |
| 19093 | } |
| 19094 | } while(0); |
| 19095 | if( bgotonextstatement ) |
| 19096 | { |
| 19097 | bool bgotonextstatement = true; |
| 19098 | do |
| 19099 | { |
| 19100 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 19101 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 19102 | { |
| 19103 | bgotonextstatement=false; |
| 19104 | { |
| 19105 | IkReal j0eval[1]; |
| 19106 | IkReal x1423=((-1.0)*new_r01); |
| 19107 | CheckValue<IkReal> x1425 = IKatan2WithCheck(IkReal(0),IkReal(x1423),IKFAST_ATAN2_MAGTHRESH); |
| 19108 | if(!x1425.valid){ |
| 19109 | continue; |
| 19110 | } |
| 19111 | IkReal x1424=((-1.0)*(x1425.value)); |
| 19112 | sj1=-1.0; |
| 19113 | cj1=0; |
| 19114 | j1=-1.5707963267949; |
| 19115 | sj2=gconst35; |
| 19116 | cj2=gconst36; |
| 19117 | j2=x1424; |
| 19118 | new_r11=0; |
| 19119 | new_r10=0; |
| 19120 | new_r22=0; |
| 19121 | new_r02=0; |
| 19122 | IkReal gconst34=x1424; |
| 19123 | IkReal gconst35=0; |
| 19124 | IkReal x1426 = new_r01*new_r01; |
| 19125 | if(IKabs(x1426)==0){ |
| 19126 | continue; |
| 19127 | } |
| 19128 | IkReal gconst36=(x1423*(pow(x1426,-0.5))); |
| 19129 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 19130 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 19131 | { |
| 19132 | { |
| 19133 | IkReal j0eval[1]; |
| 19134 | IkReal x1427=((-1.0)*new_r01); |
| 19135 | CheckValue<IkReal> x1429 = IKatan2WithCheck(IkReal(0),IkReal(x1427),IKFAST_ATAN2_MAGTHRESH); |
| 19136 | if(!x1429.valid){ |
| 19137 | continue; |
| 19138 | } |
| 19139 | IkReal x1428=((-1.0)*(x1429.value)); |
| 19140 | sj1=-1.0; |
| 19141 | cj1=0; |
| 19142 | j1=-1.5707963267949; |
| 19143 | sj2=gconst35; |
| 19144 | cj2=gconst36; |
| 19145 | j2=x1428; |
| 19146 | new_r11=0; |
| 19147 | new_r10=0; |
| 19148 | new_r22=0; |
| 19149 | new_r02=0; |
| 19150 | IkReal gconst34=x1428; |
| 19151 | IkReal gconst35=0; |
| 19152 | IkReal x1430 = new_r01*new_r01; |
| 19153 | if(IKabs(x1430)==0){ |
| 19154 | continue; |
| 19155 | } |
| 19156 | IkReal gconst36=(x1427*(pow(x1430,-0.5))); |
| 19157 | j0eval[0]=new_r00; |
| 19158 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 19159 | { |
| 19160 | { |
| 19161 | IkReal j0eval[2]; |
| 19162 | IkReal x1431=((-1.0)*new_r01); |
| 19163 | CheckValue<IkReal> x1433 = IKatan2WithCheck(IkReal(0),IkReal(x1431),IKFAST_ATAN2_MAGTHRESH); |
| 19164 | if(!x1433.valid){ |
| 19165 | continue; |
| 19166 | } |
| 19167 | IkReal x1432=((-1.0)*(x1433.value)); |
| 19168 | sj1=-1.0; |
| 19169 | cj1=0; |
| 19170 | j1=-1.5707963267949; |
| 19171 | sj2=gconst35; |
| 19172 | cj2=gconst36; |
| 19173 | j2=x1432; |
| 19174 | new_r11=0; |
| 19175 | new_r10=0; |
| 19176 | new_r22=0; |
| 19177 | new_r02=0; |
| 19178 | IkReal gconst34=x1432; |
| 19179 | IkReal gconst35=0; |
| 19180 | IkReal x1434 = new_r01*new_r01; |
| 19181 | if(IKabs(x1434)==0){ |
| 19182 | continue; |
| 19183 | } |
| 19184 | IkReal gconst36=(x1431*(pow(x1434,-0.5))); |
| 19185 | j0eval[0]=new_r00; |
| 19186 | j0eval[1]=new_r01; |
| 19187 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 19188 | { |
| 19189 | continue; // 3 cases reached |
| 19190 | |
| 19191 | } else |
| 19192 | { |
| 19193 | { |
| 19194 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19195 | bool j0valid[1]={false}; |
| 19196 | _nj0 = 1; |
| 19197 | CheckValue<IkReal> x1435=IKPowWithIntegerCheck(new_r00,-1); |
| 19198 | if(!x1435.valid){ |
| 19199 | continue; |
| 19200 | } |
| 19201 | CheckValue<IkReal> x1436=IKPowWithIntegerCheck(new_r01,-1); |
| 19202 | if(!x1436.valid){ |
| 19203 | continue; |
| 19204 | } |
| 19205 | if( IKabs(((-1.0)*gconst36*(x1435.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst36*(x1436.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst36*(x1435.value)))+IKsqr((gconst36*(x1436.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 19206 | continue; |
| 19207 | j0array[0]=IKatan2(((-1.0)*gconst36*(x1435.value)), (gconst36*(x1436.value))); |
| 19208 | sj0array[0]=IKsin(j0array[0]); |
| 19209 | cj0array[0]=IKcos(j0array[0]); |
| 19210 | if( j0array[0] > IKPI ) |
| 19211 | { |
| 19212 | j0array[0]-=IK2PI; |
| 19213 | } |
| 19214 | else if( j0array[0] < -IKPI ) |
| 19215 | { j0array[0]+=IK2PI; |
| 19216 | } |
| 19217 | j0valid[0] = true; |
| 19218 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19219 | { |
| 19220 | if( !j0valid[ij0] ) |
| 19221 | { |
| 19222 | continue; |
| 19223 | } |
| 19224 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19225 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19226 | { |
| 19227 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19228 | { |
| 19229 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19230 | } |
| 19231 | } |
| 19232 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19233 | { |
| 19234 | IkReal evalcond[8]; |
| 19235 | IkReal x1437=IKsin(j0); |
| 19236 | IkReal x1438=IKcos(j0); |
| 19237 | IkReal x1439=((1.0)*gconst36); |
| 19238 | IkReal x1440=((-1.0)*x1437); |
| 19239 | evalcond[0]=(new_r00*x1438); |
| 19240 | evalcond[1]=(new_r01*x1440); |
| 19241 | evalcond[2]=(gconst36*x1440); |
| 19242 | evalcond[3]=((-1.0)*gconst36*x1438); |
| 19243 | evalcond[4]=(((new_r00*x1437))+gconst36); |
| 19244 | evalcond[5]=(((gconst36*x1437))+new_r00); |
| 19245 | evalcond[6]=((((-1.0)*x1438*x1439))+new_r01); |
| 19246 | evalcond[7]=(((new_r01*x1438))+(((-1.0)*x1439))); |
| 19247 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19248 | { |
| 19249 | continue; |
| 19250 | } |
| 19251 | } |
| 19252 | |
| 19253 | { |
| 19254 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19255 | vinfos[0].jointtype = 1; |
| 19256 | vinfos[0].foffset = j0; |
| 19257 | vinfos[0].indices[0] = _ij0[0]; |
| 19258 | vinfos[0].indices[1] = _ij0[1]; |
| 19259 | vinfos[0].maxsolutions = _nj0; |
| 19260 | vinfos[1].jointtype = 1; |
| 19261 | vinfos[1].foffset = j1; |
| 19262 | vinfos[1].indices[0] = _ij1[0]; |
| 19263 | vinfos[1].indices[1] = _ij1[1]; |
| 19264 | vinfos[1].maxsolutions = _nj1; |
| 19265 | vinfos[2].jointtype = 1; |
| 19266 | vinfos[2].foffset = j2; |
| 19267 | vinfos[2].indices[0] = _ij2[0]; |
| 19268 | vinfos[2].indices[1] = _ij2[1]; |
| 19269 | vinfos[2].maxsolutions = _nj2; |
| 19270 | vinfos[3].jointtype = 1; |
| 19271 | vinfos[3].foffset = j3; |
| 19272 | vinfos[3].indices[0] = _ij3[0]; |
| 19273 | vinfos[3].indices[1] = _ij3[1]; |
| 19274 | vinfos[3].maxsolutions = _nj3; |
| 19275 | vinfos[4].jointtype = 1; |
| 19276 | vinfos[4].foffset = j4; |
| 19277 | vinfos[4].indices[0] = _ij4[0]; |
| 19278 | vinfos[4].indices[1] = _ij4[1]; |
| 19279 | vinfos[4].maxsolutions = _nj4; |
| 19280 | vinfos[5].jointtype = 1; |
| 19281 | vinfos[5].foffset = j5; |
| 19282 | vinfos[5].indices[0] = _ij5[0]; |
| 19283 | vinfos[5].indices[1] = _ij5[1]; |
| 19284 | vinfos[5].maxsolutions = _nj5; |
| 19285 | std::vector<int> vfree(0); |
| 19286 | solutions.AddSolution(vinfos,vfree); |
| 19287 | } |
| 19288 | } |
| 19289 | } |
| 19290 | |
| 19291 | } |
| 19292 | |
| 19293 | } |
| 19294 | |
| 19295 | } else |
| 19296 | { |
| 19297 | { |
| 19298 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19299 | bool j0valid[1]={false}; |
| 19300 | _nj0 = 1; |
| 19301 | CheckValue<IkReal> x1441=IKPowWithIntegerCheck(new_r00,-1); |
| 19302 | if(!x1441.valid){ |
| 19303 | continue; |
| 19304 | } |
| 19305 | CheckValue<IkReal> x1442=IKPowWithIntegerCheck(gconst36,-1); |
| 19306 | if(!x1442.valid){ |
| 19307 | continue; |
| 19308 | } |
| 19309 | if( IKabs(((-1.0)*gconst36*(x1441.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r01*(x1442.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*gconst36*(x1441.value)))+IKsqr((new_r01*(x1442.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 19310 | continue; |
| 19311 | j0array[0]=IKatan2(((-1.0)*gconst36*(x1441.value)), (new_r01*(x1442.value))); |
| 19312 | sj0array[0]=IKsin(j0array[0]); |
| 19313 | cj0array[0]=IKcos(j0array[0]); |
| 19314 | if( j0array[0] > IKPI ) |
| 19315 | { |
| 19316 | j0array[0]-=IK2PI; |
| 19317 | } |
| 19318 | else if( j0array[0] < -IKPI ) |
| 19319 | { j0array[0]+=IK2PI; |
| 19320 | } |
| 19321 | j0valid[0] = true; |
| 19322 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19323 | { |
| 19324 | if( !j0valid[ij0] ) |
| 19325 | { |
| 19326 | continue; |
| 19327 | } |
| 19328 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19329 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19330 | { |
| 19331 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19332 | { |
| 19333 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19334 | } |
| 19335 | } |
| 19336 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19337 | { |
| 19338 | IkReal evalcond[8]; |
| 19339 | IkReal x1443=IKsin(j0); |
| 19340 | IkReal x1444=IKcos(j0); |
| 19341 | IkReal x1445=((1.0)*gconst36); |
| 19342 | IkReal x1446=((-1.0)*x1443); |
| 19343 | evalcond[0]=(new_r00*x1444); |
| 19344 | evalcond[1]=(new_r01*x1446); |
| 19345 | evalcond[2]=(gconst36*x1446); |
| 19346 | evalcond[3]=((-1.0)*gconst36*x1444); |
| 19347 | evalcond[4]=(gconst36+((new_r00*x1443))); |
| 19348 | evalcond[5]=(((gconst36*x1443))+new_r00); |
| 19349 | evalcond[6]=(new_r01+(((-1.0)*x1444*x1445))); |
| 19350 | evalcond[7]=(((new_r01*x1444))+(((-1.0)*x1445))); |
| 19351 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19352 | { |
| 19353 | continue; |
| 19354 | } |
| 19355 | } |
| 19356 | |
| 19357 | { |
| 19358 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19359 | vinfos[0].jointtype = 1; |
| 19360 | vinfos[0].foffset = j0; |
| 19361 | vinfos[0].indices[0] = _ij0[0]; |
| 19362 | vinfos[0].indices[1] = _ij0[1]; |
| 19363 | vinfos[0].maxsolutions = _nj0; |
| 19364 | vinfos[1].jointtype = 1; |
| 19365 | vinfos[1].foffset = j1; |
| 19366 | vinfos[1].indices[0] = _ij1[0]; |
| 19367 | vinfos[1].indices[1] = _ij1[1]; |
| 19368 | vinfos[1].maxsolutions = _nj1; |
| 19369 | vinfos[2].jointtype = 1; |
| 19370 | vinfos[2].foffset = j2; |
| 19371 | vinfos[2].indices[0] = _ij2[0]; |
| 19372 | vinfos[2].indices[1] = _ij2[1]; |
| 19373 | vinfos[2].maxsolutions = _nj2; |
| 19374 | vinfos[3].jointtype = 1; |
| 19375 | vinfos[3].foffset = j3; |
| 19376 | vinfos[3].indices[0] = _ij3[0]; |
| 19377 | vinfos[3].indices[1] = _ij3[1]; |
| 19378 | vinfos[3].maxsolutions = _nj3; |
| 19379 | vinfos[4].jointtype = 1; |
| 19380 | vinfos[4].foffset = j4; |
| 19381 | vinfos[4].indices[0] = _ij4[0]; |
| 19382 | vinfos[4].indices[1] = _ij4[1]; |
| 19383 | vinfos[4].maxsolutions = _nj4; |
| 19384 | vinfos[5].jointtype = 1; |
| 19385 | vinfos[5].foffset = j5; |
| 19386 | vinfos[5].indices[0] = _ij5[0]; |
| 19387 | vinfos[5].indices[1] = _ij5[1]; |
| 19388 | vinfos[5].maxsolutions = _nj5; |
| 19389 | std::vector<int> vfree(0); |
| 19390 | solutions.AddSolution(vinfos,vfree); |
| 19391 | } |
| 19392 | } |
| 19393 | } |
| 19394 | |
| 19395 | } |
| 19396 | |
| 19397 | } |
| 19398 | |
| 19399 | } else |
| 19400 | { |
| 19401 | { |
| 19402 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19403 | bool j0valid[1]={false}; |
| 19404 | _nj0 = 1; |
| 19405 | CheckValue<IkReal> x1447 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 19406 | if(!x1447.valid){ |
| 19407 | continue; |
| 19408 | } |
| 19409 | CheckValue<IkReal> x1448=IKPowWithIntegerCheck(IKsign(gconst36),-1); |
| 19410 | if(!x1448.valid){ |
| 19411 | continue; |
| 19412 | } |
| 19413 | j0array[0]=((-1.5707963267949)+(x1447.value)+(((1.5707963267949)*(x1448.value)))); |
| 19414 | sj0array[0]=IKsin(j0array[0]); |
| 19415 | cj0array[0]=IKcos(j0array[0]); |
| 19416 | if( j0array[0] > IKPI ) |
| 19417 | { |
| 19418 | j0array[0]-=IK2PI; |
| 19419 | } |
| 19420 | else if( j0array[0] < -IKPI ) |
| 19421 | { j0array[0]+=IK2PI; |
| 19422 | } |
| 19423 | j0valid[0] = true; |
| 19424 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19425 | { |
| 19426 | if( !j0valid[ij0] ) |
| 19427 | { |
| 19428 | continue; |
| 19429 | } |
| 19430 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19431 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19432 | { |
| 19433 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19434 | { |
| 19435 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19436 | } |
| 19437 | } |
| 19438 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19439 | { |
| 19440 | IkReal evalcond[8]; |
| 19441 | IkReal x1449=IKsin(j0); |
| 19442 | IkReal x1450=IKcos(j0); |
| 19443 | IkReal x1451=((1.0)*gconst36); |
| 19444 | IkReal x1452=((-1.0)*x1449); |
| 19445 | evalcond[0]=(new_r00*x1450); |
| 19446 | evalcond[1]=(new_r01*x1452); |
| 19447 | evalcond[2]=(gconst36*x1452); |
| 19448 | evalcond[3]=((-1.0)*gconst36*x1450); |
| 19449 | evalcond[4]=(gconst36+((new_r00*x1449))); |
| 19450 | evalcond[5]=(((gconst36*x1449))+new_r00); |
| 19451 | evalcond[6]=(new_r01+(((-1.0)*x1450*x1451))); |
| 19452 | evalcond[7]=((((-1.0)*x1451))+((new_r01*x1450))); |
| 19453 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19454 | { |
| 19455 | continue; |
| 19456 | } |
| 19457 | } |
| 19458 | |
| 19459 | { |
| 19460 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19461 | vinfos[0].jointtype = 1; |
| 19462 | vinfos[0].foffset = j0; |
| 19463 | vinfos[0].indices[0] = _ij0[0]; |
| 19464 | vinfos[0].indices[1] = _ij0[1]; |
| 19465 | vinfos[0].maxsolutions = _nj0; |
| 19466 | vinfos[1].jointtype = 1; |
| 19467 | vinfos[1].foffset = j1; |
| 19468 | vinfos[1].indices[0] = _ij1[0]; |
| 19469 | vinfos[1].indices[1] = _ij1[1]; |
| 19470 | vinfos[1].maxsolutions = _nj1; |
| 19471 | vinfos[2].jointtype = 1; |
| 19472 | vinfos[2].foffset = j2; |
| 19473 | vinfos[2].indices[0] = _ij2[0]; |
| 19474 | vinfos[2].indices[1] = _ij2[1]; |
| 19475 | vinfos[2].maxsolutions = _nj2; |
| 19476 | vinfos[3].jointtype = 1; |
| 19477 | vinfos[3].foffset = j3; |
| 19478 | vinfos[3].indices[0] = _ij3[0]; |
| 19479 | vinfos[3].indices[1] = _ij3[1]; |
| 19480 | vinfos[3].maxsolutions = _nj3; |
| 19481 | vinfos[4].jointtype = 1; |
| 19482 | vinfos[4].foffset = j4; |
| 19483 | vinfos[4].indices[0] = _ij4[0]; |
| 19484 | vinfos[4].indices[1] = _ij4[1]; |
| 19485 | vinfos[4].maxsolutions = _nj4; |
| 19486 | vinfos[5].jointtype = 1; |
| 19487 | vinfos[5].foffset = j5; |
| 19488 | vinfos[5].indices[0] = _ij5[0]; |
| 19489 | vinfos[5].indices[1] = _ij5[1]; |
| 19490 | vinfos[5].maxsolutions = _nj5; |
| 19491 | std::vector<int> vfree(0); |
| 19492 | solutions.AddSolution(vinfos,vfree); |
| 19493 | } |
| 19494 | } |
| 19495 | } |
| 19496 | |
| 19497 | } |
| 19498 | |
| 19499 | } |
| 19500 | |
| 19501 | } |
| 19502 | } while(0); |
| 19503 | if( bgotonextstatement ) |
| 19504 | { |
| 19505 | bool bgotonextstatement = true; |
| 19506 | do |
| 19507 | { |
| 19508 | if( 1 ) |
| 19509 | { |
| 19510 | bgotonextstatement=false; |
| 19511 | continue; // branch miss [j0] |
| 19512 | |
| 19513 | } |
| 19514 | } while(0); |
| 19515 | if( bgotonextstatement ) |
| 19516 | { |
| 19517 | } |
| 19518 | } |
| 19519 | } |
| 19520 | } |
| 19521 | } |
| 19522 | |
| 19523 | } else |
| 19524 | { |
| 19525 | { |
| 19526 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19527 | bool j0valid[1]={false}; |
| 19528 | _nj0 = 1; |
| 19529 | IkReal x1453=((1.0)*gconst36); |
| 19530 | CheckValue<IkReal> x1454=IKPowWithIntegerCheck(IKsign(((((-1.0)*new_r10*x1453))+((gconst35*new_r00)))),-1); |
| 19531 | if(!x1454.valid){ |
| 19532 | continue; |
| 19533 | } |
| 19534 | CheckValue<IkReal> x1455 = IKatan2WithCheck(IkReal(((((-1.0)*gconst35*x1453))+((new_r00*new_r10)))),IkReal(((((-1.0)*gconst36*x1453))+(new_r00*new_r00))),IKFAST_ATAN2_MAGTHRESH); |
| 19535 | if(!x1455.valid){ |
| 19536 | continue; |
| 19537 | } |
| 19538 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1454.value)))+(x1455.value)); |
| 19539 | sj0array[0]=IKsin(j0array[0]); |
| 19540 | cj0array[0]=IKcos(j0array[0]); |
| 19541 | if( j0array[0] > IKPI ) |
| 19542 | { |
| 19543 | j0array[0]-=IK2PI; |
| 19544 | } |
| 19545 | else if( j0array[0] < -IKPI ) |
| 19546 | { j0array[0]+=IK2PI; |
| 19547 | } |
| 19548 | j0valid[0] = true; |
| 19549 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19550 | { |
| 19551 | if( !j0valid[ij0] ) |
| 19552 | { |
| 19553 | continue; |
| 19554 | } |
| 19555 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19556 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19557 | { |
| 19558 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19559 | { |
| 19560 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19561 | } |
| 19562 | } |
| 19563 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19564 | { |
| 19565 | IkReal evalcond[8]; |
| 19566 | IkReal x1456=IKsin(j0); |
| 19567 | IkReal x1457=IKcos(j0); |
| 19568 | IkReal x1458=((1.0)*gconst35); |
| 19569 | IkReal x1459=(gconst35*x1457); |
| 19570 | IkReal x1460=((1.0)*x1457); |
| 19571 | IkReal x1461=(gconst36*x1456); |
| 19572 | IkReal x1462=(((x1456*x1458))+((gconst36*x1460))); |
| 19573 | evalcond[0]=(gconst35+((new_r11*x1457))+(((-1.0)*new_r01*x1456))); |
| 19574 | evalcond[1]=((((-1.0)*new_r10*x1460))+gconst36+((new_r00*x1456))); |
| 19575 | evalcond[2]=((((-1.0)*x1457*x1458))+x1461+new_r00); |
| 19576 | evalcond[3]=(x1459+new_r11+(((-1.0)*x1461))); |
| 19577 | evalcond[4]=((((-1.0)*x1458))+((new_r00*x1457))+((new_r10*x1456))); |
| 19578 | evalcond[5]=(((new_r01*x1457))+((new_r11*x1456))+(((-1.0)*gconst36))); |
| 19579 | evalcond[6]=((((-1.0)*x1462))+new_r01); |
| 19580 | evalcond[7]=((((-1.0)*x1462))+new_r10); |
| 19581 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19582 | { |
| 19583 | continue; |
| 19584 | } |
| 19585 | } |
| 19586 | |
| 19587 | { |
| 19588 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19589 | vinfos[0].jointtype = 1; |
| 19590 | vinfos[0].foffset = j0; |
| 19591 | vinfos[0].indices[0] = _ij0[0]; |
| 19592 | vinfos[0].indices[1] = _ij0[1]; |
| 19593 | vinfos[0].maxsolutions = _nj0; |
| 19594 | vinfos[1].jointtype = 1; |
| 19595 | vinfos[1].foffset = j1; |
| 19596 | vinfos[1].indices[0] = _ij1[0]; |
| 19597 | vinfos[1].indices[1] = _ij1[1]; |
| 19598 | vinfos[1].maxsolutions = _nj1; |
| 19599 | vinfos[2].jointtype = 1; |
| 19600 | vinfos[2].foffset = j2; |
| 19601 | vinfos[2].indices[0] = _ij2[0]; |
| 19602 | vinfos[2].indices[1] = _ij2[1]; |
| 19603 | vinfos[2].maxsolutions = _nj2; |
| 19604 | vinfos[3].jointtype = 1; |
| 19605 | vinfos[3].foffset = j3; |
| 19606 | vinfos[3].indices[0] = _ij3[0]; |
| 19607 | vinfos[3].indices[1] = _ij3[1]; |
| 19608 | vinfos[3].maxsolutions = _nj3; |
| 19609 | vinfos[4].jointtype = 1; |
| 19610 | vinfos[4].foffset = j4; |
| 19611 | vinfos[4].indices[0] = _ij4[0]; |
| 19612 | vinfos[4].indices[1] = _ij4[1]; |
| 19613 | vinfos[4].maxsolutions = _nj4; |
| 19614 | vinfos[5].jointtype = 1; |
| 19615 | vinfos[5].foffset = j5; |
| 19616 | vinfos[5].indices[0] = _ij5[0]; |
| 19617 | vinfos[5].indices[1] = _ij5[1]; |
| 19618 | vinfos[5].maxsolutions = _nj5; |
| 19619 | std::vector<int> vfree(0); |
| 19620 | solutions.AddSolution(vinfos,vfree); |
| 19621 | } |
| 19622 | } |
| 19623 | } |
| 19624 | |
| 19625 | } |
| 19626 | |
| 19627 | } |
| 19628 | |
| 19629 | } else |
| 19630 | { |
| 19631 | { |
| 19632 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19633 | bool j0valid[1]={false}; |
| 19634 | _nj0 = 1; |
| 19635 | CheckValue<IkReal> x1463 = IKatan2WithCheck(IkReal((((gconst35*new_r00))+((gconst35*new_r11)))),IkReal((((gconst35*new_r01))+(((-1.0)*gconst35*new_r10)))),IKFAST_ATAN2_MAGTHRESH); |
| 19636 | if(!x1463.valid){ |
| 19637 | continue; |
| 19638 | } |
| 19639 | CheckValue<IkReal> x1464=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 19640 | if(!x1464.valid){ |
| 19641 | continue; |
| 19642 | } |
| 19643 | j0array[0]=((-1.5707963267949)+(x1463.value)+(((1.5707963267949)*(x1464.value)))); |
| 19644 | sj0array[0]=IKsin(j0array[0]); |
| 19645 | cj0array[0]=IKcos(j0array[0]); |
| 19646 | if( j0array[0] > IKPI ) |
| 19647 | { |
| 19648 | j0array[0]-=IK2PI; |
| 19649 | } |
| 19650 | else if( j0array[0] < -IKPI ) |
| 19651 | { j0array[0]+=IK2PI; |
| 19652 | } |
| 19653 | j0valid[0] = true; |
| 19654 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19655 | { |
| 19656 | if( !j0valid[ij0] ) |
| 19657 | { |
| 19658 | continue; |
| 19659 | } |
| 19660 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19661 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19662 | { |
| 19663 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19664 | { |
| 19665 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19666 | } |
| 19667 | } |
| 19668 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19669 | { |
| 19670 | IkReal evalcond[8]; |
| 19671 | IkReal x1465=IKsin(j0); |
| 19672 | IkReal x1466=IKcos(j0); |
| 19673 | IkReal x1467=((1.0)*gconst35); |
| 19674 | IkReal x1468=(gconst35*x1466); |
| 19675 | IkReal x1469=((1.0)*x1466); |
| 19676 | IkReal x1470=(gconst36*x1465); |
| 19677 | IkReal x1471=(((gconst36*x1469))+((x1465*x1467))); |
| 19678 | evalcond[0]=((((-1.0)*new_r01*x1465))+gconst35+((new_r11*x1466))); |
| 19679 | evalcond[1]=((((-1.0)*new_r10*x1469))+((new_r00*x1465))+gconst36); |
| 19680 | evalcond[2]=((((-1.0)*x1466*x1467))+x1470+new_r00); |
| 19681 | evalcond[3]=((((-1.0)*x1470))+x1468+new_r11); |
| 19682 | evalcond[4]=(((new_r00*x1466))+(((-1.0)*x1467))+((new_r10*x1465))); |
| 19683 | evalcond[5]=(((new_r01*x1466))+((new_r11*x1465))+(((-1.0)*gconst36))); |
| 19684 | evalcond[6]=((((-1.0)*x1471))+new_r01); |
| 19685 | evalcond[7]=((((-1.0)*x1471))+new_r10); |
| 19686 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19687 | { |
| 19688 | continue; |
| 19689 | } |
| 19690 | } |
| 19691 | |
| 19692 | { |
| 19693 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19694 | vinfos[0].jointtype = 1; |
| 19695 | vinfos[0].foffset = j0; |
| 19696 | vinfos[0].indices[0] = _ij0[0]; |
| 19697 | vinfos[0].indices[1] = _ij0[1]; |
| 19698 | vinfos[0].maxsolutions = _nj0; |
| 19699 | vinfos[1].jointtype = 1; |
| 19700 | vinfos[1].foffset = j1; |
| 19701 | vinfos[1].indices[0] = _ij1[0]; |
| 19702 | vinfos[1].indices[1] = _ij1[1]; |
| 19703 | vinfos[1].maxsolutions = _nj1; |
| 19704 | vinfos[2].jointtype = 1; |
| 19705 | vinfos[2].foffset = j2; |
| 19706 | vinfos[2].indices[0] = _ij2[0]; |
| 19707 | vinfos[2].indices[1] = _ij2[1]; |
| 19708 | vinfos[2].maxsolutions = _nj2; |
| 19709 | vinfos[3].jointtype = 1; |
| 19710 | vinfos[3].foffset = j3; |
| 19711 | vinfos[3].indices[0] = _ij3[0]; |
| 19712 | vinfos[3].indices[1] = _ij3[1]; |
| 19713 | vinfos[3].maxsolutions = _nj3; |
| 19714 | vinfos[4].jointtype = 1; |
| 19715 | vinfos[4].foffset = j4; |
| 19716 | vinfos[4].indices[0] = _ij4[0]; |
| 19717 | vinfos[4].indices[1] = _ij4[1]; |
| 19718 | vinfos[4].maxsolutions = _nj4; |
| 19719 | vinfos[5].jointtype = 1; |
| 19720 | vinfos[5].foffset = j5; |
| 19721 | vinfos[5].indices[0] = _ij5[0]; |
| 19722 | vinfos[5].indices[1] = _ij5[1]; |
| 19723 | vinfos[5].maxsolutions = _nj5; |
| 19724 | std::vector<int> vfree(0); |
| 19725 | solutions.AddSolution(vinfos,vfree); |
| 19726 | } |
| 19727 | } |
| 19728 | } |
| 19729 | |
| 19730 | } |
| 19731 | |
| 19732 | } |
| 19733 | |
| 19734 | } else |
| 19735 | { |
| 19736 | { |
| 19737 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 19738 | bool j0valid[1]={false}; |
| 19739 | _nj0 = 1; |
| 19740 | CheckValue<IkReal> x1472=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| 19741 | if(!x1472.valid){ |
| 19742 | continue; |
| 19743 | } |
| 19744 | CheckValue<IkReal> x1473 = IKatan2WithCheck(IkReal((((gconst36*new_r11))+((gconst35*new_r10)))),IkReal((((gconst35*new_r00))+((gconst36*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 19745 | if(!x1473.valid){ |
| 19746 | continue; |
| 19747 | } |
| 19748 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1472.value)))+(x1473.value)); |
| 19749 | sj0array[0]=IKsin(j0array[0]); |
| 19750 | cj0array[0]=IKcos(j0array[0]); |
| 19751 | if( j0array[0] > IKPI ) |
| 19752 | { |
| 19753 | j0array[0]-=IK2PI; |
| 19754 | } |
| 19755 | else if( j0array[0] < -IKPI ) |
| 19756 | { j0array[0]+=IK2PI; |
| 19757 | } |
| 19758 | j0valid[0] = true; |
| 19759 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 19760 | { |
| 19761 | if( !j0valid[ij0] ) |
| 19762 | { |
| 19763 | continue; |
| 19764 | } |
| 19765 | _ij0[0] = ij0; _ij0[1] = -1; |
| 19766 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 19767 | { |
| 19768 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 19769 | { |
| 19770 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 19771 | } |
| 19772 | } |
| 19773 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 19774 | { |
| 19775 | IkReal evalcond[8]; |
| 19776 | IkReal x1474=IKsin(j0); |
| 19777 | IkReal x1475=IKcos(j0); |
| 19778 | IkReal x1476=((1.0)*gconst35); |
| 19779 | IkReal x1477=(gconst35*x1475); |
| 19780 | IkReal x1478=((1.0)*x1475); |
| 19781 | IkReal x1479=(gconst36*x1474); |
| 19782 | IkReal x1480=(((x1474*x1476))+((gconst36*x1478))); |
| 19783 | evalcond[0]=(((new_r11*x1475))+gconst35+(((-1.0)*new_r01*x1474))); |
| 19784 | evalcond[1]=(gconst36+((new_r00*x1474))+(((-1.0)*new_r10*x1478))); |
| 19785 | evalcond[2]=((((-1.0)*x1475*x1476))+x1479+new_r00); |
| 19786 | evalcond[3]=((((-1.0)*x1479))+x1477+new_r11); |
| 19787 | evalcond[4]=(((new_r10*x1474))+((new_r00*x1475))+(((-1.0)*x1476))); |
| 19788 | evalcond[5]=(((new_r11*x1474))+((new_r01*x1475))+(((-1.0)*gconst36))); |
| 19789 | evalcond[6]=((((-1.0)*x1480))+new_r01); |
| 19790 | evalcond[7]=((((-1.0)*x1480))+new_r10); |
| 19791 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 19792 | { |
| 19793 | continue; |
| 19794 | } |
| 19795 | } |
| 19796 | |
| 19797 | { |
| 19798 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 19799 | vinfos[0].jointtype = 1; |
| 19800 | vinfos[0].foffset = j0; |
| 19801 | vinfos[0].indices[0] = _ij0[0]; |
| 19802 | vinfos[0].indices[1] = _ij0[1]; |
| 19803 | vinfos[0].maxsolutions = _nj0; |
| 19804 | vinfos[1].jointtype = 1; |
| 19805 | vinfos[1].foffset = j1; |
| 19806 | vinfos[1].indices[0] = _ij1[0]; |
| 19807 | vinfos[1].indices[1] = _ij1[1]; |
| 19808 | vinfos[1].maxsolutions = _nj1; |
| 19809 | vinfos[2].jointtype = 1; |
| 19810 | vinfos[2].foffset = j2; |
| 19811 | vinfos[2].indices[0] = _ij2[0]; |
| 19812 | vinfos[2].indices[1] = _ij2[1]; |
| 19813 | vinfos[2].maxsolutions = _nj2; |
| 19814 | vinfos[3].jointtype = 1; |
| 19815 | vinfos[3].foffset = j3; |
| 19816 | vinfos[3].indices[0] = _ij3[0]; |
| 19817 | vinfos[3].indices[1] = _ij3[1]; |
| 19818 | vinfos[3].maxsolutions = _nj3; |
| 19819 | vinfos[4].jointtype = 1; |
| 19820 | vinfos[4].foffset = j4; |
| 19821 | vinfos[4].indices[0] = _ij4[0]; |
| 19822 | vinfos[4].indices[1] = _ij4[1]; |
| 19823 | vinfos[4].maxsolutions = _nj4; |
| 19824 | vinfos[5].jointtype = 1; |
| 19825 | vinfos[5].foffset = j5; |
| 19826 | vinfos[5].indices[0] = _ij5[0]; |
| 19827 | vinfos[5].indices[1] = _ij5[1]; |
| 19828 | vinfos[5].maxsolutions = _nj5; |
| 19829 | std::vector<int> vfree(0); |
| 19830 | solutions.AddSolution(vinfos,vfree); |
| 19831 | } |
| 19832 | } |
| 19833 | } |
| 19834 | |
| 19835 | } |
| 19836 | |
| 19837 | } |
| 19838 | |
| 19839 | } |
| 19840 | } while(0); |
| 19841 | if( bgotonextstatement ) |
| 19842 | { |
| 19843 | bool bgotonextstatement = true; |
| 19844 | do |
| 19845 | { |
| 19846 | IkReal x1483 = ((new_r01*new_r01)+(new_r11*new_r11)); |
| 19847 | if(IKabs(x1483)==0){ |
| 19848 | continue; |
| 19849 | } |
| 19850 | IkReal x1481=pow(x1483,-0.5); |
| 19851 | IkReal x1482=((1.0)*x1481); |
| 19852 | CheckValue<IkReal> x1484 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19853 | if(!x1484.valid){ |
| 19854 | continue; |
| 19855 | } |
| 19856 | IkReal gconst37=((3.14159265358979)+(((-1.0)*(x1484.value)))); |
| 19857 | IkReal gconst38=(new_r11*x1482); |
| 19858 | IkReal gconst39=(new_r01*x1482); |
| 19859 | CheckValue<IkReal> x1485 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19860 | if(!x1485.valid){ |
| 19861 | continue; |
| 19862 | } |
| 19863 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+(x1485.value)+j2)))), 6.28318530717959))); |
| 19864 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 19865 | { |
| 19866 | bgotonextstatement=false; |
| 19867 | { |
| 19868 | IkReal j0eval[3]; |
| 19869 | CheckValue<IkReal> x1489 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19870 | if(!x1489.valid){ |
| 19871 | continue; |
| 19872 | } |
| 19873 | IkReal x1486=((1.0)*(x1489.value)); |
| 19874 | IkReal x1487=x1481; |
| 19875 | IkReal x1488=((1.0)*x1487); |
| 19876 | sj1=-1.0; |
| 19877 | cj1=0; |
| 19878 | j1=-1.5707963267949; |
| 19879 | sj2=gconst38; |
| 19880 | cj2=gconst39; |
| 19881 | j2=((3.14159265)+(((-1.0)*x1486))); |
| 19882 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1486))); |
| 19883 | IkReal gconst38=(new_r11*x1488); |
| 19884 | IkReal gconst39=(new_r01*x1488); |
| 19885 | IkReal x1490=new_r01*new_r01; |
| 19886 | IkReal x1491=(((new_r01*new_r10))+(((-1.0)*new_r00*new_r11))); |
| 19887 | IkReal x1492=x1481; |
| 19888 | IkReal x1493=(new_r11*x1492); |
| 19889 | j0eval[0]=x1491; |
| 19890 | j0eval[1]=IKsign(x1491); |
| 19891 | j0eval[2]=((IKabs((((new_r00*x1493))+((x1490*x1492)))))+(IKabs((((new_r01*x1493))+((new_r10*x1493)))))); |
| 19892 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 19893 | { |
| 19894 | { |
| 19895 | IkReal j0eval[1]; |
| 19896 | CheckValue<IkReal> x1497 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19897 | if(!x1497.valid){ |
| 19898 | continue; |
| 19899 | } |
| 19900 | IkReal x1494=((1.0)*(x1497.value)); |
| 19901 | IkReal x1495=x1481; |
| 19902 | IkReal x1496=((1.0)*x1495); |
| 19903 | sj1=-1.0; |
| 19904 | cj1=0; |
| 19905 | j1=-1.5707963267949; |
| 19906 | sj2=gconst38; |
| 19907 | cj2=gconst39; |
| 19908 | j2=((3.14159265)+(((-1.0)*x1494))); |
| 19909 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1494))); |
| 19910 | IkReal gconst38=(new_r11*x1496); |
| 19911 | IkReal gconst39=(new_r01*x1496); |
| 19912 | IkReal x1498=new_r01*new_r01; |
| 19913 | IkReal x1499=new_r11*new_r11*new_r11; |
| 19914 | CheckValue<IkReal> x1503=IKPowWithIntegerCheck(((new_r11*new_r11)+x1498),-1); |
| 19915 | if(!x1503.valid){ |
| 19916 | continue; |
| 19917 | } |
| 19918 | IkReal x1500=x1503.value; |
| 19919 | IkReal x1501=(x1498*x1500); |
| 19920 | IkReal x1502=(x1499*x1500); |
| 19921 | j0eval[0]=((IKabs((((new_r10*x1502))+((new_r01*new_r11*x1500))+((new_r10*new_r11*x1501)))))+(IKabs((((new_r00*new_r11*x1501))+x1501+((new_r00*x1502)))))); |
| 19922 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 19923 | { |
| 19924 | { |
| 19925 | IkReal j0eval[3]; |
| 19926 | CheckValue<IkReal> x1507 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19927 | if(!x1507.valid){ |
| 19928 | continue; |
| 19929 | } |
| 19930 | IkReal x1504=((1.0)*(x1507.value)); |
| 19931 | IkReal x1505=x1481; |
| 19932 | IkReal x1506=((1.0)*x1505); |
| 19933 | sj1=-1.0; |
| 19934 | cj1=0; |
| 19935 | j1=-1.5707963267949; |
| 19936 | sj2=gconst38; |
| 19937 | cj2=gconst39; |
| 19938 | j2=((3.14159265)+(((-1.0)*x1504))); |
| 19939 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1504))); |
| 19940 | IkReal gconst38=(new_r11*x1506); |
| 19941 | IkReal gconst39=(new_r01*x1506); |
| 19942 | IkReal x1508=new_r11*new_r11; |
| 19943 | IkReal x1509=(new_r10*new_r11); |
| 19944 | IkReal x1510=(((new_r00*new_r01))+x1509); |
| 19945 | IkReal x1511=x1481; |
| 19946 | IkReal x1512=(new_r11*x1511); |
| 19947 | j0eval[0]=x1510; |
| 19948 | j0eval[1]=IKsign(x1510); |
| 19949 | j0eval[2]=((IKabs(((((-1.0)*x1509*x1511))+((new_r01*x1512)))))+(IKabs((((x1508*x1511))+((new_r00*x1512)))))); |
| 19950 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 19951 | { |
| 19952 | { |
| 19953 | IkReal evalcond[2]; |
| 19954 | bool bgotonextstatement = true; |
| 19955 | do |
| 19956 | { |
| 19957 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r00))); |
| 19958 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 19959 | { |
| 19960 | bgotonextstatement=false; |
| 19961 | { |
| 19962 | IkReal j0eval[1]; |
| 19963 | CheckValue<IkReal> x1514 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 19964 | if(!x1514.valid){ |
| 19965 | continue; |
| 19966 | } |
| 19967 | IkReal x1513=((1.0)*(x1514.value)); |
| 19968 | sj1=-1.0; |
| 19969 | cj1=0; |
| 19970 | j1=-1.5707963267949; |
| 19971 | sj2=gconst38; |
| 19972 | cj2=gconst39; |
| 19973 | j2=((3.14159265)+(((-1.0)*x1513))); |
| 19974 | new_r11=0; |
| 19975 | new_r00=0; |
| 19976 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1513))); |
| 19977 | IkReal gconst38=0; |
| 19978 | IkReal x1515 = new_r01*new_r01; |
| 19979 | if(IKabs(x1515)==0){ |
| 19980 | continue; |
| 19981 | } |
| 19982 | IkReal gconst39=((1.0)*new_r01*(pow(x1515,-0.5))); |
| 19983 | j0eval[0]=new_r10; |
| 19984 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 19985 | { |
| 19986 | { |
| 19987 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 19988 | bool j0valid[2]={false}; |
| 19989 | _nj0 = 2; |
| 19990 | CheckValue<IkReal> x1516=IKPowWithIntegerCheck(gconst39,-1); |
| 19991 | if(!x1516.valid){ |
| 19992 | continue; |
| 19993 | } |
| 19994 | cj0array[0]=(new_r01*(x1516.value)); |
| 19995 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 19996 | { |
| 19997 | j0valid[0] = j0valid[1] = true; |
| 19998 | j0array[0] = IKacos(cj0array[0]); |
| 19999 | sj0array[0] = IKsin(j0array[0]); |
| 20000 | cj0array[1] = cj0array[0]; |
| 20001 | j0array[1] = -j0array[0]; |
| 20002 | sj0array[1] = -sj0array[0]; |
| 20003 | } |
| 20004 | else if( isnan(cj0array[0]) ) |
| 20005 | { |
| 20006 | // probably any value will work |
| 20007 | j0valid[0] = true; |
| 20008 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 20009 | } |
| 20010 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 20011 | { |
| 20012 | if( !j0valid[ij0] ) |
| 20013 | { |
| 20014 | continue; |
| 20015 | } |
| 20016 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20017 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 20018 | { |
| 20019 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20020 | { |
| 20021 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20022 | } |
| 20023 | } |
| 20024 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20025 | { |
| 20026 | IkReal evalcond[6]; |
| 20027 | IkReal x1517=IKsin(j0); |
| 20028 | IkReal x1518=IKcos(j0); |
| 20029 | IkReal x1519=((1.0)*x1518); |
| 20030 | evalcond[0]=(new_r10*x1517); |
| 20031 | evalcond[1]=(gconst39*x1517); |
| 20032 | evalcond[2]=((-1.0)*new_r01*x1517); |
| 20033 | evalcond[3]=((((-1.0)*new_r10*x1519))+gconst39); |
| 20034 | evalcond[4]=((((-1.0)*gconst39*x1519))+new_r10); |
| 20035 | evalcond[5]=(((new_r01*x1518))+(((-1.0)*gconst39))); |
| 20036 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20037 | { |
| 20038 | continue; |
| 20039 | } |
| 20040 | } |
| 20041 | |
| 20042 | { |
| 20043 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20044 | vinfos[0].jointtype = 1; |
| 20045 | vinfos[0].foffset = j0; |
| 20046 | vinfos[0].indices[0] = _ij0[0]; |
| 20047 | vinfos[0].indices[1] = _ij0[1]; |
| 20048 | vinfos[0].maxsolutions = _nj0; |
| 20049 | vinfos[1].jointtype = 1; |
| 20050 | vinfos[1].foffset = j1; |
| 20051 | vinfos[1].indices[0] = _ij1[0]; |
| 20052 | vinfos[1].indices[1] = _ij1[1]; |
| 20053 | vinfos[1].maxsolutions = _nj1; |
| 20054 | vinfos[2].jointtype = 1; |
| 20055 | vinfos[2].foffset = j2; |
| 20056 | vinfos[2].indices[0] = _ij2[0]; |
| 20057 | vinfos[2].indices[1] = _ij2[1]; |
| 20058 | vinfos[2].maxsolutions = _nj2; |
| 20059 | vinfos[3].jointtype = 1; |
| 20060 | vinfos[3].foffset = j3; |
| 20061 | vinfos[3].indices[0] = _ij3[0]; |
| 20062 | vinfos[3].indices[1] = _ij3[1]; |
| 20063 | vinfos[3].maxsolutions = _nj3; |
| 20064 | vinfos[4].jointtype = 1; |
| 20065 | vinfos[4].foffset = j4; |
| 20066 | vinfos[4].indices[0] = _ij4[0]; |
| 20067 | vinfos[4].indices[1] = _ij4[1]; |
| 20068 | vinfos[4].maxsolutions = _nj4; |
| 20069 | vinfos[5].jointtype = 1; |
| 20070 | vinfos[5].foffset = j5; |
| 20071 | vinfos[5].indices[0] = _ij5[0]; |
| 20072 | vinfos[5].indices[1] = _ij5[1]; |
| 20073 | vinfos[5].maxsolutions = _nj5; |
| 20074 | std::vector<int> vfree(0); |
| 20075 | solutions.AddSolution(vinfos,vfree); |
| 20076 | } |
| 20077 | } |
| 20078 | } |
| 20079 | |
| 20080 | } else |
| 20081 | { |
| 20082 | { |
| 20083 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 20084 | bool j0valid[2]={false}; |
| 20085 | _nj0 = 2; |
| 20086 | CheckValue<IkReal> x1520=IKPowWithIntegerCheck(new_r10,-1); |
| 20087 | if(!x1520.valid){ |
| 20088 | continue; |
| 20089 | } |
| 20090 | cj0array[0]=(gconst39*(x1520.value)); |
| 20091 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 20092 | { |
| 20093 | j0valid[0] = j0valid[1] = true; |
| 20094 | j0array[0] = IKacos(cj0array[0]); |
| 20095 | sj0array[0] = IKsin(j0array[0]); |
| 20096 | cj0array[1] = cj0array[0]; |
| 20097 | j0array[1] = -j0array[0]; |
| 20098 | sj0array[1] = -sj0array[0]; |
| 20099 | } |
| 20100 | else if( isnan(cj0array[0]) ) |
| 20101 | { |
| 20102 | // probably any value will work |
| 20103 | j0valid[0] = true; |
| 20104 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 20105 | } |
| 20106 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 20107 | { |
| 20108 | if( !j0valid[ij0] ) |
| 20109 | { |
| 20110 | continue; |
| 20111 | } |
| 20112 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20113 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 20114 | { |
| 20115 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20116 | { |
| 20117 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20118 | } |
| 20119 | } |
| 20120 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20121 | { |
| 20122 | IkReal evalcond[6]; |
| 20123 | IkReal x1521=IKsin(j0); |
| 20124 | IkReal x1522=IKcos(j0); |
| 20125 | IkReal x1523=((1.0)*gconst39); |
| 20126 | IkReal x1524=(x1522*x1523); |
| 20127 | evalcond[0]=(new_r10*x1521); |
| 20128 | evalcond[1]=(gconst39*x1521); |
| 20129 | evalcond[2]=((-1.0)*new_r01*x1521); |
| 20130 | evalcond[3]=((((-1.0)*x1524))+new_r01); |
| 20131 | evalcond[4]=((((-1.0)*x1524))+new_r10); |
| 20132 | evalcond[5]=((((-1.0)*x1523))+((new_r01*x1522))); |
| 20133 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20134 | { |
| 20135 | continue; |
| 20136 | } |
| 20137 | } |
| 20138 | |
| 20139 | { |
| 20140 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20141 | vinfos[0].jointtype = 1; |
| 20142 | vinfos[0].foffset = j0; |
| 20143 | vinfos[0].indices[0] = _ij0[0]; |
| 20144 | vinfos[0].indices[1] = _ij0[1]; |
| 20145 | vinfos[0].maxsolutions = _nj0; |
| 20146 | vinfos[1].jointtype = 1; |
| 20147 | vinfos[1].foffset = j1; |
| 20148 | vinfos[1].indices[0] = _ij1[0]; |
| 20149 | vinfos[1].indices[1] = _ij1[1]; |
| 20150 | vinfos[1].maxsolutions = _nj1; |
| 20151 | vinfos[2].jointtype = 1; |
| 20152 | vinfos[2].foffset = j2; |
| 20153 | vinfos[2].indices[0] = _ij2[0]; |
| 20154 | vinfos[2].indices[1] = _ij2[1]; |
| 20155 | vinfos[2].maxsolutions = _nj2; |
| 20156 | vinfos[3].jointtype = 1; |
| 20157 | vinfos[3].foffset = j3; |
| 20158 | vinfos[3].indices[0] = _ij3[0]; |
| 20159 | vinfos[3].indices[1] = _ij3[1]; |
| 20160 | vinfos[3].maxsolutions = _nj3; |
| 20161 | vinfos[4].jointtype = 1; |
| 20162 | vinfos[4].foffset = j4; |
| 20163 | vinfos[4].indices[0] = _ij4[0]; |
| 20164 | vinfos[4].indices[1] = _ij4[1]; |
| 20165 | vinfos[4].maxsolutions = _nj4; |
| 20166 | vinfos[5].jointtype = 1; |
| 20167 | vinfos[5].foffset = j5; |
| 20168 | vinfos[5].indices[0] = _ij5[0]; |
| 20169 | vinfos[5].indices[1] = _ij5[1]; |
| 20170 | vinfos[5].maxsolutions = _nj5; |
| 20171 | std::vector<int> vfree(0); |
| 20172 | solutions.AddSolution(vinfos,vfree); |
| 20173 | } |
| 20174 | } |
| 20175 | } |
| 20176 | |
| 20177 | } |
| 20178 | |
| 20179 | } |
| 20180 | |
| 20181 | } |
| 20182 | } while(0); |
| 20183 | if( bgotonextstatement ) |
| 20184 | { |
| 20185 | bool bgotonextstatement = true; |
| 20186 | do |
| 20187 | { |
| 20188 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 20189 | evalcond[1]=gconst39; |
| 20190 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 20191 | { |
| 20192 | bgotonextstatement=false; |
| 20193 | { |
| 20194 | IkReal j0eval[4]; |
| 20195 | CheckValue<IkReal> x1526 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20196 | if(!x1526.valid){ |
| 20197 | continue; |
| 20198 | } |
| 20199 | IkReal x1525=((1.0)*(x1526.value)); |
| 20200 | sj1=-1.0; |
| 20201 | cj1=0; |
| 20202 | j1=-1.5707963267949; |
| 20203 | sj2=gconst38; |
| 20204 | cj2=gconst39; |
| 20205 | j2=((3.14159265)+(((-1.0)*x1525))); |
| 20206 | new_r00=0; |
| 20207 | new_r10=0; |
| 20208 | new_r21=0; |
| 20209 | new_r22=0; |
| 20210 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1525))); |
| 20211 | IkReal gconst38=((1.0)*new_r11); |
| 20212 | IkReal gconst39=((1.0)*new_r01); |
| 20213 | j0eval[0]=1.0; |
| 20214 | j0eval[1]=1.0; |
| 20215 | j0eval[2]=new_r01; |
| 20216 | j0eval[3]=1.0; |
| 20217 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| 20218 | { |
| 20219 | { |
| 20220 | IkReal j0eval[4]; |
| 20221 | CheckValue<IkReal> x1528 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20222 | if(!x1528.valid){ |
| 20223 | continue; |
| 20224 | } |
| 20225 | IkReal x1527=((1.0)*(x1528.value)); |
| 20226 | sj1=-1.0; |
| 20227 | cj1=0; |
| 20228 | j1=-1.5707963267949; |
| 20229 | sj2=gconst38; |
| 20230 | cj2=gconst39; |
| 20231 | j2=((3.14159265)+(((-1.0)*x1527))); |
| 20232 | new_r00=0; |
| 20233 | new_r10=0; |
| 20234 | new_r21=0; |
| 20235 | new_r22=0; |
| 20236 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1527))); |
| 20237 | IkReal gconst38=((1.0)*new_r11); |
| 20238 | IkReal gconst39=((1.0)*new_r01); |
| 20239 | j0eval[0]=1.0; |
| 20240 | j0eval[1]=new_r01; |
| 20241 | j0eval[2]=1.0; |
| 20242 | j0eval[3]=1.0; |
| 20243 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 || IKabs(j0eval[3]) < 0.0000010000000000 ) |
| 20244 | { |
| 20245 | { |
| 20246 | IkReal j0eval[3]; |
| 20247 | CheckValue<IkReal> x1530 = IKatan2WithCheck(IkReal(new_r11),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20248 | if(!x1530.valid){ |
| 20249 | continue; |
| 20250 | } |
| 20251 | IkReal x1529=((1.0)*(x1530.value)); |
| 20252 | sj1=-1.0; |
| 20253 | cj1=0; |
| 20254 | j1=-1.5707963267949; |
| 20255 | sj2=gconst38; |
| 20256 | cj2=gconst39; |
| 20257 | j2=((3.14159265)+(((-1.0)*x1529))); |
| 20258 | new_r00=0; |
| 20259 | new_r10=0; |
| 20260 | new_r21=0; |
| 20261 | new_r22=0; |
| 20262 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1529))); |
| 20263 | IkReal gconst38=((1.0)*new_r11); |
| 20264 | IkReal gconst39=((1.0)*new_r01); |
| 20265 | j0eval[0]=1.0; |
| 20266 | j0eval[1]=1.0; |
| 20267 | j0eval[2]=((IKabs(((-1.0)+(new_r01*new_r01))))+(IKabs(((1.0)*new_r01*new_r11)))); |
| 20268 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 20269 | { |
| 20270 | continue; // 3 cases reached |
| 20271 | |
| 20272 | } else |
| 20273 | { |
| 20274 | { |
| 20275 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20276 | bool j0valid[1]={false}; |
| 20277 | _nj0 = 1; |
| 20278 | CheckValue<IkReal> x1531 = IKatan2WithCheck(IkReal((gconst39*new_r11)),IkReal(((-1.0)*gconst38*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 20279 | if(!x1531.valid){ |
| 20280 | continue; |
| 20281 | } |
| 20282 | CheckValue<IkReal> x1532=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1); |
| 20283 | if(!x1532.valid){ |
| 20284 | continue; |
| 20285 | } |
| 20286 | j0array[0]=((-1.5707963267949)+(x1531.value)+(((1.5707963267949)*(x1532.value)))); |
| 20287 | sj0array[0]=IKsin(j0array[0]); |
| 20288 | cj0array[0]=IKcos(j0array[0]); |
| 20289 | if( j0array[0] > IKPI ) |
| 20290 | { |
| 20291 | j0array[0]-=IK2PI; |
| 20292 | } |
| 20293 | else if( j0array[0] < -IKPI ) |
| 20294 | { j0array[0]+=IK2PI; |
| 20295 | } |
| 20296 | j0valid[0] = true; |
| 20297 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 20298 | { |
| 20299 | if( !j0valid[ij0] ) |
| 20300 | { |
| 20301 | continue; |
| 20302 | } |
| 20303 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20304 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 20305 | { |
| 20306 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20307 | { |
| 20308 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20309 | } |
| 20310 | } |
| 20311 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20312 | { |
| 20313 | IkReal evalcond[6]; |
| 20314 | IkReal x1533=IKcos(j0); |
| 20315 | IkReal x1534=IKsin(j0); |
| 20316 | IkReal x1535=((1.0)*gconst39); |
| 20317 | IkReal x1536=(gconst38*x1533); |
| 20318 | IkReal x1537=((1.0)*x1534); |
| 20319 | IkReal x1538=(((x1533*x1535))+((gconst38*x1537))); |
| 20320 | evalcond[0]=(((gconst39*x1534))+(((-1.0)*x1536))); |
| 20321 | evalcond[1]=(gconst38+(((-1.0)*new_r01*x1537))+((new_r11*x1533))); |
| 20322 | evalcond[2]=(x1536+(((-1.0)*x1534*x1535))+new_r11); |
| 20323 | evalcond[3]=((-1.0)*x1538); |
| 20324 | evalcond[4]=((((-1.0)*x1535))+((new_r01*x1533))+((new_r11*x1534))); |
| 20325 | evalcond[5]=((((-1.0)*x1538))+new_r01); |
| 20326 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20327 | { |
| 20328 | continue; |
| 20329 | } |
| 20330 | } |
| 20331 | |
| 20332 | { |
| 20333 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20334 | vinfos[0].jointtype = 1; |
| 20335 | vinfos[0].foffset = j0; |
| 20336 | vinfos[0].indices[0] = _ij0[0]; |
| 20337 | vinfos[0].indices[1] = _ij0[1]; |
| 20338 | vinfos[0].maxsolutions = _nj0; |
| 20339 | vinfos[1].jointtype = 1; |
| 20340 | vinfos[1].foffset = j1; |
| 20341 | vinfos[1].indices[0] = _ij1[0]; |
| 20342 | vinfos[1].indices[1] = _ij1[1]; |
| 20343 | vinfos[1].maxsolutions = _nj1; |
| 20344 | vinfos[2].jointtype = 1; |
| 20345 | vinfos[2].foffset = j2; |
| 20346 | vinfos[2].indices[0] = _ij2[0]; |
| 20347 | vinfos[2].indices[1] = _ij2[1]; |
| 20348 | vinfos[2].maxsolutions = _nj2; |
| 20349 | vinfos[3].jointtype = 1; |
| 20350 | vinfos[3].foffset = j3; |
| 20351 | vinfos[3].indices[0] = _ij3[0]; |
| 20352 | vinfos[3].indices[1] = _ij3[1]; |
| 20353 | vinfos[3].maxsolutions = _nj3; |
| 20354 | vinfos[4].jointtype = 1; |
| 20355 | vinfos[4].foffset = j4; |
| 20356 | vinfos[4].indices[0] = _ij4[0]; |
| 20357 | vinfos[4].indices[1] = _ij4[1]; |
| 20358 | vinfos[4].maxsolutions = _nj4; |
| 20359 | vinfos[5].jointtype = 1; |
| 20360 | vinfos[5].foffset = j5; |
| 20361 | vinfos[5].indices[0] = _ij5[0]; |
| 20362 | vinfos[5].indices[1] = _ij5[1]; |
| 20363 | vinfos[5].maxsolutions = _nj5; |
| 20364 | std::vector<int> vfree(0); |
| 20365 | solutions.AddSolution(vinfos,vfree); |
| 20366 | } |
| 20367 | } |
| 20368 | } |
| 20369 | |
| 20370 | } |
| 20371 | |
| 20372 | } |
| 20373 | |
| 20374 | } else |
| 20375 | { |
| 20376 | { |
| 20377 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20378 | bool j0valid[1]={false}; |
| 20379 | _nj0 = 1; |
| 20380 | CheckValue<IkReal> x1539 = IKatan2WithCheck(IkReal((gconst38*new_r01)),IkReal((gconst39*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20381 | if(!x1539.valid){ |
| 20382 | continue; |
| 20383 | } |
| 20384 | CheckValue<IkReal> x1540=IKPowWithIntegerCheck(IKsign(((gconst38*gconst38)+(gconst39*gconst39))),-1); |
| 20385 | if(!x1540.valid){ |
| 20386 | continue; |
| 20387 | } |
| 20388 | j0array[0]=((-1.5707963267949)+(x1539.value)+(((1.5707963267949)*(x1540.value)))); |
| 20389 | sj0array[0]=IKsin(j0array[0]); |
| 20390 | cj0array[0]=IKcos(j0array[0]); |
| 20391 | if( j0array[0] > IKPI ) |
| 20392 | { |
| 20393 | j0array[0]-=IK2PI; |
| 20394 | } |
| 20395 | else if( j0array[0] < -IKPI ) |
| 20396 | { j0array[0]+=IK2PI; |
| 20397 | } |
| 20398 | j0valid[0] = true; |
| 20399 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 20400 | { |
| 20401 | if( !j0valid[ij0] ) |
| 20402 | { |
| 20403 | continue; |
| 20404 | } |
| 20405 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20406 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 20407 | { |
| 20408 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20409 | { |
| 20410 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20411 | } |
| 20412 | } |
| 20413 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20414 | { |
| 20415 | IkReal evalcond[6]; |
| 20416 | IkReal x1541=IKcos(j0); |
| 20417 | IkReal x1542=IKsin(j0); |
| 20418 | IkReal x1543=((1.0)*gconst39); |
| 20419 | IkReal x1544=(gconst38*x1541); |
| 20420 | IkReal x1545=((1.0)*x1542); |
| 20421 | IkReal x1546=(((x1541*x1543))+((gconst38*x1545))); |
| 20422 | evalcond[0]=((((-1.0)*x1544))+((gconst39*x1542))); |
| 20423 | evalcond[1]=(((new_r11*x1541))+gconst38+(((-1.0)*new_r01*x1545))); |
| 20424 | evalcond[2]=(x1544+(((-1.0)*x1542*x1543))+new_r11); |
| 20425 | evalcond[3]=((-1.0)*x1546); |
| 20426 | evalcond[4]=(((new_r01*x1541))+((new_r11*x1542))+(((-1.0)*x1543))); |
| 20427 | evalcond[5]=(new_r01+(((-1.0)*x1546))); |
| 20428 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20429 | { |
| 20430 | continue; |
| 20431 | } |
| 20432 | } |
| 20433 | |
| 20434 | { |
| 20435 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20436 | vinfos[0].jointtype = 1; |
| 20437 | vinfos[0].foffset = j0; |
| 20438 | vinfos[0].indices[0] = _ij0[0]; |
| 20439 | vinfos[0].indices[1] = _ij0[1]; |
| 20440 | vinfos[0].maxsolutions = _nj0; |
| 20441 | vinfos[1].jointtype = 1; |
| 20442 | vinfos[1].foffset = j1; |
| 20443 | vinfos[1].indices[0] = _ij1[0]; |
| 20444 | vinfos[1].indices[1] = _ij1[1]; |
| 20445 | vinfos[1].maxsolutions = _nj1; |
| 20446 | vinfos[2].jointtype = 1; |
| 20447 | vinfos[2].foffset = j2; |
| 20448 | vinfos[2].indices[0] = _ij2[0]; |
| 20449 | vinfos[2].indices[1] = _ij2[1]; |
| 20450 | vinfos[2].maxsolutions = _nj2; |
| 20451 | vinfos[3].jointtype = 1; |
| 20452 | vinfos[3].foffset = j3; |
| 20453 | vinfos[3].indices[0] = _ij3[0]; |
| 20454 | vinfos[3].indices[1] = _ij3[1]; |
| 20455 | vinfos[3].maxsolutions = _nj3; |
| 20456 | vinfos[4].jointtype = 1; |
| 20457 | vinfos[4].foffset = j4; |
| 20458 | vinfos[4].indices[0] = _ij4[0]; |
| 20459 | vinfos[4].indices[1] = _ij4[1]; |
| 20460 | vinfos[4].maxsolutions = _nj4; |
| 20461 | vinfos[5].jointtype = 1; |
| 20462 | vinfos[5].foffset = j5; |
| 20463 | vinfos[5].indices[0] = _ij5[0]; |
| 20464 | vinfos[5].indices[1] = _ij5[1]; |
| 20465 | vinfos[5].maxsolutions = _nj5; |
| 20466 | std::vector<int> vfree(0); |
| 20467 | solutions.AddSolution(vinfos,vfree); |
| 20468 | } |
| 20469 | } |
| 20470 | } |
| 20471 | |
| 20472 | } |
| 20473 | |
| 20474 | } |
| 20475 | |
| 20476 | } else |
| 20477 | { |
| 20478 | { |
| 20479 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20480 | bool j0valid[1]={false}; |
| 20481 | _nj0 = 1; |
| 20482 | CheckValue<IkReal> x1547 = IKatan2WithCheck(IkReal((gconst38*gconst39)),IkReal(gconst39*gconst39),IKFAST_ATAN2_MAGTHRESH); |
| 20483 | if(!x1547.valid){ |
| 20484 | continue; |
| 20485 | } |
| 20486 | CheckValue<IkReal> x1548=IKPowWithIntegerCheck(IKsign((((gconst39*new_r01))+((gconst38*new_r11)))),-1); |
| 20487 | if(!x1548.valid){ |
| 20488 | continue; |
| 20489 | } |
| 20490 | j0array[0]=((-1.5707963267949)+(x1547.value)+(((1.5707963267949)*(x1548.value)))); |
| 20491 | sj0array[0]=IKsin(j0array[0]); |
| 20492 | cj0array[0]=IKcos(j0array[0]); |
| 20493 | if( j0array[0] > IKPI ) |
| 20494 | { |
| 20495 | j0array[0]-=IK2PI; |
| 20496 | } |
| 20497 | else if( j0array[0] < -IKPI ) |
| 20498 | { j0array[0]+=IK2PI; |
| 20499 | } |
| 20500 | j0valid[0] = true; |
| 20501 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 20502 | { |
| 20503 | if( !j0valid[ij0] ) |
| 20504 | { |
| 20505 | continue; |
| 20506 | } |
| 20507 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20508 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 20509 | { |
| 20510 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20511 | { |
| 20512 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20513 | } |
| 20514 | } |
| 20515 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20516 | { |
| 20517 | IkReal evalcond[6]; |
| 20518 | IkReal x1549=IKcos(j0); |
| 20519 | IkReal x1550=IKsin(j0); |
| 20520 | IkReal x1551=((1.0)*gconst39); |
| 20521 | IkReal x1552=(gconst38*x1549); |
| 20522 | IkReal x1553=((1.0)*x1550); |
| 20523 | IkReal x1554=(((x1549*x1551))+((gconst38*x1553))); |
| 20524 | evalcond[0]=((((-1.0)*x1552))+((gconst39*x1550))); |
| 20525 | evalcond[1]=(((new_r11*x1549))+gconst38+(((-1.0)*new_r01*x1553))); |
| 20526 | evalcond[2]=(x1552+(((-1.0)*x1550*x1551))+new_r11); |
| 20527 | evalcond[3]=((-1.0)*x1554); |
| 20528 | evalcond[4]=(((new_r01*x1549))+((new_r11*x1550))+(((-1.0)*x1551))); |
| 20529 | evalcond[5]=((((-1.0)*x1554))+new_r01); |
| 20530 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20531 | { |
| 20532 | continue; |
| 20533 | } |
| 20534 | } |
| 20535 | |
| 20536 | { |
| 20537 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20538 | vinfos[0].jointtype = 1; |
| 20539 | vinfos[0].foffset = j0; |
| 20540 | vinfos[0].indices[0] = _ij0[0]; |
| 20541 | vinfos[0].indices[1] = _ij0[1]; |
| 20542 | vinfos[0].maxsolutions = _nj0; |
| 20543 | vinfos[1].jointtype = 1; |
| 20544 | vinfos[1].foffset = j1; |
| 20545 | vinfos[1].indices[0] = _ij1[0]; |
| 20546 | vinfos[1].indices[1] = _ij1[1]; |
| 20547 | vinfos[1].maxsolutions = _nj1; |
| 20548 | vinfos[2].jointtype = 1; |
| 20549 | vinfos[2].foffset = j2; |
| 20550 | vinfos[2].indices[0] = _ij2[0]; |
| 20551 | vinfos[2].indices[1] = _ij2[1]; |
| 20552 | vinfos[2].maxsolutions = _nj2; |
| 20553 | vinfos[3].jointtype = 1; |
| 20554 | vinfos[3].foffset = j3; |
| 20555 | vinfos[3].indices[0] = _ij3[0]; |
| 20556 | vinfos[3].indices[1] = _ij3[1]; |
| 20557 | vinfos[3].maxsolutions = _nj3; |
| 20558 | vinfos[4].jointtype = 1; |
| 20559 | vinfos[4].foffset = j4; |
| 20560 | vinfos[4].indices[0] = _ij4[0]; |
| 20561 | vinfos[4].indices[1] = _ij4[1]; |
| 20562 | vinfos[4].maxsolutions = _nj4; |
| 20563 | vinfos[5].jointtype = 1; |
| 20564 | vinfos[5].foffset = j5; |
| 20565 | vinfos[5].indices[0] = _ij5[0]; |
| 20566 | vinfos[5].indices[1] = _ij5[1]; |
| 20567 | vinfos[5].maxsolutions = _nj5; |
| 20568 | std::vector<int> vfree(0); |
| 20569 | solutions.AddSolution(vinfos,vfree); |
| 20570 | } |
| 20571 | } |
| 20572 | } |
| 20573 | |
| 20574 | } |
| 20575 | |
| 20576 | } |
| 20577 | |
| 20578 | } |
| 20579 | } while(0); |
| 20580 | if( bgotonextstatement ) |
| 20581 | { |
| 20582 | bool bgotonextstatement = true; |
| 20583 | do |
| 20584 | { |
| 20585 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r01))); |
| 20586 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 20587 | { |
| 20588 | bgotonextstatement=false; |
| 20589 | { |
| 20590 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 20591 | bool j0valid[2]={false}; |
| 20592 | _nj0 = 2; |
| 20593 | CheckValue<IkReal> x1555=IKPowWithIntegerCheck(gconst38,-1); |
| 20594 | if(!x1555.valid){ |
| 20595 | continue; |
| 20596 | } |
| 20597 | cj0array[0]=(new_r00*(x1555.value)); |
| 20598 | if( cj0array[0] >= -1-IKFAST_SINCOS_THRESH && cj0array[0] <= 1+IKFAST_SINCOS_THRESH ) |
| 20599 | { |
| 20600 | j0valid[0] = j0valid[1] = true; |
| 20601 | j0array[0] = IKacos(cj0array[0]); |
| 20602 | sj0array[0] = IKsin(j0array[0]); |
| 20603 | cj0array[1] = cj0array[0]; |
| 20604 | j0array[1] = -j0array[0]; |
| 20605 | sj0array[1] = -sj0array[0]; |
| 20606 | } |
| 20607 | else if( isnan(cj0array[0]) ) |
| 20608 | { |
| 20609 | // probably any value will work |
| 20610 | j0valid[0] = true; |
| 20611 | cj0array[0] = 1; sj0array[0] = 0; j0array[0] = 0; |
| 20612 | } |
| 20613 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 20614 | { |
| 20615 | if( !j0valid[ij0] ) |
| 20616 | { |
| 20617 | continue; |
| 20618 | } |
| 20619 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20620 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 20621 | { |
| 20622 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20623 | { |
| 20624 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20625 | } |
| 20626 | } |
| 20627 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20628 | { |
| 20629 | IkReal evalcond[6]; |
| 20630 | IkReal x1556=IKsin(j0); |
| 20631 | IkReal x1557=IKcos(j0); |
| 20632 | evalcond[0]=(new_r00*x1556); |
| 20633 | evalcond[1]=(new_r11*x1556); |
| 20634 | evalcond[2]=((-1.0)*gconst38*x1556); |
| 20635 | evalcond[3]=(gconst38+((new_r11*x1557))); |
| 20636 | evalcond[4]=(new_r11+((gconst38*x1557))); |
| 20637 | evalcond[5]=(((new_r00*x1557))+(((-1.0)*gconst38))); |
| 20638 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH ) |
| 20639 | { |
| 20640 | continue; |
| 20641 | } |
| 20642 | } |
| 20643 | |
| 20644 | { |
| 20645 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20646 | vinfos[0].jointtype = 1; |
| 20647 | vinfos[0].foffset = j0; |
| 20648 | vinfos[0].indices[0] = _ij0[0]; |
| 20649 | vinfos[0].indices[1] = _ij0[1]; |
| 20650 | vinfos[0].maxsolutions = _nj0; |
| 20651 | vinfos[1].jointtype = 1; |
| 20652 | vinfos[1].foffset = j1; |
| 20653 | vinfos[1].indices[0] = _ij1[0]; |
| 20654 | vinfos[1].indices[1] = _ij1[1]; |
| 20655 | vinfos[1].maxsolutions = _nj1; |
| 20656 | vinfos[2].jointtype = 1; |
| 20657 | vinfos[2].foffset = j2; |
| 20658 | vinfos[2].indices[0] = _ij2[0]; |
| 20659 | vinfos[2].indices[1] = _ij2[1]; |
| 20660 | vinfos[2].maxsolutions = _nj2; |
| 20661 | vinfos[3].jointtype = 1; |
| 20662 | vinfos[3].foffset = j3; |
| 20663 | vinfos[3].indices[0] = _ij3[0]; |
| 20664 | vinfos[3].indices[1] = _ij3[1]; |
| 20665 | vinfos[3].maxsolutions = _nj3; |
| 20666 | vinfos[4].jointtype = 1; |
| 20667 | vinfos[4].foffset = j4; |
| 20668 | vinfos[4].indices[0] = _ij4[0]; |
| 20669 | vinfos[4].indices[1] = _ij4[1]; |
| 20670 | vinfos[4].maxsolutions = _nj4; |
| 20671 | vinfos[5].jointtype = 1; |
| 20672 | vinfos[5].foffset = j5; |
| 20673 | vinfos[5].indices[0] = _ij5[0]; |
| 20674 | vinfos[5].indices[1] = _ij5[1]; |
| 20675 | vinfos[5].maxsolutions = _nj5; |
| 20676 | std::vector<int> vfree(0); |
| 20677 | solutions.AddSolution(vinfos,vfree); |
| 20678 | } |
| 20679 | } |
| 20680 | } |
| 20681 | |
| 20682 | } |
| 20683 | } while(0); |
| 20684 | if( bgotonextstatement ) |
| 20685 | { |
| 20686 | bool bgotonextstatement = true; |
| 20687 | do |
| 20688 | { |
| 20689 | evalcond[0]=IKabs(new_r11); |
| 20690 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 20691 | { |
| 20692 | bgotonextstatement=false; |
| 20693 | { |
| 20694 | IkReal j0eval[1]; |
| 20695 | CheckValue<IkReal> x1559 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20696 | if(!x1559.valid){ |
| 20697 | continue; |
| 20698 | } |
| 20699 | IkReal x1558=((1.0)*(x1559.value)); |
| 20700 | sj1=-1.0; |
| 20701 | cj1=0; |
| 20702 | j1=-1.5707963267949; |
| 20703 | sj2=gconst38; |
| 20704 | cj2=gconst39; |
| 20705 | j2=((3.14159265)+(((-1.0)*x1558))); |
| 20706 | new_r11=0; |
| 20707 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1558))); |
| 20708 | IkReal gconst38=0; |
| 20709 | IkReal x1560 = new_r01*new_r01; |
| 20710 | if(IKabs(x1560)==0){ |
| 20711 | continue; |
| 20712 | } |
| 20713 | IkReal gconst39=((1.0)*new_r01*(pow(x1560,-0.5))); |
| 20714 | j0eval[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 20715 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 20716 | { |
| 20717 | { |
| 20718 | IkReal j0eval[1]; |
| 20719 | CheckValue<IkReal> x1562 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20720 | if(!x1562.valid){ |
| 20721 | continue; |
| 20722 | } |
| 20723 | IkReal x1561=((1.0)*(x1562.value)); |
| 20724 | sj1=-1.0; |
| 20725 | cj1=0; |
| 20726 | j1=-1.5707963267949; |
| 20727 | sj2=gconst38; |
| 20728 | cj2=gconst39; |
| 20729 | j2=((3.14159265)+(((-1.0)*x1561))); |
| 20730 | new_r11=0; |
| 20731 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1561))); |
| 20732 | IkReal gconst38=0; |
| 20733 | IkReal x1563 = new_r01*new_r01; |
| 20734 | if(IKabs(x1563)==0){ |
| 20735 | continue; |
| 20736 | } |
| 20737 | IkReal gconst39=((1.0)*new_r01*(pow(x1563,-0.5))); |
| 20738 | j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 20739 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 20740 | { |
| 20741 | { |
| 20742 | IkReal j0eval[1]; |
| 20743 | CheckValue<IkReal> x1565 = IKatan2WithCheck(IkReal(0),IkReal(((-1.0)*new_r01)),IKFAST_ATAN2_MAGTHRESH); |
| 20744 | if(!x1565.valid){ |
| 20745 | continue; |
| 20746 | } |
| 20747 | IkReal x1564=((1.0)*(x1565.value)); |
| 20748 | sj1=-1.0; |
| 20749 | cj1=0; |
| 20750 | j1=-1.5707963267949; |
| 20751 | sj2=gconst38; |
| 20752 | cj2=gconst39; |
| 20753 | j2=((3.14159265)+(((-1.0)*x1564))); |
| 20754 | new_r11=0; |
| 20755 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1564))); |
| 20756 | IkReal gconst38=0; |
| 20757 | IkReal x1566 = new_r01*new_r01; |
| 20758 | if(IKabs(x1566)==0){ |
| 20759 | continue; |
| 20760 | } |
| 20761 | IkReal gconst39=((1.0)*new_r01*(pow(x1566,-0.5))); |
| 20762 | j0eval[0]=new_r01; |
| 20763 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 20764 | { |
| 20765 | continue; // 3 cases reached |
| 20766 | |
| 20767 | } else |
| 20768 | { |
| 20769 | { |
| 20770 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20771 | bool j0valid[1]={false}; |
| 20772 | _nj0 = 1; |
| 20773 | CheckValue<IkReal> x1567=IKPowWithIntegerCheck(gconst39,-1); |
| 20774 | if(!x1567.valid){ |
| 20775 | continue; |
| 20776 | } |
| 20777 | CheckValue<IkReal> x1568=IKPowWithIntegerCheck(new_r01,-1); |
| 20778 | if(!x1568.valid){ |
| 20779 | continue; |
| 20780 | } |
| 20781 | if( IKabs(((-1.0)*new_r00*(x1567.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((gconst39*(x1568.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00*(x1567.value)))+IKsqr((gconst39*(x1568.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 20782 | continue; |
| 20783 | j0array[0]=IKatan2(((-1.0)*new_r00*(x1567.value)), (gconst39*(x1568.value))); |
| 20784 | sj0array[0]=IKsin(j0array[0]); |
| 20785 | cj0array[0]=IKcos(j0array[0]); |
| 20786 | if( j0array[0] > IKPI ) |
| 20787 | { |
| 20788 | j0array[0]-=IK2PI; |
| 20789 | } |
| 20790 | else if( j0array[0] < -IKPI ) |
| 20791 | { j0array[0]+=IK2PI; |
| 20792 | } |
| 20793 | j0valid[0] = true; |
| 20794 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 20795 | { |
| 20796 | if( !j0valid[ij0] ) |
| 20797 | { |
| 20798 | continue; |
| 20799 | } |
| 20800 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20801 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 20802 | { |
| 20803 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20804 | { |
| 20805 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20806 | } |
| 20807 | } |
| 20808 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20809 | { |
| 20810 | IkReal evalcond[8]; |
| 20811 | IkReal x1569=IKsin(j0); |
| 20812 | IkReal x1570=IKcos(j0); |
| 20813 | IkReal x1571=((1.0)*x1570); |
| 20814 | IkReal x1572=(gconst39*x1571); |
| 20815 | IkReal x1573=((-1.0)*x1569); |
| 20816 | evalcond[0]=(new_r01*x1573); |
| 20817 | evalcond[1]=(gconst39*x1573); |
| 20818 | evalcond[2]=(((gconst39*x1569))+new_r00); |
| 20819 | evalcond[3]=(new_r01+(((-1.0)*x1572))); |
| 20820 | evalcond[4]=(new_r10+(((-1.0)*x1572))); |
| 20821 | evalcond[5]=(((new_r01*x1570))+(((-1.0)*gconst39))); |
| 20822 | evalcond[6]=(((new_r00*x1570))+((new_r10*x1569))); |
| 20823 | evalcond[7]=(((new_r00*x1569))+(((-1.0)*new_r10*x1571))+gconst39); |
| 20824 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 20825 | { |
| 20826 | continue; |
| 20827 | } |
| 20828 | } |
| 20829 | |
| 20830 | { |
| 20831 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20832 | vinfos[0].jointtype = 1; |
| 20833 | vinfos[0].foffset = j0; |
| 20834 | vinfos[0].indices[0] = _ij0[0]; |
| 20835 | vinfos[0].indices[1] = _ij0[1]; |
| 20836 | vinfos[0].maxsolutions = _nj0; |
| 20837 | vinfos[1].jointtype = 1; |
| 20838 | vinfos[1].foffset = j1; |
| 20839 | vinfos[1].indices[0] = _ij1[0]; |
| 20840 | vinfos[1].indices[1] = _ij1[1]; |
| 20841 | vinfos[1].maxsolutions = _nj1; |
| 20842 | vinfos[2].jointtype = 1; |
| 20843 | vinfos[2].foffset = j2; |
| 20844 | vinfos[2].indices[0] = _ij2[0]; |
| 20845 | vinfos[2].indices[1] = _ij2[1]; |
| 20846 | vinfos[2].maxsolutions = _nj2; |
| 20847 | vinfos[3].jointtype = 1; |
| 20848 | vinfos[3].foffset = j3; |
| 20849 | vinfos[3].indices[0] = _ij3[0]; |
| 20850 | vinfos[3].indices[1] = _ij3[1]; |
| 20851 | vinfos[3].maxsolutions = _nj3; |
| 20852 | vinfos[4].jointtype = 1; |
| 20853 | vinfos[4].foffset = j4; |
| 20854 | vinfos[4].indices[0] = _ij4[0]; |
| 20855 | vinfos[4].indices[1] = _ij4[1]; |
| 20856 | vinfos[4].maxsolutions = _nj4; |
| 20857 | vinfos[5].jointtype = 1; |
| 20858 | vinfos[5].foffset = j5; |
| 20859 | vinfos[5].indices[0] = _ij5[0]; |
| 20860 | vinfos[5].indices[1] = _ij5[1]; |
| 20861 | vinfos[5].maxsolutions = _nj5; |
| 20862 | std::vector<int> vfree(0); |
| 20863 | solutions.AddSolution(vinfos,vfree); |
| 20864 | } |
| 20865 | } |
| 20866 | } |
| 20867 | |
| 20868 | } |
| 20869 | |
| 20870 | } |
| 20871 | |
| 20872 | } else |
| 20873 | { |
| 20874 | { |
| 20875 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20876 | bool j0valid[1]={false}; |
| 20877 | _nj0 = 1; |
| 20878 | CheckValue<IkReal> x1574 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 20879 | if(!x1574.valid){ |
| 20880 | continue; |
| 20881 | } |
| 20882 | CheckValue<IkReal> x1575=IKPowWithIntegerCheck(IKsign(gconst39),-1); |
| 20883 | if(!x1575.valid){ |
| 20884 | continue; |
| 20885 | } |
| 20886 | j0array[0]=((-1.5707963267949)+(x1574.value)+(((1.5707963267949)*(x1575.value)))); |
| 20887 | sj0array[0]=IKsin(j0array[0]); |
| 20888 | cj0array[0]=IKcos(j0array[0]); |
| 20889 | if( j0array[0] > IKPI ) |
| 20890 | { |
| 20891 | j0array[0]-=IK2PI; |
| 20892 | } |
| 20893 | else if( j0array[0] < -IKPI ) |
| 20894 | { j0array[0]+=IK2PI; |
| 20895 | } |
| 20896 | j0valid[0] = true; |
| 20897 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 20898 | { |
| 20899 | if( !j0valid[ij0] ) |
| 20900 | { |
| 20901 | continue; |
| 20902 | } |
| 20903 | _ij0[0] = ij0; _ij0[1] = -1; |
| 20904 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 20905 | { |
| 20906 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 20907 | { |
| 20908 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 20909 | } |
| 20910 | } |
| 20911 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 20912 | { |
| 20913 | IkReal evalcond[8]; |
| 20914 | IkReal x1576=IKsin(j0); |
| 20915 | IkReal x1577=IKcos(j0); |
| 20916 | IkReal x1578=((1.0)*x1577); |
| 20917 | IkReal x1579=(gconst39*x1578); |
| 20918 | IkReal x1580=((-1.0)*x1576); |
| 20919 | evalcond[0]=(new_r01*x1580); |
| 20920 | evalcond[1]=(gconst39*x1580); |
| 20921 | evalcond[2]=(((gconst39*x1576))+new_r00); |
| 20922 | evalcond[3]=(new_r01+(((-1.0)*x1579))); |
| 20923 | evalcond[4]=(new_r10+(((-1.0)*x1579))); |
| 20924 | evalcond[5]=(((new_r01*x1577))+(((-1.0)*gconst39))); |
| 20925 | evalcond[6]=(((new_r00*x1577))+((new_r10*x1576))); |
| 20926 | evalcond[7]=(((new_r00*x1576))+(((-1.0)*new_r10*x1578))+gconst39); |
| 20927 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 20928 | { |
| 20929 | continue; |
| 20930 | } |
| 20931 | } |
| 20932 | |
| 20933 | { |
| 20934 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 20935 | vinfos[0].jointtype = 1; |
| 20936 | vinfos[0].foffset = j0; |
| 20937 | vinfos[0].indices[0] = _ij0[0]; |
| 20938 | vinfos[0].indices[1] = _ij0[1]; |
| 20939 | vinfos[0].maxsolutions = _nj0; |
| 20940 | vinfos[1].jointtype = 1; |
| 20941 | vinfos[1].foffset = j1; |
| 20942 | vinfos[1].indices[0] = _ij1[0]; |
| 20943 | vinfos[1].indices[1] = _ij1[1]; |
| 20944 | vinfos[1].maxsolutions = _nj1; |
| 20945 | vinfos[2].jointtype = 1; |
| 20946 | vinfos[2].foffset = j2; |
| 20947 | vinfos[2].indices[0] = _ij2[0]; |
| 20948 | vinfos[2].indices[1] = _ij2[1]; |
| 20949 | vinfos[2].maxsolutions = _nj2; |
| 20950 | vinfos[3].jointtype = 1; |
| 20951 | vinfos[3].foffset = j3; |
| 20952 | vinfos[3].indices[0] = _ij3[0]; |
| 20953 | vinfos[3].indices[1] = _ij3[1]; |
| 20954 | vinfos[3].maxsolutions = _nj3; |
| 20955 | vinfos[4].jointtype = 1; |
| 20956 | vinfos[4].foffset = j4; |
| 20957 | vinfos[4].indices[0] = _ij4[0]; |
| 20958 | vinfos[4].indices[1] = _ij4[1]; |
| 20959 | vinfos[4].maxsolutions = _nj4; |
| 20960 | vinfos[5].jointtype = 1; |
| 20961 | vinfos[5].foffset = j5; |
| 20962 | vinfos[5].indices[0] = _ij5[0]; |
| 20963 | vinfos[5].indices[1] = _ij5[1]; |
| 20964 | vinfos[5].maxsolutions = _nj5; |
| 20965 | std::vector<int> vfree(0); |
| 20966 | solutions.AddSolution(vinfos,vfree); |
| 20967 | } |
| 20968 | } |
| 20969 | } |
| 20970 | |
| 20971 | } |
| 20972 | |
| 20973 | } |
| 20974 | |
| 20975 | } else |
| 20976 | { |
| 20977 | { |
| 20978 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 20979 | bool j0valid[1]={false}; |
| 20980 | _nj0 = 1; |
| 20981 | CheckValue<IkReal> x1581 = IKatan2WithCheck(IkReal(((-1.0)*new_r00)),IkReal(new_r01),IKFAST_ATAN2_MAGTHRESH); |
| 20982 | if(!x1581.valid){ |
| 20983 | continue; |
| 20984 | } |
| 20985 | CheckValue<IkReal> x1582=IKPowWithIntegerCheck(IKsign(gconst39),-1); |
| 20986 | if(!x1582.valid){ |
| 20987 | continue; |
| 20988 | } |
| 20989 | j0array[0]=((-1.5707963267949)+(x1581.value)+(((1.5707963267949)*(x1582.value)))); |
| 20990 | sj0array[0]=IKsin(j0array[0]); |
| 20991 | cj0array[0]=IKcos(j0array[0]); |
| 20992 | if( j0array[0] > IKPI ) |
| 20993 | { |
| 20994 | j0array[0]-=IK2PI; |
| 20995 | } |
| 20996 | else if( j0array[0] < -IKPI ) |
| 20997 | { j0array[0]+=IK2PI; |
| 20998 | } |
| 20999 | j0valid[0] = true; |
| 21000 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21001 | { |
| 21002 | if( !j0valid[ij0] ) |
| 21003 | { |
| 21004 | continue; |
| 21005 | } |
| 21006 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21007 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21008 | { |
| 21009 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21010 | { |
| 21011 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21012 | } |
| 21013 | } |
| 21014 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21015 | { |
| 21016 | IkReal evalcond[8]; |
| 21017 | IkReal x1583=IKsin(j0); |
| 21018 | IkReal x1584=IKcos(j0); |
| 21019 | IkReal x1585=((1.0)*x1584); |
| 21020 | IkReal x1586=(gconst39*x1585); |
| 21021 | IkReal x1587=((-1.0)*x1583); |
| 21022 | evalcond[0]=(new_r01*x1587); |
| 21023 | evalcond[1]=(gconst39*x1587); |
| 21024 | evalcond[2]=(((gconst39*x1583))+new_r00); |
| 21025 | evalcond[3]=((((-1.0)*x1586))+new_r01); |
| 21026 | evalcond[4]=((((-1.0)*x1586))+new_r10); |
| 21027 | evalcond[5]=(((new_r01*x1584))+(((-1.0)*gconst39))); |
| 21028 | evalcond[6]=(((new_r10*x1583))+((new_r00*x1584))); |
| 21029 | evalcond[7]=(((new_r00*x1583))+(((-1.0)*new_r10*x1585))+gconst39); |
| 21030 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21031 | { |
| 21032 | continue; |
| 21033 | } |
| 21034 | } |
| 21035 | |
| 21036 | { |
| 21037 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21038 | vinfos[0].jointtype = 1; |
| 21039 | vinfos[0].foffset = j0; |
| 21040 | vinfos[0].indices[0] = _ij0[0]; |
| 21041 | vinfos[0].indices[1] = _ij0[1]; |
| 21042 | vinfos[0].maxsolutions = _nj0; |
| 21043 | vinfos[1].jointtype = 1; |
| 21044 | vinfos[1].foffset = j1; |
| 21045 | vinfos[1].indices[0] = _ij1[0]; |
| 21046 | vinfos[1].indices[1] = _ij1[1]; |
| 21047 | vinfos[1].maxsolutions = _nj1; |
| 21048 | vinfos[2].jointtype = 1; |
| 21049 | vinfos[2].foffset = j2; |
| 21050 | vinfos[2].indices[0] = _ij2[0]; |
| 21051 | vinfos[2].indices[1] = _ij2[1]; |
| 21052 | vinfos[2].maxsolutions = _nj2; |
| 21053 | vinfos[3].jointtype = 1; |
| 21054 | vinfos[3].foffset = j3; |
| 21055 | vinfos[3].indices[0] = _ij3[0]; |
| 21056 | vinfos[3].indices[1] = _ij3[1]; |
| 21057 | vinfos[3].maxsolutions = _nj3; |
| 21058 | vinfos[4].jointtype = 1; |
| 21059 | vinfos[4].foffset = j4; |
| 21060 | vinfos[4].indices[0] = _ij4[0]; |
| 21061 | vinfos[4].indices[1] = _ij4[1]; |
| 21062 | vinfos[4].maxsolutions = _nj4; |
| 21063 | vinfos[5].jointtype = 1; |
| 21064 | vinfos[5].foffset = j5; |
| 21065 | vinfos[5].indices[0] = _ij5[0]; |
| 21066 | vinfos[5].indices[1] = _ij5[1]; |
| 21067 | vinfos[5].maxsolutions = _nj5; |
| 21068 | std::vector<int> vfree(0); |
| 21069 | solutions.AddSolution(vinfos,vfree); |
| 21070 | } |
| 21071 | } |
| 21072 | } |
| 21073 | |
| 21074 | } |
| 21075 | |
| 21076 | } |
| 21077 | |
| 21078 | } |
| 21079 | } while(0); |
| 21080 | if( bgotonextstatement ) |
| 21081 | { |
| 21082 | bool bgotonextstatement = true; |
| 21083 | do |
| 21084 | { |
| 21085 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 21086 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 21087 | { |
| 21088 | bgotonextstatement=false; |
| 21089 | { |
| 21090 | IkReal j0eval[1]; |
| 21091 | CheckValue<IkReal> x1589 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 21092 | if(!x1589.valid){ |
| 21093 | continue; |
| 21094 | } |
| 21095 | IkReal x1588=((1.0)*(x1589.value)); |
| 21096 | sj1=-1.0; |
| 21097 | cj1=0; |
| 21098 | j1=-1.5707963267949; |
| 21099 | sj2=gconst38; |
| 21100 | cj2=gconst39; |
| 21101 | j2=((3.14159265)+(((-1.0)*x1588))); |
| 21102 | new_r00=0; |
| 21103 | new_r01=0; |
| 21104 | new_r12=0; |
| 21105 | new_r22=0; |
| 21106 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1588))); |
| 21107 | IkReal x1590 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 21108 | if(IKabs(x1590)==0){ |
| 21109 | continue; |
| 21110 | } |
| 21111 | IkReal gconst38=((1.0)*new_r11*(pow(x1590,-0.5))); |
| 21112 | IkReal gconst39=0; |
| 21113 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 21114 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 21115 | { |
| 21116 | { |
| 21117 | IkReal j0eval[1]; |
| 21118 | CheckValue<IkReal> x1592 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 21119 | if(!x1592.valid){ |
| 21120 | continue; |
| 21121 | } |
| 21122 | IkReal x1591=((1.0)*(x1592.value)); |
| 21123 | sj1=-1.0; |
| 21124 | cj1=0; |
| 21125 | j1=-1.5707963267949; |
| 21126 | sj2=gconst38; |
| 21127 | cj2=gconst39; |
| 21128 | j2=((3.14159265)+(((-1.0)*x1591))); |
| 21129 | new_r00=0; |
| 21130 | new_r01=0; |
| 21131 | new_r12=0; |
| 21132 | new_r22=0; |
| 21133 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1591))); |
| 21134 | IkReal x1593 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 21135 | if(IKabs(x1593)==0){ |
| 21136 | continue; |
| 21137 | } |
| 21138 | IkReal gconst38=((1.0)*new_r11*(pow(x1593,-0.5))); |
| 21139 | IkReal gconst39=0; |
| 21140 | j0eval[0]=new_r11; |
| 21141 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 21142 | { |
| 21143 | { |
| 21144 | IkReal j0eval[2]; |
| 21145 | CheckValue<IkReal> x1595 = IKatan2WithCheck(IkReal(new_r11),IkReal(0),IKFAST_ATAN2_MAGTHRESH); |
| 21146 | if(!x1595.valid){ |
| 21147 | continue; |
| 21148 | } |
| 21149 | IkReal x1594=((1.0)*(x1595.value)); |
| 21150 | sj1=-1.0; |
| 21151 | cj1=0; |
| 21152 | j1=-1.5707963267949; |
| 21153 | sj2=gconst38; |
| 21154 | cj2=gconst39; |
| 21155 | j2=((3.14159265)+(((-1.0)*x1594))); |
| 21156 | new_r00=0; |
| 21157 | new_r01=0; |
| 21158 | new_r12=0; |
| 21159 | new_r22=0; |
| 21160 | IkReal gconst37=((3.14159265358979)+(((-1.0)*x1594))); |
| 21161 | IkReal x1596 = ((1.0)+(((-1.0)*(new_r10*new_r10)))); |
| 21162 | if(IKabs(x1596)==0){ |
| 21163 | continue; |
| 21164 | } |
| 21165 | IkReal gconst38=((1.0)*new_r11*(pow(x1596,-0.5))); |
| 21166 | IkReal gconst39=0; |
| 21167 | j0eval[0]=new_r10; |
| 21168 | j0eval[1]=new_r11; |
| 21169 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 21170 | { |
| 21171 | continue; // 3 cases reached |
| 21172 | |
| 21173 | } else |
| 21174 | { |
| 21175 | { |
| 21176 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21177 | bool j0valid[1]={false}; |
| 21178 | _nj0 = 1; |
| 21179 | CheckValue<IkReal> x1597=IKPowWithIntegerCheck(new_r10,-1); |
| 21180 | if(!x1597.valid){ |
| 21181 | continue; |
| 21182 | } |
| 21183 | CheckValue<IkReal> x1598=IKPowWithIntegerCheck(new_r11,-1); |
| 21184 | if(!x1598.valid){ |
| 21185 | continue; |
| 21186 | } |
| 21187 | if( IKabs((gconst38*(x1597.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst38*(x1598.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((gconst38*(x1597.value)))+IKsqr(((-1.0)*gconst38*(x1598.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 21188 | continue; |
| 21189 | j0array[0]=IKatan2((gconst38*(x1597.value)), ((-1.0)*gconst38*(x1598.value))); |
| 21190 | sj0array[0]=IKsin(j0array[0]); |
| 21191 | cj0array[0]=IKcos(j0array[0]); |
| 21192 | if( j0array[0] > IKPI ) |
| 21193 | { |
| 21194 | j0array[0]-=IK2PI; |
| 21195 | } |
| 21196 | else if( j0array[0] < -IKPI ) |
| 21197 | { j0array[0]+=IK2PI; |
| 21198 | } |
| 21199 | j0valid[0] = true; |
| 21200 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21201 | { |
| 21202 | if( !j0valid[ij0] ) |
| 21203 | { |
| 21204 | continue; |
| 21205 | } |
| 21206 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21207 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21208 | { |
| 21209 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21210 | { |
| 21211 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21212 | } |
| 21213 | } |
| 21214 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21215 | { |
| 21216 | IkReal evalcond[8]; |
| 21217 | IkReal x1599=IKcos(j0); |
| 21218 | IkReal x1600=IKsin(j0); |
| 21219 | IkReal x1601=(gconst38*x1600); |
| 21220 | IkReal x1602=(gconst38*x1599); |
| 21221 | evalcond[0]=(new_r11*x1600); |
| 21222 | evalcond[1]=((-1.0)*new_r10*x1599); |
| 21223 | evalcond[2]=((-1.0)*x1602); |
| 21224 | evalcond[3]=((-1.0)*x1601); |
| 21225 | evalcond[4]=(((new_r11*x1599))+gconst38); |
| 21226 | evalcond[5]=(x1602+new_r11); |
| 21227 | evalcond[6]=((((-1.0)*x1601))+new_r10); |
| 21228 | evalcond[7]=(((new_r10*x1600))+(((-1.0)*gconst38))); |
| 21229 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21230 | { |
| 21231 | continue; |
| 21232 | } |
| 21233 | } |
| 21234 | |
| 21235 | { |
| 21236 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21237 | vinfos[0].jointtype = 1; |
| 21238 | vinfos[0].foffset = j0; |
| 21239 | vinfos[0].indices[0] = _ij0[0]; |
| 21240 | vinfos[0].indices[1] = _ij0[1]; |
| 21241 | vinfos[0].maxsolutions = _nj0; |
| 21242 | vinfos[1].jointtype = 1; |
| 21243 | vinfos[1].foffset = j1; |
| 21244 | vinfos[1].indices[0] = _ij1[0]; |
| 21245 | vinfos[1].indices[1] = _ij1[1]; |
| 21246 | vinfos[1].maxsolutions = _nj1; |
| 21247 | vinfos[2].jointtype = 1; |
| 21248 | vinfos[2].foffset = j2; |
| 21249 | vinfos[2].indices[0] = _ij2[0]; |
| 21250 | vinfos[2].indices[1] = _ij2[1]; |
| 21251 | vinfos[2].maxsolutions = _nj2; |
| 21252 | vinfos[3].jointtype = 1; |
| 21253 | vinfos[3].foffset = j3; |
| 21254 | vinfos[3].indices[0] = _ij3[0]; |
| 21255 | vinfos[3].indices[1] = _ij3[1]; |
| 21256 | vinfos[3].maxsolutions = _nj3; |
| 21257 | vinfos[4].jointtype = 1; |
| 21258 | vinfos[4].foffset = j4; |
| 21259 | vinfos[4].indices[0] = _ij4[0]; |
| 21260 | vinfos[4].indices[1] = _ij4[1]; |
| 21261 | vinfos[4].maxsolutions = _nj4; |
| 21262 | vinfos[5].jointtype = 1; |
| 21263 | vinfos[5].foffset = j5; |
| 21264 | vinfos[5].indices[0] = _ij5[0]; |
| 21265 | vinfos[5].indices[1] = _ij5[1]; |
| 21266 | vinfos[5].maxsolutions = _nj5; |
| 21267 | std::vector<int> vfree(0); |
| 21268 | solutions.AddSolution(vinfos,vfree); |
| 21269 | } |
| 21270 | } |
| 21271 | } |
| 21272 | |
| 21273 | } |
| 21274 | |
| 21275 | } |
| 21276 | |
| 21277 | } else |
| 21278 | { |
| 21279 | { |
| 21280 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21281 | bool j0valid[1]={false}; |
| 21282 | _nj0 = 1; |
| 21283 | CheckValue<IkReal> x1603=IKPowWithIntegerCheck(gconst38,-1); |
| 21284 | if(!x1603.valid){ |
| 21285 | continue; |
| 21286 | } |
| 21287 | CheckValue<IkReal> x1604=IKPowWithIntegerCheck(new_r11,-1); |
| 21288 | if(!x1604.valid){ |
| 21289 | continue; |
| 21290 | } |
| 21291 | if( IKabs((new_r10*(x1603.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*gconst38*(x1604.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r10*(x1603.value)))+IKsqr(((-1.0)*gconst38*(x1604.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 21292 | continue; |
| 21293 | j0array[0]=IKatan2((new_r10*(x1603.value)), ((-1.0)*gconst38*(x1604.value))); |
| 21294 | sj0array[0]=IKsin(j0array[0]); |
| 21295 | cj0array[0]=IKcos(j0array[0]); |
| 21296 | if( j0array[0] > IKPI ) |
| 21297 | { |
| 21298 | j0array[0]-=IK2PI; |
| 21299 | } |
| 21300 | else if( j0array[0] < -IKPI ) |
| 21301 | { j0array[0]+=IK2PI; |
| 21302 | } |
| 21303 | j0valid[0] = true; |
| 21304 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21305 | { |
| 21306 | if( !j0valid[ij0] ) |
| 21307 | { |
| 21308 | continue; |
| 21309 | } |
| 21310 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21311 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21312 | { |
| 21313 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21314 | { |
| 21315 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21316 | } |
| 21317 | } |
| 21318 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21319 | { |
| 21320 | IkReal evalcond[8]; |
| 21321 | IkReal x1605=IKcos(j0); |
| 21322 | IkReal x1606=IKsin(j0); |
| 21323 | IkReal x1607=(gconst38*x1606); |
| 21324 | IkReal x1608=(gconst38*x1605); |
| 21325 | evalcond[0]=(new_r11*x1606); |
| 21326 | evalcond[1]=((-1.0)*new_r10*x1605); |
| 21327 | evalcond[2]=((-1.0)*x1608); |
| 21328 | evalcond[3]=((-1.0)*x1607); |
| 21329 | evalcond[4]=(gconst38+((new_r11*x1605))); |
| 21330 | evalcond[5]=(x1608+new_r11); |
| 21331 | evalcond[6]=((((-1.0)*x1607))+new_r10); |
| 21332 | evalcond[7]=(((new_r10*x1606))+(((-1.0)*gconst38))); |
| 21333 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21334 | { |
| 21335 | continue; |
| 21336 | } |
| 21337 | } |
| 21338 | |
| 21339 | { |
| 21340 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21341 | vinfos[0].jointtype = 1; |
| 21342 | vinfos[0].foffset = j0; |
| 21343 | vinfos[0].indices[0] = _ij0[0]; |
| 21344 | vinfos[0].indices[1] = _ij0[1]; |
| 21345 | vinfos[0].maxsolutions = _nj0; |
| 21346 | vinfos[1].jointtype = 1; |
| 21347 | vinfos[1].foffset = j1; |
| 21348 | vinfos[1].indices[0] = _ij1[0]; |
| 21349 | vinfos[1].indices[1] = _ij1[1]; |
| 21350 | vinfos[1].maxsolutions = _nj1; |
| 21351 | vinfos[2].jointtype = 1; |
| 21352 | vinfos[2].foffset = j2; |
| 21353 | vinfos[2].indices[0] = _ij2[0]; |
| 21354 | vinfos[2].indices[1] = _ij2[1]; |
| 21355 | vinfos[2].maxsolutions = _nj2; |
| 21356 | vinfos[3].jointtype = 1; |
| 21357 | vinfos[3].foffset = j3; |
| 21358 | vinfos[3].indices[0] = _ij3[0]; |
| 21359 | vinfos[3].indices[1] = _ij3[1]; |
| 21360 | vinfos[3].maxsolutions = _nj3; |
| 21361 | vinfos[4].jointtype = 1; |
| 21362 | vinfos[4].foffset = j4; |
| 21363 | vinfos[4].indices[0] = _ij4[0]; |
| 21364 | vinfos[4].indices[1] = _ij4[1]; |
| 21365 | vinfos[4].maxsolutions = _nj4; |
| 21366 | vinfos[5].jointtype = 1; |
| 21367 | vinfos[5].foffset = j5; |
| 21368 | vinfos[5].indices[0] = _ij5[0]; |
| 21369 | vinfos[5].indices[1] = _ij5[1]; |
| 21370 | vinfos[5].maxsolutions = _nj5; |
| 21371 | std::vector<int> vfree(0); |
| 21372 | solutions.AddSolution(vinfos,vfree); |
| 21373 | } |
| 21374 | } |
| 21375 | } |
| 21376 | |
| 21377 | } |
| 21378 | |
| 21379 | } |
| 21380 | |
| 21381 | } else |
| 21382 | { |
| 21383 | { |
| 21384 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21385 | bool j0valid[1]={false}; |
| 21386 | _nj0 = 1; |
| 21387 | CheckValue<IkReal> x1609 = IKatan2WithCheck(IkReal(new_r10),IkReal(((-1.0)*new_r11)),IKFAST_ATAN2_MAGTHRESH); |
| 21388 | if(!x1609.valid){ |
| 21389 | continue; |
| 21390 | } |
| 21391 | CheckValue<IkReal> x1610=IKPowWithIntegerCheck(IKsign(gconst38),-1); |
| 21392 | if(!x1610.valid){ |
| 21393 | continue; |
| 21394 | } |
| 21395 | j0array[0]=((-1.5707963267949)+(x1609.value)+(((1.5707963267949)*(x1610.value)))); |
| 21396 | sj0array[0]=IKsin(j0array[0]); |
| 21397 | cj0array[0]=IKcos(j0array[0]); |
| 21398 | if( j0array[0] > IKPI ) |
| 21399 | { |
| 21400 | j0array[0]-=IK2PI; |
| 21401 | } |
| 21402 | else if( j0array[0] < -IKPI ) |
| 21403 | { j0array[0]+=IK2PI; |
| 21404 | } |
| 21405 | j0valid[0] = true; |
| 21406 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21407 | { |
| 21408 | if( !j0valid[ij0] ) |
| 21409 | { |
| 21410 | continue; |
| 21411 | } |
| 21412 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21413 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21414 | { |
| 21415 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21416 | { |
| 21417 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21418 | } |
| 21419 | } |
| 21420 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21421 | { |
| 21422 | IkReal evalcond[8]; |
| 21423 | IkReal x1611=IKcos(j0); |
| 21424 | IkReal x1612=IKsin(j0); |
| 21425 | IkReal x1613=(gconst38*x1612); |
| 21426 | IkReal x1614=(gconst38*x1611); |
| 21427 | evalcond[0]=(new_r11*x1612); |
| 21428 | evalcond[1]=((-1.0)*new_r10*x1611); |
| 21429 | evalcond[2]=((-1.0)*x1614); |
| 21430 | evalcond[3]=((-1.0)*x1613); |
| 21431 | evalcond[4]=(((new_r11*x1611))+gconst38); |
| 21432 | evalcond[5]=(x1614+new_r11); |
| 21433 | evalcond[6]=((((-1.0)*x1613))+new_r10); |
| 21434 | evalcond[7]=(((new_r10*x1612))+(((-1.0)*gconst38))); |
| 21435 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21436 | { |
| 21437 | continue; |
| 21438 | } |
| 21439 | } |
| 21440 | |
| 21441 | { |
| 21442 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21443 | vinfos[0].jointtype = 1; |
| 21444 | vinfos[0].foffset = j0; |
| 21445 | vinfos[0].indices[0] = _ij0[0]; |
| 21446 | vinfos[0].indices[1] = _ij0[1]; |
| 21447 | vinfos[0].maxsolutions = _nj0; |
| 21448 | vinfos[1].jointtype = 1; |
| 21449 | vinfos[1].foffset = j1; |
| 21450 | vinfos[1].indices[0] = _ij1[0]; |
| 21451 | vinfos[1].indices[1] = _ij1[1]; |
| 21452 | vinfos[1].maxsolutions = _nj1; |
| 21453 | vinfos[2].jointtype = 1; |
| 21454 | vinfos[2].foffset = j2; |
| 21455 | vinfos[2].indices[0] = _ij2[0]; |
| 21456 | vinfos[2].indices[1] = _ij2[1]; |
| 21457 | vinfos[2].maxsolutions = _nj2; |
| 21458 | vinfos[3].jointtype = 1; |
| 21459 | vinfos[3].foffset = j3; |
| 21460 | vinfos[3].indices[0] = _ij3[0]; |
| 21461 | vinfos[3].indices[1] = _ij3[1]; |
| 21462 | vinfos[3].maxsolutions = _nj3; |
| 21463 | vinfos[4].jointtype = 1; |
| 21464 | vinfos[4].foffset = j4; |
| 21465 | vinfos[4].indices[0] = _ij4[0]; |
| 21466 | vinfos[4].indices[1] = _ij4[1]; |
| 21467 | vinfos[4].maxsolutions = _nj4; |
| 21468 | vinfos[5].jointtype = 1; |
| 21469 | vinfos[5].foffset = j5; |
| 21470 | vinfos[5].indices[0] = _ij5[0]; |
| 21471 | vinfos[5].indices[1] = _ij5[1]; |
| 21472 | vinfos[5].maxsolutions = _nj5; |
| 21473 | std::vector<int> vfree(0); |
| 21474 | solutions.AddSolution(vinfos,vfree); |
| 21475 | } |
| 21476 | } |
| 21477 | } |
| 21478 | |
| 21479 | } |
| 21480 | |
| 21481 | } |
| 21482 | |
| 21483 | } |
| 21484 | } while(0); |
| 21485 | if( bgotonextstatement ) |
| 21486 | { |
| 21487 | bool bgotonextstatement = true; |
| 21488 | do |
| 21489 | { |
| 21490 | if( 1 ) |
| 21491 | { |
| 21492 | bgotonextstatement=false; |
| 21493 | continue; // branch miss [j0] |
| 21494 | |
| 21495 | } |
| 21496 | } while(0); |
| 21497 | if( bgotonextstatement ) |
| 21498 | { |
| 21499 | } |
| 21500 | } |
| 21501 | } |
| 21502 | } |
| 21503 | } |
| 21504 | } |
| 21505 | } |
| 21506 | |
| 21507 | } else |
| 21508 | { |
| 21509 | { |
| 21510 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21511 | bool j0valid[1]={false}; |
| 21512 | _nj0 = 1; |
| 21513 | CheckValue<IkReal> x1615 = IKatan2WithCheck(IkReal((((gconst38*new_r00))+((gconst38*new_r11)))),IkReal(((((-1.0)*gconst38*new_r10))+((gconst38*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 21514 | if(!x1615.valid){ |
| 21515 | continue; |
| 21516 | } |
| 21517 | CheckValue<IkReal> x1616=IKPowWithIntegerCheck(IKsign((((new_r10*new_r11))+((new_r00*new_r01)))),-1); |
| 21518 | if(!x1616.valid){ |
| 21519 | continue; |
| 21520 | } |
| 21521 | j0array[0]=((-1.5707963267949)+(x1615.value)+(((1.5707963267949)*(x1616.value)))); |
| 21522 | sj0array[0]=IKsin(j0array[0]); |
| 21523 | cj0array[0]=IKcos(j0array[0]); |
| 21524 | if( j0array[0] > IKPI ) |
| 21525 | { |
| 21526 | j0array[0]-=IK2PI; |
| 21527 | } |
| 21528 | else if( j0array[0] < -IKPI ) |
| 21529 | { j0array[0]+=IK2PI; |
| 21530 | } |
| 21531 | j0valid[0] = true; |
| 21532 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21533 | { |
| 21534 | if( !j0valid[ij0] ) |
| 21535 | { |
| 21536 | continue; |
| 21537 | } |
| 21538 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21539 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21540 | { |
| 21541 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21542 | { |
| 21543 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21544 | } |
| 21545 | } |
| 21546 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21547 | { |
| 21548 | IkReal evalcond[8]; |
| 21549 | IkReal x1617=IKsin(j0); |
| 21550 | IkReal x1618=IKcos(j0); |
| 21551 | IkReal x1619=((1.0)*gconst39); |
| 21552 | IkReal x1620=((1.0)*gconst38); |
| 21553 | IkReal x1621=((1.0)*x1618); |
| 21554 | IkReal x1622=(((x1617*x1620))+((x1618*x1619))); |
| 21555 | evalcond[0]=(((new_r11*x1618))+(((-1.0)*new_r01*x1617))+gconst38); |
| 21556 | evalcond[1]=((((-1.0)*new_r10*x1621))+gconst39+((new_r00*x1617))); |
| 21557 | evalcond[2]=(((gconst39*x1617))+new_r00+(((-1.0)*x1618*x1620))); |
| 21558 | evalcond[3]=(((gconst38*x1618))+(((-1.0)*x1617*x1619))+new_r11); |
| 21559 | evalcond[4]=(((new_r10*x1617))+(((-1.0)*x1620))+((new_r00*x1618))); |
| 21560 | evalcond[5]=(((new_r11*x1617))+(((-1.0)*x1619))+((new_r01*x1618))); |
| 21561 | evalcond[6]=((((-1.0)*x1622))+new_r01); |
| 21562 | evalcond[7]=((((-1.0)*x1622))+new_r10); |
| 21563 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21564 | { |
| 21565 | continue; |
| 21566 | } |
| 21567 | } |
| 21568 | |
| 21569 | { |
| 21570 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21571 | vinfos[0].jointtype = 1; |
| 21572 | vinfos[0].foffset = j0; |
| 21573 | vinfos[0].indices[0] = _ij0[0]; |
| 21574 | vinfos[0].indices[1] = _ij0[1]; |
| 21575 | vinfos[0].maxsolutions = _nj0; |
| 21576 | vinfos[1].jointtype = 1; |
| 21577 | vinfos[1].foffset = j1; |
| 21578 | vinfos[1].indices[0] = _ij1[0]; |
| 21579 | vinfos[1].indices[1] = _ij1[1]; |
| 21580 | vinfos[1].maxsolutions = _nj1; |
| 21581 | vinfos[2].jointtype = 1; |
| 21582 | vinfos[2].foffset = j2; |
| 21583 | vinfos[2].indices[0] = _ij2[0]; |
| 21584 | vinfos[2].indices[1] = _ij2[1]; |
| 21585 | vinfos[2].maxsolutions = _nj2; |
| 21586 | vinfos[3].jointtype = 1; |
| 21587 | vinfos[3].foffset = j3; |
| 21588 | vinfos[3].indices[0] = _ij3[0]; |
| 21589 | vinfos[3].indices[1] = _ij3[1]; |
| 21590 | vinfos[3].maxsolutions = _nj3; |
| 21591 | vinfos[4].jointtype = 1; |
| 21592 | vinfos[4].foffset = j4; |
| 21593 | vinfos[4].indices[0] = _ij4[0]; |
| 21594 | vinfos[4].indices[1] = _ij4[1]; |
| 21595 | vinfos[4].maxsolutions = _nj4; |
| 21596 | vinfos[5].jointtype = 1; |
| 21597 | vinfos[5].foffset = j5; |
| 21598 | vinfos[5].indices[0] = _ij5[0]; |
| 21599 | vinfos[5].indices[1] = _ij5[1]; |
| 21600 | vinfos[5].maxsolutions = _nj5; |
| 21601 | std::vector<int> vfree(0); |
| 21602 | solutions.AddSolution(vinfos,vfree); |
| 21603 | } |
| 21604 | } |
| 21605 | } |
| 21606 | |
| 21607 | } |
| 21608 | |
| 21609 | } |
| 21610 | |
| 21611 | } else |
| 21612 | { |
| 21613 | { |
| 21614 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21615 | bool j0valid[1]={false}; |
| 21616 | _nj0 = 1; |
| 21617 | CheckValue<IkReal> x1623=IKPowWithIntegerCheck(IKsign(((((-1.0)*gconst38*new_r00))+((gconst39*new_r10)))),-1); |
| 21618 | if(!x1623.valid){ |
| 21619 | continue; |
| 21620 | } |
| 21621 | CheckValue<IkReal> x1624 = IKatan2WithCheck(IkReal((((new_r10*new_r11))+((gconst38*gconst39)))),IkReal((((new_r00*new_r11))+(gconst39*gconst39))),IKFAST_ATAN2_MAGTHRESH); |
| 21622 | if(!x1624.valid){ |
| 21623 | continue; |
| 21624 | } |
| 21625 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1623.value)))+(x1624.value)); |
| 21626 | sj0array[0]=IKsin(j0array[0]); |
| 21627 | cj0array[0]=IKcos(j0array[0]); |
| 21628 | if( j0array[0] > IKPI ) |
| 21629 | { |
| 21630 | j0array[0]-=IK2PI; |
| 21631 | } |
| 21632 | else if( j0array[0] < -IKPI ) |
| 21633 | { j0array[0]+=IK2PI; |
| 21634 | } |
| 21635 | j0valid[0] = true; |
| 21636 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21637 | { |
| 21638 | if( !j0valid[ij0] ) |
| 21639 | { |
| 21640 | continue; |
| 21641 | } |
| 21642 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21643 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21644 | { |
| 21645 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21646 | { |
| 21647 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21648 | } |
| 21649 | } |
| 21650 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21651 | { |
| 21652 | IkReal evalcond[8]; |
| 21653 | IkReal x1625=IKsin(j0); |
| 21654 | IkReal x1626=IKcos(j0); |
| 21655 | IkReal x1627=((1.0)*gconst39); |
| 21656 | IkReal x1628=((1.0)*gconst38); |
| 21657 | IkReal x1629=((1.0)*x1626); |
| 21658 | IkReal x1630=(((x1626*x1627))+((x1625*x1628))); |
| 21659 | evalcond[0]=(((new_r11*x1626))+(((-1.0)*new_r01*x1625))+gconst38); |
| 21660 | evalcond[1]=((((-1.0)*new_r10*x1629))+gconst39+((new_r00*x1625))); |
| 21661 | evalcond[2]=(((gconst39*x1625))+new_r00+(((-1.0)*x1626*x1628))); |
| 21662 | evalcond[3]=(((gconst38*x1626))+(((-1.0)*x1625*x1627))+new_r11); |
| 21663 | evalcond[4]=(((new_r10*x1625))+(((-1.0)*x1628))+((new_r00*x1626))); |
| 21664 | evalcond[5]=(((new_r11*x1625))+((new_r01*x1626))+(((-1.0)*x1627))); |
| 21665 | evalcond[6]=((((-1.0)*x1630))+new_r01); |
| 21666 | evalcond[7]=((((-1.0)*x1630))+new_r10); |
| 21667 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21668 | { |
| 21669 | continue; |
| 21670 | } |
| 21671 | } |
| 21672 | |
| 21673 | { |
| 21674 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21675 | vinfos[0].jointtype = 1; |
| 21676 | vinfos[0].foffset = j0; |
| 21677 | vinfos[0].indices[0] = _ij0[0]; |
| 21678 | vinfos[0].indices[1] = _ij0[1]; |
| 21679 | vinfos[0].maxsolutions = _nj0; |
| 21680 | vinfos[1].jointtype = 1; |
| 21681 | vinfos[1].foffset = j1; |
| 21682 | vinfos[1].indices[0] = _ij1[0]; |
| 21683 | vinfos[1].indices[1] = _ij1[1]; |
| 21684 | vinfos[1].maxsolutions = _nj1; |
| 21685 | vinfos[2].jointtype = 1; |
| 21686 | vinfos[2].foffset = j2; |
| 21687 | vinfos[2].indices[0] = _ij2[0]; |
| 21688 | vinfos[2].indices[1] = _ij2[1]; |
| 21689 | vinfos[2].maxsolutions = _nj2; |
| 21690 | vinfos[3].jointtype = 1; |
| 21691 | vinfos[3].foffset = j3; |
| 21692 | vinfos[3].indices[0] = _ij3[0]; |
| 21693 | vinfos[3].indices[1] = _ij3[1]; |
| 21694 | vinfos[3].maxsolutions = _nj3; |
| 21695 | vinfos[4].jointtype = 1; |
| 21696 | vinfos[4].foffset = j4; |
| 21697 | vinfos[4].indices[0] = _ij4[0]; |
| 21698 | vinfos[4].indices[1] = _ij4[1]; |
| 21699 | vinfos[4].maxsolutions = _nj4; |
| 21700 | vinfos[5].jointtype = 1; |
| 21701 | vinfos[5].foffset = j5; |
| 21702 | vinfos[5].indices[0] = _ij5[0]; |
| 21703 | vinfos[5].indices[1] = _ij5[1]; |
| 21704 | vinfos[5].maxsolutions = _nj5; |
| 21705 | std::vector<int> vfree(0); |
| 21706 | solutions.AddSolution(vinfos,vfree); |
| 21707 | } |
| 21708 | } |
| 21709 | } |
| 21710 | |
| 21711 | } |
| 21712 | |
| 21713 | } |
| 21714 | |
| 21715 | } else |
| 21716 | { |
| 21717 | { |
| 21718 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 21719 | bool j0valid[1]={false}; |
| 21720 | _nj0 = 1; |
| 21721 | CheckValue<IkReal> x1631 = IKatan2WithCheck(IkReal((((gconst39*new_r11))+((gconst38*new_r10)))),IkReal((((gconst39*new_r01))+((gconst38*new_r00)))),IKFAST_ATAN2_MAGTHRESH); |
| 21722 | if(!x1631.valid){ |
| 21723 | continue; |
| 21724 | } |
| 21725 | CheckValue<IkReal> x1632=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| 21726 | if(!x1632.valid){ |
| 21727 | continue; |
| 21728 | } |
| 21729 | j0array[0]=((-1.5707963267949)+(x1631.value)+(((1.5707963267949)*(x1632.value)))); |
| 21730 | sj0array[0]=IKsin(j0array[0]); |
| 21731 | cj0array[0]=IKcos(j0array[0]); |
| 21732 | if( j0array[0] > IKPI ) |
| 21733 | { |
| 21734 | j0array[0]-=IK2PI; |
| 21735 | } |
| 21736 | else if( j0array[0] < -IKPI ) |
| 21737 | { j0array[0]+=IK2PI; |
| 21738 | } |
| 21739 | j0valid[0] = true; |
| 21740 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 21741 | { |
| 21742 | if( !j0valid[ij0] ) |
| 21743 | { |
| 21744 | continue; |
| 21745 | } |
| 21746 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21747 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 21748 | { |
| 21749 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21750 | { |
| 21751 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21752 | } |
| 21753 | } |
| 21754 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21755 | { |
| 21756 | IkReal evalcond[8]; |
| 21757 | IkReal x1633=IKsin(j0); |
| 21758 | IkReal x1634=IKcos(j0); |
| 21759 | IkReal x1635=((1.0)*gconst39); |
| 21760 | IkReal x1636=((1.0)*gconst38); |
| 21761 | IkReal x1637=((1.0)*x1634); |
| 21762 | IkReal x1638=(((x1634*x1635))+((x1633*x1636))); |
| 21763 | evalcond[0]=(((new_r11*x1634))+gconst38+(((-1.0)*new_r01*x1633))); |
| 21764 | evalcond[1]=(gconst39+((new_r00*x1633))+(((-1.0)*new_r10*x1637))); |
| 21765 | evalcond[2]=((((-1.0)*x1634*x1636))+((gconst39*x1633))+new_r00); |
| 21766 | evalcond[3]=((((-1.0)*x1633*x1635))+((gconst38*x1634))+new_r11); |
| 21767 | evalcond[4]=(((new_r10*x1633))+(((-1.0)*x1636))+((new_r00*x1634))); |
| 21768 | evalcond[5]=(((new_r11*x1633))+(((-1.0)*x1635))+((new_r01*x1634))); |
| 21769 | evalcond[6]=((((-1.0)*x1638))+new_r01); |
| 21770 | evalcond[7]=((((-1.0)*x1638))+new_r10); |
| 21771 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 21772 | { |
| 21773 | continue; |
| 21774 | } |
| 21775 | } |
| 21776 | |
| 21777 | { |
| 21778 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21779 | vinfos[0].jointtype = 1; |
| 21780 | vinfos[0].foffset = j0; |
| 21781 | vinfos[0].indices[0] = _ij0[0]; |
| 21782 | vinfos[0].indices[1] = _ij0[1]; |
| 21783 | vinfos[0].maxsolutions = _nj0; |
| 21784 | vinfos[1].jointtype = 1; |
| 21785 | vinfos[1].foffset = j1; |
| 21786 | vinfos[1].indices[0] = _ij1[0]; |
| 21787 | vinfos[1].indices[1] = _ij1[1]; |
| 21788 | vinfos[1].maxsolutions = _nj1; |
| 21789 | vinfos[2].jointtype = 1; |
| 21790 | vinfos[2].foffset = j2; |
| 21791 | vinfos[2].indices[0] = _ij2[0]; |
| 21792 | vinfos[2].indices[1] = _ij2[1]; |
| 21793 | vinfos[2].maxsolutions = _nj2; |
| 21794 | vinfos[3].jointtype = 1; |
| 21795 | vinfos[3].foffset = j3; |
| 21796 | vinfos[3].indices[0] = _ij3[0]; |
| 21797 | vinfos[3].indices[1] = _ij3[1]; |
| 21798 | vinfos[3].maxsolutions = _nj3; |
| 21799 | vinfos[4].jointtype = 1; |
| 21800 | vinfos[4].foffset = j4; |
| 21801 | vinfos[4].indices[0] = _ij4[0]; |
| 21802 | vinfos[4].indices[1] = _ij4[1]; |
| 21803 | vinfos[4].maxsolutions = _nj4; |
| 21804 | vinfos[5].jointtype = 1; |
| 21805 | vinfos[5].foffset = j5; |
| 21806 | vinfos[5].indices[0] = _ij5[0]; |
| 21807 | vinfos[5].indices[1] = _ij5[1]; |
| 21808 | vinfos[5].maxsolutions = _nj5; |
| 21809 | std::vector<int> vfree(0); |
| 21810 | solutions.AddSolution(vinfos,vfree); |
| 21811 | } |
| 21812 | } |
| 21813 | } |
| 21814 | |
| 21815 | } |
| 21816 | |
| 21817 | } |
| 21818 | |
| 21819 | } |
| 21820 | } while(0); |
| 21821 | if( bgotonextstatement ) |
| 21822 | { |
| 21823 | bool bgotonextstatement = true; |
| 21824 | do |
| 21825 | { |
| 21826 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 21827 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 21828 | { |
| 21829 | bgotonextstatement=false; |
| 21830 | { |
| 21831 | IkReal j0eval[1]; |
| 21832 | sj1=-1.0; |
| 21833 | cj1=0; |
| 21834 | j1=-1.5707963267949; |
| 21835 | new_r11=0; |
| 21836 | new_r01=0; |
| 21837 | new_r22=0; |
| 21838 | new_r20=0; |
| 21839 | j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 21840 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 21841 | { |
| 21842 | continue; // no branches [j0] |
| 21843 | |
| 21844 | } else |
| 21845 | { |
| 21846 | { |
| 21847 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 21848 | bool j0valid[2]={false}; |
| 21849 | _nj0 = 2; |
| 21850 | CheckValue<IkReal> x1640 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 21851 | if(!x1640.valid){ |
| 21852 | continue; |
| 21853 | } |
| 21854 | IkReal x1639=x1640.value; |
| 21855 | j0array[0]=((-1.0)*x1639); |
| 21856 | sj0array[0]=IKsin(j0array[0]); |
| 21857 | cj0array[0]=IKcos(j0array[0]); |
| 21858 | j0array[1]=((3.14159265358979)+(((-1.0)*x1639))); |
| 21859 | sj0array[1]=IKsin(j0array[1]); |
| 21860 | cj0array[1]=IKcos(j0array[1]); |
| 21861 | if( j0array[0] > IKPI ) |
| 21862 | { |
| 21863 | j0array[0]-=IK2PI; |
| 21864 | } |
| 21865 | else if( j0array[0] < -IKPI ) |
| 21866 | { j0array[0]+=IK2PI; |
| 21867 | } |
| 21868 | j0valid[0] = true; |
| 21869 | if( j0array[1] > IKPI ) |
| 21870 | { |
| 21871 | j0array[1]-=IK2PI; |
| 21872 | } |
| 21873 | else if( j0array[1] < -IKPI ) |
| 21874 | { j0array[1]+=IK2PI; |
| 21875 | } |
| 21876 | j0valid[1] = true; |
| 21877 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 21878 | { |
| 21879 | if( !j0valid[ij0] ) |
| 21880 | { |
| 21881 | continue; |
| 21882 | } |
| 21883 | _ij0[0] = ij0; _ij0[1] = -1; |
| 21884 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 21885 | { |
| 21886 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 21887 | { |
| 21888 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 21889 | } |
| 21890 | } |
| 21891 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 21892 | { |
| 21893 | IkReal evalcond[1]; |
| 21894 | evalcond[0]=(((new_r00*(IKsin(j0))))+(((-1.0)*new_r10*(IKcos(j0))))); |
| 21895 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| 21896 | { |
| 21897 | continue; |
| 21898 | } |
| 21899 | } |
| 21900 | |
| 21901 | { |
| 21902 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 21903 | vinfos[0].jointtype = 1; |
| 21904 | vinfos[0].foffset = j0; |
| 21905 | vinfos[0].indices[0] = _ij0[0]; |
| 21906 | vinfos[0].indices[1] = _ij0[1]; |
| 21907 | vinfos[0].maxsolutions = _nj0; |
| 21908 | vinfos[1].jointtype = 1; |
| 21909 | vinfos[1].foffset = j1; |
| 21910 | vinfos[1].indices[0] = _ij1[0]; |
| 21911 | vinfos[1].indices[1] = _ij1[1]; |
| 21912 | vinfos[1].maxsolutions = _nj1; |
| 21913 | vinfos[2].jointtype = 1; |
| 21914 | vinfos[2].foffset = j2; |
| 21915 | vinfos[2].indices[0] = _ij2[0]; |
| 21916 | vinfos[2].indices[1] = _ij2[1]; |
| 21917 | vinfos[2].maxsolutions = _nj2; |
| 21918 | vinfos[3].jointtype = 1; |
| 21919 | vinfos[3].foffset = j3; |
| 21920 | vinfos[3].indices[0] = _ij3[0]; |
| 21921 | vinfos[3].indices[1] = _ij3[1]; |
| 21922 | vinfos[3].maxsolutions = _nj3; |
| 21923 | vinfos[4].jointtype = 1; |
| 21924 | vinfos[4].foffset = j4; |
| 21925 | vinfos[4].indices[0] = _ij4[0]; |
| 21926 | vinfos[4].indices[1] = _ij4[1]; |
| 21927 | vinfos[4].maxsolutions = _nj4; |
| 21928 | vinfos[5].jointtype = 1; |
| 21929 | vinfos[5].foffset = j5; |
| 21930 | vinfos[5].indices[0] = _ij5[0]; |
| 21931 | vinfos[5].indices[1] = _ij5[1]; |
| 21932 | vinfos[5].maxsolutions = _nj5; |
| 21933 | std::vector<int> vfree(0); |
| 21934 | solutions.AddSolution(vinfos,vfree); |
| 21935 | } |
| 21936 | } |
| 21937 | } |
| 21938 | |
| 21939 | } |
| 21940 | |
| 21941 | } |
| 21942 | |
| 21943 | } |
| 21944 | } while(0); |
| 21945 | if( bgotonextstatement ) |
| 21946 | { |
| 21947 | bool bgotonextstatement = true; |
| 21948 | do |
| 21949 | { |
| 21950 | evalcond[0]=((IKabs(new_r11))+(IKabs(new_r10))); |
| 21951 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 21952 | { |
| 21953 | bgotonextstatement=false; |
| 21954 | { |
| 21955 | IkReal j0eval[3]; |
| 21956 | sj1=-1.0; |
| 21957 | cj1=0; |
| 21958 | j1=-1.5707963267949; |
| 21959 | new_r11=0; |
| 21960 | new_r10=0; |
| 21961 | new_r22=0; |
| 21962 | new_r02=0; |
| 21963 | j0eval[0]=new_r00; |
| 21964 | j0eval[1]=((IKabs(cj2))+(IKabs(sj2))); |
| 21965 | j0eval[2]=IKsign(new_r00); |
| 21966 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 21967 | { |
| 21968 | { |
| 21969 | IkReal j0eval[2]; |
| 21970 | sj1=-1.0; |
| 21971 | cj1=0; |
| 21972 | j1=-1.5707963267949; |
| 21973 | new_r11=0; |
| 21974 | new_r10=0; |
| 21975 | new_r22=0; |
| 21976 | new_r02=0; |
| 21977 | j0eval[0]=new_r01; |
| 21978 | j0eval[1]=new_r00; |
| 21979 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 21980 | { |
| 21981 | { |
| 21982 | IkReal j0eval[2]; |
| 21983 | sj1=-1.0; |
| 21984 | cj1=0; |
| 21985 | j1=-1.5707963267949; |
| 21986 | new_r11=0; |
| 21987 | new_r10=0; |
| 21988 | new_r22=0; |
| 21989 | new_r02=0; |
| 21990 | j0eval[0]=new_r00; |
| 21991 | j0eval[1]=sj2; |
| 21992 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 21993 | { |
| 21994 | { |
| 21995 | IkReal evalcond[1]; |
| 21996 | bool bgotonextstatement = true; |
| 21997 | do |
| 21998 | { |
| 21999 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j2))), 6.28318530717959))); |
| 22000 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 22001 | { |
| 22002 | bgotonextstatement=false; |
| 22003 | { |
| 22004 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22005 | bool j0valid[1]={false}; |
| 22006 | _nj0 = 1; |
| 22007 | if( IKabs(((-1.0)*new_r00)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r01) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r00))+IKsqr(new_r01)-1) <= IKFAST_SINCOS_THRESH ) |
| 22008 | continue; |
| 22009 | j0array[0]=IKatan2(((-1.0)*new_r00), new_r01); |
| 22010 | sj0array[0]=IKsin(j0array[0]); |
| 22011 | cj0array[0]=IKcos(j0array[0]); |
| 22012 | if( j0array[0] > IKPI ) |
| 22013 | { |
| 22014 | j0array[0]-=IK2PI; |
| 22015 | } |
| 22016 | else if( j0array[0] < -IKPI ) |
| 22017 | { j0array[0]+=IK2PI; |
| 22018 | } |
| 22019 | j0valid[0] = true; |
| 22020 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22021 | { |
| 22022 | if( !j0valid[ij0] ) |
| 22023 | { |
| 22024 | continue; |
| 22025 | } |
| 22026 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22027 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22028 | { |
| 22029 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22030 | { |
| 22031 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22032 | } |
| 22033 | } |
| 22034 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22035 | { |
| 22036 | IkReal evalcond[8]; |
| 22037 | IkReal x1641=IKsin(j0); |
| 22038 | IkReal x1642=IKcos(j0); |
| 22039 | IkReal x1643=((-1.0)*x1641); |
| 22040 | evalcond[0]=(new_r00*x1642); |
| 22041 | evalcond[1]=(x1641+new_r00); |
| 22042 | evalcond[2]=x1643; |
| 22043 | evalcond[3]=((-1.0)*x1642); |
| 22044 | evalcond[4]=(new_r01*x1643); |
| 22045 | evalcond[5]=((1.0)+((new_r00*x1641))); |
| 22046 | evalcond[6]=((-1.0)+((new_r01*x1642))); |
| 22047 | evalcond[7]=((((-1.0)*x1642))+new_r01); |
| 22048 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22049 | { |
| 22050 | continue; |
| 22051 | } |
| 22052 | } |
| 22053 | |
| 22054 | { |
| 22055 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22056 | vinfos[0].jointtype = 1; |
| 22057 | vinfos[0].foffset = j0; |
| 22058 | vinfos[0].indices[0] = _ij0[0]; |
| 22059 | vinfos[0].indices[1] = _ij0[1]; |
| 22060 | vinfos[0].maxsolutions = _nj0; |
| 22061 | vinfos[1].jointtype = 1; |
| 22062 | vinfos[1].foffset = j1; |
| 22063 | vinfos[1].indices[0] = _ij1[0]; |
| 22064 | vinfos[1].indices[1] = _ij1[1]; |
| 22065 | vinfos[1].maxsolutions = _nj1; |
| 22066 | vinfos[2].jointtype = 1; |
| 22067 | vinfos[2].foffset = j2; |
| 22068 | vinfos[2].indices[0] = _ij2[0]; |
| 22069 | vinfos[2].indices[1] = _ij2[1]; |
| 22070 | vinfos[2].maxsolutions = _nj2; |
| 22071 | vinfos[3].jointtype = 1; |
| 22072 | vinfos[3].foffset = j3; |
| 22073 | vinfos[3].indices[0] = _ij3[0]; |
| 22074 | vinfos[3].indices[1] = _ij3[1]; |
| 22075 | vinfos[3].maxsolutions = _nj3; |
| 22076 | vinfos[4].jointtype = 1; |
| 22077 | vinfos[4].foffset = j4; |
| 22078 | vinfos[4].indices[0] = _ij4[0]; |
| 22079 | vinfos[4].indices[1] = _ij4[1]; |
| 22080 | vinfos[4].maxsolutions = _nj4; |
| 22081 | vinfos[5].jointtype = 1; |
| 22082 | vinfos[5].foffset = j5; |
| 22083 | vinfos[5].indices[0] = _ij5[0]; |
| 22084 | vinfos[5].indices[1] = _ij5[1]; |
| 22085 | vinfos[5].maxsolutions = _nj5; |
| 22086 | std::vector<int> vfree(0); |
| 22087 | solutions.AddSolution(vinfos,vfree); |
| 22088 | } |
| 22089 | } |
| 22090 | } |
| 22091 | |
| 22092 | } |
| 22093 | } while(0); |
| 22094 | if( bgotonextstatement ) |
| 22095 | { |
| 22096 | bool bgotonextstatement = true; |
| 22097 | do |
| 22098 | { |
| 22099 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j2)))), 6.28318530717959))); |
| 22100 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 22101 | { |
| 22102 | bgotonextstatement=false; |
| 22103 | { |
| 22104 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22105 | bool j0valid[1]={false}; |
| 22106 | _nj0 = 1; |
| 22107 | if( IKabs(new_r00) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r01)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r00)+IKsqr(((-1.0)*new_r01))-1) <= IKFAST_SINCOS_THRESH ) |
| 22108 | continue; |
| 22109 | j0array[0]=IKatan2(new_r00, ((-1.0)*new_r01)); |
| 22110 | sj0array[0]=IKsin(j0array[0]); |
| 22111 | cj0array[0]=IKcos(j0array[0]); |
| 22112 | if( j0array[0] > IKPI ) |
| 22113 | { |
| 22114 | j0array[0]-=IK2PI; |
| 22115 | } |
| 22116 | else if( j0array[0] < -IKPI ) |
| 22117 | { j0array[0]+=IK2PI; |
| 22118 | } |
| 22119 | j0valid[0] = true; |
| 22120 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22121 | { |
| 22122 | if( !j0valid[ij0] ) |
| 22123 | { |
| 22124 | continue; |
| 22125 | } |
| 22126 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22127 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22128 | { |
| 22129 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22130 | { |
| 22131 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22132 | } |
| 22133 | } |
| 22134 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22135 | { |
| 22136 | IkReal evalcond[8]; |
| 22137 | IkReal x1644=IKcos(j0); |
| 22138 | IkReal x1645=IKsin(j0); |
| 22139 | evalcond[0]=x1645; |
| 22140 | evalcond[1]=x1644; |
| 22141 | evalcond[2]=(new_r00*x1644); |
| 22142 | evalcond[3]=(x1644+new_r01); |
| 22143 | evalcond[4]=((-1.0)*new_r01*x1645); |
| 22144 | evalcond[5]=((-1.0)+((new_r00*x1645))); |
| 22145 | evalcond[6]=((1.0)+((new_r01*x1644))); |
| 22146 | evalcond[7]=((((-1.0)*x1645))+new_r00); |
| 22147 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22148 | { |
| 22149 | continue; |
| 22150 | } |
| 22151 | } |
| 22152 | |
| 22153 | { |
| 22154 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22155 | vinfos[0].jointtype = 1; |
| 22156 | vinfos[0].foffset = j0; |
| 22157 | vinfos[0].indices[0] = _ij0[0]; |
| 22158 | vinfos[0].indices[1] = _ij0[1]; |
| 22159 | vinfos[0].maxsolutions = _nj0; |
| 22160 | vinfos[1].jointtype = 1; |
| 22161 | vinfos[1].foffset = j1; |
| 22162 | vinfos[1].indices[0] = _ij1[0]; |
| 22163 | vinfos[1].indices[1] = _ij1[1]; |
| 22164 | vinfos[1].maxsolutions = _nj1; |
| 22165 | vinfos[2].jointtype = 1; |
| 22166 | vinfos[2].foffset = j2; |
| 22167 | vinfos[2].indices[0] = _ij2[0]; |
| 22168 | vinfos[2].indices[1] = _ij2[1]; |
| 22169 | vinfos[2].maxsolutions = _nj2; |
| 22170 | vinfos[3].jointtype = 1; |
| 22171 | vinfos[3].foffset = j3; |
| 22172 | vinfos[3].indices[0] = _ij3[0]; |
| 22173 | vinfos[3].indices[1] = _ij3[1]; |
| 22174 | vinfos[3].maxsolutions = _nj3; |
| 22175 | vinfos[4].jointtype = 1; |
| 22176 | vinfos[4].foffset = j4; |
| 22177 | vinfos[4].indices[0] = _ij4[0]; |
| 22178 | vinfos[4].indices[1] = _ij4[1]; |
| 22179 | vinfos[4].maxsolutions = _nj4; |
| 22180 | vinfos[5].jointtype = 1; |
| 22181 | vinfos[5].foffset = j5; |
| 22182 | vinfos[5].indices[0] = _ij5[0]; |
| 22183 | vinfos[5].indices[1] = _ij5[1]; |
| 22184 | vinfos[5].maxsolutions = _nj5; |
| 22185 | std::vector<int> vfree(0); |
| 22186 | solutions.AddSolution(vinfos,vfree); |
| 22187 | } |
| 22188 | } |
| 22189 | } |
| 22190 | |
| 22191 | } |
| 22192 | } while(0); |
| 22193 | if( bgotonextstatement ) |
| 22194 | { |
| 22195 | bool bgotonextstatement = true; |
| 22196 | do |
| 22197 | { |
| 22198 | if( 1 ) |
| 22199 | { |
| 22200 | bgotonextstatement=false; |
| 22201 | continue; // branch miss [j0] |
| 22202 | |
| 22203 | } |
| 22204 | } while(0); |
| 22205 | if( bgotonextstatement ) |
| 22206 | { |
| 22207 | } |
| 22208 | } |
| 22209 | } |
| 22210 | } |
| 22211 | |
| 22212 | } else |
| 22213 | { |
| 22214 | { |
| 22215 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22216 | bool j0valid[1]={false}; |
| 22217 | _nj0 = 1; |
| 22218 | CheckValue<IkReal> x1648=IKPowWithIntegerCheck(new_r00,-1); |
| 22219 | if(!x1648.valid){ |
| 22220 | continue; |
| 22221 | } |
| 22222 | IkReal x1646=x1648.value; |
| 22223 | IkReal x1647=((-1.0)*x1646); |
| 22224 | CheckValue<IkReal> x1649=IKPowWithIntegerCheck(sj2,-1); |
| 22225 | if(!x1649.valid){ |
| 22226 | continue; |
| 22227 | } |
| 22228 | if( IKabs((cj2*x1647)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1647*(cj2*cj2)*(x1649.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((cj2*x1647))+IKsqr((x1647*(cj2*cj2)*(x1649.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 22229 | continue; |
| 22230 | j0array[0]=IKatan2((cj2*x1647), (x1647*(cj2*cj2)*(x1649.value))); |
| 22231 | sj0array[0]=IKsin(j0array[0]); |
| 22232 | cj0array[0]=IKcos(j0array[0]); |
| 22233 | if( j0array[0] > IKPI ) |
| 22234 | { |
| 22235 | j0array[0]-=IK2PI; |
| 22236 | } |
| 22237 | else if( j0array[0] < -IKPI ) |
| 22238 | { j0array[0]+=IK2PI; |
| 22239 | } |
| 22240 | j0valid[0] = true; |
| 22241 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22242 | { |
| 22243 | if( !j0valid[ij0] ) |
| 22244 | { |
| 22245 | continue; |
| 22246 | } |
| 22247 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22248 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22249 | { |
| 22250 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22251 | { |
| 22252 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22253 | } |
| 22254 | } |
| 22255 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22256 | { |
| 22257 | IkReal evalcond[8]; |
| 22258 | IkReal x1650=IKsin(j0); |
| 22259 | IkReal x1651=IKcos(j0); |
| 22260 | IkReal x1652=((1.0)*sj2); |
| 22261 | IkReal x1653=((1.0)*cj2); |
| 22262 | IkReal x1654=(cj2*x1650); |
| 22263 | IkReal x1655=(((x1650*x1652))+((x1651*x1653))); |
| 22264 | evalcond[0]=(cj2+((new_r00*x1650))); |
| 22265 | evalcond[1]=(sj2+(((-1.0)*new_r01*x1650))); |
| 22266 | evalcond[2]=((((-1.0)*x1652))+((new_r00*x1651))); |
| 22267 | evalcond[3]=((((-1.0)*x1653))+((new_r01*x1651))); |
| 22268 | evalcond[4]=((((-1.0)*x1650*x1653))+((sj2*x1651))); |
| 22269 | evalcond[5]=(x1654+new_r00+(((-1.0)*x1651*x1652))); |
| 22270 | evalcond[6]=((-1.0)*x1655); |
| 22271 | evalcond[7]=((((-1.0)*x1655))+new_r01); |
| 22272 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22273 | { |
| 22274 | continue; |
| 22275 | } |
| 22276 | } |
| 22277 | |
| 22278 | { |
| 22279 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22280 | vinfos[0].jointtype = 1; |
| 22281 | vinfos[0].foffset = j0; |
| 22282 | vinfos[0].indices[0] = _ij0[0]; |
| 22283 | vinfos[0].indices[1] = _ij0[1]; |
| 22284 | vinfos[0].maxsolutions = _nj0; |
| 22285 | vinfos[1].jointtype = 1; |
| 22286 | vinfos[1].foffset = j1; |
| 22287 | vinfos[1].indices[0] = _ij1[0]; |
| 22288 | vinfos[1].indices[1] = _ij1[1]; |
| 22289 | vinfos[1].maxsolutions = _nj1; |
| 22290 | vinfos[2].jointtype = 1; |
| 22291 | vinfos[2].foffset = j2; |
| 22292 | vinfos[2].indices[0] = _ij2[0]; |
| 22293 | vinfos[2].indices[1] = _ij2[1]; |
| 22294 | vinfos[2].maxsolutions = _nj2; |
| 22295 | vinfos[3].jointtype = 1; |
| 22296 | vinfos[3].foffset = j3; |
| 22297 | vinfos[3].indices[0] = _ij3[0]; |
| 22298 | vinfos[3].indices[1] = _ij3[1]; |
| 22299 | vinfos[3].maxsolutions = _nj3; |
| 22300 | vinfos[4].jointtype = 1; |
| 22301 | vinfos[4].foffset = j4; |
| 22302 | vinfos[4].indices[0] = _ij4[0]; |
| 22303 | vinfos[4].indices[1] = _ij4[1]; |
| 22304 | vinfos[4].maxsolutions = _nj4; |
| 22305 | vinfos[5].jointtype = 1; |
| 22306 | vinfos[5].foffset = j5; |
| 22307 | vinfos[5].indices[0] = _ij5[0]; |
| 22308 | vinfos[5].indices[1] = _ij5[1]; |
| 22309 | vinfos[5].maxsolutions = _nj5; |
| 22310 | std::vector<int> vfree(0); |
| 22311 | solutions.AddSolution(vinfos,vfree); |
| 22312 | } |
| 22313 | } |
| 22314 | } |
| 22315 | |
| 22316 | } |
| 22317 | |
| 22318 | } |
| 22319 | |
| 22320 | } else |
| 22321 | { |
| 22322 | { |
| 22323 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22324 | bool j0valid[1]={false}; |
| 22325 | _nj0 = 1; |
| 22326 | CheckValue<IkReal> x1656=IKPowWithIntegerCheck(new_r01,-1); |
| 22327 | if(!x1656.valid){ |
| 22328 | continue; |
| 22329 | } |
| 22330 | CheckValue<IkReal> x1657=IKPowWithIntegerCheck(new_r00,-1); |
| 22331 | if(!x1657.valid){ |
| 22332 | continue; |
| 22333 | } |
| 22334 | if( IKabs((sj2*(x1656.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs((sj2*(x1657.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x1656.value)))+IKsqr((sj2*(x1657.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 22335 | continue; |
| 22336 | j0array[0]=IKatan2((sj2*(x1656.value)), (sj2*(x1657.value))); |
| 22337 | sj0array[0]=IKsin(j0array[0]); |
| 22338 | cj0array[0]=IKcos(j0array[0]); |
| 22339 | if( j0array[0] > IKPI ) |
| 22340 | { |
| 22341 | j0array[0]-=IK2PI; |
| 22342 | } |
| 22343 | else if( j0array[0] < -IKPI ) |
| 22344 | { j0array[0]+=IK2PI; |
| 22345 | } |
| 22346 | j0valid[0] = true; |
| 22347 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22348 | { |
| 22349 | if( !j0valid[ij0] ) |
| 22350 | { |
| 22351 | continue; |
| 22352 | } |
| 22353 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22354 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22355 | { |
| 22356 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22357 | { |
| 22358 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22359 | } |
| 22360 | } |
| 22361 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22362 | { |
| 22363 | IkReal evalcond[8]; |
| 22364 | IkReal x1658=IKsin(j0); |
| 22365 | IkReal x1659=IKcos(j0); |
| 22366 | IkReal x1660=((1.0)*sj2); |
| 22367 | IkReal x1661=((1.0)*cj2); |
| 22368 | IkReal x1662=(cj2*x1658); |
| 22369 | IkReal x1663=(((x1658*x1660))+((x1659*x1661))); |
| 22370 | evalcond[0]=(cj2+((new_r00*x1658))); |
| 22371 | evalcond[1]=(sj2+(((-1.0)*new_r01*x1658))); |
| 22372 | evalcond[2]=(((new_r00*x1659))+(((-1.0)*x1660))); |
| 22373 | evalcond[3]=((((-1.0)*x1661))+((new_r01*x1659))); |
| 22374 | evalcond[4]=(((sj2*x1659))+(((-1.0)*x1658*x1661))); |
| 22375 | evalcond[5]=(x1662+new_r00+(((-1.0)*x1659*x1660))); |
| 22376 | evalcond[6]=((-1.0)*x1663); |
| 22377 | evalcond[7]=((((-1.0)*x1663))+new_r01); |
| 22378 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22379 | { |
| 22380 | continue; |
| 22381 | } |
| 22382 | } |
| 22383 | |
| 22384 | { |
| 22385 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22386 | vinfos[0].jointtype = 1; |
| 22387 | vinfos[0].foffset = j0; |
| 22388 | vinfos[0].indices[0] = _ij0[0]; |
| 22389 | vinfos[0].indices[1] = _ij0[1]; |
| 22390 | vinfos[0].maxsolutions = _nj0; |
| 22391 | vinfos[1].jointtype = 1; |
| 22392 | vinfos[1].foffset = j1; |
| 22393 | vinfos[1].indices[0] = _ij1[0]; |
| 22394 | vinfos[1].indices[1] = _ij1[1]; |
| 22395 | vinfos[1].maxsolutions = _nj1; |
| 22396 | vinfos[2].jointtype = 1; |
| 22397 | vinfos[2].foffset = j2; |
| 22398 | vinfos[2].indices[0] = _ij2[0]; |
| 22399 | vinfos[2].indices[1] = _ij2[1]; |
| 22400 | vinfos[2].maxsolutions = _nj2; |
| 22401 | vinfos[3].jointtype = 1; |
| 22402 | vinfos[3].foffset = j3; |
| 22403 | vinfos[3].indices[0] = _ij3[0]; |
| 22404 | vinfos[3].indices[1] = _ij3[1]; |
| 22405 | vinfos[3].maxsolutions = _nj3; |
| 22406 | vinfos[4].jointtype = 1; |
| 22407 | vinfos[4].foffset = j4; |
| 22408 | vinfos[4].indices[0] = _ij4[0]; |
| 22409 | vinfos[4].indices[1] = _ij4[1]; |
| 22410 | vinfos[4].maxsolutions = _nj4; |
| 22411 | vinfos[5].jointtype = 1; |
| 22412 | vinfos[5].foffset = j5; |
| 22413 | vinfos[5].indices[0] = _ij5[0]; |
| 22414 | vinfos[5].indices[1] = _ij5[1]; |
| 22415 | vinfos[5].maxsolutions = _nj5; |
| 22416 | std::vector<int> vfree(0); |
| 22417 | solutions.AddSolution(vinfos,vfree); |
| 22418 | } |
| 22419 | } |
| 22420 | } |
| 22421 | |
| 22422 | } |
| 22423 | |
| 22424 | } |
| 22425 | |
| 22426 | } else |
| 22427 | { |
| 22428 | { |
| 22429 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22430 | bool j0valid[1]={false}; |
| 22431 | _nj0 = 1; |
| 22432 | CheckValue<IkReal> x1664=IKPowWithIntegerCheck(IKsign(new_r00),-1); |
| 22433 | if(!x1664.valid){ |
| 22434 | continue; |
| 22435 | } |
| 22436 | CheckValue<IkReal> x1665 = IKatan2WithCheck(IkReal(((-1.0)*cj2)),IkReal(sj2),IKFAST_ATAN2_MAGTHRESH); |
| 22437 | if(!x1665.valid){ |
| 22438 | continue; |
| 22439 | } |
| 22440 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1664.value)))+(x1665.value)); |
| 22441 | sj0array[0]=IKsin(j0array[0]); |
| 22442 | cj0array[0]=IKcos(j0array[0]); |
| 22443 | if( j0array[0] > IKPI ) |
| 22444 | { |
| 22445 | j0array[0]-=IK2PI; |
| 22446 | } |
| 22447 | else if( j0array[0] < -IKPI ) |
| 22448 | { j0array[0]+=IK2PI; |
| 22449 | } |
| 22450 | j0valid[0] = true; |
| 22451 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22452 | { |
| 22453 | if( !j0valid[ij0] ) |
| 22454 | { |
| 22455 | continue; |
| 22456 | } |
| 22457 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22458 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22459 | { |
| 22460 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22461 | { |
| 22462 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22463 | } |
| 22464 | } |
| 22465 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22466 | { |
| 22467 | IkReal evalcond[8]; |
| 22468 | IkReal x1666=IKsin(j0); |
| 22469 | IkReal x1667=IKcos(j0); |
| 22470 | IkReal x1668=((1.0)*sj2); |
| 22471 | IkReal x1669=((1.0)*cj2); |
| 22472 | IkReal x1670=(cj2*x1666); |
| 22473 | IkReal x1671=(((x1667*x1669))+((x1666*x1668))); |
| 22474 | evalcond[0]=(cj2+((new_r00*x1666))); |
| 22475 | evalcond[1]=(sj2+(((-1.0)*new_r01*x1666))); |
| 22476 | evalcond[2]=((((-1.0)*x1668))+((new_r00*x1667))); |
| 22477 | evalcond[3]=(((new_r01*x1667))+(((-1.0)*x1669))); |
| 22478 | evalcond[4]=(((sj2*x1667))+(((-1.0)*x1666*x1669))); |
| 22479 | evalcond[5]=(x1670+(((-1.0)*x1667*x1668))+new_r00); |
| 22480 | evalcond[6]=((-1.0)*x1671); |
| 22481 | evalcond[7]=(new_r01+(((-1.0)*x1671))); |
| 22482 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22483 | { |
| 22484 | continue; |
| 22485 | } |
| 22486 | } |
| 22487 | |
| 22488 | { |
| 22489 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22490 | vinfos[0].jointtype = 1; |
| 22491 | vinfos[0].foffset = j0; |
| 22492 | vinfos[0].indices[0] = _ij0[0]; |
| 22493 | vinfos[0].indices[1] = _ij0[1]; |
| 22494 | vinfos[0].maxsolutions = _nj0; |
| 22495 | vinfos[1].jointtype = 1; |
| 22496 | vinfos[1].foffset = j1; |
| 22497 | vinfos[1].indices[0] = _ij1[0]; |
| 22498 | vinfos[1].indices[1] = _ij1[1]; |
| 22499 | vinfos[1].maxsolutions = _nj1; |
| 22500 | vinfos[2].jointtype = 1; |
| 22501 | vinfos[2].foffset = j2; |
| 22502 | vinfos[2].indices[0] = _ij2[0]; |
| 22503 | vinfos[2].indices[1] = _ij2[1]; |
| 22504 | vinfos[2].maxsolutions = _nj2; |
| 22505 | vinfos[3].jointtype = 1; |
| 22506 | vinfos[3].foffset = j3; |
| 22507 | vinfos[3].indices[0] = _ij3[0]; |
| 22508 | vinfos[3].indices[1] = _ij3[1]; |
| 22509 | vinfos[3].maxsolutions = _nj3; |
| 22510 | vinfos[4].jointtype = 1; |
| 22511 | vinfos[4].foffset = j4; |
| 22512 | vinfos[4].indices[0] = _ij4[0]; |
| 22513 | vinfos[4].indices[1] = _ij4[1]; |
| 22514 | vinfos[4].maxsolutions = _nj4; |
| 22515 | vinfos[5].jointtype = 1; |
| 22516 | vinfos[5].foffset = j5; |
| 22517 | vinfos[5].indices[0] = _ij5[0]; |
| 22518 | vinfos[5].indices[1] = _ij5[1]; |
| 22519 | vinfos[5].maxsolutions = _nj5; |
| 22520 | std::vector<int> vfree(0); |
| 22521 | solutions.AddSolution(vinfos,vfree); |
| 22522 | } |
| 22523 | } |
| 22524 | } |
| 22525 | |
| 22526 | } |
| 22527 | |
| 22528 | } |
| 22529 | |
| 22530 | } |
| 22531 | } while(0); |
| 22532 | if( bgotonextstatement ) |
| 22533 | { |
| 22534 | bool bgotonextstatement = true; |
| 22535 | do |
| 22536 | { |
| 22537 | evalcond[0]=((IKabs(new_r00))+(IKabs(new_r01))); |
| 22538 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 22539 | { |
| 22540 | bgotonextstatement=false; |
| 22541 | { |
| 22542 | IkReal j0eval[3]; |
| 22543 | sj1=-1.0; |
| 22544 | cj1=0; |
| 22545 | j1=-1.5707963267949; |
| 22546 | new_r00=0; |
| 22547 | new_r01=0; |
| 22548 | new_r12=0; |
| 22549 | new_r22=0; |
| 22550 | j0eval[0]=new_r10; |
| 22551 | j0eval[1]=IKsign(new_r10); |
| 22552 | j0eval[2]=((IKabs(cj2))+(IKabs(sj2))); |
| 22553 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 22554 | { |
| 22555 | { |
| 22556 | IkReal j0eval[3]; |
| 22557 | sj1=-1.0; |
| 22558 | cj1=0; |
| 22559 | j1=-1.5707963267949; |
| 22560 | new_r00=0; |
| 22561 | new_r01=0; |
| 22562 | new_r12=0; |
| 22563 | new_r22=0; |
| 22564 | j0eval[0]=new_r11; |
| 22565 | j0eval[1]=IKsign(new_r11); |
| 22566 | j0eval[2]=((IKabs(cj2))+(IKabs(sj2))); |
| 22567 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 || IKabs(j0eval[2]) < 0.0000010000000000 ) |
| 22568 | { |
| 22569 | { |
| 22570 | IkReal j0eval[2]; |
| 22571 | sj1=-1.0; |
| 22572 | cj1=0; |
| 22573 | j1=-1.5707963267949; |
| 22574 | new_r00=0; |
| 22575 | new_r01=0; |
| 22576 | new_r12=0; |
| 22577 | new_r22=0; |
| 22578 | j0eval[0]=new_r10; |
| 22579 | j0eval[1]=new_r11; |
| 22580 | if( IKabs(j0eval[0]) < 0.0000010000000000 || IKabs(j0eval[1]) < 0.0000010000000000 ) |
| 22581 | { |
| 22582 | continue; // no branches [j0] |
| 22583 | |
| 22584 | } else |
| 22585 | { |
| 22586 | { |
| 22587 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22588 | bool j0valid[1]={false}; |
| 22589 | _nj0 = 1; |
| 22590 | CheckValue<IkReal> x1672=IKPowWithIntegerCheck(new_r10,-1); |
| 22591 | if(!x1672.valid){ |
| 22592 | continue; |
| 22593 | } |
| 22594 | CheckValue<IkReal> x1673=IKPowWithIntegerCheck(new_r11,-1); |
| 22595 | if(!x1673.valid){ |
| 22596 | continue; |
| 22597 | } |
| 22598 | if( IKabs((sj2*(x1672.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*sj2*(x1673.value))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((sj2*(x1672.value)))+IKsqr(((-1.0)*sj2*(x1673.value)))-1) <= IKFAST_SINCOS_THRESH ) |
| 22599 | continue; |
| 22600 | j0array[0]=IKatan2((sj2*(x1672.value)), ((-1.0)*sj2*(x1673.value))); |
| 22601 | sj0array[0]=IKsin(j0array[0]); |
| 22602 | cj0array[0]=IKcos(j0array[0]); |
| 22603 | if( j0array[0] > IKPI ) |
| 22604 | { |
| 22605 | j0array[0]-=IK2PI; |
| 22606 | } |
| 22607 | else if( j0array[0] < -IKPI ) |
| 22608 | { j0array[0]+=IK2PI; |
| 22609 | } |
| 22610 | j0valid[0] = true; |
| 22611 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22612 | { |
| 22613 | if( !j0valid[ij0] ) |
| 22614 | { |
| 22615 | continue; |
| 22616 | } |
| 22617 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22618 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22619 | { |
| 22620 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22621 | { |
| 22622 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22623 | } |
| 22624 | } |
| 22625 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22626 | { |
| 22627 | IkReal evalcond[8]; |
| 22628 | IkReal x1674=IKcos(j0); |
| 22629 | IkReal x1675=IKsin(j0); |
| 22630 | IkReal x1676=((1.0)*sj2); |
| 22631 | IkReal x1677=(sj2*x1674); |
| 22632 | IkReal x1678=((1.0)*x1674); |
| 22633 | IkReal x1679=(cj2*x1675); |
| 22634 | IkReal x1680=(((x1675*x1676))+((cj2*x1678))); |
| 22635 | evalcond[0]=(sj2+((new_r11*x1674))); |
| 22636 | evalcond[1]=(cj2+(((-1.0)*new_r10*x1678))); |
| 22637 | evalcond[2]=(((new_r10*x1675))+(((-1.0)*x1676))); |
| 22638 | evalcond[3]=(((new_r11*x1675))+(((-1.0)*cj2))); |
| 22639 | evalcond[4]=(x1679+(((-1.0)*x1674*x1676))); |
| 22640 | evalcond[5]=(x1677+(((-1.0)*x1679))+new_r11); |
| 22641 | evalcond[6]=((-1.0)*x1680); |
| 22642 | evalcond[7]=((((-1.0)*x1680))+new_r10); |
| 22643 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22644 | { |
| 22645 | continue; |
| 22646 | } |
| 22647 | } |
| 22648 | |
| 22649 | { |
| 22650 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22651 | vinfos[0].jointtype = 1; |
| 22652 | vinfos[0].foffset = j0; |
| 22653 | vinfos[0].indices[0] = _ij0[0]; |
| 22654 | vinfos[0].indices[1] = _ij0[1]; |
| 22655 | vinfos[0].maxsolutions = _nj0; |
| 22656 | vinfos[1].jointtype = 1; |
| 22657 | vinfos[1].foffset = j1; |
| 22658 | vinfos[1].indices[0] = _ij1[0]; |
| 22659 | vinfos[1].indices[1] = _ij1[1]; |
| 22660 | vinfos[1].maxsolutions = _nj1; |
| 22661 | vinfos[2].jointtype = 1; |
| 22662 | vinfos[2].foffset = j2; |
| 22663 | vinfos[2].indices[0] = _ij2[0]; |
| 22664 | vinfos[2].indices[1] = _ij2[1]; |
| 22665 | vinfos[2].maxsolutions = _nj2; |
| 22666 | vinfos[3].jointtype = 1; |
| 22667 | vinfos[3].foffset = j3; |
| 22668 | vinfos[3].indices[0] = _ij3[0]; |
| 22669 | vinfos[3].indices[1] = _ij3[1]; |
| 22670 | vinfos[3].maxsolutions = _nj3; |
| 22671 | vinfos[4].jointtype = 1; |
| 22672 | vinfos[4].foffset = j4; |
| 22673 | vinfos[4].indices[0] = _ij4[0]; |
| 22674 | vinfos[4].indices[1] = _ij4[1]; |
| 22675 | vinfos[4].maxsolutions = _nj4; |
| 22676 | vinfos[5].jointtype = 1; |
| 22677 | vinfos[5].foffset = j5; |
| 22678 | vinfos[5].indices[0] = _ij5[0]; |
| 22679 | vinfos[5].indices[1] = _ij5[1]; |
| 22680 | vinfos[5].maxsolutions = _nj5; |
| 22681 | std::vector<int> vfree(0); |
| 22682 | solutions.AddSolution(vinfos,vfree); |
| 22683 | } |
| 22684 | } |
| 22685 | } |
| 22686 | |
| 22687 | } |
| 22688 | |
| 22689 | } |
| 22690 | |
| 22691 | } else |
| 22692 | { |
| 22693 | { |
| 22694 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22695 | bool j0valid[1]={false}; |
| 22696 | _nj0 = 1; |
| 22697 | CheckValue<IkReal> x1681=IKPowWithIntegerCheck(IKsign(new_r11),-1); |
| 22698 | if(!x1681.valid){ |
| 22699 | continue; |
| 22700 | } |
| 22701 | CheckValue<IkReal> x1682 = IKatan2WithCheck(IkReal(cj2),IkReal(((-1.0)*sj2)),IKFAST_ATAN2_MAGTHRESH); |
| 22702 | if(!x1682.valid){ |
| 22703 | continue; |
| 22704 | } |
| 22705 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1681.value)))+(x1682.value)); |
| 22706 | sj0array[0]=IKsin(j0array[0]); |
| 22707 | cj0array[0]=IKcos(j0array[0]); |
| 22708 | if( j0array[0] > IKPI ) |
| 22709 | { |
| 22710 | j0array[0]-=IK2PI; |
| 22711 | } |
| 22712 | else if( j0array[0] < -IKPI ) |
| 22713 | { j0array[0]+=IK2PI; |
| 22714 | } |
| 22715 | j0valid[0] = true; |
| 22716 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22717 | { |
| 22718 | if( !j0valid[ij0] ) |
| 22719 | { |
| 22720 | continue; |
| 22721 | } |
| 22722 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22723 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22724 | { |
| 22725 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22726 | { |
| 22727 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22728 | } |
| 22729 | } |
| 22730 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22731 | { |
| 22732 | IkReal evalcond[8]; |
| 22733 | IkReal x1683=IKcos(j0); |
| 22734 | IkReal x1684=IKsin(j0); |
| 22735 | IkReal x1685=((1.0)*sj2); |
| 22736 | IkReal x1686=(sj2*x1683); |
| 22737 | IkReal x1687=((1.0)*x1683); |
| 22738 | IkReal x1688=(cj2*x1684); |
| 22739 | IkReal x1689=(((x1684*x1685))+((cj2*x1687))); |
| 22740 | evalcond[0]=(sj2+((new_r11*x1683))); |
| 22741 | evalcond[1]=(cj2+(((-1.0)*new_r10*x1687))); |
| 22742 | evalcond[2]=((((-1.0)*x1685))+((new_r10*x1684))); |
| 22743 | evalcond[3]=(((new_r11*x1684))+(((-1.0)*cj2))); |
| 22744 | evalcond[4]=(x1688+(((-1.0)*x1683*x1685))); |
| 22745 | evalcond[5]=(x1686+(((-1.0)*x1688))+new_r11); |
| 22746 | evalcond[6]=((-1.0)*x1689); |
| 22747 | evalcond[7]=((((-1.0)*x1689))+new_r10); |
| 22748 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22749 | { |
| 22750 | continue; |
| 22751 | } |
| 22752 | } |
| 22753 | |
| 22754 | { |
| 22755 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22756 | vinfos[0].jointtype = 1; |
| 22757 | vinfos[0].foffset = j0; |
| 22758 | vinfos[0].indices[0] = _ij0[0]; |
| 22759 | vinfos[0].indices[1] = _ij0[1]; |
| 22760 | vinfos[0].maxsolutions = _nj0; |
| 22761 | vinfos[1].jointtype = 1; |
| 22762 | vinfos[1].foffset = j1; |
| 22763 | vinfos[1].indices[0] = _ij1[0]; |
| 22764 | vinfos[1].indices[1] = _ij1[1]; |
| 22765 | vinfos[1].maxsolutions = _nj1; |
| 22766 | vinfos[2].jointtype = 1; |
| 22767 | vinfos[2].foffset = j2; |
| 22768 | vinfos[2].indices[0] = _ij2[0]; |
| 22769 | vinfos[2].indices[1] = _ij2[1]; |
| 22770 | vinfos[2].maxsolutions = _nj2; |
| 22771 | vinfos[3].jointtype = 1; |
| 22772 | vinfos[3].foffset = j3; |
| 22773 | vinfos[3].indices[0] = _ij3[0]; |
| 22774 | vinfos[3].indices[1] = _ij3[1]; |
| 22775 | vinfos[3].maxsolutions = _nj3; |
| 22776 | vinfos[4].jointtype = 1; |
| 22777 | vinfos[4].foffset = j4; |
| 22778 | vinfos[4].indices[0] = _ij4[0]; |
| 22779 | vinfos[4].indices[1] = _ij4[1]; |
| 22780 | vinfos[4].maxsolutions = _nj4; |
| 22781 | vinfos[5].jointtype = 1; |
| 22782 | vinfos[5].foffset = j5; |
| 22783 | vinfos[5].indices[0] = _ij5[0]; |
| 22784 | vinfos[5].indices[1] = _ij5[1]; |
| 22785 | vinfos[5].maxsolutions = _nj5; |
| 22786 | std::vector<int> vfree(0); |
| 22787 | solutions.AddSolution(vinfos,vfree); |
| 22788 | } |
| 22789 | } |
| 22790 | } |
| 22791 | |
| 22792 | } |
| 22793 | |
| 22794 | } |
| 22795 | |
| 22796 | } else |
| 22797 | { |
| 22798 | { |
| 22799 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 22800 | bool j0valid[1]={false}; |
| 22801 | _nj0 = 1; |
| 22802 | CheckValue<IkReal> x1690=IKPowWithIntegerCheck(IKsign(new_r10),-1); |
| 22803 | if(!x1690.valid){ |
| 22804 | continue; |
| 22805 | } |
| 22806 | CheckValue<IkReal> x1691 = IKatan2WithCheck(IkReal(sj2),IkReal(cj2),IKFAST_ATAN2_MAGTHRESH); |
| 22807 | if(!x1691.valid){ |
| 22808 | continue; |
| 22809 | } |
| 22810 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1690.value)))+(x1691.value)); |
| 22811 | sj0array[0]=IKsin(j0array[0]); |
| 22812 | cj0array[0]=IKcos(j0array[0]); |
| 22813 | if( j0array[0] > IKPI ) |
| 22814 | { |
| 22815 | j0array[0]-=IK2PI; |
| 22816 | } |
| 22817 | else if( j0array[0] < -IKPI ) |
| 22818 | { j0array[0]+=IK2PI; |
| 22819 | } |
| 22820 | j0valid[0] = true; |
| 22821 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 22822 | { |
| 22823 | if( !j0valid[ij0] ) |
| 22824 | { |
| 22825 | continue; |
| 22826 | } |
| 22827 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22828 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 22829 | { |
| 22830 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22831 | { |
| 22832 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22833 | } |
| 22834 | } |
| 22835 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22836 | { |
| 22837 | IkReal evalcond[8]; |
| 22838 | IkReal x1692=IKcos(j0); |
| 22839 | IkReal x1693=IKsin(j0); |
| 22840 | IkReal x1694=((1.0)*sj2); |
| 22841 | IkReal x1695=(sj2*x1692); |
| 22842 | IkReal x1696=((1.0)*x1692); |
| 22843 | IkReal x1697=(cj2*x1693); |
| 22844 | IkReal x1698=(((x1693*x1694))+((cj2*x1696))); |
| 22845 | evalcond[0]=(sj2+((new_r11*x1692))); |
| 22846 | evalcond[1]=(cj2+(((-1.0)*new_r10*x1696))); |
| 22847 | evalcond[2]=((((-1.0)*x1694))+((new_r10*x1693))); |
| 22848 | evalcond[3]=(((new_r11*x1693))+(((-1.0)*cj2))); |
| 22849 | evalcond[4]=((((-1.0)*x1692*x1694))+x1697); |
| 22850 | evalcond[5]=(x1695+(((-1.0)*x1697))+new_r11); |
| 22851 | evalcond[6]=((-1.0)*x1698); |
| 22852 | evalcond[7]=((((-1.0)*x1698))+new_r10); |
| 22853 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 22854 | { |
| 22855 | continue; |
| 22856 | } |
| 22857 | } |
| 22858 | |
| 22859 | { |
| 22860 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22861 | vinfos[0].jointtype = 1; |
| 22862 | vinfos[0].foffset = j0; |
| 22863 | vinfos[0].indices[0] = _ij0[0]; |
| 22864 | vinfos[0].indices[1] = _ij0[1]; |
| 22865 | vinfos[0].maxsolutions = _nj0; |
| 22866 | vinfos[1].jointtype = 1; |
| 22867 | vinfos[1].foffset = j1; |
| 22868 | vinfos[1].indices[0] = _ij1[0]; |
| 22869 | vinfos[1].indices[1] = _ij1[1]; |
| 22870 | vinfos[1].maxsolutions = _nj1; |
| 22871 | vinfos[2].jointtype = 1; |
| 22872 | vinfos[2].foffset = j2; |
| 22873 | vinfos[2].indices[0] = _ij2[0]; |
| 22874 | vinfos[2].indices[1] = _ij2[1]; |
| 22875 | vinfos[2].maxsolutions = _nj2; |
| 22876 | vinfos[3].jointtype = 1; |
| 22877 | vinfos[3].foffset = j3; |
| 22878 | vinfos[3].indices[0] = _ij3[0]; |
| 22879 | vinfos[3].indices[1] = _ij3[1]; |
| 22880 | vinfos[3].maxsolutions = _nj3; |
| 22881 | vinfos[4].jointtype = 1; |
| 22882 | vinfos[4].foffset = j4; |
| 22883 | vinfos[4].indices[0] = _ij4[0]; |
| 22884 | vinfos[4].indices[1] = _ij4[1]; |
| 22885 | vinfos[4].maxsolutions = _nj4; |
| 22886 | vinfos[5].jointtype = 1; |
| 22887 | vinfos[5].foffset = j5; |
| 22888 | vinfos[5].indices[0] = _ij5[0]; |
| 22889 | vinfos[5].indices[1] = _ij5[1]; |
| 22890 | vinfos[5].maxsolutions = _nj5; |
| 22891 | std::vector<int> vfree(0); |
| 22892 | solutions.AddSolution(vinfos,vfree); |
| 22893 | } |
| 22894 | } |
| 22895 | } |
| 22896 | |
| 22897 | } |
| 22898 | |
| 22899 | } |
| 22900 | |
| 22901 | } |
| 22902 | } while(0); |
| 22903 | if( bgotonextstatement ) |
| 22904 | { |
| 22905 | bool bgotonextstatement = true; |
| 22906 | do |
| 22907 | { |
| 22908 | evalcond[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 22909 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 22910 | { |
| 22911 | bgotonextstatement=false; |
| 22912 | { |
| 22913 | IkReal j0eval[1]; |
| 22914 | sj1=-1.0; |
| 22915 | cj1=0; |
| 22916 | j1=-1.5707963267949; |
| 22917 | new_r00=0; |
| 22918 | new_r10=0; |
| 22919 | new_r21=0; |
| 22920 | new_r22=0; |
| 22921 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 22922 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 22923 | { |
| 22924 | continue; // no branches [j0] |
| 22925 | |
| 22926 | } else |
| 22927 | { |
| 22928 | { |
| 22929 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 22930 | bool j0valid[2]={false}; |
| 22931 | _nj0 = 2; |
| 22932 | CheckValue<IkReal> x1700 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| 22933 | if(!x1700.valid){ |
| 22934 | continue; |
| 22935 | } |
| 22936 | IkReal x1699=x1700.value; |
| 22937 | j0array[0]=((-1.0)*x1699); |
| 22938 | sj0array[0]=IKsin(j0array[0]); |
| 22939 | cj0array[0]=IKcos(j0array[0]); |
| 22940 | j0array[1]=((3.14159265358979)+(((-1.0)*x1699))); |
| 22941 | sj0array[1]=IKsin(j0array[1]); |
| 22942 | cj0array[1]=IKcos(j0array[1]); |
| 22943 | if( j0array[0] > IKPI ) |
| 22944 | { |
| 22945 | j0array[0]-=IK2PI; |
| 22946 | } |
| 22947 | else if( j0array[0] < -IKPI ) |
| 22948 | { j0array[0]+=IK2PI; |
| 22949 | } |
| 22950 | j0valid[0] = true; |
| 22951 | if( j0array[1] > IKPI ) |
| 22952 | { |
| 22953 | j0array[1]-=IK2PI; |
| 22954 | } |
| 22955 | else if( j0array[1] < -IKPI ) |
| 22956 | { j0array[1]+=IK2PI; |
| 22957 | } |
| 22958 | j0valid[1] = true; |
| 22959 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 22960 | { |
| 22961 | if( !j0valid[ij0] ) |
| 22962 | { |
| 22963 | continue; |
| 22964 | } |
| 22965 | _ij0[0] = ij0; _ij0[1] = -1; |
| 22966 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 22967 | { |
| 22968 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 22969 | { |
| 22970 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 22971 | } |
| 22972 | } |
| 22973 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 22974 | { |
| 22975 | IkReal evalcond[1]; |
| 22976 | evalcond[0]=(((new_r11*(IKcos(j0))))+(((-1.0)*new_r01*(IKsin(j0))))); |
| 22977 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH ) |
| 22978 | { |
| 22979 | continue; |
| 22980 | } |
| 22981 | } |
| 22982 | |
| 22983 | { |
| 22984 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 22985 | vinfos[0].jointtype = 1; |
| 22986 | vinfos[0].foffset = j0; |
| 22987 | vinfos[0].indices[0] = _ij0[0]; |
| 22988 | vinfos[0].indices[1] = _ij0[1]; |
| 22989 | vinfos[0].maxsolutions = _nj0; |
| 22990 | vinfos[1].jointtype = 1; |
| 22991 | vinfos[1].foffset = j1; |
| 22992 | vinfos[1].indices[0] = _ij1[0]; |
| 22993 | vinfos[1].indices[1] = _ij1[1]; |
| 22994 | vinfos[1].maxsolutions = _nj1; |
| 22995 | vinfos[2].jointtype = 1; |
| 22996 | vinfos[2].foffset = j2; |
| 22997 | vinfos[2].indices[0] = _ij2[0]; |
| 22998 | vinfos[2].indices[1] = _ij2[1]; |
| 22999 | vinfos[2].maxsolutions = _nj2; |
| 23000 | vinfos[3].jointtype = 1; |
| 23001 | vinfos[3].foffset = j3; |
| 23002 | vinfos[3].indices[0] = _ij3[0]; |
| 23003 | vinfos[3].indices[1] = _ij3[1]; |
| 23004 | vinfos[3].maxsolutions = _nj3; |
| 23005 | vinfos[4].jointtype = 1; |
| 23006 | vinfos[4].foffset = j4; |
| 23007 | vinfos[4].indices[0] = _ij4[0]; |
| 23008 | vinfos[4].indices[1] = _ij4[1]; |
| 23009 | vinfos[4].maxsolutions = _nj4; |
| 23010 | vinfos[5].jointtype = 1; |
| 23011 | vinfos[5].foffset = j5; |
| 23012 | vinfos[5].indices[0] = _ij5[0]; |
| 23013 | vinfos[5].indices[1] = _ij5[1]; |
| 23014 | vinfos[5].maxsolutions = _nj5; |
| 23015 | std::vector<int> vfree(0); |
| 23016 | solutions.AddSolution(vinfos,vfree); |
| 23017 | } |
| 23018 | } |
| 23019 | } |
| 23020 | |
| 23021 | } |
| 23022 | |
| 23023 | } |
| 23024 | |
| 23025 | } |
| 23026 | } while(0); |
| 23027 | if( bgotonextstatement ) |
| 23028 | { |
| 23029 | bool bgotonextstatement = true; |
| 23030 | do |
| 23031 | { |
| 23032 | if( 1 ) |
| 23033 | { |
| 23034 | bgotonextstatement=false; |
| 23035 | continue; // branch miss [j0] |
| 23036 | |
| 23037 | } |
| 23038 | } while(0); |
| 23039 | if( bgotonextstatement ) |
| 23040 | { |
| 23041 | } |
| 23042 | } |
| 23043 | } |
| 23044 | } |
| 23045 | } |
| 23046 | } |
| 23047 | } |
| 23048 | } |
| 23049 | } |
| 23050 | } |
| 23051 | |
| 23052 | } else |
| 23053 | { |
| 23054 | { |
| 23055 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 23056 | bool j0valid[1]={false}; |
| 23057 | _nj0 = 1; |
| 23058 | IkReal x1701=((1.0)*new_r00); |
| 23059 | CheckValue<IkReal> x1702=IKPowWithIntegerCheck(IKsign(((((-1.0)*sj2*x1701))+((cj2*new_r10)))),-1); |
| 23060 | if(!x1702.valid){ |
| 23061 | continue; |
| 23062 | } |
| 23063 | CheckValue<IkReal> x1703 = IKatan2WithCheck(IkReal((((cj2*sj2))+(((-1.0)*new_r10*x1701)))),IkReal(((cj2*cj2)+(((-1.0)*new_r00*x1701)))),IKFAST_ATAN2_MAGTHRESH); |
| 23064 | if(!x1703.valid){ |
| 23065 | continue; |
| 23066 | } |
| 23067 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1702.value)))+(x1703.value)); |
| 23068 | sj0array[0]=IKsin(j0array[0]); |
| 23069 | cj0array[0]=IKcos(j0array[0]); |
| 23070 | if( j0array[0] > IKPI ) |
| 23071 | { |
| 23072 | j0array[0]-=IK2PI; |
| 23073 | } |
| 23074 | else if( j0array[0] < -IKPI ) |
| 23075 | { j0array[0]+=IK2PI; |
| 23076 | } |
| 23077 | j0valid[0] = true; |
| 23078 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 23079 | { |
| 23080 | if( !j0valid[ij0] ) |
| 23081 | { |
| 23082 | continue; |
| 23083 | } |
| 23084 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23085 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 23086 | { |
| 23087 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23088 | { |
| 23089 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23090 | } |
| 23091 | } |
| 23092 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23093 | { |
| 23094 | IkReal evalcond[8]; |
| 23095 | IkReal x1704=IKsin(j0); |
| 23096 | IkReal x1705=IKcos(j0); |
| 23097 | IkReal x1706=((1.0)*sj2); |
| 23098 | IkReal x1707=(sj2*x1705); |
| 23099 | IkReal x1708=((1.0)*x1705); |
| 23100 | IkReal x1709=(cj2*x1704); |
| 23101 | IkReal x1710=(((x1704*x1706))+((cj2*x1708))); |
| 23102 | evalcond[0]=(sj2+(((-1.0)*new_r01*x1704))+((new_r11*x1705))); |
| 23103 | evalcond[1]=(cj2+((new_r00*x1704))+(((-1.0)*new_r10*x1708))); |
| 23104 | evalcond[2]=(x1709+(((-1.0)*x1705*x1706))+new_r00); |
| 23105 | evalcond[3]=(x1707+(((-1.0)*x1709))+new_r11); |
| 23106 | evalcond[4]=(((new_r00*x1705))+(((-1.0)*x1706))+((new_r10*x1704))); |
| 23107 | evalcond[5]=(((new_r01*x1705))+((new_r11*x1704))+(((-1.0)*cj2))); |
| 23108 | evalcond[6]=((((-1.0)*x1710))+new_r01); |
| 23109 | evalcond[7]=((((-1.0)*x1710))+new_r10); |
| 23110 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 23111 | { |
| 23112 | continue; |
| 23113 | } |
| 23114 | } |
| 23115 | |
| 23116 | { |
| 23117 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23118 | vinfos[0].jointtype = 1; |
| 23119 | vinfos[0].foffset = j0; |
| 23120 | vinfos[0].indices[0] = _ij0[0]; |
| 23121 | vinfos[0].indices[1] = _ij0[1]; |
| 23122 | vinfos[0].maxsolutions = _nj0; |
| 23123 | vinfos[1].jointtype = 1; |
| 23124 | vinfos[1].foffset = j1; |
| 23125 | vinfos[1].indices[0] = _ij1[0]; |
| 23126 | vinfos[1].indices[1] = _ij1[1]; |
| 23127 | vinfos[1].maxsolutions = _nj1; |
| 23128 | vinfos[2].jointtype = 1; |
| 23129 | vinfos[2].foffset = j2; |
| 23130 | vinfos[2].indices[0] = _ij2[0]; |
| 23131 | vinfos[2].indices[1] = _ij2[1]; |
| 23132 | vinfos[2].maxsolutions = _nj2; |
| 23133 | vinfos[3].jointtype = 1; |
| 23134 | vinfos[3].foffset = j3; |
| 23135 | vinfos[3].indices[0] = _ij3[0]; |
| 23136 | vinfos[3].indices[1] = _ij3[1]; |
| 23137 | vinfos[3].maxsolutions = _nj3; |
| 23138 | vinfos[4].jointtype = 1; |
| 23139 | vinfos[4].foffset = j4; |
| 23140 | vinfos[4].indices[0] = _ij4[0]; |
| 23141 | vinfos[4].indices[1] = _ij4[1]; |
| 23142 | vinfos[4].maxsolutions = _nj4; |
| 23143 | vinfos[5].jointtype = 1; |
| 23144 | vinfos[5].foffset = j5; |
| 23145 | vinfos[5].indices[0] = _ij5[0]; |
| 23146 | vinfos[5].indices[1] = _ij5[1]; |
| 23147 | vinfos[5].maxsolutions = _nj5; |
| 23148 | std::vector<int> vfree(0); |
| 23149 | solutions.AddSolution(vinfos,vfree); |
| 23150 | } |
| 23151 | } |
| 23152 | } |
| 23153 | |
| 23154 | } |
| 23155 | |
| 23156 | } |
| 23157 | |
| 23158 | } else |
| 23159 | { |
| 23160 | { |
| 23161 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 23162 | bool j0valid[1]={false}; |
| 23163 | _nj0 = 1; |
| 23164 | IkReal x1711=((1.0)*sj2); |
| 23165 | CheckValue<IkReal> x1712 = IKatan2WithCheck(IkReal(((-1.0)+(cj2*cj2)+(new_r11*new_r11))),IkReal((((new_r01*new_r11))+(((-1.0)*cj2*x1711)))),IKFAST_ATAN2_MAGTHRESH); |
| 23166 | if(!x1712.valid){ |
| 23167 | continue; |
| 23168 | } |
| 23169 | CheckValue<IkReal> x1713=IKPowWithIntegerCheck(IKsign((((cj2*new_r11))+(((-1.0)*new_r01*x1711)))),-1); |
| 23170 | if(!x1713.valid){ |
| 23171 | continue; |
| 23172 | } |
| 23173 | j0array[0]=((-1.5707963267949)+(x1712.value)+(((1.5707963267949)*(x1713.value)))); |
| 23174 | sj0array[0]=IKsin(j0array[0]); |
| 23175 | cj0array[0]=IKcos(j0array[0]); |
| 23176 | if( j0array[0] > IKPI ) |
| 23177 | { |
| 23178 | j0array[0]-=IK2PI; |
| 23179 | } |
| 23180 | else if( j0array[0] < -IKPI ) |
| 23181 | { j0array[0]+=IK2PI; |
| 23182 | } |
| 23183 | j0valid[0] = true; |
| 23184 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 23185 | { |
| 23186 | if( !j0valid[ij0] ) |
| 23187 | { |
| 23188 | continue; |
| 23189 | } |
| 23190 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23191 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 23192 | { |
| 23193 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23194 | { |
| 23195 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23196 | } |
| 23197 | } |
| 23198 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23199 | { |
| 23200 | IkReal evalcond[8]; |
| 23201 | IkReal x1714=IKsin(j0); |
| 23202 | IkReal x1715=IKcos(j0); |
| 23203 | IkReal x1716=((1.0)*sj2); |
| 23204 | IkReal x1717=(sj2*x1715); |
| 23205 | IkReal x1718=((1.0)*x1715); |
| 23206 | IkReal x1719=(cj2*x1714); |
| 23207 | IkReal x1720=(((x1714*x1716))+((cj2*x1718))); |
| 23208 | evalcond[0]=(((new_r11*x1715))+sj2+(((-1.0)*new_r01*x1714))); |
| 23209 | evalcond[1]=(cj2+((new_r00*x1714))+(((-1.0)*new_r10*x1718))); |
| 23210 | evalcond[2]=(x1719+(((-1.0)*x1715*x1716))+new_r00); |
| 23211 | evalcond[3]=(x1717+(((-1.0)*x1719))+new_r11); |
| 23212 | evalcond[4]=(((new_r10*x1714))+(((-1.0)*x1716))+((new_r00*x1715))); |
| 23213 | evalcond[5]=(((new_r11*x1714))+((new_r01*x1715))+(((-1.0)*cj2))); |
| 23214 | evalcond[6]=(new_r01+(((-1.0)*x1720))); |
| 23215 | evalcond[7]=(new_r10+(((-1.0)*x1720))); |
| 23216 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 23217 | { |
| 23218 | continue; |
| 23219 | } |
| 23220 | } |
| 23221 | |
| 23222 | { |
| 23223 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23224 | vinfos[0].jointtype = 1; |
| 23225 | vinfos[0].foffset = j0; |
| 23226 | vinfos[0].indices[0] = _ij0[0]; |
| 23227 | vinfos[0].indices[1] = _ij0[1]; |
| 23228 | vinfos[0].maxsolutions = _nj0; |
| 23229 | vinfos[1].jointtype = 1; |
| 23230 | vinfos[1].foffset = j1; |
| 23231 | vinfos[1].indices[0] = _ij1[0]; |
| 23232 | vinfos[1].indices[1] = _ij1[1]; |
| 23233 | vinfos[1].maxsolutions = _nj1; |
| 23234 | vinfos[2].jointtype = 1; |
| 23235 | vinfos[2].foffset = j2; |
| 23236 | vinfos[2].indices[0] = _ij2[0]; |
| 23237 | vinfos[2].indices[1] = _ij2[1]; |
| 23238 | vinfos[2].maxsolutions = _nj2; |
| 23239 | vinfos[3].jointtype = 1; |
| 23240 | vinfos[3].foffset = j3; |
| 23241 | vinfos[3].indices[0] = _ij3[0]; |
| 23242 | vinfos[3].indices[1] = _ij3[1]; |
| 23243 | vinfos[3].maxsolutions = _nj3; |
| 23244 | vinfos[4].jointtype = 1; |
| 23245 | vinfos[4].foffset = j4; |
| 23246 | vinfos[4].indices[0] = _ij4[0]; |
| 23247 | vinfos[4].indices[1] = _ij4[1]; |
| 23248 | vinfos[4].maxsolutions = _nj4; |
| 23249 | vinfos[5].jointtype = 1; |
| 23250 | vinfos[5].foffset = j5; |
| 23251 | vinfos[5].indices[0] = _ij5[0]; |
| 23252 | vinfos[5].indices[1] = _ij5[1]; |
| 23253 | vinfos[5].maxsolutions = _nj5; |
| 23254 | std::vector<int> vfree(0); |
| 23255 | solutions.AddSolution(vinfos,vfree); |
| 23256 | } |
| 23257 | } |
| 23258 | } |
| 23259 | |
| 23260 | } |
| 23261 | |
| 23262 | } |
| 23263 | |
| 23264 | } else |
| 23265 | { |
| 23266 | { |
| 23267 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 23268 | bool j0valid[1]={false}; |
| 23269 | _nj0 = 1; |
| 23270 | CheckValue<IkReal> x1721 = IKatan2WithCheck(IkReal((((new_r10*sj2))+((cj2*new_r11)))),IkReal((((new_r00*sj2))+((cj2*new_r01)))),IKFAST_ATAN2_MAGTHRESH); |
| 23271 | if(!x1721.valid){ |
| 23272 | continue; |
| 23273 | } |
| 23274 | CheckValue<IkReal> x1722=IKPowWithIntegerCheck(IKsign((((new_r01*new_r10))+(((-1.0)*new_r00*new_r11)))),-1); |
| 23275 | if(!x1722.valid){ |
| 23276 | continue; |
| 23277 | } |
| 23278 | j0array[0]=((-1.5707963267949)+(x1721.value)+(((1.5707963267949)*(x1722.value)))); |
| 23279 | sj0array[0]=IKsin(j0array[0]); |
| 23280 | cj0array[0]=IKcos(j0array[0]); |
| 23281 | if( j0array[0] > IKPI ) |
| 23282 | { |
| 23283 | j0array[0]-=IK2PI; |
| 23284 | } |
| 23285 | else if( j0array[0] < -IKPI ) |
| 23286 | { j0array[0]+=IK2PI; |
| 23287 | } |
| 23288 | j0valid[0] = true; |
| 23289 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 23290 | { |
| 23291 | if( !j0valid[ij0] ) |
| 23292 | { |
| 23293 | continue; |
| 23294 | } |
| 23295 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23296 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 23297 | { |
| 23298 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23299 | { |
| 23300 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23301 | } |
| 23302 | } |
| 23303 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23304 | { |
| 23305 | IkReal evalcond[8]; |
| 23306 | IkReal x1723=IKsin(j0); |
| 23307 | IkReal x1724=IKcos(j0); |
| 23308 | IkReal x1725=((1.0)*sj2); |
| 23309 | IkReal x1726=(sj2*x1724); |
| 23310 | IkReal x1727=((1.0)*x1724); |
| 23311 | IkReal x1728=(cj2*x1723); |
| 23312 | IkReal x1729=(((x1723*x1725))+((cj2*x1727))); |
| 23313 | evalcond[0]=(sj2+((new_r11*x1724))+(((-1.0)*new_r01*x1723))); |
| 23314 | evalcond[1]=(cj2+(((-1.0)*new_r10*x1727))+((new_r00*x1723))); |
| 23315 | evalcond[2]=(x1728+(((-1.0)*x1724*x1725))+new_r00); |
| 23316 | evalcond[3]=(x1726+new_r11+(((-1.0)*x1728))); |
| 23317 | evalcond[4]=(((new_r10*x1723))+(((-1.0)*x1725))+((new_r00*x1724))); |
| 23318 | evalcond[5]=(((new_r11*x1723))+(((-1.0)*cj2))+((new_r01*x1724))); |
| 23319 | evalcond[6]=(new_r01+(((-1.0)*x1729))); |
| 23320 | evalcond[7]=(new_r10+(((-1.0)*x1729))); |
| 23321 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 23322 | { |
| 23323 | continue; |
| 23324 | } |
| 23325 | } |
| 23326 | |
| 23327 | { |
| 23328 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23329 | vinfos[0].jointtype = 1; |
| 23330 | vinfos[0].foffset = j0; |
| 23331 | vinfos[0].indices[0] = _ij0[0]; |
| 23332 | vinfos[0].indices[1] = _ij0[1]; |
| 23333 | vinfos[0].maxsolutions = _nj0; |
| 23334 | vinfos[1].jointtype = 1; |
| 23335 | vinfos[1].foffset = j1; |
| 23336 | vinfos[1].indices[0] = _ij1[0]; |
| 23337 | vinfos[1].indices[1] = _ij1[1]; |
| 23338 | vinfos[1].maxsolutions = _nj1; |
| 23339 | vinfos[2].jointtype = 1; |
| 23340 | vinfos[2].foffset = j2; |
| 23341 | vinfos[2].indices[0] = _ij2[0]; |
| 23342 | vinfos[2].indices[1] = _ij2[1]; |
| 23343 | vinfos[2].maxsolutions = _nj2; |
| 23344 | vinfos[3].jointtype = 1; |
| 23345 | vinfos[3].foffset = j3; |
| 23346 | vinfos[3].indices[0] = _ij3[0]; |
| 23347 | vinfos[3].indices[1] = _ij3[1]; |
| 23348 | vinfos[3].maxsolutions = _nj3; |
| 23349 | vinfos[4].jointtype = 1; |
| 23350 | vinfos[4].foffset = j4; |
| 23351 | vinfos[4].indices[0] = _ij4[0]; |
| 23352 | vinfos[4].indices[1] = _ij4[1]; |
| 23353 | vinfos[4].maxsolutions = _nj4; |
| 23354 | vinfos[5].jointtype = 1; |
| 23355 | vinfos[5].foffset = j5; |
| 23356 | vinfos[5].indices[0] = _ij5[0]; |
| 23357 | vinfos[5].indices[1] = _ij5[1]; |
| 23358 | vinfos[5].maxsolutions = _nj5; |
| 23359 | std::vector<int> vfree(0); |
| 23360 | solutions.AddSolution(vinfos,vfree); |
| 23361 | } |
| 23362 | } |
| 23363 | } |
| 23364 | |
| 23365 | } |
| 23366 | |
| 23367 | } |
| 23368 | |
| 23369 | } |
| 23370 | } while(0); |
| 23371 | if( bgotonextstatement ) |
| 23372 | { |
| 23373 | bool bgotonextstatement = true; |
| 23374 | do |
| 23375 | { |
| 23376 | evalcond[0]=((IKabs(new_r12))+(IKabs(new_r02))); |
| 23377 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 23378 | { |
| 23379 | bgotonextstatement=false; |
| 23380 | { |
| 23381 | IkReal j0eval[1]; |
| 23382 | new_r02=0; |
| 23383 | new_r12=0; |
| 23384 | new_r20=0; |
| 23385 | new_r21=0; |
| 23386 | j0eval[0]=((IKabs(new_r10))+(IKabs(new_r00))); |
| 23387 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 23388 | { |
| 23389 | { |
| 23390 | IkReal j0eval[1]; |
| 23391 | new_r02=0; |
| 23392 | new_r12=0; |
| 23393 | new_r20=0; |
| 23394 | new_r21=0; |
| 23395 | j0eval[0]=((IKabs(new_r11))+(IKabs(new_r01))); |
| 23396 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 23397 | { |
| 23398 | { |
| 23399 | IkReal j0eval[1]; |
| 23400 | new_r02=0; |
| 23401 | new_r12=0; |
| 23402 | new_r20=0; |
| 23403 | new_r21=0; |
| 23404 | j0eval[0]=((IKabs((new_r10*new_r22)))+(IKabs((new_r00*new_r22)))); |
| 23405 | if( IKabs(j0eval[0]) < 0.0000010000000000 ) |
| 23406 | { |
| 23407 | continue; // no branches [j0] |
| 23408 | |
| 23409 | } else |
| 23410 | { |
| 23411 | { |
| 23412 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 23413 | bool j0valid[2]={false}; |
| 23414 | _nj0 = 2; |
| 23415 | IkReal x1730=((-1.0)*new_r22); |
| 23416 | CheckValue<IkReal> x1732 = IKatan2WithCheck(IkReal((new_r00*x1730)),IkReal((new_r10*x1730)),IKFAST_ATAN2_MAGTHRESH); |
| 23417 | if(!x1732.valid){ |
| 23418 | continue; |
| 23419 | } |
| 23420 | IkReal x1731=x1732.value; |
| 23421 | j0array[0]=((-1.0)*x1731); |
| 23422 | sj0array[0]=IKsin(j0array[0]); |
| 23423 | cj0array[0]=IKcos(j0array[0]); |
| 23424 | j0array[1]=((3.14159265358979)+(((-1.0)*x1731))); |
| 23425 | sj0array[1]=IKsin(j0array[1]); |
| 23426 | cj0array[1]=IKcos(j0array[1]); |
| 23427 | if( j0array[0] > IKPI ) |
| 23428 | { |
| 23429 | j0array[0]-=IK2PI; |
| 23430 | } |
| 23431 | else if( j0array[0] < -IKPI ) |
| 23432 | { j0array[0]+=IK2PI; |
| 23433 | } |
| 23434 | j0valid[0] = true; |
| 23435 | if( j0array[1] > IKPI ) |
| 23436 | { |
| 23437 | j0array[1]-=IK2PI; |
| 23438 | } |
| 23439 | else if( j0array[1] < -IKPI ) |
| 23440 | { j0array[1]+=IK2PI; |
| 23441 | } |
| 23442 | j0valid[1] = true; |
| 23443 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 23444 | { |
| 23445 | if( !j0valid[ij0] ) |
| 23446 | { |
| 23447 | continue; |
| 23448 | } |
| 23449 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23450 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 23451 | { |
| 23452 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23453 | { |
| 23454 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23455 | } |
| 23456 | } |
| 23457 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23458 | { |
| 23459 | IkReal evalcond[5]; |
| 23460 | IkReal x1733=IKsin(j0); |
| 23461 | IkReal x1734=IKcos(j0); |
| 23462 | IkReal x1735=((1.0)*x1734); |
| 23463 | IkReal x1736=(new_r11*x1733); |
| 23464 | evalcond[0]=(((new_r10*x1733))+((new_r00*x1734))); |
| 23465 | evalcond[1]=(x1736+((new_r01*x1734))); |
| 23466 | evalcond[2]=(((new_r11*x1734))+(((-1.0)*new_r01*x1733))); |
| 23467 | evalcond[3]=((((-1.0)*new_r10*x1735))+((new_r00*x1733))); |
| 23468 | evalcond[4]=((((-1.0)*new_r22*x1736))+(((-1.0)*new_r01*new_r22*x1735))); |
| 23469 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 23470 | { |
| 23471 | continue; |
| 23472 | } |
| 23473 | } |
| 23474 | |
| 23475 | { |
| 23476 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23477 | vinfos[0].jointtype = 1; |
| 23478 | vinfos[0].foffset = j0; |
| 23479 | vinfos[0].indices[0] = _ij0[0]; |
| 23480 | vinfos[0].indices[1] = _ij0[1]; |
| 23481 | vinfos[0].maxsolutions = _nj0; |
| 23482 | vinfos[1].jointtype = 1; |
| 23483 | vinfos[1].foffset = j1; |
| 23484 | vinfos[1].indices[0] = _ij1[0]; |
| 23485 | vinfos[1].indices[1] = _ij1[1]; |
| 23486 | vinfos[1].maxsolutions = _nj1; |
| 23487 | vinfos[2].jointtype = 1; |
| 23488 | vinfos[2].foffset = j2; |
| 23489 | vinfos[2].indices[0] = _ij2[0]; |
| 23490 | vinfos[2].indices[1] = _ij2[1]; |
| 23491 | vinfos[2].maxsolutions = _nj2; |
| 23492 | vinfos[3].jointtype = 1; |
| 23493 | vinfos[3].foffset = j3; |
| 23494 | vinfos[3].indices[0] = _ij3[0]; |
| 23495 | vinfos[3].indices[1] = _ij3[1]; |
| 23496 | vinfos[3].maxsolutions = _nj3; |
| 23497 | vinfos[4].jointtype = 1; |
| 23498 | vinfos[4].foffset = j4; |
| 23499 | vinfos[4].indices[0] = _ij4[0]; |
| 23500 | vinfos[4].indices[1] = _ij4[1]; |
| 23501 | vinfos[4].maxsolutions = _nj4; |
| 23502 | vinfos[5].jointtype = 1; |
| 23503 | vinfos[5].foffset = j5; |
| 23504 | vinfos[5].indices[0] = _ij5[0]; |
| 23505 | vinfos[5].indices[1] = _ij5[1]; |
| 23506 | vinfos[5].maxsolutions = _nj5; |
| 23507 | std::vector<int> vfree(0); |
| 23508 | solutions.AddSolution(vinfos,vfree); |
| 23509 | } |
| 23510 | } |
| 23511 | } |
| 23512 | |
| 23513 | } |
| 23514 | |
| 23515 | } |
| 23516 | |
| 23517 | } else |
| 23518 | { |
| 23519 | { |
| 23520 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 23521 | bool j0valid[2]={false}; |
| 23522 | _nj0 = 2; |
| 23523 | CheckValue<IkReal> x1738 = IKatan2WithCheck(IkReal(new_r01),IkReal(new_r11),IKFAST_ATAN2_MAGTHRESH); |
| 23524 | if(!x1738.valid){ |
| 23525 | continue; |
| 23526 | } |
| 23527 | IkReal x1737=x1738.value; |
| 23528 | j0array[0]=((-1.0)*x1737); |
| 23529 | sj0array[0]=IKsin(j0array[0]); |
| 23530 | cj0array[0]=IKcos(j0array[0]); |
| 23531 | j0array[1]=((3.14159265358979)+(((-1.0)*x1737))); |
| 23532 | sj0array[1]=IKsin(j0array[1]); |
| 23533 | cj0array[1]=IKcos(j0array[1]); |
| 23534 | if( j0array[0] > IKPI ) |
| 23535 | { |
| 23536 | j0array[0]-=IK2PI; |
| 23537 | } |
| 23538 | else if( j0array[0] < -IKPI ) |
| 23539 | { j0array[0]+=IK2PI; |
| 23540 | } |
| 23541 | j0valid[0] = true; |
| 23542 | if( j0array[1] > IKPI ) |
| 23543 | { |
| 23544 | j0array[1]-=IK2PI; |
| 23545 | } |
| 23546 | else if( j0array[1] < -IKPI ) |
| 23547 | { j0array[1]+=IK2PI; |
| 23548 | } |
| 23549 | j0valid[1] = true; |
| 23550 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 23551 | { |
| 23552 | if( !j0valid[ij0] ) |
| 23553 | { |
| 23554 | continue; |
| 23555 | } |
| 23556 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23557 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 23558 | { |
| 23559 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23560 | { |
| 23561 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23562 | } |
| 23563 | } |
| 23564 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23565 | { |
| 23566 | IkReal evalcond[5]; |
| 23567 | IkReal x1739=IKcos(j0); |
| 23568 | IkReal x1740=IKsin(j0); |
| 23569 | IkReal x1741=((1.0)*new_r22); |
| 23570 | IkReal x1742=(new_r10*x1740); |
| 23571 | IkReal x1743=(new_r00*x1739); |
| 23572 | evalcond[0]=(x1742+x1743); |
| 23573 | evalcond[1]=(((new_r11*x1739))+(((-1.0)*new_r01*x1740))); |
| 23574 | evalcond[2]=(((new_r00*x1740))+(((-1.0)*new_r10*x1739))); |
| 23575 | evalcond[3]=((((-1.0)*x1741*x1742))+(((-1.0)*x1741*x1743))); |
| 23576 | evalcond[4]=((((-1.0)*new_r11*x1740*x1741))+(((-1.0)*new_r01*x1739*x1741))); |
| 23577 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 23578 | { |
| 23579 | continue; |
| 23580 | } |
| 23581 | } |
| 23582 | |
| 23583 | { |
| 23584 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23585 | vinfos[0].jointtype = 1; |
| 23586 | vinfos[0].foffset = j0; |
| 23587 | vinfos[0].indices[0] = _ij0[0]; |
| 23588 | vinfos[0].indices[1] = _ij0[1]; |
| 23589 | vinfos[0].maxsolutions = _nj0; |
| 23590 | vinfos[1].jointtype = 1; |
| 23591 | vinfos[1].foffset = j1; |
| 23592 | vinfos[1].indices[0] = _ij1[0]; |
| 23593 | vinfos[1].indices[1] = _ij1[1]; |
| 23594 | vinfos[1].maxsolutions = _nj1; |
| 23595 | vinfos[2].jointtype = 1; |
| 23596 | vinfos[2].foffset = j2; |
| 23597 | vinfos[2].indices[0] = _ij2[0]; |
| 23598 | vinfos[2].indices[1] = _ij2[1]; |
| 23599 | vinfos[2].maxsolutions = _nj2; |
| 23600 | vinfos[3].jointtype = 1; |
| 23601 | vinfos[3].foffset = j3; |
| 23602 | vinfos[3].indices[0] = _ij3[0]; |
| 23603 | vinfos[3].indices[1] = _ij3[1]; |
| 23604 | vinfos[3].maxsolutions = _nj3; |
| 23605 | vinfos[4].jointtype = 1; |
| 23606 | vinfos[4].foffset = j4; |
| 23607 | vinfos[4].indices[0] = _ij4[0]; |
| 23608 | vinfos[4].indices[1] = _ij4[1]; |
| 23609 | vinfos[4].maxsolutions = _nj4; |
| 23610 | vinfos[5].jointtype = 1; |
| 23611 | vinfos[5].foffset = j5; |
| 23612 | vinfos[5].indices[0] = _ij5[0]; |
| 23613 | vinfos[5].indices[1] = _ij5[1]; |
| 23614 | vinfos[5].maxsolutions = _nj5; |
| 23615 | std::vector<int> vfree(0); |
| 23616 | solutions.AddSolution(vinfos,vfree); |
| 23617 | } |
| 23618 | } |
| 23619 | } |
| 23620 | |
| 23621 | } |
| 23622 | |
| 23623 | } |
| 23624 | |
| 23625 | } else |
| 23626 | { |
| 23627 | { |
| 23628 | IkReal j0array[2], cj0array[2], sj0array[2]; |
| 23629 | bool j0valid[2]={false}; |
| 23630 | _nj0 = 2; |
| 23631 | CheckValue<IkReal> x1745 = IKatan2WithCheck(IkReal(new_r00),IkReal(new_r10),IKFAST_ATAN2_MAGTHRESH); |
| 23632 | if(!x1745.valid){ |
| 23633 | continue; |
| 23634 | } |
| 23635 | IkReal x1744=x1745.value; |
| 23636 | j0array[0]=((-1.0)*x1744); |
| 23637 | sj0array[0]=IKsin(j0array[0]); |
| 23638 | cj0array[0]=IKcos(j0array[0]); |
| 23639 | j0array[1]=((3.14159265358979)+(((-1.0)*x1744))); |
| 23640 | sj0array[1]=IKsin(j0array[1]); |
| 23641 | cj0array[1]=IKcos(j0array[1]); |
| 23642 | if( j0array[0] > IKPI ) |
| 23643 | { |
| 23644 | j0array[0]-=IK2PI; |
| 23645 | } |
| 23646 | else if( j0array[0] < -IKPI ) |
| 23647 | { j0array[0]+=IK2PI; |
| 23648 | } |
| 23649 | j0valid[0] = true; |
| 23650 | if( j0array[1] > IKPI ) |
| 23651 | { |
| 23652 | j0array[1]-=IK2PI; |
| 23653 | } |
| 23654 | else if( j0array[1] < -IKPI ) |
| 23655 | { j0array[1]+=IK2PI; |
| 23656 | } |
| 23657 | j0valid[1] = true; |
| 23658 | for(int ij0 = 0; ij0 < 2; ++ij0) |
| 23659 | { |
| 23660 | if( !j0valid[ij0] ) |
| 23661 | { |
| 23662 | continue; |
| 23663 | } |
| 23664 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23665 | for(int iij0 = ij0+1; iij0 < 2; ++iij0) |
| 23666 | { |
| 23667 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23668 | { |
| 23669 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23670 | } |
| 23671 | } |
| 23672 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23673 | { |
| 23674 | IkReal evalcond[5]; |
| 23675 | IkReal x1746=IKcos(j0); |
| 23676 | IkReal x1747=IKsin(j0); |
| 23677 | IkReal x1748=((1.0)*new_r10); |
| 23678 | IkReal x1749=((1.0)*new_r01); |
| 23679 | IkReal x1750=(new_r22*x1747); |
| 23680 | IkReal x1751=(new_r22*x1746); |
| 23681 | evalcond[0]=(((new_r01*x1746))+((new_r11*x1747))); |
| 23682 | evalcond[1]=((((-1.0)*x1747*x1749))+((new_r11*x1746))); |
| 23683 | evalcond[2]=((((-1.0)*x1746*x1748))+((new_r00*x1747))); |
| 23684 | evalcond[3]=((((-1.0)*x1748*x1750))+(((-1.0)*new_r00*x1751))); |
| 23685 | evalcond[4]=((((-1.0)*x1749*x1751))+(((-1.0)*new_r11*x1750))); |
| 23686 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH ) |
| 23687 | { |
| 23688 | continue; |
| 23689 | } |
| 23690 | } |
| 23691 | |
| 23692 | { |
| 23693 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23694 | vinfos[0].jointtype = 1; |
| 23695 | vinfos[0].foffset = j0; |
| 23696 | vinfos[0].indices[0] = _ij0[0]; |
| 23697 | vinfos[0].indices[1] = _ij0[1]; |
| 23698 | vinfos[0].maxsolutions = _nj0; |
| 23699 | vinfos[1].jointtype = 1; |
| 23700 | vinfos[1].foffset = j1; |
| 23701 | vinfos[1].indices[0] = _ij1[0]; |
| 23702 | vinfos[1].indices[1] = _ij1[1]; |
| 23703 | vinfos[1].maxsolutions = _nj1; |
| 23704 | vinfos[2].jointtype = 1; |
| 23705 | vinfos[2].foffset = j2; |
| 23706 | vinfos[2].indices[0] = _ij2[0]; |
| 23707 | vinfos[2].indices[1] = _ij2[1]; |
| 23708 | vinfos[2].maxsolutions = _nj2; |
| 23709 | vinfos[3].jointtype = 1; |
| 23710 | vinfos[3].foffset = j3; |
| 23711 | vinfos[3].indices[0] = _ij3[0]; |
| 23712 | vinfos[3].indices[1] = _ij3[1]; |
| 23713 | vinfos[3].maxsolutions = _nj3; |
| 23714 | vinfos[4].jointtype = 1; |
| 23715 | vinfos[4].foffset = j4; |
| 23716 | vinfos[4].indices[0] = _ij4[0]; |
| 23717 | vinfos[4].indices[1] = _ij4[1]; |
| 23718 | vinfos[4].maxsolutions = _nj4; |
| 23719 | vinfos[5].jointtype = 1; |
| 23720 | vinfos[5].foffset = j5; |
| 23721 | vinfos[5].indices[0] = _ij5[0]; |
| 23722 | vinfos[5].indices[1] = _ij5[1]; |
| 23723 | vinfos[5].maxsolutions = _nj5; |
| 23724 | std::vector<int> vfree(0); |
| 23725 | solutions.AddSolution(vinfos,vfree); |
| 23726 | } |
| 23727 | } |
| 23728 | } |
| 23729 | |
| 23730 | } |
| 23731 | |
| 23732 | } |
| 23733 | |
| 23734 | } |
| 23735 | } while(0); |
| 23736 | if( bgotonextstatement ) |
| 23737 | { |
| 23738 | bool bgotonextstatement = true; |
| 23739 | do |
| 23740 | { |
| 23741 | if( 1 ) |
| 23742 | { |
| 23743 | bgotonextstatement=false; |
| 23744 | continue; // branch miss [j0] |
| 23745 | |
| 23746 | } |
| 23747 | } while(0); |
| 23748 | if( bgotonextstatement ) |
| 23749 | { |
| 23750 | } |
| 23751 | } |
| 23752 | } |
| 23753 | } |
| 23754 | } |
| 23755 | |
| 23756 | } else |
| 23757 | { |
| 23758 | { |
| 23759 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 23760 | bool j0valid[1]={false}; |
| 23761 | _nj0 = 1; |
| 23762 | CheckValue<IkReal> x1753=IKPowWithIntegerCheck(cj1,-1); |
| 23763 | if(!x1753.valid){ |
| 23764 | continue; |
| 23765 | } |
| 23766 | IkReal x1752=x1753.value; |
| 23767 | CheckValue<IkReal> x1754=IKPowWithIntegerCheck(new_r01,-1); |
| 23768 | if(!x1754.valid){ |
| 23769 | continue; |
| 23770 | } |
| 23771 | if( IKabs((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs((new_r02*x1752)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11))))))+IKsqr((new_r02*x1752))-1) <= IKFAST_SINCOS_THRESH ) |
| 23772 | continue; |
| 23773 | j0array[0]=IKatan2((x1752*(x1754.value)*((((cj1*sj2))+((new_r02*new_r11))))), (new_r02*x1752)); |
| 23774 | sj0array[0]=IKsin(j0array[0]); |
| 23775 | cj0array[0]=IKcos(j0array[0]); |
| 23776 | if( j0array[0] > IKPI ) |
| 23777 | { |
| 23778 | j0array[0]-=IK2PI; |
| 23779 | } |
| 23780 | else if( j0array[0] < -IKPI ) |
| 23781 | { j0array[0]+=IK2PI; |
| 23782 | } |
| 23783 | j0valid[0] = true; |
| 23784 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 23785 | { |
| 23786 | if( !j0valid[ij0] ) |
| 23787 | { |
| 23788 | continue; |
| 23789 | } |
| 23790 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23791 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 23792 | { |
| 23793 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23794 | { |
| 23795 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23796 | } |
| 23797 | } |
| 23798 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23799 | { |
| 23800 | IkReal evalcond[18]; |
| 23801 | IkReal x1755=IKcos(j0); |
| 23802 | IkReal x1756=IKsin(j0); |
| 23803 | IkReal x1757=(sj1*sj2); |
| 23804 | IkReal x1758=((1.0)*sj1); |
| 23805 | IkReal x1759=(cj2*sj1); |
| 23806 | IkReal x1760=((1.0)*cj1); |
| 23807 | IkReal x1761=((1.0)*cj2); |
| 23808 | IkReal x1762=(new_r10*x1756); |
| 23809 | IkReal x1763=(new_r01*x1755); |
| 23810 | IkReal x1764=(new_r00*x1755); |
| 23811 | IkReal x1765=((1.0)*x1756); |
| 23812 | IkReal x1766=(new_r11*x1756); |
| 23813 | IkReal x1767=(new_r12*x1756); |
| 23814 | IkReal x1768=(new_r02*x1755); |
| 23815 | evalcond[0]=((((-1.0)*x1755*x1760))+new_r02); |
| 23816 | evalcond[1]=((((-1.0)*x1756*x1760))+new_r12); |
| 23817 | evalcond[2]=((((-1.0)*new_r02*x1765))+((new_r12*x1755))); |
| 23818 | evalcond[3]=(sj2+(((-1.0)*new_r01*x1765))+((new_r11*x1755))); |
| 23819 | evalcond[4]=(cj2+((new_r00*x1756))+(((-1.0)*new_r10*x1755))); |
| 23820 | evalcond[5]=(((cj2*x1756))+new_r00+((x1755*x1757))); |
| 23821 | evalcond[6]=(((sj2*x1755))+new_r11+((x1756*x1759))); |
| 23822 | evalcond[7]=((((-1.0)*x1760))+x1768+x1767); |
| 23823 | evalcond[8]=(x1762+x1764+x1757); |
| 23824 | evalcond[9]=(x1763+x1766+x1759); |
| 23825 | evalcond[10]=((((-1.0)*sj2*x1765))+new_r01+((x1755*x1759))); |
| 23826 | evalcond[11]=((((-1.0)*x1755*x1761))+new_r10+((x1756*x1757))); |
| 23827 | evalcond[12]=(((new_r20*sj1))+((cj1*x1762))+((cj1*x1764))); |
| 23828 | evalcond[13]=(((new_r21*sj1))+((cj1*x1763))+((cj1*x1766))); |
| 23829 | evalcond[14]=((-1.0)+((new_r22*sj1))+((cj1*x1768))+((cj1*x1767))); |
| 23830 | evalcond[15]=(((cj1*new_r22))+(((-1.0)*x1758*x1767))+(((-1.0)*x1758*x1768))); |
| 23831 | evalcond[16]=((((-1.0)*sj2))+((cj1*new_r20))+(((-1.0)*x1758*x1764))+(((-1.0)*x1758*x1762))); |
| 23832 | evalcond[17]=((((-1.0)*x1761))+((cj1*new_r21))+(((-1.0)*x1758*x1763))+(((-1.0)*x1758*x1766))); |
| 23833 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH ) |
| 23834 | { |
| 23835 | continue; |
| 23836 | } |
| 23837 | } |
| 23838 | |
| 23839 | { |
| 23840 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23841 | vinfos[0].jointtype = 1; |
| 23842 | vinfos[0].foffset = j0; |
| 23843 | vinfos[0].indices[0] = _ij0[0]; |
| 23844 | vinfos[0].indices[1] = _ij0[1]; |
| 23845 | vinfos[0].maxsolutions = _nj0; |
| 23846 | vinfos[1].jointtype = 1; |
| 23847 | vinfos[1].foffset = j1; |
| 23848 | vinfos[1].indices[0] = _ij1[0]; |
| 23849 | vinfos[1].indices[1] = _ij1[1]; |
| 23850 | vinfos[1].maxsolutions = _nj1; |
| 23851 | vinfos[2].jointtype = 1; |
| 23852 | vinfos[2].foffset = j2; |
| 23853 | vinfos[2].indices[0] = _ij2[0]; |
| 23854 | vinfos[2].indices[1] = _ij2[1]; |
| 23855 | vinfos[2].maxsolutions = _nj2; |
| 23856 | vinfos[3].jointtype = 1; |
| 23857 | vinfos[3].foffset = j3; |
| 23858 | vinfos[3].indices[0] = _ij3[0]; |
| 23859 | vinfos[3].indices[1] = _ij3[1]; |
| 23860 | vinfos[3].maxsolutions = _nj3; |
| 23861 | vinfos[4].jointtype = 1; |
| 23862 | vinfos[4].foffset = j4; |
| 23863 | vinfos[4].indices[0] = _ij4[0]; |
| 23864 | vinfos[4].indices[1] = _ij4[1]; |
| 23865 | vinfos[4].maxsolutions = _nj4; |
| 23866 | vinfos[5].jointtype = 1; |
| 23867 | vinfos[5].foffset = j5; |
| 23868 | vinfos[5].indices[0] = _ij5[0]; |
| 23869 | vinfos[5].indices[1] = _ij5[1]; |
| 23870 | vinfos[5].maxsolutions = _nj5; |
| 23871 | std::vector<int> vfree(0); |
| 23872 | solutions.AddSolution(vinfos,vfree); |
| 23873 | } |
| 23874 | } |
| 23875 | } |
| 23876 | |
| 23877 | } |
| 23878 | |
| 23879 | } |
| 23880 | |
| 23881 | } else |
| 23882 | { |
| 23883 | { |
| 23884 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 23885 | bool j0valid[1]={false}; |
| 23886 | _nj0 = 1; |
| 23887 | CheckValue<IkReal> x1769=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| 23888 | if(!x1769.valid){ |
| 23889 | continue; |
| 23890 | } |
| 23891 | CheckValue<IkReal> x1770 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH); |
| 23892 | if(!x1770.valid){ |
| 23893 | continue; |
| 23894 | } |
| 23895 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1769.value)))+(x1770.value)); |
| 23896 | sj0array[0]=IKsin(j0array[0]); |
| 23897 | cj0array[0]=IKcos(j0array[0]); |
| 23898 | if( j0array[0] > IKPI ) |
| 23899 | { |
| 23900 | j0array[0]-=IK2PI; |
| 23901 | } |
| 23902 | else if( j0array[0] < -IKPI ) |
| 23903 | { j0array[0]+=IK2PI; |
| 23904 | } |
| 23905 | j0valid[0] = true; |
| 23906 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 23907 | { |
| 23908 | if( !j0valid[ij0] ) |
| 23909 | { |
| 23910 | continue; |
| 23911 | } |
| 23912 | _ij0[0] = ij0; _ij0[1] = -1; |
| 23913 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 23914 | { |
| 23915 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 23916 | { |
| 23917 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 23918 | } |
| 23919 | } |
| 23920 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 23921 | { |
| 23922 | IkReal evalcond[18]; |
| 23923 | IkReal x1771=IKcos(j0); |
| 23924 | IkReal x1772=IKsin(j0); |
| 23925 | IkReal x1773=(sj1*sj2); |
| 23926 | IkReal x1774=((1.0)*sj1); |
| 23927 | IkReal x1775=(cj2*sj1); |
| 23928 | IkReal x1776=((1.0)*cj1); |
| 23929 | IkReal x1777=((1.0)*cj2); |
| 23930 | IkReal x1778=(new_r10*x1772); |
| 23931 | IkReal x1779=(new_r01*x1771); |
| 23932 | IkReal x1780=(new_r00*x1771); |
| 23933 | IkReal x1781=((1.0)*x1772); |
| 23934 | IkReal x1782=(new_r11*x1772); |
| 23935 | IkReal x1783=(new_r12*x1772); |
| 23936 | IkReal x1784=(new_r02*x1771); |
| 23937 | evalcond[0]=((((-1.0)*x1771*x1776))+new_r02); |
| 23938 | evalcond[1]=((((-1.0)*x1772*x1776))+new_r12); |
| 23939 | evalcond[2]=((((-1.0)*new_r02*x1781))+((new_r12*x1771))); |
| 23940 | evalcond[3]=(sj2+(((-1.0)*new_r01*x1781))+((new_r11*x1771))); |
| 23941 | evalcond[4]=(cj2+((new_r00*x1772))+(((-1.0)*new_r10*x1771))); |
| 23942 | evalcond[5]=(((x1771*x1773))+new_r00+((cj2*x1772))); |
| 23943 | evalcond[6]=(((sj2*x1771))+new_r11+((x1772*x1775))); |
| 23944 | evalcond[7]=(x1783+x1784+(((-1.0)*x1776))); |
| 23945 | evalcond[8]=(x1780+x1773+x1778); |
| 23946 | evalcond[9]=(x1782+x1775+x1779); |
| 23947 | evalcond[10]=(((x1771*x1775))+new_r01+(((-1.0)*sj2*x1781))); |
| 23948 | evalcond[11]=((((-1.0)*x1771*x1777))+new_r10+((x1772*x1773))); |
| 23949 | evalcond[12]=(((new_r20*sj1))+((cj1*x1780))+((cj1*x1778))); |
| 23950 | evalcond[13]=(((cj1*x1782))+((new_r21*sj1))+((cj1*x1779))); |
| 23951 | evalcond[14]=((-1.0)+((cj1*x1784))+((cj1*x1783))+((new_r22*sj1))); |
| 23952 | evalcond[15]=((((-1.0)*x1774*x1784))+(((-1.0)*x1774*x1783))+((cj1*new_r22))); |
| 23953 | evalcond[16]=((((-1.0)*sj2))+(((-1.0)*x1774*x1780))+((cj1*new_r20))+(((-1.0)*x1774*x1778))); |
| 23954 | evalcond[17]=((((-1.0)*x1774*x1782))+((cj1*new_r21))+(((-1.0)*x1777))+(((-1.0)*x1774*x1779))); |
| 23955 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[12]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[13]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[14]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[15]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[16]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[17]) > IKFAST_EVALCOND_THRESH ) |
| 23956 | { |
| 23957 | continue; |
| 23958 | } |
| 23959 | } |
| 23960 | |
| 23961 | { |
| 23962 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 23963 | vinfos[0].jointtype = 1; |
| 23964 | vinfos[0].foffset = j0; |
| 23965 | vinfos[0].indices[0] = _ij0[0]; |
| 23966 | vinfos[0].indices[1] = _ij0[1]; |
| 23967 | vinfos[0].maxsolutions = _nj0; |
| 23968 | vinfos[1].jointtype = 1; |
| 23969 | vinfos[1].foffset = j1; |
| 23970 | vinfos[1].indices[0] = _ij1[0]; |
| 23971 | vinfos[1].indices[1] = _ij1[1]; |
| 23972 | vinfos[1].maxsolutions = _nj1; |
| 23973 | vinfos[2].jointtype = 1; |
| 23974 | vinfos[2].foffset = j2; |
| 23975 | vinfos[2].indices[0] = _ij2[0]; |
| 23976 | vinfos[2].indices[1] = _ij2[1]; |
| 23977 | vinfos[2].maxsolutions = _nj2; |
| 23978 | vinfos[3].jointtype = 1; |
| 23979 | vinfos[3].foffset = j3; |
| 23980 | vinfos[3].indices[0] = _ij3[0]; |
| 23981 | vinfos[3].indices[1] = _ij3[1]; |
| 23982 | vinfos[3].maxsolutions = _nj3; |
| 23983 | vinfos[4].jointtype = 1; |
| 23984 | vinfos[4].foffset = j4; |
| 23985 | vinfos[4].indices[0] = _ij4[0]; |
| 23986 | vinfos[4].indices[1] = _ij4[1]; |
| 23987 | vinfos[4].maxsolutions = _nj4; |
| 23988 | vinfos[5].jointtype = 1; |
| 23989 | vinfos[5].foffset = j5; |
| 23990 | vinfos[5].indices[0] = _ij5[0]; |
| 23991 | vinfos[5].indices[1] = _ij5[1]; |
| 23992 | vinfos[5].maxsolutions = _nj5; |
| 23993 | std::vector<int> vfree(0); |
| 23994 | solutions.AddSolution(vinfos,vfree); |
| 23995 | } |
| 23996 | } |
| 23997 | } |
| 23998 | |
| 23999 | } |
| 24000 | |
| 24001 | } |
| 24002 | } |
| 24003 | } |
| 24004 | |
| 24005 | } |
| 24006 | |
| 24007 | } |
| 24008 | |
| 24009 | } else |
| 24010 | { |
| 24011 | { |
| 24012 | IkReal j0array[1], cj0array[1], sj0array[1]; |
| 24013 | bool j0valid[1]={false}; |
| 24014 | _nj0 = 1; |
| 24015 | CheckValue<IkReal> x1785=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| 24016 | if(!x1785.valid){ |
| 24017 | continue; |
| 24018 | } |
| 24019 | CheckValue<IkReal> x1786 = IKatan2WithCheck(IkReal(new_r12),IkReal(new_r02),IKFAST_ATAN2_MAGTHRESH); |
| 24020 | if(!x1786.valid){ |
| 24021 | continue; |
| 24022 | } |
| 24023 | j0array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1785.value)))+(x1786.value)); |
| 24024 | sj0array[0]=IKsin(j0array[0]); |
| 24025 | cj0array[0]=IKcos(j0array[0]); |
| 24026 | if( j0array[0] > IKPI ) |
| 24027 | { |
| 24028 | j0array[0]-=IK2PI; |
| 24029 | } |
| 24030 | else if( j0array[0] < -IKPI ) |
| 24031 | { j0array[0]+=IK2PI; |
| 24032 | } |
| 24033 | j0valid[0] = true; |
| 24034 | for(int ij0 = 0; ij0 < 1; ++ij0) |
| 24035 | { |
| 24036 | if( !j0valid[ij0] ) |
| 24037 | { |
| 24038 | continue; |
| 24039 | } |
| 24040 | _ij0[0] = ij0; _ij0[1] = -1; |
| 24041 | for(int iij0 = ij0+1; iij0 < 1; ++iij0) |
| 24042 | { |
| 24043 | if( j0valid[iij0] && IKabs(cj0array[ij0]-cj0array[iij0]) < IKFAST_SOLUTION_THRESH && IKabs(sj0array[ij0]-sj0array[iij0]) < IKFAST_SOLUTION_THRESH ) |
| 24044 | { |
| 24045 | j0valid[iij0]=false; _ij0[1] = iij0; break; |
| 24046 | } |
| 24047 | } |
| 24048 | j0 = j0array[ij0]; cj0 = cj0array[ij0]; sj0 = sj0array[ij0]; |
| 24049 | { |
| 24050 | IkReal evalcond[8]; |
| 24051 | IkReal x1787=IKcos(j0); |
| 24052 | IkReal x1788=IKsin(j0); |
| 24053 | IkReal x1789=(cj1*x1787); |
| 24054 | IkReal x1790=(cj1*x1788); |
| 24055 | IkReal x1791=((1.0)*x1788); |
| 24056 | IkReal x1792=(new_r02*x1787); |
| 24057 | evalcond[0]=((((-1.0)*x1789))+new_r02); |
| 24058 | evalcond[1]=((((-1.0)*x1790))+new_r12); |
| 24059 | evalcond[2]=(((new_r12*x1787))+(((-1.0)*new_r02*x1791))); |
| 24060 | evalcond[3]=(x1792+((new_r12*x1788))+(((-1.0)*cj1))); |
| 24061 | evalcond[4]=(((new_r20*sj1))+((new_r10*x1790))+((new_r00*x1789))); |
| 24062 | evalcond[5]=(((new_r11*x1790))+((new_r01*x1789))+((new_r21*sj1))); |
| 24063 | evalcond[6]=((-1.0)+((new_r12*x1790))+((new_r22*sj1))+((new_r02*x1789))); |
| 24064 | evalcond[7]=(((cj1*new_r22))+(((-1.0)*new_r12*sj1*x1791))+(((-1.0)*sj1*x1792))); |
| 24065 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24066 | { |
| 24067 | continue; |
| 24068 | } |
| 24069 | } |
| 24070 | |
| 24071 | { |
| 24072 | IkReal j2eval[3]; |
| 24073 | j2eval[0]=cj1; |
| 24074 | j2eval[1]=IKsign(cj1); |
| 24075 | j2eval[2]=((IKabs(new_r20))+(IKabs(new_r21))); |
| 24076 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 24077 | { |
| 24078 | { |
| 24079 | IkReal j2eval[2]; |
| 24080 | j2eval[0]=cj1; |
| 24081 | j2eval[1]=sj0; |
| 24082 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 ) |
| 24083 | { |
| 24084 | { |
| 24085 | IkReal j2eval[3]; |
| 24086 | j2eval[0]=cj1; |
| 24087 | j2eval[1]=sj0; |
| 24088 | j2eval[2]=sj1; |
| 24089 | if( IKabs(j2eval[0]) < 0.0000010000000000 || IKabs(j2eval[1]) < 0.0000010000000000 || IKabs(j2eval[2]) < 0.0000010000000000 ) |
| 24090 | { |
| 24091 | { |
| 24092 | IkReal evalcond[5]; |
| 24093 | bool bgotonextstatement = true; |
| 24094 | do |
| 24095 | { |
| 24096 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-1.5707963267949)+j1)))), 6.28318530717959))); |
| 24097 | evalcond[1]=new_r02; |
| 24098 | evalcond[2]=new_r12; |
| 24099 | evalcond[3]=new_r20; |
| 24100 | evalcond[4]=new_r21; |
| 24101 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 24102 | { |
| 24103 | bgotonextstatement=false; |
| 24104 | { |
| 24105 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24106 | bool j2valid[1]={false}; |
| 24107 | _nj2 = 1; |
| 24108 | IkReal x1793=((1.0)*cj0); |
| 24109 | if( IKabs((((new_r01*sj0))+(((-1.0)*new_r00*x1793)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+(((-1.0)*new_r00*x1793))))+IKsqr(((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH ) |
| 24110 | continue; |
| 24111 | j2array[0]=IKatan2((((new_r01*sj0))+(((-1.0)*new_r00*x1793))), ((((-1.0)*new_r01*x1793))+(((-1.0)*new_r00*sj0)))); |
| 24112 | sj2array[0]=IKsin(j2array[0]); |
| 24113 | cj2array[0]=IKcos(j2array[0]); |
| 24114 | if( j2array[0] > IKPI ) |
| 24115 | { |
| 24116 | j2array[0]-=IK2PI; |
| 24117 | } |
| 24118 | else if( j2array[0] < -IKPI ) |
| 24119 | { j2array[0]+=IK2PI; |
| 24120 | } |
| 24121 | j2valid[0] = true; |
| 24122 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24123 | { |
| 24124 | if( !j2valid[ij2] ) |
| 24125 | { |
| 24126 | continue; |
| 24127 | } |
| 24128 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24129 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24130 | { |
| 24131 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24132 | { |
| 24133 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24134 | } |
| 24135 | } |
| 24136 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24137 | { |
| 24138 | IkReal evalcond[8]; |
| 24139 | IkReal x1794=IKsin(j2); |
| 24140 | IkReal x1795=IKcos(j2); |
| 24141 | IkReal x1796=((1.0)*cj0); |
| 24142 | IkReal x1797=(sj0*x1795); |
| 24143 | IkReal x1798=(cj0*x1794); |
| 24144 | IkReal x1799=(sj0*x1794); |
| 24145 | IkReal x1800=(x1798+x1797); |
| 24146 | evalcond[0]=(x1794+((new_r10*sj0))+((cj0*new_r00))); |
| 24147 | evalcond[1]=(x1795+((new_r11*sj0))+((cj0*new_r01))); |
| 24148 | evalcond[2]=((((-1.0)*new_r01*sj0))+x1794+((cj0*new_r11))); |
| 24149 | evalcond[3]=((((-1.0)*new_r10*x1796))+x1795+((new_r00*sj0))); |
| 24150 | evalcond[4]=(x1800+new_r00); |
| 24151 | evalcond[5]=(x1800+new_r11); |
| 24152 | evalcond[6]=((((-1.0)*x1799))+new_r01+((cj0*x1795))); |
| 24153 | evalcond[7]=((((-1.0)*x1795*x1796))+x1799+new_r10); |
| 24154 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24155 | { |
| 24156 | continue; |
| 24157 | } |
| 24158 | } |
| 24159 | |
| 24160 | { |
| 24161 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24162 | vinfos[0].jointtype = 1; |
| 24163 | vinfos[0].foffset = j0; |
| 24164 | vinfos[0].indices[0] = _ij0[0]; |
| 24165 | vinfos[0].indices[1] = _ij0[1]; |
| 24166 | vinfos[0].maxsolutions = _nj0; |
| 24167 | vinfos[1].jointtype = 1; |
| 24168 | vinfos[1].foffset = j1; |
| 24169 | vinfos[1].indices[0] = _ij1[0]; |
| 24170 | vinfos[1].indices[1] = _ij1[1]; |
| 24171 | vinfos[1].maxsolutions = _nj1; |
| 24172 | vinfos[2].jointtype = 1; |
| 24173 | vinfos[2].foffset = j2; |
| 24174 | vinfos[2].indices[0] = _ij2[0]; |
| 24175 | vinfos[2].indices[1] = _ij2[1]; |
| 24176 | vinfos[2].maxsolutions = _nj2; |
| 24177 | vinfos[3].jointtype = 1; |
| 24178 | vinfos[3].foffset = j3; |
| 24179 | vinfos[3].indices[0] = _ij3[0]; |
| 24180 | vinfos[3].indices[1] = _ij3[1]; |
| 24181 | vinfos[3].maxsolutions = _nj3; |
| 24182 | vinfos[4].jointtype = 1; |
| 24183 | vinfos[4].foffset = j4; |
| 24184 | vinfos[4].indices[0] = _ij4[0]; |
| 24185 | vinfos[4].indices[1] = _ij4[1]; |
| 24186 | vinfos[4].maxsolutions = _nj4; |
| 24187 | vinfos[5].jointtype = 1; |
| 24188 | vinfos[5].foffset = j5; |
| 24189 | vinfos[5].indices[0] = _ij5[0]; |
| 24190 | vinfos[5].indices[1] = _ij5[1]; |
| 24191 | vinfos[5].maxsolutions = _nj5; |
| 24192 | std::vector<int> vfree(0); |
| 24193 | solutions.AddSolution(vinfos,vfree); |
| 24194 | } |
| 24195 | } |
| 24196 | } |
| 24197 | |
| 24198 | } |
| 24199 | } while(0); |
| 24200 | if( bgotonextstatement ) |
| 24201 | { |
| 24202 | bool bgotonextstatement = true; |
| 24203 | do |
| 24204 | { |
| 24205 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((1.5707963267949)+j1)))), 6.28318530717959))); |
| 24206 | evalcond[1]=new_r02; |
| 24207 | evalcond[2]=new_r12; |
| 24208 | evalcond[3]=new_r20; |
| 24209 | evalcond[4]=new_r21; |
| 24210 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 && IKabs(evalcond[2]) < 0.0000050000000000 && IKabs(evalcond[3]) < 0.0000050000000000 && IKabs(evalcond[4]) < 0.0000050000000000 ) |
| 24211 | { |
| 24212 | bgotonextstatement=false; |
| 24213 | { |
| 24214 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24215 | bool j2valid[1]={false}; |
| 24216 | _nj2 = 1; |
| 24217 | if( IKabs((((new_r01*sj0))+((cj0*new_r00)))) < IKFAST_ATAN2_MAGTHRESH && IKabs((((cj0*new_r01))+(((-1.0)*new_r00*sj0)))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((((new_r01*sj0))+((cj0*new_r00))))+IKsqr((((cj0*new_r01))+(((-1.0)*new_r00*sj0))))-1) <= IKFAST_SINCOS_THRESH ) |
| 24218 | continue; |
| 24219 | j2array[0]=IKatan2((((new_r01*sj0))+((cj0*new_r00))), (((cj0*new_r01))+(((-1.0)*new_r00*sj0)))); |
| 24220 | sj2array[0]=IKsin(j2array[0]); |
| 24221 | cj2array[0]=IKcos(j2array[0]); |
| 24222 | if( j2array[0] > IKPI ) |
| 24223 | { |
| 24224 | j2array[0]-=IK2PI; |
| 24225 | } |
| 24226 | else if( j2array[0] < -IKPI ) |
| 24227 | { j2array[0]+=IK2PI; |
| 24228 | } |
| 24229 | j2valid[0] = true; |
| 24230 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24231 | { |
| 24232 | if( !j2valid[ij2] ) |
| 24233 | { |
| 24234 | continue; |
| 24235 | } |
| 24236 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24237 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24238 | { |
| 24239 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24240 | { |
| 24241 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24242 | } |
| 24243 | } |
| 24244 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24245 | { |
| 24246 | IkReal evalcond[8]; |
| 24247 | IkReal x1801=IKsin(j2); |
| 24248 | IkReal x1802=IKcos(j2); |
| 24249 | IkReal x1803=((1.0)*sj0); |
| 24250 | IkReal x1804=((1.0)*cj0); |
| 24251 | IkReal x1805=((1.0)*x1802); |
| 24252 | IkReal x1806=(((x1802*x1804))+((x1801*x1803))); |
| 24253 | evalcond[0]=((((-1.0)*new_r01*x1803))+x1801+((cj0*new_r11))); |
| 24254 | evalcond[1]=(((new_r00*sj0))+x1802+(((-1.0)*new_r10*x1804))); |
| 24255 | evalcond[2]=(((new_r10*sj0))+((cj0*new_r00))+(((-1.0)*x1801))); |
| 24256 | evalcond[3]=(((new_r11*sj0))+(((-1.0)*x1805))+((cj0*new_r01))); |
| 24257 | evalcond[4]=(((sj0*x1802))+(((-1.0)*x1801*x1804))+new_r00); |
| 24258 | evalcond[5]=(((cj0*x1801))+(((-1.0)*x1802*x1803))+new_r11); |
| 24259 | evalcond[6]=((((-1.0)*x1806))+new_r01); |
| 24260 | evalcond[7]=((((-1.0)*x1806))+new_r10); |
| 24261 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24262 | { |
| 24263 | continue; |
| 24264 | } |
| 24265 | } |
| 24266 | |
| 24267 | { |
| 24268 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24269 | vinfos[0].jointtype = 1; |
| 24270 | vinfos[0].foffset = j0; |
| 24271 | vinfos[0].indices[0] = _ij0[0]; |
| 24272 | vinfos[0].indices[1] = _ij0[1]; |
| 24273 | vinfos[0].maxsolutions = _nj0; |
| 24274 | vinfos[1].jointtype = 1; |
| 24275 | vinfos[1].foffset = j1; |
| 24276 | vinfos[1].indices[0] = _ij1[0]; |
| 24277 | vinfos[1].indices[1] = _ij1[1]; |
| 24278 | vinfos[1].maxsolutions = _nj1; |
| 24279 | vinfos[2].jointtype = 1; |
| 24280 | vinfos[2].foffset = j2; |
| 24281 | vinfos[2].indices[0] = _ij2[0]; |
| 24282 | vinfos[2].indices[1] = _ij2[1]; |
| 24283 | vinfos[2].maxsolutions = _nj2; |
| 24284 | vinfos[3].jointtype = 1; |
| 24285 | vinfos[3].foffset = j3; |
| 24286 | vinfos[3].indices[0] = _ij3[0]; |
| 24287 | vinfos[3].indices[1] = _ij3[1]; |
| 24288 | vinfos[3].maxsolutions = _nj3; |
| 24289 | vinfos[4].jointtype = 1; |
| 24290 | vinfos[4].foffset = j4; |
| 24291 | vinfos[4].indices[0] = _ij4[0]; |
| 24292 | vinfos[4].indices[1] = _ij4[1]; |
| 24293 | vinfos[4].maxsolutions = _nj4; |
| 24294 | vinfos[5].jointtype = 1; |
| 24295 | vinfos[5].foffset = j5; |
| 24296 | vinfos[5].indices[0] = _ij5[0]; |
| 24297 | vinfos[5].indices[1] = _ij5[1]; |
| 24298 | vinfos[5].maxsolutions = _nj5; |
| 24299 | std::vector<int> vfree(0); |
| 24300 | solutions.AddSolution(vinfos,vfree); |
| 24301 | } |
| 24302 | } |
| 24303 | } |
| 24304 | |
| 24305 | } |
| 24306 | } while(0); |
| 24307 | if( bgotonextstatement ) |
| 24308 | { |
| 24309 | bool bgotonextstatement = true; |
| 24310 | do |
| 24311 | { |
| 24312 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j0))), 6.28318530717959))); |
| 24313 | evalcond[1]=new_r12; |
| 24314 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 24315 | { |
| 24316 | bgotonextstatement=false; |
| 24317 | { |
| 24318 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24319 | bool j2valid[1]={false}; |
| 24320 | _nj2 = 1; |
| 24321 | if( IKabs(((-1.0)*new_r11)) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r10) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r11))+IKsqr(new_r10)-1) <= IKFAST_SINCOS_THRESH ) |
| 24322 | continue; |
| 24323 | j2array[0]=IKatan2(((-1.0)*new_r11), new_r10); |
| 24324 | sj2array[0]=IKsin(j2array[0]); |
| 24325 | cj2array[0]=IKcos(j2array[0]); |
| 24326 | if( j2array[0] > IKPI ) |
| 24327 | { |
| 24328 | j2array[0]-=IK2PI; |
| 24329 | } |
| 24330 | else if( j2array[0] < -IKPI ) |
| 24331 | { j2array[0]+=IK2PI; |
| 24332 | } |
| 24333 | j2valid[0] = true; |
| 24334 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24335 | { |
| 24336 | if( !j2valid[ij2] ) |
| 24337 | { |
| 24338 | continue; |
| 24339 | } |
| 24340 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24341 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24342 | { |
| 24343 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24344 | { |
| 24345 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24346 | } |
| 24347 | } |
| 24348 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24349 | { |
| 24350 | IkReal evalcond[8]; |
| 24351 | IkReal x1807=IKsin(j2); |
| 24352 | IkReal x1808=IKcos(j2); |
| 24353 | IkReal x1809=((1.0)*sj1); |
| 24354 | IkReal x1810=((1.0)*cj1); |
| 24355 | evalcond[0]=(x1807+new_r11); |
| 24356 | evalcond[1]=(x1808+(((-1.0)*new_r10))); |
| 24357 | evalcond[2]=(((sj1*x1807))+new_r00); |
| 24358 | evalcond[3]=(((sj1*x1808))+new_r01); |
| 24359 | evalcond[4]=((((-1.0)*x1807*x1810))+new_r20); |
| 24360 | evalcond[5]=((((-1.0)*x1808*x1810))+new_r21); |
| 24361 | evalcond[6]=(((cj1*new_r20))+(((-1.0)*new_r00*x1809))+(((-1.0)*x1807))); |
| 24362 | evalcond[7]=((((-1.0)*new_r01*x1809))+((cj1*new_r21))+(((-1.0)*x1808))); |
| 24363 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24364 | { |
| 24365 | continue; |
| 24366 | } |
| 24367 | } |
| 24368 | |
| 24369 | { |
| 24370 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24371 | vinfos[0].jointtype = 1; |
| 24372 | vinfos[0].foffset = j0; |
| 24373 | vinfos[0].indices[0] = _ij0[0]; |
| 24374 | vinfos[0].indices[1] = _ij0[1]; |
| 24375 | vinfos[0].maxsolutions = _nj0; |
| 24376 | vinfos[1].jointtype = 1; |
| 24377 | vinfos[1].foffset = j1; |
| 24378 | vinfos[1].indices[0] = _ij1[0]; |
| 24379 | vinfos[1].indices[1] = _ij1[1]; |
| 24380 | vinfos[1].maxsolutions = _nj1; |
| 24381 | vinfos[2].jointtype = 1; |
| 24382 | vinfos[2].foffset = j2; |
| 24383 | vinfos[2].indices[0] = _ij2[0]; |
| 24384 | vinfos[2].indices[1] = _ij2[1]; |
| 24385 | vinfos[2].maxsolutions = _nj2; |
| 24386 | vinfos[3].jointtype = 1; |
| 24387 | vinfos[3].foffset = j3; |
| 24388 | vinfos[3].indices[0] = _ij3[0]; |
| 24389 | vinfos[3].indices[1] = _ij3[1]; |
| 24390 | vinfos[3].maxsolutions = _nj3; |
| 24391 | vinfos[4].jointtype = 1; |
| 24392 | vinfos[4].foffset = j4; |
| 24393 | vinfos[4].indices[0] = _ij4[0]; |
| 24394 | vinfos[4].indices[1] = _ij4[1]; |
| 24395 | vinfos[4].maxsolutions = _nj4; |
| 24396 | vinfos[5].jointtype = 1; |
| 24397 | vinfos[5].foffset = j5; |
| 24398 | vinfos[5].indices[0] = _ij5[0]; |
| 24399 | vinfos[5].indices[1] = _ij5[1]; |
| 24400 | vinfos[5].maxsolutions = _nj5; |
| 24401 | std::vector<int> vfree(0); |
| 24402 | solutions.AddSolution(vinfos,vfree); |
| 24403 | } |
| 24404 | } |
| 24405 | } |
| 24406 | |
| 24407 | } |
| 24408 | } while(0); |
| 24409 | if( bgotonextstatement ) |
| 24410 | { |
| 24411 | bool bgotonextstatement = true; |
| 24412 | do |
| 24413 | { |
| 24414 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j0)))), 6.28318530717959))); |
| 24415 | evalcond[1]=new_r12; |
| 24416 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 24417 | { |
| 24418 | bgotonextstatement=false; |
| 24419 | { |
| 24420 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24421 | bool j2valid[1]={false}; |
| 24422 | _nj2 = 1; |
| 24423 | if( IKabs(new_r11) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r10)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r11)+IKsqr(((-1.0)*new_r10))-1) <= IKFAST_SINCOS_THRESH ) |
| 24424 | continue; |
| 24425 | j2array[0]=IKatan2(new_r11, ((-1.0)*new_r10)); |
| 24426 | sj2array[0]=IKsin(j2array[0]); |
| 24427 | cj2array[0]=IKcos(j2array[0]); |
| 24428 | if( j2array[0] > IKPI ) |
| 24429 | { |
| 24430 | j2array[0]-=IK2PI; |
| 24431 | } |
| 24432 | else if( j2array[0] < -IKPI ) |
| 24433 | { j2array[0]+=IK2PI; |
| 24434 | } |
| 24435 | j2valid[0] = true; |
| 24436 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24437 | { |
| 24438 | if( !j2valid[ij2] ) |
| 24439 | { |
| 24440 | continue; |
| 24441 | } |
| 24442 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24443 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24444 | { |
| 24445 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24446 | { |
| 24447 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24448 | } |
| 24449 | } |
| 24450 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24451 | { |
| 24452 | IkReal evalcond[8]; |
| 24453 | IkReal x1811=IKsin(j2); |
| 24454 | IkReal x1812=IKcos(j2); |
| 24455 | IkReal x1813=((1.0)*cj1); |
| 24456 | evalcond[0]=(x1812+new_r10); |
| 24457 | evalcond[1]=(x1811+(((-1.0)*new_r11))); |
| 24458 | evalcond[2]=((((-1.0)*x1811*x1813))+new_r20); |
| 24459 | evalcond[3]=((((-1.0)*x1812*x1813))+new_r21); |
| 24460 | evalcond[4]=(((sj1*x1811))+(((-1.0)*new_r00))); |
| 24461 | evalcond[5]=(((sj1*x1812))+(((-1.0)*new_r01))); |
| 24462 | evalcond[6]=(((cj1*new_r20))+((new_r00*sj1))+(((-1.0)*x1811))); |
| 24463 | evalcond[7]=(((cj1*new_r21))+((new_r01*sj1))+(((-1.0)*x1812))); |
| 24464 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24465 | { |
| 24466 | continue; |
| 24467 | } |
| 24468 | } |
| 24469 | |
| 24470 | { |
| 24471 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24472 | vinfos[0].jointtype = 1; |
| 24473 | vinfos[0].foffset = j0; |
| 24474 | vinfos[0].indices[0] = _ij0[0]; |
| 24475 | vinfos[0].indices[1] = _ij0[1]; |
| 24476 | vinfos[0].maxsolutions = _nj0; |
| 24477 | vinfos[1].jointtype = 1; |
| 24478 | vinfos[1].foffset = j1; |
| 24479 | vinfos[1].indices[0] = _ij1[0]; |
| 24480 | vinfos[1].indices[1] = _ij1[1]; |
| 24481 | vinfos[1].maxsolutions = _nj1; |
| 24482 | vinfos[2].jointtype = 1; |
| 24483 | vinfos[2].foffset = j2; |
| 24484 | vinfos[2].indices[0] = _ij2[0]; |
| 24485 | vinfos[2].indices[1] = _ij2[1]; |
| 24486 | vinfos[2].maxsolutions = _nj2; |
| 24487 | vinfos[3].jointtype = 1; |
| 24488 | vinfos[3].foffset = j3; |
| 24489 | vinfos[3].indices[0] = _ij3[0]; |
| 24490 | vinfos[3].indices[1] = _ij3[1]; |
| 24491 | vinfos[3].maxsolutions = _nj3; |
| 24492 | vinfos[4].jointtype = 1; |
| 24493 | vinfos[4].foffset = j4; |
| 24494 | vinfos[4].indices[0] = _ij4[0]; |
| 24495 | vinfos[4].indices[1] = _ij4[1]; |
| 24496 | vinfos[4].maxsolutions = _nj4; |
| 24497 | vinfos[5].jointtype = 1; |
| 24498 | vinfos[5].foffset = j5; |
| 24499 | vinfos[5].indices[0] = _ij5[0]; |
| 24500 | vinfos[5].indices[1] = _ij5[1]; |
| 24501 | vinfos[5].maxsolutions = _nj5; |
| 24502 | std::vector<int> vfree(0); |
| 24503 | solutions.AddSolution(vinfos,vfree); |
| 24504 | } |
| 24505 | } |
| 24506 | } |
| 24507 | |
| 24508 | } |
| 24509 | } while(0); |
| 24510 | if( bgotonextstatement ) |
| 24511 | { |
| 24512 | bool bgotonextstatement = true; |
| 24513 | do |
| 24514 | { |
| 24515 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(j1))), 6.28318530717959))); |
| 24516 | evalcond[1]=new_r22; |
| 24517 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 24518 | { |
| 24519 | bgotonextstatement=false; |
| 24520 | { |
| 24521 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24522 | bool j2valid[1]={false}; |
| 24523 | _nj2 = 1; |
| 24524 | if( IKabs(new_r20) < IKFAST_ATAN2_MAGTHRESH && IKabs(new_r21) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(new_r20)+IKsqr(new_r21)-1) <= IKFAST_SINCOS_THRESH ) |
| 24525 | continue; |
| 24526 | j2array[0]=IKatan2(new_r20, new_r21); |
| 24527 | sj2array[0]=IKsin(j2array[0]); |
| 24528 | cj2array[0]=IKcos(j2array[0]); |
| 24529 | if( j2array[0] > IKPI ) |
| 24530 | { |
| 24531 | j2array[0]-=IK2PI; |
| 24532 | } |
| 24533 | else if( j2array[0] < -IKPI ) |
| 24534 | { j2array[0]+=IK2PI; |
| 24535 | } |
| 24536 | j2valid[0] = true; |
| 24537 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24538 | { |
| 24539 | if( !j2valid[ij2] ) |
| 24540 | { |
| 24541 | continue; |
| 24542 | } |
| 24543 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24544 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24545 | { |
| 24546 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24547 | { |
| 24548 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24549 | } |
| 24550 | } |
| 24551 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24552 | { |
| 24553 | IkReal evalcond[8]; |
| 24554 | IkReal x1814=IKcos(j2); |
| 24555 | IkReal x1815=IKsin(j2); |
| 24556 | IkReal x1816=((1.0)*sj0); |
| 24557 | IkReal x1817=((1.0)*x1814); |
| 24558 | evalcond[0]=(new_r20+(((-1.0)*x1815))); |
| 24559 | evalcond[1]=((((-1.0)*x1817))+new_r21); |
| 24560 | evalcond[2]=(((sj0*x1814))+new_r00); |
| 24561 | evalcond[3]=(((cj0*x1815))+new_r11); |
| 24562 | evalcond[4]=((((-1.0)*x1815*x1816))+new_r01); |
| 24563 | evalcond[5]=((((-1.0)*new_r02*x1817))+new_r10); |
| 24564 | evalcond[6]=((((-1.0)*new_r01*x1816))+x1815+((cj0*new_r11))); |
| 24565 | evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1814); |
| 24566 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24567 | { |
| 24568 | continue; |
| 24569 | } |
| 24570 | } |
| 24571 | |
| 24572 | { |
| 24573 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24574 | vinfos[0].jointtype = 1; |
| 24575 | vinfos[0].foffset = j0; |
| 24576 | vinfos[0].indices[0] = _ij0[0]; |
| 24577 | vinfos[0].indices[1] = _ij0[1]; |
| 24578 | vinfos[0].maxsolutions = _nj0; |
| 24579 | vinfos[1].jointtype = 1; |
| 24580 | vinfos[1].foffset = j1; |
| 24581 | vinfos[1].indices[0] = _ij1[0]; |
| 24582 | vinfos[1].indices[1] = _ij1[1]; |
| 24583 | vinfos[1].maxsolutions = _nj1; |
| 24584 | vinfos[2].jointtype = 1; |
| 24585 | vinfos[2].foffset = j2; |
| 24586 | vinfos[2].indices[0] = _ij2[0]; |
| 24587 | vinfos[2].indices[1] = _ij2[1]; |
| 24588 | vinfos[2].maxsolutions = _nj2; |
| 24589 | vinfos[3].jointtype = 1; |
| 24590 | vinfos[3].foffset = j3; |
| 24591 | vinfos[3].indices[0] = _ij3[0]; |
| 24592 | vinfos[3].indices[1] = _ij3[1]; |
| 24593 | vinfos[3].maxsolutions = _nj3; |
| 24594 | vinfos[4].jointtype = 1; |
| 24595 | vinfos[4].foffset = j4; |
| 24596 | vinfos[4].indices[0] = _ij4[0]; |
| 24597 | vinfos[4].indices[1] = _ij4[1]; |
| 24598 | vinfos[4].maxsolutions = _nj4; |
| 24599 | vinfos[5].jointtype = 1; |
| 24600 | vinfos[5].foffset = j5; |
| 24601 | vinfos[5].indices[0] = _ij5[0]; |
| 24602 | vinfos[5].indices[1] = _ij5[1]; |
| 24603 | vinfos[5].maxsolutions = _nj5; |
| 24604 | std::vector<int> vfree(0); |
| 24605 | solutions.AddSolution(vinfos,vfree); |
| 24606 | } |
| 24607 | } |
| 24608 | } |
| 24609 | |
| 24610 | } |
| 24611 | } while(0); |
| 24612 | if( bgotonextstatement ) |
| 24613 | { |
| 24614 | bool bgotonextstatement = true; |
| 24615 | do |
| 24616 | { |
| 24617 | evalcond[0]=((-3.14159265358979)+(IKfmod(((3.14159265358979)+(IKabs(((-3.14159265358979)+j1)))), 6.28318530717959))); |
| 24618 | evalcond[1]=new_r22; |
| 24619 | if( IKabs(evalcond[0]) < 0.0000050000000000 && IKabs(evalcond[1]) < 0.0000050000000000 ) |
| 24620 | { |
| 24621 | bgotonextstatement=false; |
| 24622 | { |
| 24623 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24624 | bool j2valid[1]={false}; |
| 24625 | _nj2 = 1; |
| 24626 | if( IKabs(((-1.0)*new_r20)) < IKFAST_ATAN2_MAGTHRESH && IKabs(((-1.0)*new_r21)) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr(((-1.0)*new_r20))+IKsqr(((-1.0)*new_r21))-1) <= IKFAST_SINCOS_THRESH ) |
| 24627 | continue; |
| 24628 | j2array[0]=IKatan2(((-1.0)*new_r20), ((-1.0)*new_r21)); |
| 24629 | sj2array[0]=IKsin(j2array[0]); |
| 24630 | cj2array[0]=IKcos(j2array[0]); |
| 24631 | if( j2array[0] > IKPI ) |
| 24632 | { |
| 24633 | j2array[0]-=IK2PI; |
| 24634 | } |
| 24635 | else if( j2array[0] < -IKPI ) |
| 24636 | { j2array[0]+=IK2PI; |
| 24637 | } |
| 24638 | j2valid[0] = true; |
| 24639 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24640 | { |
| 24641 | if( !j2valid[ij2] ) |
| 24642 | { |
| 24643 | continue; |
| 24644 | } |
| 24645 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24646 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24647 | { |
| 24648 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24649 | { |
| 24650 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24651 | } |
| 24652 | } |
| 24653 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24654 | { |
| 24655 | IkReal evalcond[8]; |
| 24656 | IkReal x1818=IKcos(j2); |
| 24657 | IkReal x1819=IKsin(j2); |
| 24658 | IkReal x1820=((1.0)*sj0); |
| 24659 | evalcond[0]=(x1819+new_r20); |
| 24660 | evalcond[1]=(x1818+new_r21); |
| 24661 | evalcond[2]=(((sj0*x1818))+new_r00); |
| 24662 | evalcond[3]=(((cj0*x1819))+new_r11); |
| 24663 | evalcond[4]=(((new_r02*x1818))+new_r10); |
| 24664 | evalcond[5]=((((-1.0)*x1819*x1820))+new_r01); |
| 24665 | evalcond[6]=((((-1.0)*new_r01*x1820))+x1819+((cj0*new_r11))); |
| 24666 | evalcond[7]=((((-1.0)*cj0*new_r10))+((new_r00*sj0))+x1818); |
| 24667 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH ) |
| 24668 | { |
| 24669 | continue; |
| 24670 | } |
| 24671 | } |
| 24672 | |
| 24673 | { |
| 24674 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24675 | vinfos[0].jointtype = 1; |
| 24676 | vinfos[0].foffset = j0; |
| 24677 | vinfos[0].indices[0] = _ij0[0]; |
| 24678 | vinfos[0].indices[1] = _ij0[1]; |
| 24679 | vinfos[0].maxsolutions = _nj0; |
| 24680 | vinfos[1].jointtype = 1; |
| 24681 | vinfos[1].foffset = j1; |
| 24682 | vinfos[1].indices[0] = _ij1[0]; |
| 24683 | vinfos[1].indices[1] = _ij1[1]; |
| 24684 | vinfos[1].maxsolutions = _nj1; |
| 24685 | vinfos[2].jointtype = 1; |
| 24686 | vinfos[2].foffset = j2; |
| 24687 | vinfos[2].indices[0] = _ij2[0]; |
| 24688 | vinfos[2].indices[1] = _ij2[1]; |
| 24689 | vinfos[2].maxsolutions = _nj2; |
| 24690 | vinfos[3].jointtype = 1; |
| 24691 | vinfos[3].foffset = j3; |
| 24692 | vinfos[3].indices[0] = _ij3[0]; |
| 24693 | vinfos[3].indices[1] = _ij3[1]; |
| 24694 | vinfos[3].maxsolutions = _nj3; |
| 24695 | vinfos[4].jointtype = 1; |
| 24696 | vinfos[4].foffset = j4; |
| 24697 | vinfos[4].indices[0] = _ij4[0]; |
| 24698 | vinfos[4].indices[1] = _ij4[1]; |
| 24699 | vinfos[4].maxsolutions = _nj4; |
| 24700 | vinfos[5].jointtype = 1; |
| 24701 | vinfos[5].foffset = j5; |
| 24702 | vinfos[5].indices[0] = _ij5[0]; |
| 24703 | vinfos[5].indices[1] = _ij5[1]; |
| 24704 | vinfos[5].maxsolutions = _nj5; |
| 24705 | std::vector<int> vfree(0); |
| 24706 | solutions.AddSolution(vinfos,vfree); |
| 24707 | } |
| 24708 | } |
| 24709 | } |
| 24710 | |
| 24711 | } |
| 24712 | } while(0); |
| 24713 | if( bgotonextstatement ) |
| 24714 | { |
| 24715 | bool bgotonextstatement = true; |
| 24716 | do |
| 24717 | { |
| 24718 | evalcond[0]=((IKabs(new_r20))+(IKabs(new_r21))); |
| 24719 | if( IKabs(evalcond[0]) < 0.0000050000000000 ) |
| 24720 | { |
| 24721 | bgotonextstatement=false; |
| 24722 | { |
| 24723 | IkReal j2eval[1]; |
| 24724 | new_r21=0; |
| 24725 | new_r20=0; |
| 24726 | new_r02=0; |
| 24727 | new_r12=0; |
| 24728 | j2eval[0]=IKabs(new_r22); |
| 24729 | if( IKabs(j2eval[0]) < 0.0000000100000000 ) |
| 24730 | { |
| 24731 | continue; // no branches [j2] |
| 24732 | |
| 24733 | } else |
| 24734 | { |
| 24735 | IkReal op[2+1], zeror[2]; |
| 24736 | int numroots; |
| 24737 | op[0]=((-1.0)*new_r22); |
| 24738 | op[1]=0; |
| 24739 | op[2]=new_r22; |
| 24740 | polyroots2(op,zeror,numroots); |
| 24741 | IkReal j2array[2], cj2array[2], sj2array[2], tempj2array[1]; |
| 24742 | int numsolutions = 0; |
| 24743 | for(int ij2 = 0; ij2 < numroots; ++ij2) |
| 24744 | { |
| 24745 | IkReal htj2 = zeror[ij2]; |
| 24746 | tempj2array[0]=((2.0)*(atan(htj2))); |
| 24747 | for(int kj2 = 0; kj2 < 1; ++kj2) |
| 24748 | { |
| 24749 | j2array[numsolutions] = tempj2array[kj2]; |
| 24750 | if( j2array[numsolutions] > IKPI ) |
| 24751 | { |
| 24752 | j2array[numsolutions]-=IK2PI; |
| 24753 | } |
| 24754 | else if( j2array[numsolutions] < -IKPI ) |
| 24755 | { |
| 24756 | j2array[numsolutions]+=IK2PI; |
| 24757 | } |
| 24758 | sj2array[numsolutions] = IKsin(j2array[numsolutions]); |
| 24759 | cj2array[numsolutions] = IKcos(j2array[numsolutions]); |
| 24760 | numsolutions++; |
| 24761 | } |
| 24762 | } |
| 24763 | bool j2valid[2]={true,true}; |
| 24764 | _nj2 = 2; |
| 24765 | for(int ij2 = 0; ij2 < numsolutions; ++ij2) |
| 24766 | { |
| 24767 | if( !j2valid[ij2] ) |
| 24768 | { |
| 24769 | continue; |
| 24770 | } |
| 24771 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24772 | htj2 = IKtan(j2/2); |
| 24773 | |
| 24774 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24775 | for(int iij2 = ij2+1; iij2 < numsolutions; ++iij2) |
| 24776 | { |
| 24777 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24778 | { |
| 24779 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24780 | } |
| 24781 | } |
| 24782 | { |
| 24783 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24784 | vinfos[0].jointtype = 1; |
| 24785 | vinfos[0].foffset = j0; |
| 24786 | vinfos[0].indices[0] = _ij0[0]; |
| 24787 | vinfos[0].indices[1] = _ij0[1]; |
| 24788 | vinfos[0].maxsolutions = _nj0; |
| 24789 | vinfos[1].jointtype = 1; |
| 24790 | vinfos[1].foffset = j1; |
| 24791 | vinfos[1].indices[0] = _ij1[0]; |
| 24792 | vinfos[1].indices[1] = _ij1[1]; |
| 24793 | vinfos[1].maxsolutions = _nj1; |
| 24794 | vinfos[2].jointtype = 1; |
| 24795 | vinfos[2].foffset = j2; |
| 24796 | vinfos[2].indices[0] = _ij2[0]; |
| 24797 | vinfos[2].indices[1] = _ij2[1]; |
| 24798 | vinfos[2].maxsolutions = _nj2; |
| 24799 | vinfos[3].jointtype = 1; |
| 24800 | vinfos[3].foffset = j3; |
| 24801 | vinfos[3].indices[0] = _ij3[0]; |
| 24802 | vinfos[3].indices[1] = _ij3[1]; |
| 24803 | vinfos[3].maxsolutions = _nj3; |
| 24804 | vinfos[4].jointtype = 1; |
| 24805 | vinfos[4].foffset = j4; |
| 24806 | vinfos[4].indices[0] = _ij4[0]; |
| 24807 | vinfos[4].indices[1] = _ij4[1]; |
| 24808 | vinfos[4].maxsolutions = _nj4; |
| 24809 | vinfos[5].jointtype = 1; |
| 24810 | vinfos[5].foffset = j5; |
| 24811 | vinfos[5].indices[0] = _ij5[0]; |
| 24812 | vinfos[5].indices[1] = _ij5[1]; |
| 24813 | vinfos[5].maxsolutions = _nj5; |
| 24814 | std::vector<int> vfree(0); |
| 24815 | solutions.AddSolution(vinfos,vfree); |
| 24816 | } |
| 24817 | } |
| 24818 | |
| 24819 | } |
| 24820 | |
| 24821 | } |
| 24822 | |
| 24823 | } |
| 24824 | } while(0); |
| 24825 | if( bgotonextstatement ) |
| 24826 | { |
| 24827 | bool bgotonextstatement = true; |
| 24828 | do |
| 24829 | { |
| 24830 | if( 1 ) |
| 24831 | { |
| 24832 | bgotonextstatement=false; |
| 24833 | continue; // branch miss [j2] |
| 24834 | |
| 24835 | } |
| 24836 | } while(0); |
| 24837 | if( bgotonextstatement ) |
| 24838 | { |
| 24839 | } |
| 24840 | } |
| 24841 | } |
| 24842 | } |
| 24843 | } |
| 24844 | } |
| 24845 | } |
| 24846 | } |
| 24847 | } |
| 24848 | |
| 24849 | } else |
| 24850 | { |
| 24851 | { |
| 24852 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24853 | bool j2valid[1]={false}; |
| 24854 | _nj2 = 1; |
| 24855 | CheckValue<IkReal> x1822=IKPowWithIntegerCheck(cj1,-1); |
| 24856 | if(!x1822.valid){ |
| 24857 | continue; |
| 24858 | } |
| 24859 | IkReal x1821=x1822.value; |
| 24860 | CheckValue<IkReal> x1823=IKPowWithIntegerCheck(sj0,-1); |
| 24861 | if(!x1823.valid){ |
| 24862 | continue; |
| 24863 | } |
| 24864 | CheckValue<IkReal> x1824=IKPowWithIntegerCheck(sj1,-1); |
| 24865 | if(!x1824.valid){ |
| 24866 | continue; |
| 24867 | } |
| 24868 | if( IKabs((new_r20*x1821)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x1821))+IKsqr((x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 24869 | continue; |
| 24870 | j2array[0]=IKatan2((new_r20*x1821), (x1821*(x1823.value)*(x1824.value)*(((((-1.0)*cj0*new_r20))+(((-1.0)*cj1*new_r11)))))); |
| 24871 | sj2array[0]=IKsin(j2array[0]); |
| 24872 | cj2array[0]=IKcos(j2array[0]); |
| 24873 | if( j2array[0] > IKPI ) |
| 24874 | { |
| 24875 | j2array[0]-=IK2PI; |
| 24876 | } |
| 24877 | else if( j2array[0] < -IKPI ) |
| 24878 | { j2array[0]+=IK2PI; |
| 24879 | } |
| 24880 | j2valid[0] = true; |
| 24881 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24882 | { |
| 24883 | if( !j2valid[ij2] ) |
| 24884 | { |
| 24885 | continue; |
| 24886 | } |
| 24887 | _ij2[0] = ij2; _ij2[1] = -1; |
| 24888 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 24889 | { |
| 24890 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 24891 | { |
| 24892 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 24893 | } |
| 24894 | } |
| 24895 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 24896 | { |
| 24897 | IkReal evalcond[12]; |
| 24898 | IkReal x1825=IKsin(j2); |
| 24899 | IkReal x1826=IKcos(j2); |
| 24900 | IkReal x1827=((1.0)*sj0); |
| 24901 | IkReal x1828=(cj0*new_r00); |
| 24902 | IkReal x1829=((1.0)*cj0); |
| 24903 | IkReal x1830=((1.0)*x1826); |
| 24904 | IkReal x1831=(sj1*x1825); |
| 24905 | IkReal x1832=(sj1*x1826); |
| 24906 | IkReal x1833=((1.0)*x1825); |
| 24907 | evalcond[0]=(new_r20+(((-1.0)*cj1*x1833))); |
| 24908 | evalcond[1]=(new_r21+(((-1.0)*cj1*x1830))); |
| 24909 | evalcond[2]=((((-1.0)*new_r01*x1827))+x1825+((cj0*new_r11))); |
| 24910 | evalcond[3]=((((-1.0)*new_r10*x1829))+((new_r00*sj0))+x1826); |
| 24911 | evalcond[4]=(((new_r10*sj0))+x1828+x1831); |
| 24912 | evalcond[5]=(((new_r11*sj0))+x1832+((cj0*new_r01))); |
| 24913 | evalcond[6]=(((cj0*x1831))+((sj0*x1826))+new_r00); |
| 24914 | evalcond[7]=(((cj0*x1825))+((sj0*x1832))+new_r11); |
| 24915 | evalcond[8]=(((cj0*x1832))+(((-1.0)*x1825*x1827))+new_r01); |
| 24916 | evalcond[9]=(((sj0*x1831))+(((-1.0)*x1826*x1829))+new_r10); |
| 24917 | evalcond[10]=(((cj1*new_r20))+(((-1.0)*x1833))+(((-1.0)*sj1*x1828))+(((-1.0)*new_r10*sj1*x1827))); |
| 24918 | evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1827))+(((-1.0)*x1830))+(((-1.0)*new_r01*sj1*x1829))); |
| 24919 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 24920 | { |
| 24921 | continue; |
| 24922 | } |
| 24923 | } |
| 24924 | |
| 24925 | { |
| 24926 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 24927 | vinfos[0].jointtype = 1; |
| 24928 | vinfos[0].foffset = j0; |
| 24929 | vinfos[0].indices[0] = _ij0[0]; |
| 24930 | vinfos[0].indices[1] = _ij0[1]; |
| 24931 | vinfos[0].maxsolutions = _nj0; |
| 24932 | vinfos[1].jointtype = 1; |
| 24933 | vinfos[1].foffset = j1; |
| 24934 | vinfos[1].indices[0] = _ij1[0]; |
| 24935 | vinfos[1].indices[1] = _ij1[1]; |
| 24936 | vinfos[1].maxsolutions = _nj1; |
| 24937 | vinfos[2].jointtype = 1; |
| 24938 | vinfos[2].foffset = j2; |
| 24939 | vinfos[2].indices[0] = _ij2[0]; |
| 24940 | vinfos[2].indices[1] = _ij2[1]; |
| 24941 | vinfos[2].maxsolutions = _nj2; |
| 24942 | vinfos[3].jointtype = 1; |
| 24943 | vinfos[3].foffset = j3; |
| 24944 | vinfos[3].indices[0] = _ij3[0]; |
| 24945 | vinfos[3].indices[1] = _ij3[1]; |
| 24946 | vinfos[3].maxsolutions = _nj3; |
| 24947 | vinfos[4].jointtype = 1; |
| 24948 | vinfos[4].foffset = j4; |
| 24949 | vinfos[4].indices[0] = _ij4[0]; |
| 24950 | vinfos[4].indices[1] = _ij4[1]; |
| 24951 | vinfos[4].maxsolutions = _nj4; |
| 24952 | vinfos[5].jointtype = 1; |
| 24953 | vinfos[5].foffset = j5; |
| 24954 | vinfos[5].indices[0] = _ij5[0]; |
| 24955 | vinfos[5].indices[1] = _ij5[1]; |
| 24956 | vinfos[5].maxsolutions = _nj5; |
| 24957 | std::vector<int> vfree(0); |
| 24958 | solutions.AddSolution(vinfos,vfree); |
| 24959 | } |
| 24960 | } |
| 24961 | } |
| 24962 | |
| 24963 | } |
| 24964 | |
| 24965 | } |
| 24966 | |
| 24967 | } else |
| 24968 | { |
| 24969 | { |
| 24970 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 24971 | bool j2valid[1]={false}; |
| 24972 | _nj2 = 1; |
| 24973 | CheckValue<IkReal> x1835=IKPowWithIntegerCheck(cj1,-1); |
| 24974 | if(!x1835.valid){ |
| 24975 | continue; |
| 24976 | } |
| 24977 | IkReal x1834=x1835.value; |
| 24978 | CheckValue<IkReal> x1836=IKPowWithIntegerCheck(sj0,-1); |
| 24979 | if(!x1836.valid){ |
| 24980 | continue; |
| 24981 | } |
| 24982 | if( IKabs((new_r20*x1834)) < IKFAST_ATAN2_MAGTHRESH && IKabs((x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))) < IKFAST_ATAN2_MAGTHRESH && IKabs(IKsqr((new_r20*x1834))+IKsqr((x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00))))))-1) <= IKFAST_SINCOS_THRESH ) |
| 24983 | continue; |
| 24984 | j2array[0]=IKatan2((new_r20*x1834), (x1834*(x1836.value)*(((((-1.0)*cj0*new_r20*sj1))+(((-1.0)*cj1*new_r00)))))); |
| 24985 | sj2array[0]=IKsin(j2array[0]); |
| 24986 | cj2array[0]=IKcos(j2array[0]); |
| 24987 | if( j2array[0] > IKPI ) |
| 24988 | { |
| 24989 | j2array[0]-=IK2PI; |
| 24990 | } |
| 24991 | else if( j2array[0] < -IKPI ) |
| 24992 | { j2array[0]+=IK2PI; |
| 24993 | } |
| 24994 | j2valid[0] = true; |
| 24995 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 24996 | { |
| 24997 | if( !j2valid[ij2] ) |
| 24998 | { |
| 24999 | continue; |
| 25000 | } |
| 25001 | _ij2[0] = ij2; _ij2[1] = -1; |
| 25002 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 25003 | { |
| 25004 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 25005 | { |
| 25006 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 25007 | } |
| 25008 | } |
| 25009 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 25010 | { |
| 25011 | IkReal evalcond[12]; |
| 25012 | IkReal x1837=IKsin(j2); |
| 25013 | IkReal x1838=IKcos(j2); |
| 25014 | IkReal x1839=((1.0)*sj0); |
| 25015 | IkReal x1840=(cj0*new_r00); |
| 25016 | IkReal x1841=((1.0)*cj0); |
| 25017 | IkReal x1842=((1.0)*x1838); |
| 25018 | IkReal x1843=(sj1*x1837); |
| 25019 | IkReal x1844=(sj1*x1838); |
| 25020 | IkReal x1845=((1.0)*x1837); |
| 25021 | evalcond[0]=((((-1.0)*cj1*x1845))+new_r20); |
| 25022 | evalcond[1]=((((-1.0)*cj1*x1842))+new_r21); |
| 25023 | evalcond[2]=((((-1.0)*new_r01*x1839))+x1837+((cj0*new_r11))); |
| 25024 | evalcond[3]=((((-1.0)*new_r10*x1841))+((new_r00*sj0))+x1838); |
| 25025 | evalcond[4]=(((new_r10*sj0))+x1843+x1840); |
| 25026 | evalcond[5]=(((new_r11*sj0))+x1844+((cj0*new_r01))); |
| 25027 | evalcond[6]=(((cj0*x1843))+((sj0*x1838))+new_r00); |
| 25028 | evalcond[7]=(((cj0*x1837))+((sj0*x1844))+new_r11); |
| 25029 | evalcond[8]=(((cj0*x1844))+(((-1.0)*x1837*x1839))+new_r01); |
| 25030 | evalcond[9]=(((sj0*x1843))+new_r10+(((-1.0)*x1838*x1841))); |
| 25031 | evalcond[10]=((((-1.0)*x1845))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1839))+(((-1.0)*sj1*x1840))); |
| 25032 | evalcond[11]=((((-1.0)*new_r11*sj1*x1839))+(((-1.0)*new_r01*sj1*x1841))+(((-1.0)*x1842))+((cj1*new_r21))); |
| 25033 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 25034 | { |
| 25035 | continue; |
| 25036 | } |
| 25037 | } |
| 25038 | |
| 25039 | { |
| 25040 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 25041 | vinfos[0].jointtype = 1; |
| 25042 | vinfos[0].foffset = j0; |
| 25043 | vinfos[0].indices[0] = _ij0[0]; |
| 25044 | vinfos[0].indices[1] = _ij0[1]; |
| 25045 | vinfos[0].maxsolutions = _nj0; |
| 25046 | vinfos[1].jointtype = 1; |
| 25047 | vinfos[1].foffset = j1; |
| 25048 | vinfos[1].indices[0] = _ij1[0]; |
| 25049 | vinfos[1].indices[1] = _ij1[1]; |
| 25050 | vinfos[1].maxsolutions = _nj1; |
| 25051 | vinfos[2].jointtype = 1; |
| 25052 | vinfos[2].foffset = j2; |
| 25053 | vinfos[2].indices[0] = _ij2[0]; |
| 25054 | vinfos[2].indices[1] = _ij2[1]; |
| 25055 | vinfos[2].maxsolutions = _nj2; |
| 25056 | vinfos[3].jointtype = 1; |
| 25057 | vinfos[3].foffset = j3; |
| 25058 | vinfos[3].indices[0] = _ij3[0]; |
| 25059 | vinfos[3].indices[1] = _ij3[1]; |
| 25060 | vinfos[3].maxsolutions = _nj3; |
| 25061 | vinfos[4].jointtype = 1; |
| 25062 | vinfos[4].foffset = j4; |
| 25063 | vinfos[4].indices[0] = _ij4[0]; |
| 25064 | vinfos[4].indices[1] = _ij4[1]; |
| 25065 | vinfos[4].maxsolutions = _nj4; |
| 25066 | vinfos[5].jointtype = 1; |
| 25067 | vinfos[5].foffset = j5; |
| 25068 | vinfos[5].indices[0] = _ij5[0]; |
| 25069 | vinfos[5].indices[1] = _ij5[1]; |
| 25070 | vinfos[5].maxsolutions = _nj5; |
| 25071 | std::vector<int> vfree(0); |
| 25072 | solutions.AddSolution(vinfos,vfree); |
| 25073 | } |
| 25074 | } |
| 25075 | } |
| 25076 | |
| 25077 | } |
| 25078 | |
| 25079 | } |
| 25080 | |
| 25081 | } else |
| 25082 | { |
| 25083 | { |
| 25084 | IkReal j2array[1], cj2array[1], sj2array[1]; |
| 25085 | bool j2valid[1]={false}; |
| 25086 | _nj2 = 1; |
| 25087 | CheckValue<IkReal> x1846=IKPowWithIntegerCheck(IKsign(cj1),-1); |
| 25088 | if(!x1846.valid){ |
| 25089 | continue; |
| 25090 | } |
| 25091 | CheckValue<IkReal> x1847 = IKatan2WithCheck(IkReal(new_r20),IkReal(new_r21),IKFAST_ATAN2_MAGTHRESH); |
| 25092 | if(!x1847.valid){ |
| 25093 | continue; |
| 25094 | } |
| 25095 | j2array[0]=((-1.5707963267949)+(((1.5707963267949)*(x1846.value)))+(x1847.value)); |
| 25096 | sj2array[0]=IKsin(j2array[0]); |
| 25097 | cj2array[0]=IKcos(j2array[0]); |
| 25098 | if( j2array[0] > IKPI ) |
| 25099 | { |
| 25100 | j2array[0]-=IK2PI; |
| 25101 | } |
| 25102 | else if( j2array[0] < -IKPI ) |
| 25103 | { j2array[0]+=IK2PI; |
| 25104 | } |
| 25105 | j2valid[0] = true; |
| 25106 | for(int ij2 = 0; ij2 < 1; ++ij2) |
| 25107 | { |
| 25108 | if( !j2valid[ij2] ) |
| 25109 | { |
| 25110 | continue; |
| 25111 | } |
| 25112 | _ij2[0] = ij2; _ij2[1] = -1; |
| 25113 | for(int iij2 = ij2+1; iij2 < 1; ++iij2) |
| 25114 | { |
| 25115 | if( j2valid[iij2] && IKabs(cj2array[ij2]-cj2array[iij2]) < IKFAST_SOLUTION_THRESH && IKabs(sj2array[ij2]-sj2array[iij2]) < IKFAST_SOLUTION_THRESH ) |
| 25116 | { |
| 25117 | j2valid[iij2]=false; _ij2[1] = iij2; break; |
| 25118 | } |
| 25119 | } |
| 25120 | j2 = j2array[ij2]; cj2 = cj2array[ij2]; sj2 = sj2array[ij2]; |
| 25121 | { |
| 25122 | IkReal evalcond[12]; |
| 25123 | IkReal x1848=IKsin(j2); |
| 25124 | IkReal x1849=IKcos(j2); |
| 25125 | IkReal x1850=((1.0)*sj0); |
| 25126 | IkReal x1851=(cj0*new_r00); |
| 25127 | IkReal x1852=((1.0)*cj0); |
| 25128 | IkReal x1853=((1.0)*x1849); |
| 25129 | IkReal x1854=(sj1*x1848); |
| 25130 | IkReal x1855=(sj1*x1849); |
| 25131 | IkReal x1856=((1.0)*x1848); |
| 25132 | evalcond[0]=(new_r20+(((-1.0)*cj1*x1856))); |
| 25133 | evalcond[1]=(new_r21+(((-1.0)*cj1*x1853))); |
| 25134 | evalcond[2]=(x1848+(((-1.0)*new_r01*x1850))+((cj0*new_r11))); |
| 25135 | evalcond[3]=(((new_r00*sj0))+(((-1.0)*new_r10*x1852))+x1849); |
| 25136 | evalcond[4]=(((new_r10*sj0))+x1851+x1854); |
| 25137 | evalcond[5]=(((new_r11*sj0))+x1855+((cj0*new_r01))); |
| 25138 | evalcond[6]=(((sj0*x1849))+new_r00+((cj0*x1854))); |
| 25139 | evalcond[7]=(((cj0*x1848))+((sj0*x1855))+new_r11); |
| 25140 | evalcond[8]=((((-1.0)*x1848*x1850))+new_r01+((cj0*x1855))); |
| 25141 | evalcond[9]=((((-1.0)*x1849*x1852))+((sj0*x1854))+new_r10); |
| 25142 | evalcond[10]=((((-1.0)*sj1*x1851))+((cj1*new_r20))+(((-1.0)*new_r10*sj1*x1850))+(((-1.0)*x1856))); |
| 25143 | evalcond[11]=(((cj1*new_r21))+(((-1.0)*new_r11*sj1*x1850))+(((-1.0)*new_r01*sj1*x1852))+(((-1.0)*x1853))); |
| 25144 | if( IKabs(evalcond[0]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[1]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[2]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[3]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[4]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[5]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[6]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[7]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[8]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[9]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[10]) > IKFAST_EVALCOND_THRESH || IKabs(evalcond[11]) > IKFAST_EVALCOND_THRESH ) |
| 25145 | { |
| 25146 | continue; |
| 25147 | } |
| 25148 | } |
| 25149 | |
| 25150 | { |
| 25151 | std::vector<IkSingleDOFSolutionBase<IkReal> > vinfos(6); |
| 25152 | vinfos[0].jointtype = 1; |
| 25153 | vinfos[0].foffset = j0; |
| 25154 | vinfos[0].indices[0] = _ij0[0]; |
| 25155 | vinfos[0].indices[1] = _ij0[1]; |
| 25156 | vinfos[0].maxsolutions = _nj0; |
| 25157 | vinfos[1].jointtype = 1; |
| 25158 | vinfos[1].foffset = j1; |
| 25159 | vinfos[1].indices[0] = _ij1[0]; |
| 25160 | vinfos[1].indices[1] = _ij1[1]; |
| 25161 | vinfos[1].maxsolutions = _nj1; |
| 25162 | vinfos[2].jointtype = 1; |
| 25163 | vinfos[2].foffset = j2; |
| 25164 | vinfos[2].indices[0] = _ij2[0]; |
| 25165 | vinfos[2].indices[1] = _ij2[1]; |
| 25166 | vinfos[2].maxsolutions = _nj2; |
| 25167 | vinfos[3].jointtype = 1; |
| 25168 | vinfos[3].foffset = j3; |
| 25169 | vinfos[3].indices[0] = _ij3[0]; |
| 25170 | vinfos[3].indices[1] = _ij3[1]; |
| 25171 | vinfos[3].maxsolutions = _nj3; |
| 25172 | vinfos[4].jointtype = 1; |
| 25173 | vinfos[4].foffset = j4; |
| 25174 | vinfos[4].indices[0] = _ij4[0]; |
| 25175 | vinfos[4].indices[1] = _ij4[1]; |
| 25176 | vinfos[4].maxsolutions = _nj4; |
| 25177 | vinfos[5].jointtype = 1; |
| 25178 | vinfos[5].foffset = j5; |
| 25179 | vinfos[5].indices[0] = _ij5[0]; |
| 25180 | vinfos[5].indices[1] = _ij5[1]; |
| 25181 | vinfos[5].maxsolutions = _nj5; |
| 25182 | std::vector<int> vfree(0); |
| 25183 | solutions.AddSolution(vinfos,vfree); |
| 25184 | } |
| 25185 | } |
| 25186 | } |
| 25187 | |
| 25188 | } |
| 25189 | |
| 25190 | } |
| 25191 | } |
| 25192 | } |
| 25193 | |
| 25194 | } |
| 25195 | |
| 25196 | } |
| 25197 | } |
| 25198 | } |
| 25199 | } |
| 25200 | }static inline void polyroots3(IkReal rawcoeffs[3+1], IkReal rawroots[3], int& numroots) |
| 25201 | { |
| 25202 | using std::complex; |
| 25203 | if( rawcoeffs[0] == 0 ) { |
| 25204 | // solve with one reduced degree |
| 25205 | polyroots2(&rawcoeffs[1], &rawroots[0], numroots); |
| 25206 | return; |
| 25207 | } |
| 25208 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25209 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25210 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25211 | complex<IkReal> coeffs[3]; |
| 25212 | const int maxsteps = 110; |
| 25213 | for(int i = 0; i < 3; ++i) { |
| 25214 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25215 | } |
| 25216 | complex<IkReal> roots[3]; |
| 25217 | IkReal err[3]; |
| 25218 | roots[0] = complex<IkReal>(1,0); |
| 25219 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25220 | err[0] = 1.0; |
| 25221 | err[1] = 1.0; |
| 25222 | for(int i = 2; i < 3; ++i) { |
| 25223 | roots[i] = roots[i-1]*roots[1]; |
| 25224 | err[i] = 1.0; |
| 25225 | } |
| 25226 | for(int step = 0; step < maxsteps; ++step) { |
| 25227 | bool changed = false; |
| 25228 | for(int i = 0; i < 3; ++i) { |
| 25229 | if ( err[i] >= tol ) { |
| 25230 | changed = true; |
| 25231 | // evaluate |
| 25232 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25233 | for(int j = 1; j < 3; ++j) { |
| 25234 | x = roots[i] * x + coeffs[j]; |
| 25235 | } |
| 25236 | for(int j = 0; j < 3; ++j) { |
| 25237 | if( i != j ) { |
| 25238 | if( roots[i] != roots[j] ) { |
| 25239 | x /= (roots[i] - roots[j]); |
| 25240 | } |
| 25241 | } |
| 25242 | } |
| 25243 | roots[i] -= x; |
| 25244 | err[i] = abs(x); |
| 25245 | } |
| 25246 | } |
| 25247 | if( !changed ) { |
| 25248 | break; |
| 25249 | } |
| 25250 | } |
| 25251 | |
| 25252 | numroots = 0; |
| 25253 | bool visited[3] = {false}; |
| 25254 | for(int i = 0; i < 3; ++i) { |
| 25255 | if( !visited[i] ) { |
| 25256 | // might be a multiple root, in which case it will have more error than the other roots |
| 25257 | // find any neighboring roots, and take the average |
| 25258 | complex<IkReal> newroot=roots[i]; |
| 25259 | int n = 1; |
| 25260 | for(int j = i+1; j < 3; ++j) { |
| 25261 | // care about error in real much more than imaginary |
| 25262 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25263 | newroot += roots[j]; |
| 25264 | n += 1; |
| 25265 | visited[j] = true; |
| 25266 | } |
| 25267 | } |
| 25268 | if( n > 1 ) { |
| 25269 | newroot /= n; |
| 25270 | } |
| 25271 | // 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 |
| 25272 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25273 | rawroots[numroots++] = real(newroot); |
| 25274 | } |
| 25275 | } |
| 25276 | } |
| 25277 | } |
| 25278 | static inline void polyroots2(IkReal rawcoeffs[2+1], IkReal rawroots[2], int& numroots) { |
| 25279 | IkReal det = rawcoeffs[1]*rawcoeffs[1]-4*rawcoeffs[0]*rawcoeffs[2]; |
| 25280 | if( det < 0 ) { |
| 25281 | numroots=0; |
| 25282 | } |
| 25283 | else if( det == 0 ) { |
| 25284 | rawroots[0] = -0.5*rawcoeffs[1]/rawcoeffs[0]; |
| 25285 | numroots = 1; |
| 25286 | } |
| 25287 | else { |
| 25288 | det = IKsqrt(det); |
| 25289 | rawroots[0] = (-rawcoeffs[1]+det)/(2*rawcoeffs[0]); |
| 25290 | rawroots[1] = (-rawcoeffs[1]-det)/(2*rawcoeffs[0]);//rawcoeffs[2]/(rawcoeffs[0]*rawroots[0]); |
| 25291 | numroots = 2; |
| 25292 | } |
| 25293 | } |
| 25294 | static inline void polyroots5(IkReal rawcoeffs[5+1], IkReal rawroots[5], int& numroots) |
| 25295 | { |
| 25296 | using std::complex; |
| 25297 | if( rawcoeffs[0] == 0 ) { |
| 25298 | // solve with one reduced degree |
| 25299 | polyroots4(&rawcoeffs[1], &rawroots[0], numroots); |
| 25300 | return; |
| 25301 | } |
| 25302 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25303 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25304 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25305 | complex<IkReal> coeffs[5]; |
| 25306 | const int maxsteps = 110; |
| 25307 | for(int i = 0; i < 5; ++i) { |
| 25308 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25309 | } |
| 25310 | complex<IkReal> roots[5]; |
| 25311 | IkReal err[5]; |
| 25312 | roots[0] = complex<IkReal>(1,0); |
| 25313 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25314 | err[0] = 1.0; |
| 25315 | err[1] = 1.0; |
| 25316 | for(int i = 2; i < 5; ++i) { |
| 25317 | roots[i] = roots[i-1]*roots[1]; |
| 25318 | err[i] = 1.0; |
| 25319 | } |
| 25320 | for(int step = 0; step < maxsteps; ++step) { |
| 25321 | bool changed = false; |
| 25322 | for(int i = 0; i < 5; ++i) { |
| 25323 | if ( err[i] >= tol ) { |
| 25324 | changed = true; |
| 25325 | // evaluate |
| 25326 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25327 | for(int j = 1; j < 5; ++j) { |
| 25328 | x = roots[i] * x + coeffs[j]; |
| 25329 | } |
| 25330 | for(int j = 0; j < 5; ++j) { |
| 25331 | if( i != j ) { |
| 25332 | if( roots[i] != roots[j] ) { |
| 25333 | x /= (roots[i] - roots[j]); |
| 25334 | } |
| 25335 | } |
| 25336 | } |
| 25337 | roots[i] -= x; |
| 25338 | err[i] = abs(x); |
| 25339 | } |
| 25340 | } |
| 25341 | if( !changed ) { |
| 25342 | break; |
| 25343 | } |
| 25344 | } |
| 25345 | |
| 25346 | numroots = 0; |
| 25347 | bool visited[5] = {false}; |
| 25348 | for(int i = 0; i < 5; ++i) { |
| 25349 | if( !visited[i] ) { |
| 25350 | // might be a multiple root, in which case it will have more error than the other roots |
| 25351 | // find any neighboring roots, and take the average |
| 25352 | complex<IkReal> newroot=roots[i]; |
| 25353 | int n = 1; |
| 25354 | for(int j = i+1; j < 5; ++j) { |
| 25355 | // care about error in real much more than imaginary |
| 25356 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25357 | newroot += roots[j]; |
| 25358 | n += 1; |
| 25359 | visited[j] = true; |
| 25360 | } |
| 25361 | } |
| 25362 | if( n > 1 ) { |
| 25363 | newroot /= n; |
| 25364 | } |
| 25365 | // 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 |
| 25366 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25367 | rawroots[numroots++] = real(newroot); |
| 25368 | } |
| 25369 | } |
| 25370 | } |
| 25371 | } |
| 25372 | static inline void polyroots4(IkReal rawcoeffs[4+1], IkReal rawroots[4], int& numroots) |
| 25373 | { |
| 25374 | using std::complex; |
| 25375 | if( rawcoeffs[0] == 0 ) { |
| 25376 | // solve with one reduced degree |
| 25377 | polyroots3(&rawcoeffs[1], &rawroots[0], numroots); |
| 25378 | return; |
| 25379 | } |
| 25380 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25381 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25382 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25383 | complex<IkReal> coeffs[4]; |
| 25384 | const int maxsteps = 110; |
| 25385 | for(int i = 0; i < 4; ++i) { |
| 25386 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25387 | } |
| 25388 | complex<IkReal> roots[4]; |
| 25389 | IkReal err[4]; |
| 25390 | roots[0] = complex<IkReal>(1,0); |
| 25391 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25392 | err[0] = 1.0; |
| 25393 | err[1] = 1.0; |
| 25394 | for(int i = 2; i < 4; ++i) { |
| 25395 | roots[i] = roots[i-1]*roots[1]; |
| 25396 | err[i] = 1.0; |
| 25397 | } |
| 25398 | for(int step = 0; step < maxsteps; ++step) { |
| 25399 | bool changed = false; |
| 25400 | for(int i = 0; i < 4; ++i) { |
| 25401 | if ( err[i] >= tol ) { |
| 25402 | changed = true; |
| 25403 | // evaluate |
| 25404 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25405 | for(int j = 1; j < 4; ++j) { |
| 25406 | x = roots[i] * x + coeffs[j]; |
| 25407 | } |
| 25408 | for(int j = 0; j < 4; ++j) { |
| 25409 | if( i != j ) { |
| 25410 | if( roots[i] != roots[j] ) { |
| 25411 | x /= (roots[i] - roots[j]); |
| 25412 | } |
| 25413 | } |
| 25414 | } |
| 25415 | roots[i] -= x; |
| 25416 | err[i] = abs(x); |
| 25417 | } |
| 25418 | } |
| 25419 | if( !changed ) { |
| 25420 | break; |
| 25421 | } |
| 25422 | } |
| 25423 | |
| 25424 | numroots = 0; |
| 25425 | bool visited[4] = {false}; |
| 25426 | for(int i = 0; i < 4; ++i) { |
| 25427 | if( !visited[i] ) { |
| 25428 | // might be a multiple root, in which case it will have more error than the other roots |
| 25429 | // find any neighboring roots, and take the average |
| 25430 | complex<IkReal> newroot=roots[i]; |
| 25431 | int n = 1; |
| 25432 | for(int j = i+1; j < 4; ++j) { |
| 25433 | // care about error in real much more than imaginary |
| 25434 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25435 | newroot += roots[j]; |
| 25436 | n += 1; |
| 25437 | visited[j] = true; |
| 25438 | } |
| 25439 | } |
| 25440 | if( n > 1 ) { |
| 25441 | newroot /= n; |
| 25442 | } |
| 25443 | // 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 |
| 25444 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25445 | rawroots[numroots++] = real(newroot); |
| 25446 | } |
| 25447 | } |
| 25448 | } |
| 25449 | } |
| 25450 | static inline void polyroots7(IkReal rawcoeffs[7+1], IkReal rawroots[7], int& numroots) |
| 25451 | { |
| 25452 | using std::complex; |
| 25453 | if( rawcoeffs[0] == 0 ) { |
| 25454 | // solve with one reduced degree |
| 25455 | polyroots6(&rawcoeffs[1], &rawroots[0], numroots); |
| 25456 | return; |
| 25457 | } |
| 25458 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25459 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25460 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25461 | complex<IkReal> coeffs[7]; |
| 25462 | const int maxsteps = 110; |
| 25463 | for(int i = 0; i < 7; ++i) { |
| 25464 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25465 | } |
| 25466 | complex<IkReal> roots[7]; |
| 25467 | IkReal err[7]; |
| 25468 | roots[0] = complex<IkReal>(1,0); |
| 25469 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25470 | err[0] = 1.0; |
| 25471 | err[1] = 1.0; |
| 25472 | for(int i = 2; i < 7; ++i) { |
| 25473 | roots[i] = roots[i-1]*roots[1]; |
| 25474 | err[i] = 1.0; |
| 25475 | } |
| 25476 | for(int step = 0; step < maxsteps; ++step) { |
| 25477 | bool changed = false; |
| 25478 | for(int i = 0; i < 7; ++i) { |
| 25479 | if ( err[i] >= tol ) { |
| 25480 | changed = true; |
| 25481 | // evaluate |
| 25482 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25483 | for(int j = 1; j < 7; ++j) { |
| 25484 | x = roots[i] * x + coeffs[j]; |
| 25485 | } |
| 25486 | for(int j = 0; j < 7; ++j) { |
| 25487 | if( i != j ) { |
| 25488 | if( roots[i] != roots[j] ) { |
| 25489 | x /= (roots[i] - roots[j]); |
| 25490 | } |
| 25491 | } |
| 25492 | } |
| 25493 | roots[i] -= x; |
| 25494 | err[i] = abs(x); |
| 25495 | } |
| 25496 | } |
| 25497 | if( !changed ) { |
| 25498 | break; |
| 25499 | } |
| 25500 | } |
| 25501 | |
| 25502 | numroots = 0; |
| 25503 | bool visited[7] = {false}; |
| 25504 | for(int i = 0; i < 7; ++i) { |
| 25505 | if( !visited[i] ) { |
| 25506 | // might be a multiple root, in which case it will have more error than the other roots |
| 25507 | // find any neighboring roots, and take the average |
| 25508 | complex<IkReal> newroot=roots[i]; |
| 25509 | int n = 1; |
| 25510 | for(int j = i+1; j < 7; ++j) { |
| 25511 | // care about error in real much more than imaginary |
| 25512 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25513 | newroot += roots[j]; |
| 25514 | n += 1; |
| 25515 | visited[j] = true; |
| 25516 | } |
| 25517 | } |
| 25518 | if( n > 1 ) { |
| 25519 | newroot /= n; |
| 25520 | } |
| 25521 | // 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 |
| 25522 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25523 | rawroots[numroots++] = real(newroot); |
| 25524 | } |
| 25525 | } |
| 25526 | } |
| 25527 | } |
| 25528 | static inline void polyroots6(IkReal rawcoeffs[6+1], IkReal rawroots[6], int& numroots) |
| 25529 | { |
| 25530 | using std::complex; |
| 25531 | if( rawcoeffs[0] == 0 ) { |
| 25532 | // solve with one reduced degree |
| 25533 | polyroots5(&rawcoeffs[1], &rawroots[0], numroots); |
| 25534 | return; |
| 25535 | } |
| 25536 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25537 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25538 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25539 | complex<IkReal> coeffs[6]; |
| 25540 | const int maxsteps = 110; |
| 25541 | for(int i = 0; i < 6; ++i) { |
| 25542 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25543 | } |
| 25544 | complex<IkReal> roots[6]; |
| 25545 | IkReal err[6]; |
| 25546 | roots[0] = complex<IkReal>(1,0); |
| 25547 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25548 | err[0] = 1.0; |
| 25549 | err[1] = 1.0; |
| 25550 | for(int i = 2; i < 6; ++i) { |
| 25551 | roots[i] = roots[i-1]*roots[1]; |
| 25552 | err[i] = 1.0; |
| 25553 | } |
| 25554 | for(int step = 0; step < maxsteps; ++step) { |
| 25555 | bool changed = false; |
| 25556 | for(int i = 0; i < 6; ++i) { |
| 25557 | if ( err[i] >= tol ) { |
| 25558 | changed = true; |
| 25559 | // evaluate |
| 25560 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25561 | for(int j = 1; j < 6; ++j) { |
| 25562 | x = roots[i] * x + coeffs[j]; |
| 25563 | } |
| 25564 | for(int j = 0; j < 6; ++j) { |
| 25565 | if( i != j ) { |
| 25566 | if( roots[i] != roots[j] ) { |
| 25567 | x /= (roots[i] - roots[j]); |
| 25568 | } |
| 25569 | } |
| 25570 | } |
| 25571 | roots[i] -= x; |
| 25572 | err[i] = abs(x); |
| 25573 | } |
| 25574 | } |
| 25575 | if( !changed ) { |
| 25576 | break; |
| 25577 | } |
| 25578 | } |
| 25579 | |
| 25580 | numroots = 0; |
| 25581 | bool visited[6] = {false}; |
| 25582 | for(int i = 0; i < 6; ++i) { |
| 25583 | if( !visited[i] ) { |
| 25584 | // might be a multiple root, in which case it will have more error than the other roots |
| 25585 | // find any neighboring roots, and take the average |
| 25586 | complex<IkReal> newroot=roots[i]; |
| 25587 | int n = 1; |
| 25588 | for(int j = i+1; j < 6; ++j) { |
| 25589 | // care about error in real much more than imaginary |
| 25590 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25591 | newroot += roots[j]; |
| 25592 | n += 1; |
| 25593 | visited[j] = true; |
| 25594 | } |
| 25595 | } |
| 25596 | if( n > 1 ) { |
| 25597 | newroot /= n; |
| 25598 | } |
| 25599 | // 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 |
| 25600 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25601 | rawroots[numroots++] = real(newroot); |
| 25602 | } |
| 25603 | } |
| 25604 | } |
| 25605 | } |
| 25606 | static inline void polyroots8(IkReal rawcoeffs[8+1], IkReal rawroots[8], int& numroots) |
| 25607 | { |
| 25608 | using std::complex; |
| 25609 | if( rawcoeffs[0] == 0 ) { |
| 25610 | // solve with one reduced degree |
| 25611 | polyroots7(&rawcoeffs[1], &rawroots[0], numroots); |
| 25612 | return; |
| 25613 | } |
| 25614 | IKFAST_ASSERT(rawcoeffs[0] != 0); |
| 25615 | const IkReal tol = 128.0*std::numeric_limits<IkReal>::epsilon(); |
| 25616 | const IkReal tolsqrt = sqrt(std::numeric_limits<IkReal>::epsilon()); |
| 25617 | complex<IkReal> coeffs[8]; |
| 25618 | const int maxsteps = 110; |
| 25619 | for(int i = 0; i < 8; ++i) { |
| 25620 | coeffs[i] = complex<IkReal>(rawcoeffs[i+1]/rawcoeffs[0]); |
| 25621 | } |
| 25622 | complex<IkReal> roots[8]; |
| 25623 | IkReal err[8]; |
| 25624 | roots[0] = complex<IkReal>(1,0); |
| 25625 | roots[1] = complex<IkReal>(0.4,0.9); // any complex number not a root of unity works |
| 25626 | err[0] = 1.0; |
| 25627 | err[1] = 1.0; |
| 25628 | for(int i = 2; i < 8; ++i) { |
| 25629 | roots[i] = roots[i-1]*roots[1]; |
| 25630 | err[i] = 1.0; |
| 25631 | } |
| 25632 | for(int step = 0; step < maxsteps; ++step) { |
| 25633 | bool changed = false; |
| 25634 | for(int i = 0; i < 8; ++i) { |
| 25635 | if ( err[i] >= tol ) { |
| 25636 | changed = true; |
| 25637 | // evaluate |
| 25638 | complex<IkReal> x = roots[i] + coeffs[0]; |
| 25639 | for(int j = 1; j < 8; ++j) { |
| 25640 | x = roots[i] * x + coeffs[j]; |
| 25641 | } |
| 25642 | for(int j = 0; j < 8; ++j) { |
| 25643 | if( i != j ) { |
| 25644 | if( roots[i] != roots[j] ) { |
| 25645 | x /= (roots[i] - roots[j]); |
| 25646 | } |
| 25647 | } |
| 25648 | } |
| 25649 | roots[i] -= x; |
| 25650 | err[i] = abs(x); |
| 25651 | } |
| 25652 | } |
| 25653 | if( !changed ) { |
| 25654 | break; |
| 25655 | } |
| 25656 | } |
| 25657 | |
| 25658 | numroots = 0; |
| 25659 | bool visited[8] = {false}; |
| 25660 | for(int i = 0; i < 8; ++i) { |
| 25661 | if( !visited[i] ) { |
| 25662 | // might be a multiple root, in which case it will have more error than the other roots |
| 25663 | // find any neighboring roots, and take the average |
| 25664 | complex<IkReal> newroot=roots[i]; |
| 25665 | int n = 1; |
| 25666 | for(int j = i+1; j < 8; ++j) { |
| 25667 | // care about error in real much more than imaginary |
| 25668 | if( abs(real(roots[i])-real(roots[j])) < tolsqrt && abs(imag(roots[i])-imag(roots[j])) < 0.002 ) { |
| 25669 | newroot += roots[j]; |
| 25670 | n += 1; |
| 25671 | visited[j] = true; |
| 25672 | } |
| 25673 | } |
| 25674 | if( n > 1 ) { |
| 25675 | newroot /= n; |
| 25676 | } |
| 25677 | // 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 |
| 25678 | if( IKabs(imag(newroot)) < tolsqrt ) { |
| 25679 | rawroots[numroots++] = real(newroot); |
| 25680 | } |
| 25681 | } |
| 25682 | } |
| 25683 | } |
| 25684 | }; |
| 25685 | |
| 25686 | |
| 25687 | /// solves the inverse kinematics equations. |
| 25688 | /// \param pfree is an array specifying the free joints of the chain. |
| 25689 | IKFAST_API bool ComputeIk(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions) { |
| 25690 | IKSolver solver; |
| 25691 | return solver.ComputeIk(eetrans,eerot,pfree,solutions); |
| 25692 | } |
| 25693 | |
| 25694 | IKFAST_API bool ComputeIk2(const IkReal* eetrans, const IkReal* eerot, const IkReal* pfree, IkSolutionListBase<IkReal>& solutions, void* pOpenRAVEManip) { |
| 25695 | IKSolver solver; |
| 25696 | return solver.ComputeIk(eetrans,eerot,pfree,solutions); |
| 25697 | } |
| 25698 | |
| 25699 | IKFAST_API const char* GetKinematicsHash() { return "<robot:GenericRobot - hya (58dbf1259c2cdf57f1e3d77f555c8c6b)>"; } |
| 25700 | |
| 25701 | IKFAST_API const char* GetIkFastVersion() { return "0x1000004a"; } |
| 25702 | |
| 25703 | #ifdef IKFAST_NAMESPACE |
| 25704 | } // end namespace |
| 25705 | #endif |
| 25706 | |
| 25707 | #ifndef IKFAST_NO_MAIN |
| 25708 | #include <stdio.h> |
| 25709 | #include <stdlib.h> |
| 25710 | #ifdef IKFAST_NAMESPACE |
| 25711 | using namespace IKFAST_NAMESPACE; |
| 25712 | #endif |
| 25713 | int main(int argc, char** argv) |
| 25714 | { |
| 25715 | if( argc != 12+GetNumFreeParameters()+1 ) { |
| 25716 | printf("\nUsage: ./ik r00 r01 r02 t0 r10 r11 r12 t1 r20 r21 r22 t2 free0 ...\n\n" |
| 25717 | "Returns the ik solutions given the transformation of the end effector specified by\n" |
| 25718 | "a 3x3 rotation R (rXX), and a 3x1 translation (tX).\n" |
| 25719 | "There are %d free parameters that have to be specified.\n\n",GetNumFreeParameters()); |
| 25720 | return 1; |
| 25721 | } |
| 25722 | |
| 25723 | IkSolutionList<IkReal> solutions; |
| 25724 | std::vector<IkReal> vfree(GetNumFreeParameters()); |
| 25725 | IkReal eerot[9],eetrans[3]; |
| 25726 | eerot[0] = atof(argv[1]); eerot[1] = atof(argv[2]); eerot[2] = atof(argv[3]); eetrans[0] = atof(argv[4]); |
| 25727 | eerot[3] = atof(argv[5]); eerot[4] = atof(argv[6]); eerot[5] = atof(argv[7]); eetrans[1] = atof(argv[8]); |
| 25728 | eerot[6] = atof(argv[9]); eerot[7] = atof(argv[10]); eerot[8] = atof(argv[11]); eetrans[2] = atof(argv[12]); |
| 25729 | for(std::size_t i = 0; i < vfree.size(); ++i) |
| 25730 | vfree[i] = atof(argv[13+i]); |
| 25731 | bool bSuccess = ComputeIk(eetrans, eerot, vfree.size() > 0 ? &vfree[0] : NULL, solutions); |
| 25732 | |
| 25733 | if( !bSuccess ) { |
| 25734 | fprintf(stderr,"Failed to get ik solution\n"); |
| 25735 | return -1; |
| 25736 | } |
| 25737 | |
| 25738 | printf("Found %d ik solutions:\n", (int)solutions.GetNumSolutions()); |
| 25739 | std::vector<IkReal> solvalues(GetNumJoints()); |
| 25740 | for(std::size_t i = 0; i < solutions.GetNumSolutions(); ++i) { |
| 25741 | const IkSolutionBase<IkReal>& sol = solutions.GetSolution(i); |
| 25742 | printf("sol%d (free=%d): ", (int)i, (int)sol.GetFree().size()); |
| 25743 | std::vector<IkReal> vsolfree(sol.GetFree().size()); |
| 25744 | sol.GetSolution(&solvalues[0],vsolfree.size()>0?&vsolfree[0]:NULL); |
| 25745 | for( std::size_t j = 0; j < solvalues.size(); ++j) |
| 25746 | printf("%.15f, ", solvalues[j]); |
| 25747 | printf("\n"); |
| 25748 | } |
| 25749 | return 0; |
| 25750 | } |
| 25751 | |
| 25752 | #endif |